diff --git a/.images/x30.png b/.images/x30.png new file mode 100644 index 0000000..7188380 Binary files /dev/null and b/.images/x30.png differ diff --git a/descriptions/README.md b/descriptions/README.md index aafd84d..fb30ada 100644 --- a/descriptions/README.md +++ b/descriptions/README.md @@ -12,6 +12,7 @@ This folder contains the URDF and SRDF files for the quadruped robot. * [Cyberdog](xiaomi/cyberdog_description/) * Deep Robotics * [Lite 3](deep_robotics/lite3_description/) + * [X30](deep_robotics/x30_description/) ## Steps to transfer urdf to Mujoco model diff --git a/descriptions/deep_robotics/x30_description/CMakeLists.txt b/descriptions/deep_robotics/x30_description/CMakeLists.txt new file mode 100644 index 0000000..a2e7446 --- /dev/null +++ b/descriptions/deep_robotics/x30_description/CMakeLists.txt @@ -0,0 +1,11 @@ +cmake_minimum_required(VERSION 3.8) +project(x30_description) + +find_package(ament_cmake REQUIRED) + +install( + DIRECTORY meshes xacro launch config urdf + DESTINATION share/${PROJECT_NAME}/ +) + +ament_package() \ No newline at end of file diff --git a/descriptions/deep_robotics/x30_description/README.md b/descriptions/deep_robotics/x30_description/README.md new file mode 100644 index 0000000..aa27226 --- /dev/null +++ b/descriptions/deep_robotics/x30_description/README.md @@ -0,0 +1,35 @@ +# DeepRobotics X30 Description +This repository contains the urdf model of x30. + +![x30](../../../.images/x30.png) + +Tested environment: +* Ubuntu 24.04 + * ROS2 Jazzy + +## Build +```bash +cd ~/ros2_ws +colcon build --packages-up-to x30_description --symlink-install +``` + +## Visualize the robot +To visualize and check the configuration of the robot in rviz, simply launch: +```bash +source ~/ros2_ws/install/setup.bash +ros2 launch x30_description visualize.launch.py +``` + +## Launch ROS2 Control + +### Gazebo Simulator +* Unitree Guide Controller + ```bash + source ~/ros2_ws/install/setup.bash + ros2 launch x30_description gazebo_unitree_guide.launch.py + ``` +* Legged Gym Controller + ```bash + source ~/ros2_ws/install/setup.bash + ros2 launch x30_description gazebo_rl_control.launch.py + ``` \ No newline at end of file diff --git a/descriptions/deep_robotics/x30_description/config/gazebo.yaml b/descriptions/deep_robotics/x30_description/config/gazebo.yaml new file mode 100644 index 0000000..559e61c --- /dev/null +++ b/descriptions/deep_robotics/x30_description/config/gazebo.yaml @@ -0,0 +1,143 @@ +# Controller Manager configuration +controller_manager: + ros__parameters: + update_rate: 2000 # Hz + + # Define the available controllers + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + + imu_sensor_broadcaster: + type: imu_sensor_broadcaster/IMUSensorBroadcaster + + leg_pd_controller: + type: leg_pd_controller/LegPdController + + unitree_guide_controller: + type: unitree_guide_controller/UnitreeGuideController + + rl_quadruped_controller: + type: rl_quadruped_controller/LeggedGymController + +imu_sensor_broadcaster: + ros__parameters: + sensor_name: "imu_sensor" + frame_id: "imu_link" + +leg_pd_controller: + ros__parameters: + joints: + - FR_HipX + - FR_HipY + - FR_Knee + - FL_HipX + - FL_HipY + - FL_Knee + - HR_HipX + - HR_HipY + - HR_Knee + - HL_HipX + - HL_HipY + - HL_Knee + + command_interfaces: + - effort + + state_interfaces: + - position + - velocity + +unitree_guide_controller: + ros__parameters: + update_rate: 200 # Hz + command_prefix: "leg_pd_controller" + joints: + - FR_HipX + - FR_HipY + - FR_Knee + - FL_HipX + - FL_HipY + - FL_Knee + - HR_HipX + - HR_HipY + - HR_Knee + - HL_HipX + - HL_HipY + - HL_Knee + + command_interfaces: + - effort + - position + - velocity + - kp + - kd + + state_interfaces: + - effort + - position + - velocity + + feet_names: + - FR_FOOT + - FL_FOOT + - HR_FOOT + - HL_FOOT + + imu_name: "imu_sensor" + base_name: "base" + + imu_interfaces: + - orientation.w + - orientation.x + - orientation.y + - orientation.z + - angular_velocity.x + - angular_velocity.y + - angular_velocity.z + - linear_acceleration.x + - linear_acceleration.y + - linear_acceleration.z + +rl_quadruped_controller: + ros__parameters: + update_rate: 200 # Hz + config_folder: "/home/tlab-uav/ros2_ws/install/a1_description/share/a1_description/config/issacgym" + command_prefix: "leg_pd_controller" + joints: + - FL_hip_joint + - FL_thigh_joint + - FL_calf_joint + - FR_hip_joint + - FR_thigh_joint + - FR_calf_joint + - RL_hip_joint + - RL_thigh_joint + - RL_calf_joint + - RR_hip_joint + - RR_thigh_joint + - RR_calf_joint + + command_interfaces: + - effort + - position + - velocity + - kp + - kd + + state_interfaces: + - effort + - position + - velocity + + imu_name: "imu_sensor" + imu_interfaces: + - orientation.w + - orientation.x + - orientation.y + - orientation.z + - angular_velocity.x + - angular_velocity.y + - angular_velocity.z + - linear_acceleration.x + - linear_acceleration.y + - linear_acceleration.z \ No newline at end of file diff --git a/descriptions/deep_robotics/x30_description/config/ocs2/gait.info b/descriptions/deep_robotics/x30_description/config/ocs2/gait.info new file mode 100644 index 0000000..6ea163b --- /dev/null +++ b/descriptions/deep_robotics/x30_description/config/ocs2/gait.info @@ -0,0 +1,255 @@ +list +{ + [0] stance + [1] trot + [2] standing_trot + [3] flying_trot + [4] pace + [5] standing_pace + [6] dynamic_walk + [7] static_walk + [8] amble + [9] lindyhop + [10] skipping + [11] pawup +} + +stance + { + modeSequence + { + [0] STANCE + } + switchingTimes + { + [0] 0.0 + [1] 0.5 + } +} + +trot + { + modeSequence + { + [0] LF_RH + [1] RF_LH + } + switchingTimes + { + [0] 0.0 + [1] 0.3 + [2] 0.6 + } +} + +standing_trot +{ + modeSequence + { + [0] LF_RH + [1] STANCE + [2] RF_LH + [3] STANCE + } + switchingTimes + { + [0] 0.00 + [1] 0.25 + [2] 0.3 + [3] 0.55 + [4] 0.6 + } +} + +flying_trot +{ + modeSequence + { + [0] LF_RH + [1] FLY + [2] RF_LH + [3] FLY + } + switchingTimes + { + [0] 0.00 + [1] 0.15 + [2] 0.2 + [3] 0.35 + [4] 0.4 + } +} + +pace +{ + modeSequence + { + [0] LF_LH + [1] FLY + [2] RF_RH + [3] FLY + } + switchingTimes + { + [0] 0.0 + [1] 0.28 + [2] 0.30 + [3] 0.58 + [4] 0.60 + } +} + +standing_pace +{ + modeSequence + { + [0] LF_LH + [1] STANCE + [2] RF_RH + [3] STANCE + } + switchingTimes + { + [0] 0.0 + [1] 0.30 + [2] 0.35 + [3] 0.65 + [4] 0.70 + } +} + +dynamic_walk +{ + modeSequence + { + [0] LF_RF_RH + [1] RF_RH + [2] RF_LH_RH + [3] LF_RF_LH + [4] LF_LH + [5] LF_LH_RH + } + switchingTimes + { + [0] 0.0 + [1] 0.2 + [2] 0.3 + [3] 0.5 + [4] 0.7 + [5] 0.8 + [6] 1.0 + } +} + +static_walk +{ + modeSequence + { + [0] LF_RF_RH + [1] RF_LH_RH + [2] LF_RF_LH + [3] LF_LH_RH + } + switchingTimes + { + [0] 0.0 + [1] 0.3 + [2] 0.6 + [3] 0.9 + [4] 1.2 + } +} + +amble +{ + modeSequence + { + [0] RF_LH + [1] LF_LH + [2] LF_RH + [3] RF_RH + } + switchingTimes + { + [0] 0.0 + [1] 0.15 + [2] 0.40 + [3] 0.55 + [4] 0.80 + } +} + +lindyhop +{ + modeSequence + { + [0] LF_RH + [1] STANCE + [2] RF_LH + [3] STANCE + [4] LF_LH + [5] RF_RH + [6] LF_LH + [7] STANCE + [8] RF_RH + [9] LF_LH + [10] RF_RH + [11] STANCE + } + switchingTimes + { + [0] 0.00 ; Step 1 + [1] 0.35 ; Stance + [2] 0.45 ; Step 2 + [3] 0.80 ; Stance + [4] 0.90 ; Tripple step + [5] 1.125 ; + [6] 1.35 ; + [7] 1.70 ; Stance + [8] 1.80 ; Tripple step + [9] 2.025 ; + [10] 2.25 ; + [11] 2.60 ; Stance + [12] 2.70 ; + } +} + +skipping +{ + modeSequence + { + [0] LF_RH + [1] FLY + [2] LF_RH + [3] FLY + [4] RF_LH + [5] FLY + [6] RF_LH + [7] FLY + } + switchingTimes + { + [0] 0.00 + [1] 0.27 + [2] 0.30 + [3] 0.57 + [4] 0.60 + [5] 0.87 + [6] 0.90 + [7] 1.17 + [8] 1.20 + } +} + +pawup +{ + modeSequence + { + [0] RF_LH_RH + } + switchingTimes + { + [0] 0.0 + [1] 2.0 + } +} diff --git a/descriptions/deep_robotics/x30_description/config/ocs2/reference.info b/descriptions/deep_robotics/x30_description/config/ocs2/reference.info new file mode 100644 index 0000000..2f69c51 --- /dev/null +++ b/descriptions/deep_robotics/x30_description/config/ocs2/reference.info @@ -0,0 +1,46 @@ +targetDisplacementVelocity 0.5; +targetRotationVelocity 1.57; + +comHeight 0.33 + +defaultJointState +{ + (0,0) -0.20 ; FL_hip_joint + (1,0) 0.72 ; FL_thigh_joint + (2,0) -1.44 ; FL_calf_joint + (3,0) 0.20 ; FR_hip_joint + (4,0) 0.72 ; FR_thigh_joint + (5,0) -1.44 ; FR_calf_joint + (6,0) -0.20 ; RL_hip_joint + (7,0) 0.72 ; RL_thigh_joint + (8,0) -1.44 ; RL_calf_joint + (9,0) 0.20 ; RR_hip_joint + (10,0) 0.72 ; RR_thigh_joint + (11,0) -1.44 ; RR_calf_joint +} + +initialModeSchedule +{ + modeSequence + { + [0] STANCE + [1] STANCE + } + eventTimes + { + [0] 0.5 + } +} + +defaultModeSequenceTemplate +{ + modeSequence + { + [0] STANCE + } + switchingTimes + { + [0] 0.0 + [1] 1.0 + } +} diff --git a/descriptions/deep_robotics/x30_description/config/ocs2/task.info b/descriptions/deep_robotics/x30_description/config/ocs2/task.info new file mode 100644 index 0000000..93f5ce4 --- /dev/null +++ b/descriptions/deep_robotics/x30_description/config/ocs2/task.info @@ -0,0 +1,319 @@ +centroidalModelType 0 // 0: FullCentroidalDynamics, 1: Single Rigid Body Dynamics + +legged_robot_interface +{ + verbose false // show the loaded parameters +} + +model_settings +{ + positionErrorGain 0.0 + phaseTransitionStanceTime 0.1 + + verboseCppAd true + recompileLibrariesCppAd false + modelFolderCppAd /tmp/ocs2_quadruped_controller/a1 +} + +swing_trajectory_config +{ + liftOffVelocity 0.05 + touchDownVelocity -0.1 + swingHeight 0.1 + swingTimeScale 0.15 +} + +; DDP settings +ddp +{ + algorithm SLQ + + nThreads 3 + threadPriority 50 + + maxNumIterations 1 + minRelCost 1e-1 + constraintTolerance 5e-3 + + displayInfo false + displayShortSummary false + checkNumericalStability false + debugPrintRollout false + debugCaching false + + AbsTolODE 1e-5 + RelTolODE 1e-3 + maxNumStepsPerSecond 10000 + timeStep 0.015 + backwardPassIntegratorType ODE45 + + constraintPenaltyInitialValue 20.0 + constraintPenaltyIncreaseRate 2.0 + + preComputeRiccatiTerms true + + useFeedbackPolicy false + + strategy LINE_SEARCH + lineSearch + { + minStepLength 1e-2 + maxStepLength 1.0 + hessianCorrectionStrategy DIAGONAL_SHIFT + hessianCorrectionMultiple 1e-5 + } +} + + +; Multiple_Shooting SQP settings +sqp +{ + nThreads 3 + dt 0.015 + sqpIteration 1 + deltaTol 1e-4 + g_max 1e-2 + g_min 1e-6 + inequalityConstraintMu 0.1 + inequalityConstraintDelta 5.0 + projectStateInputEqualityConstraints true + printSolverStatistics true + printSolverStatus false + printLinesearch false + useFeedbackPolicy false + integratorType RK2 + threadPriority 50 +} + +; Multiple_Shooting IPM settings +ipm +{ + nThreads 3 + dt 0.015 + ipmIteration 1 + deltaTol 1e-4 + g_max 10.0 + g_min 1e-6 + computeLagrangeMultipliers true + printSolverStatistics true + printSolverStatus false + printLinesearch false + useFeedbackPolicy false + integratorType RK2 + threadPriority 50 + + initialBarrierParameter 1e-4 + targetBarrierParameter 1e-4 + barrierLinearDecreaseFactor 0.2 + barrierSuperlinearDecreasePower 1.5 + barrierReductionCostTol 1e-3 + barrierReductionConstraintTol 1e-3 + + fractionToBoundaryMargin 0.995 + usePrimalStepSizeForDual false + + initialSlackLowerBound 1e-4 + initialDualLowerBound 1e-4 + initialSlackMarginRate 1e-2 + initialDualMarginRate 1e-2 +} + +; Rollout settings +rollout +{ + AbsTolODE 1e-5 + RelTolODE 1e-3 + timeStep 0.015 + integratorType ODE45 + maxNumStepsPerSecond 10000 + checkNumericalStability false +} + +mpc +{ + timeHorizon 1.0 ; [s] + solutionTimeWindow -1 ; maximum [s] + coldStart false + + debugPrint false + + mpcDesiredFrequency 100 ; [Hz] + mrtDesiredFrequency 1000 ; [Hz] Useless +} + +initialState +{ + ;; Normalized Centroidal Momentum: [linear, angular] ;; + (0,0) 0.0 ; vcom_x + (1,0) 0.0 ; vcom_y + (2,0) 0.0 ; vcom_z + (3,0) 0.0 ; L_x / robotMass + (4,0) 0.0 ; L_y / robotMass + (5,0) 0.0 ; L_z / robotMass + + ;; Base Pose: [position, orientation] ;; + (6,0) 0.0 ; p_base_x + (7,0) 0.0 ; p_base_y + (8,0) 0.33 ; p_base_z + (9,0) 0.0 ; theta_base_z + (10,0) 0.0 ; theta_base_y + (11,0) 0.0 ; theta_base_x + + ;; Leg Joint Positions: [FL, RL, FR, RR] ;; + (12,0) -0.20 ; FL_hip_joint + (13,0) 0.72 ; FL_thigh_joint + (14,0) -1.44 ; FL_calf_joint + (15,0) -0.20 ; RL_hip_joint + (16,0) 0.72 ; RL_thigh_joint + (17,0) -1.44 ; RL_calf_joint + (18,0) 0.20 ; FR_hip_joint + (19,0) 0.72 ; FR_thigh_joint + (20,0) -1.44 ; FR_calf_joint + (21,0) 0.20 ; RR_hip_joint + (22,0) 0.72 ; RR_thigh_joint + (23,0) -1.44 ; RR_calf_joint +} + +; standard state weight matrix +Q +{ + scaling 1e+0 + + ;; Normalized Centroidal Momentum: [linear, angular] ;; + (0,0) 15.0 ; vcom_x + (1,1) 15.0 ; vcom_y + (2,2) 100.0 ; vcom_z + (3,3) 10.0 ; L_x / robotMass + (4,4) 30.0 ; L_y / robotMass + (5,5) 30.0 ; L_z / robotMass + + ;; Base Pose: [position, orientation] ;; + (6,6) 1000.0 ; p_base_x + (7,7) 1000.0 ; p_base_y + (8,8) 1500.0 ; p_base_z + (9,9) 100.0 ; theta_base_z + (10,10) 300.0 ; theta_base_y + (11,11) 300.0 ; theta_base_x + + ;; Leg Joint Positions: [FL, RL, FR, RR] ;; + (12,12) 5.0 ; FL_hip_joint + (13,13) 5.0 ; FL_thigh_joint + (14,14) 2.5 ; FL_calf_joint + (15,15) 5.0 ; RL_hip_joint + (16,16) 5.0 ; RL_thigh_joint + (17,17) 2.5 ; RL_calf_joint + (18,18) 5.0 ; FR_hip_joint + (19,19) 5.0 ; FR_thigh_joint + (20,20) 2.5 ; FR_calf_joint + (21,21) 5.0 ; RR_hip_joint + (22,22) 5.0 ; RR_thigh_joint + (23,23) 2.5 ; RR_calf_joint +} + +; control weight matrix +R +{ + scaling 1e-3 + + ;; Feet Contact Forces: [FL, FR, RL, RR] ;; + (0,0) 1.0 ; front_left_force + (1,1) 1.0 ; front_left_force + (2,2) 1.0 ; front_left_force + (3,3) 1.0 ; front_right_force + (4,4) 1.0 ; front_right_force + (5,5) 1.0 ; front_right_force + (6,6) 1.0 ; rear_left_force + (7,7) 1.0 ; rear_left_force + (8,8) 1.0 ; rear_left_force + (9,9) 1.0 ; rear_right_force + (10,10) 1.0 ; rear_right_force + (11,11) 1.0 ; rear_right_force + + ;; foot velocity relative to base: [FL, RL, FR, RR] (uses the Jacobian at nominal configuration) ;; + (12,12) 5000.0 ; x + (13,13) 5000.0 ; y + (14,14) 5000.0 ; z + (15,15) 5000.0 ; x + (16,16) 5000.0 ; y + (17,17) 5000.0 ; z + (18,18) 5000.0 ; x + (19,19) 5000.0 ; y + (20,20) 5000.0 ; z + (21,21) 5000.0 ; x + (22,22) 5000.0 ; y + (23,23) 5000.0 ; z +} + +frictionConeSoftConstraint +{ + frictionCoefficient 0.3 + + ; relaxed log barrier parameters + mu 0.1 + delta 5.0 +} + +selfCollision +{ + ; Self Collision raw object pairs + collisionObjectPairs + { + } + + ; Self Collision pairs + collisionLinkPairs + { + [0] "FL_calf, FR_calf" + [1] "RL_calf, RR_calf" + [2] "FL_calf, RL_calf" + [3] "FR_calf, RR_calf" + [4] "FL_foot, FR_foot" + [5] "RL_foot, RR_foot" + [6] "FL_foot, RL_foot" + [7] "FR_foot, RR_foot" + } + + minimumDistance 0.05 + + ; relaxed log barrier parameters + mu 1e-2 + delta 1e-3 +} + +; Whole body control +torqueLimitsTask +{ + (0,0) 33.5 ; HAA + (1,0) 33.5 ; HFE + (2,0) 33.5 ; KFE +} + +frictionConeTask +{ + frictionCoefficient 0.3 +} + +swingLegTask +{ + kp 350 + kd 37 +} + +weight +{ + swingLeg 100 + baseAccel 1 + contactForce 0.01 +} + +; State Estimation +kalmanFilter +{ + footRadius 0.02 + imuProcessNoisePosition 0.02 + imuProcessNoiseVelocity 0.02 + footProcessNoisePosition 0.002 + footSensorNoisePosition 0.005 + footSensorNoiseVelocity 0.1 + footHeightSensorNoise 0.01 +} diff --git a/descriptions/deep_robotics/x30_description/config/robot_control.yaml b/descriptions/deep_robotics/x30_description/config/robot_control.yaml new file mode 100644 index 0000000..4798138 --- /dev/null +++ b/descriptions/deep_robotics/x30_description/config/robot_control.yaml @@ -0,0 +1,76 @@ +# Controller Manager configuration +controller_manager: + ros__parameters: + update_rate: 500 # Hz + + # Define the available controllers + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + + imu_sensor_broadcaster: + type: imu_sensor_broadcaster/IMUSensorBroadcaster + + unitree_guide_controller: + type: unitree_guide_controller/UnitreeGuideController + + ocs2_quadruped_controller: + type: ocs2_quadruped_controller/Ocs2QuadrupedController + + rl_quadruped_controller: + type: rl_quadruped_controller/LeggedGymController + +imu_sensor_broadcaster: + ros__parameters: + sensor_name: "imu_sensor" + frame_id: "imu_link" + + +unitree_guide_controller: + ros__parameters: + update_rate: 500 # Hz + joints: + - FR_HipX + - FR_HipY + - FR_Knee + - FL_HipX + - FL_HipY + - FL_Knee + - HR_HipX + - HR_HipY + - HR_Knee + - HL_HipX + - HL_HipY + - HL_Knee + + command_interfaces: + - effort + - position + - velocity + - kp + - kd + + state_interfaces: + - effort + - position + - velocity + + feet_names: + - FR_FOOT + - FL_FOOT + - HR_FOOT + - HL_FOOT + + imu_name: "imu_sensor" + base_name: "base" + + imu_interfaces: + - orientation.w + - orientation.x + - orientation.y + - orientation.z + - angular_velocity.x + - angular_velocity.y + - angular_velocity.z + - linear_acceleration.x + - linear_acceleration.y + - linear_acceleration.z \ No newline at end of file diff --git a/descriptions/deep_robotics/x30_description/config/visualize_urdf.rviz b/descriptions/deep_robotics/x30_description/config/visualize_urdf.rviz new file mode 100644 index 0000000..d6d4e73 --- /dev/null +++ b/descriptions/deep_robotics/x30_description/config/visualize_urdf.rviz @@ -0,0 +1,254 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 138 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /RobotModel1 + Splitter Ratio: 0.5 + Tree Height: 295 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/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_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + 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_SHANK: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + FL_THIGH: + 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_SHANK: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + FR_THIGH: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + HL_FOOT: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + HL_HIP: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + HL_SHANK: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + HL_THIGH: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + HR_FOOT: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + HR_HIP: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + HR_SHANK: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + HR_THIGH: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + INERTIA: + Alpha: 1 + Show Axes: false + Show Trail: false + Link Tree Style: Links in Alphabetic Order + TORSO: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + imu_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Mass Properties: + Inertia: false + Mass: false + Name: RobotModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: TORSO + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 1.1684969663619995 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0.011728689074516296 + Y: 0.011509218253195286 + Z: -0.10348724573850632 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.42539793252944946 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.6953961849212646 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 691 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd000000040000000000000156000001f1fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005d00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003f000001f1000000cc00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000015d0000043cfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000700000043c000000a900fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003bb0000005efc0100000002fb0000000800540069006d00650100000000000003bb0000026f00fffffffb0000000800540069006d006501000000000000045000000000000000000000025f000001f100000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 955 + X: 773 + Y: 168 diff --git a/descriptions/deep_robotics/x30_description/launch/gazebo_unitree_guide.launch.py b/descriptions/deep_robotics/x30_description/launch/gazebo_unitree_guide.launch.py new file mode 100644 index 0000000..4058737 --- /dev/null +++ b/descriptions/deep_robotics/x30_description/launch/gazebo_unitree_guide.launch.py @@ -0,0 +1,106 @@ +import os + +import xacro +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, OpaqueFunction, IncludeLaunchDescription, RegisterEventHandler +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.event_handlers import OnProcessExit +from launch.substitutions import PathJoinSubstitution +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare + +package_description = "x30_description" + + +def process_xacro(): + pkg_path = os.path.join(get_package_share_directory(package_description)) + xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro') + robot_description_config = xacro.process_file(xacro_file, mappings={'GAZEBO': 'true'}) + return robot_description_config.toxml() + + +def generate_launch_description(): + rviz_config_file = os.path.join(get_package_share_directory(package_description), "config", "visualize_urdf.rviz") + + robot_description = process_xacro() + + gz_spawn_entity = Node( + package='ros_gz_sim', + executable='create', + output='screen', + arguments=['-topic', 'robot_description', '-name', + 'x30', '-allow_renaming', 'true', '-z', '0.4'], + ) + + robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + parameters=[ + { + 'publish_frequency': 20.0, + 'use_tf_static': True, + 'robot_description': robot_description, + 'ignore_timestamp': True + } + ], + ) + + joint_state_publisher = Node( + package="controller_manager", + executable="spawner", + arguments=["joint_state_broadcaster", + "--controller-manager", "/controller_manager"], + ) + + imu_sensor_broadcaster = Node( + package="controller_manager", + executable="spawner", + arguments=["imu_sensor_broadcaster", + "--controller-manager", "/controller_manager"], + ) + + leg_pd_controller = Node( + package="controller_manager", + executable="spawner", + arguments=["leg_pd_controller", + "--controller-manager", "/controller_manager"], + ) + + unitree_guide_controller = Node( + package="controller_manager", + executable="spawner", + arguments=["unitree_guide_controller", "--controller-manager", "/controller_manager"], + ) + + return LaunchDescription([ + Node( + package='rviz2', + executable='rviz2', + name='rviz_ocs2', + output='screen', + arguments=["-d", rviz_config_file] + ), + Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['/clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock'], + output='screen' + ), + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + [PathJoinSubstitution([FindPackageShare('ros_gz_sim'), + 'launch', + 'gz_sim.launch.py'])]), + launch_arguments=[('gz_args', [' -r -v 4 empty.sdf'])]), + robot_state_publisher, + gz_spawn_entity, + leg_pd_controller, + RegisterEventHandler( + event_handler=OnProcessExit( + target_action=leg_pd_controller, + on_exit=[imu_sensor_broadcaster, joint_state_publisher, unitree_guide_controller], + ) + ), + ]) diff --git a/descriptions/deep_robotics/x30_description/launch/unitree_guide.launch.py b/descriptions/deep_robotics/x30_description/launch/unitree_guide.launch.py new file mode 100644 index 0000000..db3906b --- /dev/null +++ b/descriptions/deep_robotics/x30_description/launch/unitree_guide.launch.py @@ -0,0 +1,93 @@ +import os + +import xacro +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, OpaqueFunction, IncludeLaunchDescription, RegisterEventHandler +from launch.event_handlers import OnProcessExit +from launch.substitutions import PathJoinSubstitution +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare + +package_description = "x30_description" + + +def process_xacro(): + pkg_path = os.path.join(get_package_share_directory(package_description)) + xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro') + robot_description_config = xacro.process_file(xacro_file) + return robot_description_config.toxml() + + +def generate_launch_description(): + rviz_config_file = os.path.join(get_package_share_directory(package_description), "config", "visualize_urdf.rviz") + + robot_description = process_xacro() + + robot_controllers = PathJoinSubstitution( + [ + FindPackageShare(package_description), + "config", + "robot_control.yaml", + ] + ) + + controller_manager = Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[robot_controllers], + output="both", + ) + + robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + parameters=[ + { + 'publish_frequency': 20.0, + 'use_tf_static': True, + 'robot_description': robot_description, + 'ignore_timestamp': True + } + ], + ) + + joint_state_publisher = Node( + package="controller_manager", + executable="spawner", + arguments=["joint_state_broadcaster", + "--controller-manager", "/controller_manager"], + ) + + imu_sensor_broadcaster = Node( + package="controller_manager", + executable="spawner", + arguments=["imu_sensor_broadcaster", + "--controller-manager", "/controller_manager"], + ) + + unitree_guide_controller = Node( + package="controller_manager", + executable="spawner", + arguments=["unitree_guide_controller", "--controller-manager", "/controller_manager"], + ) + + return LaunchDescription([ + Node( + package='rviz2', + executable='rviz2', + name='rviz_ocs2', + output='screen', + arguments=["-d", rviz_config_file] + ), + robot_state_publisher, + controller_manager, + joint_state_publisher, + RegisterEventHandler( + event_handler=OnProcessExit( + target_action=joint_state_publisher, + on_exit=[imu_sensor_broadcaster, unitree_guide_controller], + ) + ), + ]) diff --git a/descriptions/deep_robotics/x30_description/launch/visualize.launch.py b/descriptions/deep_robotics/x30_description/launch/visualize.launch.py new file mode 100644 index 0000000..1f6bbaa --- /dev/null +++ b/descriptions/deep_robotics/x30_description/launch/visualize.launch.py @@ -0,0 +1,49 @@ +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch_ros.actions import Node + +import xacro + +package_description = "x30_description" + +def process_xacro(): + pkg_path = os.path.join(get_package_share_directory(package_description)) + xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro') + robot_description_config = xacro.process_file(xacro_file) + return robot_description_config.toxml() +def generate_launch_description(): + + rviz_config_file = os.path.join(get_package_share_directory(package_description), "config", "visualize_urdf.rviz") + robot_description = process_xacro() + + return LaunchDescription([ + Node( + package='rviz2', + executable='rviz2', + name='rviz_ocs2', + output='screen', + arguments=["-d", rviz_config_file] + ), + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + output='screen', + parameters=[ + { + 'publish_frequency': 100.0, + 'use_tf_static': True, + 'robot_description': robot_description + } + ], + ), + Node( + package='joint_state_publisher_gui', + executable='joint_state_publisher_gui', + name='joint_state_publisher', + output='screen', + ) + ]) \ No newline at end of file diff --git a/descriptions/deep_robotics/x30_description/meshes/hip.dae b/descriptions/deep_robotics/x30_description/meshes/hip.dae new file mode 100755 index 0000000..dfe35e5 --- /dev/null +++ b/descriptions/deep_robotics/x30_description/meshes/hip.dae @@ -0,0 +1,63 @@ + + + + + VCGLab + VCGLib | MeshLab + + Y_UP + 周四 11月 23 02:55:59 2023 + 周四 11月 23 02:55:59 2023 + + + + + + + + + -0.052187 -0.0146815 0.00680446 -0.051568 -0.0146927 -0.0105037 -0.0403549 -0.0146955 -0.0337797 -0.00247946 -0.0146935 -0.0525686 0.0394202 -0.0146949 -0.0346137 -0.0434452 -0.0157 0.00963156 -0.0441193 -0.0157 -0.00580842 -0.0444576 -0.0157 0.00194106 -0.0428629 -0.0146958 -0.016749 -0.0353016 -0.0147322 -0.0270993 -0.0239089 -0.0147491 -0.0375369 -0.0170031 -0.015017 -0.0411291 -0.00958948 -0.0147363 -0.043461 0.00580842 -0.0157 -0.0441193 0.0092215 -0.0147007 -0.0447162 0.0133814 -0.0157 -0.0424404 0.0205478 -0.0157 -0.039472 0.0328088 -0.0157 -0.0300638 0.0424887 -0.0122 -0.000981661 0.0366379 -0.0117141 0.0215418 0.041946 -0.011703 0.00684656 0.00489783 -0.0122 0.0422168 0.0125528 -0.01172 0.0406062 0.0263863 -0.0117228 0.0333182 -0.0106872 -0.0117212 0.0411354 -0.0307411 -0.0117038 0.0293484 0.0190892 -0.014681 -0.0419867 0.0174992 -0.0117 -0.0446122 0.0447573 -0.0147 0.021073 0.0282683 -0.0479915 -0.00492187 -0.0104898 -0.0150351 0.00138775 -0.00246804 -0.0182343 0.00927341 0.00724364 -0.0191 0.00957035 -0.0247858 -0.0589743 -0.0241804 -0.0441193 -0.039 -0.00580842 -0.0239098 -0.039 -0.0375309 -0.0170033 -0.0399952 -0.0411177 -0.00191504 -0.0399922 -0.0444535 0.0134045 -0.0399926 -0.0424276 0.0328088 -0.039 -0.0300638 0.0375403 -0.0399891 -0.0238854 0.0411126 -0.039 -0.0170294 0.0168129 -0.0339181 0.010203 0.00467441 -0.0339337 0.0191033 -0.0102029 -0.0339218 0.016813 -0.00249678 -0.0339243 0.0193596 -0.0154548 -0.0339233 0.0119237 -0.0191031 -0.0339203 0.004674 0.0201646 -0.0315886 -0.0188302 0.0131004 -0.031589 -0.0240981 0.0040246 -0.0315858 -0.0272943 -0.0241034 -0.0315577 -0.0130558 -0.0269893 -0.0315785 -0.00520567 -0.0419562 -0.0146937 0.0189306 -0.0435551 -0.0117 0.0206162 -0.021189 -0.0147 -0.0458086 -0.0329741 -0.0365604 0.0261267 -0.0126373 -0.0374949 0.040082 0.0399878 -0.0367223 0.0130741 0.0419723 -0.0366452 0.00285615 0.0411943 -0.0367605 -0.0089961 -0.0201095 -0.0374935 0.0368972 -0.0262448 -0.0365009 0.0328458 0.0144716 -0.0366611 0.0394722 0.0228185 -0.037494 0.0353167 0.032967 -0.0374924 -0.0260989 0.0492539 -0.0117 -0.0185161 0.0417494 -0.0117 -0.0320977 0.019798 -0.0117 -0.048675 0.0173468 -0.014696 -0.0496749 0.00466108 -0.0117 -0.0524552 -0.00756916 -0.0117 -0.0519515 -0.049072 -0.0117 -0.0191559 -0.052661 -0.0117 -0.000313448 0.0203253 -0.0221 -0.00841904 0.00963089 -0.0221 -0.0197799 -0.00886719 -0.0220397 -0.0202904 -0.0214536 -0.0315 0.00548138 -0.0219097 -0.0221 -0.00199098 -0.0219097 -0.0315 -0.00199098 -0.020084 -0.0220653 -0.00932629 -0.0150794 -0.0221 -0.0160191 0.00159832 -0.0220653 -0.0220861 0.0158421 -0.0220653 -0.0154718 -0.0275582 -0.0344326 0.0028863 0.00517983 -0.0375 -0.0271651 -0.00478327 -0.0315857 -0.0270082 -0.0138704 -0.0316017 -0.0238506 -0.0205052 -0.0325 -0.0183245 -0.0303765 -0.0285 0.0290046 -0.0245297 -0.0285 0.0340924 -0.0178476 -0.0285 0.0380192 -0.00289157 -0.0365459 0.042059 0.00484021 -0.0285 0.0417202 0.0124239 -0.0285 0.0401204 0.00686529 -0.0360611 0.0414823 0.0195844 -0.0285 0.0371544 0.0260781 -0.0285 0.0329232 0.0302976 -0.0366389 0.0291544 0.0316837 -0.0285 0.0275707 0.0362807 -0.0299327 0.0212902 0.0395038 -0.0285 0.0142635 0.0414521 -0.0285 0.00676183 0.0419888 -0.0285 -0.000970112 -0.0434453 -0.0399355 0.00960859 -0.0424404 -0.0157 -0.0133814 -0.0424285 -0.0399556 -0.0134025 -0.039472 -0.0157 -0.0205478 -0.039472 -0.039 -0.0205478 -0.0300638 -0.0157 -0.0328088 -0.0352848 -0.0399816 -0.0271067 -0.0300503 -0.0399771 -0.0328158 -0.00963156 -0.039 -0.0434452 -0.00194106 -0.0157 -0.0444576 0.00580842 -0.039 -0.0441193 0.0205478 -0.039 -0.039472 0.0271071 -0.0399906 -0.0352844 0.0270992 -0.0147388 -0.0353016 0.037537 -0.0147359 -0.0239088 0.0411126 -0.0157 -0.0170294 -0.0191406 -0.0340725 0.016389 0.00520674 -0.0399998 0.0248976 0.0236325 -0.04 0.00815507 0.0209941 -0.04 0.0135737 0.0171339 -0.0340264 0.0182056 -0.0180157 -0.0226 0.00746233 -0.0154704 -0.0226 0.0118708 -0.00254526 -0.0226 0.0193332 0.00254526 -0.0226 0.0193332 0.0118708 -0.0226 0.0154704 0.0154704 -0.0226 0.0118708 0.0180157 -0.0226 0.00746233 0.0193595 -0.0339215 0.00249693 0.0196585 -0.0226003 -0.000663464 -0.00671769 -0.0151008 0.00671747 0.00222651 -0.0151009 0.00939492 0.0047611 -0.0199999 0.0081657 0.00877688 -0.0151007 0.00363567 -0.00221786 -0.0190967 0.0120689 -0.034135 -0.0595996 0.00773301 -0.0356107 -0.011718 0.0231994 -0.0180601 -0.0285 0.0384719 -0.0180639 -0.0117185 0.0384712 -0.00294582 -0.0117388 0.0423988 0.00489783 -0.0285 0.0422168 0.0198176 -0.0285 0.0375967 0.0263885 -0.0285 0.0333151 0.0320608 -0.0285 0.027899 0.0320608 -0.0122 0.027899 0.0419456 -0.0285 0.00684233 0.0415884 -0.0117021 -0.00876316 0.0392649 -0.0285 -0.016264 0.0356078 -0.0285 -0.023202 0.0307382 -0.0285 -0.0293499 0.0307382 -0.0122 -0.0293499 0.0248274 -0.0117261 -0.0344958 0.0106841 -0.0117166 -0.0411363 0.00294289 -0.0285 -0.042398 -0.00489783 -0.0285 -0.0422168 -0.0198176 -0.0285 -0.0375967 -0.0366414 -0.0285 -0.0215328 -0.0399741 -0.0285 -0.0144333 -0.0424898 -0.011703 0.000978091 -0.0392649 -0.0285 0.016264 0.0189022 -0.04 -0.0194786 0.0128905 -0.04 -0.0228819 0.00740797 -0.04 -0.0246459 -0.0139245 -0.0340144 -0.021286 -0.0304584 -0.04 -0.0118719 -0.0330782 -0.04 -0.00771757 -0.0131426 -0.04 0.0299321 -0.00349854 -0.04 0.028509 0.0190654 -0.04 0.0166844 0.0138402 -0.0340149 0.020987 0.0254966 -0.0530085 -0.00377381 0.0221613 -0.056472 -0.0118261 0.023097 -0.04 -0.00956709 0.0240327 -0.044528 -0.00730805 -0.00996421 -0.04 0.0232006 -0.0223138 -0.04 0.0266271 -0.0260218 -0.04 0.0234065 -0.0179326 -0.04 0.0288469 -0.00823254 -0.04 0.0298171 0.0251614 -0.04 -0.00021353 0.0271285 -0.04 0.000382307 0.0252949 -0.04 0.00706505 0.0226655 -0.04 0.012189 0.00524703 -0.04 -0.0244432 0.00168361 -0.04 -0.0252789 0.00204318 -0.03401 -0.0249589 -0.00520039 -0.0340111 -0.0245822 -0.0349511 -0.04 0.00184931 -0.0340832 -0.039 0.00795496 -0.024944 -0.04 0.00167299 -0.0226327 -0.04 -0.017685 -0.0269052 -0.04 -0.0152626 -0.0209941 -0.04 -0.0135737 -0.0346064 -0.04 -0.00304999 -0.0334394 -0.04 0.00521529 0.00481026 -0.019096 -0.0104589 -0.00572065 -0.0190984 -0.0108517 0.00317672 -0.0150631 0.0109912 0.0095541 -0.018093 0.00171505 0.00343077 -0.0150996 -0.0108811 0.0110487 -0.0150601 0.000520428 0.00363567 -0.0151008 -0.00877688 -0.0100259 -0.0150603 -0.00450462 -0.00052527 -0.022587 0.00762703 0.00768186 -0.0225767 0.00196014 0.00821771 -0.0201 -0.00506843 0.00222688 -0.0201 -0.00939472 0.00421091 -0.0201904 -0.00703343 -0.00805665 -0.0200214 0.00486175 -0.00746233 -0.0226 -0.0180157 0.00205466 -0.0226 -0.00787923 -0.00850891 -0.0226 -0.00058695 0.00746233 -0.0226 -0.0180157 -0.00254526 -0.0226 -0.0193332 0.0180157 -0.0226 -0.00746233 -0.00564458 -0.0226 -0.0136272 0.0136272 -0.0226 -0.00564458 0.00746233 -0.0226 0.0180157 0.00897923 -0.0226 0.011702 -0.00941953 -0.0226 0.0172427 -0.0136272 -0.0226 0.00564458 -0.0193332 -0.0226 0.00254526 0.0154704 -0.0226 -0.0118708 0.0118708 -0.0226 -0.0154704 -0.00254526 -0.033 -0.0193332 0.00254526 -0.0226 -0.0193332 -0.00739239 -0.0339368 -0.018082 -0.0116375 -0.0226 -0.0157029 -0.0154704 -0.0226 -0.0118708 -0.0156908 -0.0339319 -0.0116541 -0.0180157 -0.0226 -0.00746233 -0.0193332 -0.0226 -0.00254526 0.0154548 -0.0339233 -0.0119237 0.0251284 -0.034 -0.00130605 0.022857 -0.034 0.0105213 0.0119235 -0.0339191 0.0154549 0.0067133 -0.034 0.0240818 -0.00173235 -0.034 0.0251026 -0.0126195 -0.0339989 0.0217054 -0.0193595 -0.0339215 -0.00249693 -0.0242545 -0.04 -0.00647192 0.0216431 -0.034 -0.0128342 0.018692 -0.04 -0.0168449 0.0131997 -0.034 -0.0214222 0.0109442 -0.04 -0.0224772 -0.0241898 -0.0339988 -0.00642628 -0.0209941 -0.034 -0.0135737 -0.0163377 -0.04 -0.01893 -0.0444546 -0.0398989 0.00192746 0.0434456 -0.039996 -0.00960499 0.0444576 -0.0157 -0.00194106 0.0441212 -0.0147437 0.00582643 0.0444543 -0.0399822 -0.00192621 0.0395159 -0.0150612 0.0204646 0.039472 -0.039 0.0205478 0.0170035 -0.0399923 0.0411177 0.00963156 -0.039 0.0434452 0.00194106 -0.0157 0.0444576 -0.0133814 -0.0157 0.0424404 -0.0205478 -0.0157 0.039472 -0.0271052 -0.0399465 0.0352862 -0.0270899 -0.0157 0.0353042 -0.0375309 -0.0157 0.0239098 -0.0411126 -0.0157 0.0170294 0.0424398 -0.0150455 0.0133925 -0.016915 -0.0146955 0.0428 -0.0480273 -0.0146972 -0.0208703 -0.0451911 -0.0147007 0.00656406 -0.0312452 -0.0146776 -0.042142 0.0303317 -0.0146935 -0.0430069 0.0167499 -0.0147 0.046561 0.0290652 -0.0117 -0.0439145 -0.00466108 -0.0117 0.0524552 0.0523991 -0.0117 -0.00325318 0.0180639 -0.0117185 -0.0384712 -0.0188107 -0.0117 -0.0437859 -0.0354357 -0.0117 -0.0389562 -0.0206387 -0.0117 -0.0484241 -0.0399738 -0.0117212 -0.0144372 -0.0433484 -0.0117 -0.029617 -0.0248236 -0.0117191 0.034498 0.0484265 -0.0117 0.0200712 0.0198147 -0.0117064 0.0375994 0.0399738 -0.0117212 0.0144372 0.0427762 -0.0117 -0.0188622 0.0518911 -0.0117 0.0089769 0.0429676 -0.0117 0.0180301 0.0188107 -0.0117 0.0437859 0.00756916 -0.0117 0.0519515 0.0354357 -0.0117 0.0389562 -0.0429676 -0.0117 -0.0180301 -0.0469851 -0.0117 0.0168867 -0.051149 -0.0117 0.0118334 -0.0125718 -0.0285 -0.040598 -0.0263885 -0.0285 -0.0333151 -0.0320608 -0.0285 -0.027899 -0.0362807 -0.0299327 -0.0212902 -0.0419888 -0.0285 0.000970112 -0.0419456 -0.0285 -0.00684233 -0.0424887 -0.0285 0.000981661 -0.0415848 -0.0285 0.00877222 -0.0388029 -0.0285 0.0160727 -0.0351889 -0.0285 0.0229291 -0.0356078 -0.0285 0.023202 -0.0307382 -0.0285 0.0293499 -0.0248218 -0.0285 0.0344983 -0.0105577 -0.0285 0.0406514 -0.0106834 -0.0285 0.0411353 -0.00290826 -0.0285 0.0418992 -0.00294289 -0.0285 0.042398 0.0125718 -0.0285 0.040598 0.0366414 -0.0285 0.0215328 0.0399741 -0.0285 0.0144333 0.0410956 -0.0285 -0.00866901 0.0424887 -0.0285 -0.000981661 0.0415848 -0.0285 -0.00877222 0.0386839 -0.0295024 -0.0164543 0.0351889 -0.0285 -0.0229291 0.0303765 -0.0285 -0.0290046 0.0248218 -0.0285 -0.0344983 0.0180601 -0.0285 -0.0384719 0.0106834 -0.0285 -0.0411353 0.0245297 -0.0285 -0.0340924 0.0178476 -0.0285 -0.0380192 0.0105577 -0.0285 -0.0406514 0.00290826 -0.0285 -0.0418992 -0.00484021 -0.0285 -0.0417202 -0.00686529 -0.0360611 -0.0414823 -0.0124239 -0.0285 -0.0401204 -0.0195844 -0.0285 -0.0371544 -0.0302976 -0.0366389 -0.0291544 -0.0260781 -0.0285 -0.0329232 -0.0316837 -0.0285 -0.0275707 -0.0395038 -0.0285 -0.0142635 -0.0414521 -0.0285 -0.00676183 -0.0421546 -0.0374136 0.00209402 -0.0410956 -0.0285 0.00866901 -0.0269059 -0.0375 -0.00606185 0.0267223 -0.0375 -0.00711962 -0.00711962 -0.0375 -0.0267223 -0.0240686 -0.0375 -0.0133023 -0.0180089 -0.0375 -0.0209869 0.0381691 -0.0375 0.0118196 0.0271651 -0.0375 0.00517983 0.0240686 -0.0375 0.0133023 0.0118196 -0.0375 -0.0381691 0.0133023 -0.0375 -0.0240686 0.0209869 -0.0375 -0.0180089 -0.0040246 -0.0315858 0.0272943 -0.00517983 -0.0375 0.0271651 0.00711962 -0.0375 0.0267223 0.0138704 -0.0316017 0.0238506 0.0180089 -0.0375 0.0209869 0.0228451 -0.0315915 0.0154693 -0.0226249 -0.0350011 0.0161329 -0.0146304 -0.0375 0.0233043 -0.0194453 -0.0315819 0.0195219 -0.0250615 -0.0315437 0.0106815 -0.0127328 -0.0315 -0.0181158 -0.0196931 -0.0315 -0.0101235 -0.00767596 -0.0315 0.0207698 0.00285546 -0.0315 0.0219579 0.00478327 -0.0315857 0.0270082 0.0219097 -0.0315 0.00199098 0.0164489 -0.0315 -0.0148235 0.00767596 -0.0315 -0.0207698 -0.00285546 -0.0315 -0.0219579 0.0214536 -0.0315 -0.00548138 0.0150794 -0.0221 0.0160191 0.0196931 -0.0315 0.0101235 0.0127328 -0.0315 0.0181158 -0.00963089 -0.0221 0.0197799 -0.0164489 -0.0315 0.0148235 -0.0212176 -0.0220653 0.00633735 -0.0158421 -0.0220653 0.0154718 -0.00159832 -0.0220653 0.0220861 0.00884865 -0.0220653 0.020299 0.0101201 -0.0190859 0.0164639 0.020084 -0.0220653 0.00932629 0.0194494 -0.0190891 0.00316161 0.0221168 -0.02202 -0.00108073 -0.0175647 -0.0190869 0.00806222 -0.00780512 -0.0190967 0.0176913 0.000573857 -0.0191 0.0189913 -0.0187919 -0.0190991 -0.00350903 0.0151271 -0.0190897 -0.0120332 -0.0123005 -0.0190862 -0.0153135 0.00334458 -0.0190971 -0.0190455 -0.0464631 -0.0117 0.0247882 -0.0359593 -0.0116998 0.0384998 -0.0212737 -0.0117 0.0481306 -0.00984784 -0.0146946 0.0515275 0.00248083 -0.0146841 0.0525692 0.0158795 -0.014643 0.0500034 0.0206387 -0.0117 0.0484241 0.0272309 -0.0146756 0.0450382 0.0433484 -0.0117 0.029617 0.0511437 -0.0146623 -0.01169 -0.018821 -0.04 0.0164551 -0.0249568 -0.0340254 0.00171846 0.0168517 -0.0364068 -0.0387077 0.00289157 -0.0365459 -0.042059 -0.0389302 -0.0373983 0.0161487 -0.0144716 -0.0366611 -0.0394722 0.0262448 -0.0365009 -0.0328458 -0.0228185 -0.037494 -0.0353167 -0.040606 -0.0374901 -0.0109294 -0.0185573 -0.0146907 -0.0492013 -0.0460225 -0.0147 0.0163713 0.0204709 -0.0147 0.0441837 0.0298294 -0.061 -0.0010007 0.0249329 -0.044528 -0.0129742 0.022328 -0.061 -0.0191786 0.0255032 -0.0574861 0.0133735 0.0300447 -0.040006 0.00104896 0.0280664 -0.0400067 0.0082445 0.0280569 -0.0569991 0.00824858 0.0251836 -0.041 0.0138198 0.0211751 -0.0597136 0.0188068 0.0163184 -0.041 0.0228563 0.0107151 -0.061 0.0258686 -0.00235049 -0.041 0.0312806 -0.0135394 -0.0400257 0.0329201 -0.028327 -0.0400651 0.0253489 -0.0321428 -0.041 0.0202693 -0.0379435 -0.061 0.00212171 -0.0271793 -0.0576448 -0.0188839 -0.0327283 -0.0400215 -0.0138553 -0.0357804 -0.0597821 -0.00900642 -0.0238047 -0.0400121 -0.0204565 0.00803544 -0.041 -0.0275795 -0.0107151 -0.061 -0.0258686 -0.00462301 -0.041 -0.0277007 0.0217836 -0.0410603 -0.0203934 -0.018094 -0.061 -0.0228158 0.00174985 -0.0597142 -0.0282707 0.0296054 -0.059674 -0.000101167 0.0328785 -0.0582355 0.0100463 0.0293912 -0.0584467 0.00430883 0.0162 -0.0609995 0.0229511 -0.0218651 -0.058926 -0.0255484 -0.0390535 -0.061 0.014613 0.00342908 -0.061 0.0289081 0.00258675 -0.0590202 0.0335536 -0.00489259 -0.061 0.0317341 -0.00779459 -0.061 0.032785 -0.0134409 -0.061 0.0329144 -0.0282742 -0.061 0.0253836 -0.0335681 -0.061 0.0183665 -0.0362595 -0.061 0.010188 -0.00349852 -0.0595997 0.0285089 0.0104855 -0.0596 0.0253143 -0.00823252 -0.0595997 0.0298171 -0.0131426 -0.0595997 0.0299321 -0.0260218 -0.0595996 0.0234065 -0.0240088 -0.059687 0.0290935 -0.0323359 -0.0595996 0.0133935 -0.0349511 -0.0595997 0.00184935 -0.0375544 -0.0596922 -0.00359213 -0.0304584 -0.0595997 -0.0118719 -0.0269052 -0.0595997 -0.0152626 -0.0290192 -0.0596 -0.0173325 0.00168358 -0.0595996 -0.025279 0.0204655 -0.0596 -0.0220697 0.027142 -0.0595995 0.000397068 0.0226655 -0.0595996 0.012189 0.0190654 -0.0595996 0.0166844 0.0268063 -0.0601169 0.0100899 -0.00677465 -0.05962 -0.0267615 0.0128731 -0.061 -0.025679 -0.00476754 -0.0609996 -0.0276875 -0.0327781 -0.061 -0.0137699 -0.0350887 -0.0596255 0.0141605 -0.00549405 -0.0596 0.0318359 -0.018909 -0.0596974 0.0316813 0.0209233 -0.061 -0.0214141 -0.0131004 -0.031589 0.0240981 0.0272946 -0.0315909 0.00402516 0.0263379 -0.0315899 -0.00821621 -0.0180157 -0.033 -0.00746233 -0.0118708 -0.033 -0.0154704 0.00249678 -0.0339243 -0.0193596 0.0102029 -0.0339218 -0.016813 0.0191239 -0.0339175 -0.00468938 0.0441193 -0.039 0.00580842 0.0424276 -0.0399919 0.0134044 0.0352843 -0.0399916 0.0271071 0.0300502 -0.0399892 0.0328159 0.0239098 -0.039 0.0375309 0.00191492 -0.0399942 0.0444535 -0.00580842 -0.039 0.0441193 -0.0134036 -0.0399759 0.042428 -0.0205478 -0.039 0.039472 -0.0328088 -0.039 0.0300638 -0.0375389 -0.0399359 0.0238883 -0.0411126 -0.039 0.0170294 0.00887482 -0.0584754 -0.0274335 0.0155013 -0.0570155 -0.0250705 0.0155268 -0.0570033 -0.0307477 -0.0396866 -0.0576492 0.0168611 -0.0341725 -0.0570314 0.0165711 -0.0364816 -0.0569973 0.0105001 -0.0257526 -0.061 -0.0190354 0.0034868 -0.057 0.0288632 -0.000676236 -0.059591 0.0344207 -0.00395597 -0.0570182 0.031937 0.0161504 -0.061001 -0.0302906 0.0307537 -0.061 0.0115942 -0.0179963 -0.057 -0.0228529 -0.0115629 -0.0190975 0.0031407 0.0120158 -0.019098 -0.00138635 -0.0226327 -0.0595995 -0.017685 -0.00957359 -0.0595997 -0.0230943 -0.00404853 -0.0595996 -0.0247559 0.00740795 -0.0595996 -0.0246459 0.0128904 -0.0595996 -0.022882 -0.0346065 -0.0595997 -0.00304998 -0.0330782 -0.0595997 -0.00771755 -0.0296045 -0.0595996 0.0186699 0.0189244 -0.0595992 -0.0194457 -0.0179326 -0.0595997 0.0288469 -0.0223138 -0.0595997 0.0266271 0.0252949 -0.0595996 0.00706504 0.00956067 -0.0595995 0.0230997 0.0146424 -0.0595996 0.0203678 -0.00671951 -0.0152019 0.00945582 0.00892127 -0.015101 0.00684554 0.00954826 -0.015053 -0.00497814 -0.00424637 -0.0150496 -0.00929018 -0.00927343 -0.0180606 -0.00246814 -0.00499184 -0.0200429 -0.00804033 -0.0283664 -0.04 0.0203065 -0.0290635 -0.0375027 0.00323819 -0.0319929 -0.0375142 0.0141676 -0.0212626 -0.0375016 0.017506 0.0268044 -0.056472 -0.0084561 0.023469 -0.0530085 -0.0165084 0.0206973 -0.0479915 -0.0153604 0.0491953 -0.0146978 0.018234 -0.016862 -0.0117 0.0448438 -0.0224024 -0.0146971 0.0476784 -0.0415866 -0.011718 0.00876877 -0.0392673 -0.0117074 0.0162609 -0.036637 -0.0117148 -0.0215434 -0.0419458 -0.0117248 -0.00684694 -0.0263863 -0.0117022 -0.0333183 -0.0320608 -0.0122 -0.027899 -0.00489322 -0.0117022 -0.0422186 -0.0125685 -0.0117172 -0.0406001 -0.0198148 -0.0117208 -0.0375994 0.00294289 -0.0122 -0.042398 0.0392672 -0.011721 -0.016261 0.03561 -0.0117024 -0.0232009 0.0431367 -0.0146963 -0.0162331 0.0434452 -0.0157 -0.00963156 0.00963156 -0.0157 0.0434452 0.0170294 -0.0157 0.0411126 0.0239098 -0.0157 0.0375309 0.0216886 -0.0147004 0.0401763 0.0300638 -0.0157 0.0328088 0.0353042 -0.0157 0.0270899 0.0334185 -0.0147 0.0306224 -0.00580842 -0.0157 0.0441193 0.00656406 -0.0147005 0.0451913 -0.0328088 -0.0157 0.0300638 -0.0306224 -0.0147 0.0334185 0.0476864 -0.0146883 -0.0220954 0.0525937 -0.0146944 0.00187023 0.0475488 -0.0146166 0.0221772 0.0403354 -0.0146952 0.0338068 -0.0187733 -0.0146947 0.0488943 -0.0370023 -0.0146895 0.0374334 -0.0477473 -0.0146609 0.0220465 -0.00480821 -0.04 0.0329894 -0.00779459 -0.041 0.032785 -0.0189497 -0.041 0.0316693 -0.0240039 -0.0400565 0.0291125 -0.0351565 -0.0400686 0.0144509 -0.0370609 -0.041 0.00839581 -0.0379638 -0.0400625 0.00189194 -0.0375506 -0.041 -0.00362637 -0.0357915 -0.0400487 -0.00901049 -0.0286941 -0.041 -0.0176709 0.0211349 -0.0400071 0.0188766 0.0106822 -0.04001 0.0258899 0.0293128 -0.041 -0.00240022 -0.0107151 -0.041 -0.0258686 -0.00795561 -0.04 -0.0277375 0.0018281 -0.0400061 -0.0282902 0.0140524 -0.0400095 -0.0256556 0.0197135 -0.0400055 -0.0224703 0.0267925 -0.04 -0.0110978 0.0356004 -0.0106998 -0.0313315 -0.0492087 0.008 -0.0265862 -0.0493349 -0.008 0.0255226 -0.0494161 0.008 0.0265183 0.026869 0.0094947 0.0451823 0.0338382 0.00949366 0.0402177 0.039923 0.00949369 0.0341634 0.0487359 0.00949452 0.0195152 -0.00883079 0.00949798 -0.0517668 -2.41978e-05 0.00949384 -0.0524974 -0.0259191 0.00949419 -0.0457222 -0.0513006 0.00949792 -0.011304 -0.0259204 0.00949374 0.0457215 0.0629269 0.00920335 0.00210651 0.0511116 0.0085857 0.00336087 0.052 0.0017569 -0.0090301 0.0629101 0.00240657 -0.00890325 0.0629036 0.0080851 -0.00480594 0.0629153 0.00510601 0.00778513 0.052 0.000356594 0.00896748 -0.0518951 0.00258903 0.0274929 -0.0515378 0.00289687 0.032497 -0.055536 0.00131779 0.0320978 -0.0542541 0.00190154 -0.0183547 -0.054702 0.00274918 -0.0324355 -0.0298806 0.00900678 -0.0238821 -0.0357468 0.00900707 -0.0130986 -0.0382506 0.0090171 -0.00249728 -0.0357468 0.00900768 0.0130985 -0.0298806 0.00900722 0.023882 -0.0182438 0.00900752 0.0336194 0.0629089 -0.00439647 -0.0107388 0.0172482 0.0224943 0.0334913 0.0320259 0.0224939 0.0204356 0.0290314 0.0224901 -0.0244947 -0.0332068 0.0175279 0.00305821 -0.031208 0.0224885 -0.0113545 0.0617596 -0.0103293 -0.00506875 0.0629366 -0.00973108 0.00582603 0.062844 -0.0114013 -0.000683154 0.0629176 -0.00443364 0.010742 0.0629224 0.00231607 -0.0112656 -0.00313267 0.00185 0.0472314 -0.00208745 0.00689165 0.0456846 -0.00181859 0.00247514 -0.0427337 0.0270467 0.00179382 -0.0331471 0.0329528 0.00185 -0.0361027 0.0314649 -0.0106995 -0.035831 0.0346866 -0.010697 -0.0348639 0.0358971 0.00185 -0.0317847 -0.0211689 -0.0117 0.0464426 -0.0215968 -0.0065 0.0455281 0.0174935 -0.0117 -0.0479625 0.0177148 -0.0065 -0.0481024 -0.0205391 -0.0103388 -0.0461033 -0.0466928 -0.0113557 -0.0200107 -0.0451025 -0.00110276 -0.0168179 -0.045101 -0.00130861 0.0206245 -0.0454377 -0.00110276 0.0168179 -0.0470322 -0.0117 0.0181213 0.0487316 0.0094971 -0.0195245 0.0136341 -0.0107776 -0.0507565 0.012656 0.009 -0.0509517 0.0268692 0.00949519 -0.0451823 0.0344603 -0.0117017 -0.0396033 0.048878 -0.0117028 -0.0192101 -0.051399 0.00949842 0.010806 -0.0507729 -0.00798734 0.0140316 -0.0401638 -0.0117128 0.0337359 -0.0458067 -0.011707 0.0256333 -0.00944895 0.00949432 0.051663 -0.00986372 -0.0117 0.0515627 -0.0177916 0.00949341 0.0494501 -0.0332689 0.00949334 0.0407091 -0.0266327 -0.0107686 0.0452513 -0.0526742 0.00949365 -1.65458e-08 -0.0525 -0.0117 -5.55112e-17 -0.0340846 -0.011702 -0.0399253 -0.0176655 0.00904246 -0.0494988 -0.0231793 0.017 -0.0301118 -0.0331977 0.017 -0.018491 -0.0379723 0.00950327 0.00389043 -0.0362471 0.017 0.0114082 -0.0331977 0.017 0.018491 -0.0287811 0.017 0.0248123 -0.0231793 0.017 0.0301118 0.000118311 0.0168624 0.0381619 0.000429605 0.0175279 -0.0333446 -0.0102254 0.0189 -0.0336001 -0.0302676 0.0189 -0.017475 -0.0347585 0.0211 -0.00365327 -0.0347585 0.0189 0.00365327 -0.0302676 0.0211 0.017475 -0.0102254 0.0211 0.0336001 -0.0103807 0.0224895 -0.0313906 -0.022251 0.0224892 -0.0244544 0.00130772 0.0095 -0.0458004 0.0149038 0.00950002 -0.0432489 0.0450749 0.0095 -0.0069 0.0456766 0.0111819 -0.00400965 -0.00396536 0.0117291 0.0453515 -0.0369701 0.0094999 0.0273183 -0.0139669 0.00949996 -0.0435958 9.99201e-16 0.009 -0.0426 -0.00782773 0.009 -0.0418747 -0.0339955 0.009 -0.0256722 -0.0424183 0.009 0.00393063 -0.0286994 0.009 0.0314818 -0.0296633 0.00185 0.0304839 9.99201e-16 0.009 0.0426 -0.0153889 0.009 -0.0397233 -0.038134 0.009 -0.0189885 -0.0409738 0.009 -0.011658 -0.0424167 0.0018346 -0.00484266 -0.0407702 -0.0104 -0.0123311 -0.0423818 -0.0106975 -0.00519649 -0.038134 0.009 0.0189885 -0.0409738 0.009 0.011658 -0.0405666 -0.0104 0.0130042 -0.022426 0.009 0.0362193 -0.0153889 0.009 0.0397233 -0.00944936 0.0119466 0.0447097 -0.0086384 0.0119487 -0.0447567 -0.0199489 0.0119247 -0.0411664 -0.0306661 0.0119498 -0.0337191 -0.0384941 0.0119316 -0.0247156 -0.0448017 0.0119483 -0.00925181 -0.0451385 0.011951 0.00739114 -0.0275137 0.0119451 0.0365213 -0.0371723 0.0199753 0.0173856 -0.0333791 0.0199767 0.0238519 0.0121577 0.0224825 -0.0357414 0.019394 0.0200004 -0.0322508 0.030591 0.0200004 -0.021921 0.0356875 0.0200515 -0.0114855 0.0373855 0.022483 -0.00346519 0.025978 0.0199998 0.0272323 0.0098988 0.0199963 0.036557 -0.0391897 0.0119406 0.0237013 -0.0213782 0.0120398 0.03711 0.0436358 0.011935 0.0132731 -0.0410632 0.0123082 0.00283529 0.0156938 0.0119339 -0.0429148 0.03732 0.0120439 -0.0203977 0.0452873 0.0119413 0.000575685 0.018421 0.0119493 0.0417159 -0.0188036 0.019982 0.0365603 -0.0236513 0.0199764 -0.0337527 -0.0345154 0.0199742 -0.0225571 -0.0114823 0.0199791 -0.0394704 -7.53593e-06 0.013303 -0.0413014 0.00468798 0.019967 -0.0411007 0.0264362 0.0199775 -0.0313999 0.0345197 0.0199769 -0.0225426 0.0404119 0.0199753 -0.00817354 -0.00750205 0.0206322 0.0369355 -0.0390721 0.0199751 -0.0125698 -0.0407491 0.0199742 -0.00498581 -0.0409633 0.0199751 0.00253089 -0.0397579 0.0199757 0.010148 -0.0282476 0.0199664 0.0297366 0.0193188 0.0199767 -0.0362923 0.00824021 0.020002 -0.0365708 0.0196509 0.0199594 0.0362009 0.0371968 0.0199742 0.0173255 0.0345994 0.0199998 0.0148122 0.039737 0.0199747 0.0102498 0.0377707 0.0200255 0.00063525 -0.019394 0.0200004 0.0322508 -0.030591 0.0200005 0.021921 -0.0369778 0.020036 0.00730088 -0.0367627 0.0200307 -0.00835553 -0.0309187 0.0199998 -0.0214599 -0.0199791 0.0199998 -0.0318942 0.0307086 0.0199774 0.0274538 0.0409624 0.0199749 0.00254874 -0.015873 0.0133372 0.0380054 -0.0228457 0.0133634 0.0341008 -0.038103 0.0130385 0.0155115 -0.0372739 0.0134133 -0.0172855 0.0160299 0.0129428 -0.0380744 0.0253619 0.012374 -0.0323376 0.0312882 0.0130098 -0.0267327 0.0369661 0.0134109 -0.0180167 0.0408624 0.012394 0.00640032 0.0355629 0.0135401 0.0209121 0.0280664 0.0122439 0.0300969 0.0166743 0.012417 0.0377568 -0.0232144 0.0130573 -0.0339074 -0.0406448 0.0133636 -0.00630689 -0.0362377 0.0120388 0.0225372 -0.0316017 0.0134417 0.0265528 -0.00819398 0.0122069 0.0402747 0.038138 0.0120421 0.0187319 0.0406519 0.0129161 -0.00632425 -0.0119784 0.0123311 -0.0394032 -0.0312065 0.0122917 -0.0269579 -0.0399384 0.0120542 -0.0147195 0.00280449 0.00951797 0.0458537 0.00214961 0.0119328 -0.0456666 0.0293615 0.0119487 0.034991 0.0389788 0.0119535 0.0238118 0.0424172 0.0119502 -0.0172039 0.0317912 0.0119584 -0.0330825 -0.0599946 -0.00538503 -0.0321881 -0.059 0.005 -0.0325 -0.0442532 0.00502376 -0.0324827 -0.059 -0.005 0.0325 -0.0599981 0.00538511 0.0321877 -0.0450025 0.00500123 0.0324997 0.0424183 0.009 0.00393063 0.0424183 0.009 -0.00393063 0.0263162 -0.0106999 -0.0335852 0.0286994 0.009 -0.0314818 0.0141393 -0.0106968 0.0402519 0.0208956 -0.0106977 0.0371873 0.0409738 0.009 0.011658 0.0424167 0.0018346 0.00484266 0.0409738 0.009 -0.011658 0.022426 0.009 -0.0362193 0.0153889 0.009 -0.0397233 0.00782773 0.009 -0.0418747 -0.0335361 -0.0107 0.039219 -0.0135525 -0.0107 0.0500614 0.00459276 -0.0108069 -0.0522901 -0.0449818 -0.0107 0.0258157 -0.0451689 -0.0107165 0.016832 0.045047 -0.0108473 0.0269627 -0.0151435 -0.0107714 -0.0493005 0.0380277 -0.0106948 0.0192523 0.00027783 -0.0106973 -0.0493593 -0.0265836 -0.0108136 -0.045283 -0.00060777 -0.0109118 -0.0524846 0.046481 -0.0117 -0.0173247 0.0435095 -0.0107304 0.0194995 0.0169444 -0.0117 0.0446288 0.0277537 -0.0107607 0.044568 0.0190867 -0.0117 0.0471112 0.0138219 -0.0107806 0.0507183 -0.0192071 -0.0107291 0.0424096 -0.0194776 -0.01174 0.0488395 -0.0442571 -0.0107413 0.0205073 -0.0495442 -0.0117 0.0172655 -0.0517182 -0.0117 0.00902628 -0.0496112 -0.0116965 -0.0171623 -0.018682 -0.0117235 -0.0492121 -0.0401462 -0.0108057 -0.0336964 -0.016741 -0.0107579 -0.0450627 -0.0190318 -0.0107317 -0.0434212 -0.00983752 -0.0117 -0.0515701 0.0205957 -0.010721 -0.0430812 0.0402434 -0.0117006 -0.0337127 0.0406978 0.00949955 -0.021192 -0.0394544 0.00949996 -0.0232121 -0.0333357 0.00950157 -0.0406589 -0.0451357 0.00949996 -0.00762251 -0.0448863 0.00949997 0.00896795 0.045258 0.00949591 0.00736403 0.0405619 0.0095 0.0208348 -0.0285889 0.00949996 -0.0357524 -0.0399895 0.00948034 0.0341821 -0.021784 0.00949996 0.0402545 -0.00935782 0.0095 0.0446295 8.71186e-06 0.00949166 0.0524984 0.0525383 0.00949574 -0.00694458 0.0338395 0.00949276 -0.0402166 0.0287674 0.00950018 -0.0356525 0.0336882 0.0094998 0.0309565 0.0189304 0.00949997 0.0418529 0.00910116 0.0119294 0.044582 0.00328457 0.0224896 -0.032899 -0.0178829 0.0224835 -0.0331249 -0.029502 0.0224918 0.0160424 -0.0290314 0.0224901 0.0244947 -0.0163819 0.0224898 0.0287188 -0.0110361 0.022491 0.036457 0.0158968 0.0211 0.0295549 0.0297639 0.0211 0.0139257 0.0327593 0.0211353 -8.43882e-05 0.0266467 0.0224899 -0.0195728 0.0077519 0.0211 -0.0322316 -0.0279628 0.0211024 0.0185406 -0.0342113 0.0211 0.0079446 -0.0327593 0.0211353 8.43882e-05 -0.0297639 0.0211 -0.0139257 -0.0323472 0.0211 -0.0136815 -0.0239859 0.0211 -0.0256555 -0.0158968 0.0211 -0.0295549 -0.0114771 0.0211 -0.0331934 0.0279628 0.0211024 -0.0185406 0.0230078 0.0211 -0.0265362 0.0302676 0.0211 -0.017475 0.0347585 0.0211 0.00365327 0.0239859 0.0211 0.0256555 -0.0077519 0.0211 0.0322316 -0.0230078 0.0211 0.0265362 0 0.02 0.03495 0.0114771 0.0211 0.0331934 0.0302676 0.0189 0.017475 0.0323472 0.0211 0.0136815 0.0342113 0.0211 -0.0079446 0.0102254 0.0211 -0.0336001 0 0.02 -0.03495 0.0239859 0.0189 -0.0256555 0.0114771 0.0189 -0.0331934 -0.0077519 0.0189 -0.0322316 -0.0224417 0.0189 -0.0240039 -0.0230078 0.0189 -0.0265362 -0.0342113 0.0189 -0.0079446 -0.0330207 0.0189 -0.00598582 -0.0323472 0.0189 0.0136815 -0.0265435 0.0189 0.0205339 -0.0239859 0.0189 0.0256555 -0.0102034 0.0188647 0.0311298 -0.0114771 0.0189 0.0331934 0.0102254 0.0189 0.0336001 0.0230078 0.0189 0.0265362 0.0342113 0.0189 0.0079446 0.0347585 0.0189 -0.00365327 0.0323472 0.0189 -0.0136815 0.00424564 0.0188829 0.0324566 0.0201915 0.0189 0.0262921 0.0302648 0.0189 0.0128008 0.0326006 0.0189 -0.00796244 0.0158968 0.0189 -0.0295549 -0.0250673 0.0175279 0.0219926 -0.0286624 0.0175279 -0.0170443 -0.0163732 0.0175266 -0.0287164 -0.0116578 0.0175 -0.0337158 0.0326055 0.0172215 0.0145169 0.0197682 0.0174999 0.030491 0.035668 0.0175 -0.000668436 0.0323125 0.0175 -0.0151181 -0.0203726 0.017 -0.0296679 -0.0243633 0.0175 -0.0260592 -0.0326055 0.0172215 -0.0145169 -0.035668 0.0175 0.000668436 -0.0323125 0.0175 0.0151181 -0.0202953 0.0174834 0.0290761 -0.00182693 0.0172929 0.035884 0.016623 0.017 0.0341713 0.0231417 0.0170011 0.0301132 0.0362471 0.017 0.0114082 0.0358482 0.017 -0.00649836 0.0331977 0.017 -0.018491 0.019466 0.0171821 -0.0305731 -0.0219204 0.017 0.0285434 -0.00938218 0.017 0.0368236 -0.016623 0.017 0.0341713 -0.0358482 0.017 0.00649836 -0.0378039 0.017 0.00385566 -0.0378039 0.017 -0.00385566 -0.0362471 0.017 -0.0114082 -0.0287811 0.017 -0.0248123 0 0.0172176 -0.0357509 -0.016623 0.017 -0.0341713 -0.00909932 0.0169907 -0.0369031 0.00831927 0.00901059 0.0371615 0.000878904 0.0170046 -0.0380721 -4.33427e-05 0.00901383 -0.0380022 0.00926178 0.0170004 0.0368335 0.0331977 0.017 0.018491 0.0287811 0.017 0.0248123 0.0298806 0.00900678 0.0238821 0.0378039 0.017 0.00385566 0.0362471 0.017 -0.0114082 0.0231793 0.017 -0.0301118 0.0287811 0.017 -0.0248123 0.00938218 0.017 -0.0368236 0.016623 0.017 -0.0341713 0.038134 0.009 0.0189885 0.0339955 0.009 0.0256722 0.0286994 0.009 0.0314818 0.0182438 0.00900725 0.0336194 0.022426 0.009 0.0362193 0.0153889 0.009 0.0397233 0.00782773 0.009 0.0418747 -0.00418311 0.00901848 0.0378783 -0.00782773 0.009 0.0418747 -0.0339955 0.009 0.0256722 -0.0424183 0.009 -0.00393063 -0.0286994 0.009 -0.0314818 -0.022426 0.009 -0.0362193 -0.0182438 0.00900725 -0.0336194 -0.00827939 0.00901031 -0.0371715 0.0221912 0.00900787 -0.0309483 0.0339955 0.009 -0.0256722 0.038134 0.009 -0.0189885 -0.000415456 -0.011725 0.0525317 0.00450573 -0.0117 0.0523063 0.0488638 -0.0117043 0.0192581 0.0447363 0.00949405 0.0274748 0.040233 -0.0117006 0.0337222 0.0344719 -0.0117019 0.0395925 0.0204929 -0.0117 0.0483352 0.0190175 0.00949331 0.0490017 0.00992911 0.0094943 0.0516275 -0.059983 0.0079735 0.0185253 -0.0599916 -0.0079747 0.018525 -0.045 0.008 0.0295 -0.059 0.008 0.0295 -0.0464937 0.00820544 0.0254216 -0.0599896 -0.00796217 0.0295996 -0.0472464 -0.008 0.024888 -0.0599907 -0.00797329 -0.0185185 -0.0599833 0.00797491 -0.0185218 -0.0474551 0.00800661 -0.0243741 -0.052634 0.0079986 -0.0174373 -0.0450036 0.00799976 -0.0295011 -0.0475226 -0.008 -0.0273349 -0.0509646 -0.008 -0.0143447 -0.0464421 -0.00799896 -0.0247836 -0.0493948 -0.008 -0.025746 -0.044059 -0.00164577 -0.0201773 -0.0179211 -0.00158431 -0.0470453 -0.0181276 -0.00107942 -0.0435277 0.0461482 -0.0111479 -0.0204932 0.0444866 -0.00102903 -0.0170587 0.0441958 -0.00102903 0.0172266 0.0453925 -0.0117 0.0167525 0.0464464 -0.0112336 0.0203447 0.0181276 -0.00107942 0.0435277 0.020416 -0.0107076 0.0442164 0.0179211 -0.00158431 0.0470453 0.0203892 -0.0117023 -0.0483845 -0.0162116 -0.0107584 0.0469172 -0.0157908 -0.0065 0.0450133 0.0166774 -0.0107134 -0.0434763 -0.045354 -0.0107595 -0.0167244 -0.0458072 -0.0107929 -0.0255151 -0.0500345 -0.0107 -0.0137358 -0.051499 -0.0108274 0.00341445 -0.0340757 -0.011701 0.0399332 0.00341445 -0.0108464 0.051499 0.039219 -0.0107 0.0335361 0.0514456 -0.0107 -0.00401845 0.0499395 -0.0107 0.0139755 0.0435185 -0.0107173 -0.0189128 0.0277458 -0.0107974 -0.0445716 0.0384203 -0.0107 -0.0344482 -0.043574 -0.0117 -0.0194873 0.0450473 -0.0108234 -0.0269593 0.00284177 0.00185 0.0479036 -0.000460798 0.00185 0.0490843 -0.00337447 -0.0106998 0.0461926 0.0267145 0.00181305 0.0333102 0.0356751 0.00185 0.0316001 0.034181 0.00185 0.035278 0.0356374 -0.0106995 0.0312047 0.030277 -0.0106998 0.0350492 -0.035961 0.00185 0.0319977 -0.0334397 0.00184995 0.0264581 -0.0338582 0.00185 0.0354643 -0.0455 0.00212323 4.11645e-12 -0.0472643 0.00185 -0.00313419 -0.0479036 0.00185 0.00284177 -0.0491149 0.00185 -0.000775687 -0.0461926 -0.0106998 -0.00337447 -0.0270099 0.00177564 -0.03308 -0.0358254 0.00185 -0.0316348 -0.0346867 0.00185 -0.0348632 -0.031465 0.00185 -0.0358307 -0.0320982 0.00215423 -0.0323781 -0.0361284 -0.0106995 -0.0325301 -0.0333649 0.00185886 -0.0266719 0.00489886 0.00176704 -0.0423762 0.000460798 0.00185 -0.0490843 0.00313267 0.00185 -0.0472314 -0.00284177 0.00185 -0.0479036 -0.00463423 0.00180365 -0.0423773 0.0424684 0.0018444 -0.00459664 0.0479036 0.00185 -0.00284177 0.0455 0.00212323 -4.11645e-12 0.0491149 0.00185 0.000775687 0.0472643 0.00185 0.00313419 0.03383 0.00185429 0.0259582 0.026294 -0.0106985 0.0336474 0.0312047 0.00185 0.0356371 -0.00489886 0.00176704 0.0423762 -0.0302784 0.00185 0.0350495 -0.0265987 -0.0106991 0.033519 -0.026139 0.00172722 0.0336765 -0.0424684 0.0018444 0.00459664 -0.0334129 -0.0106985 -0.0267171 -0.00313434 -0.0106995 -0.0472645 0.0332532 0.00184993 -0.0267388 0.00463423 0.00180365 0.0423773 -0.0323174 0.0024613 0.0325658 0.0321734 0.00213613 -0.0321734 0.0320293 0.00244688 0.0325658 0.00208745 0.00689165 -0.0456846 0.00181859 0.00247514 0.0427337 0.0629159 0.00241025 0.0112578 0.0629267 0.0116705 0.00258757 0.045777 0.0114096 0.00344202 -0.00328457 0.0224896 0.032899 0.0103807 0.0224895 0.0313906 0.022251 0.0224892 0.0244544 0.0302737 0.022489 0.0132898 0.0322966 0.0225 -0.00686485 0.0163819 0.0224898 -0.0287188 0.0166825 0.0175266 -0.0285378 0.0268476 0.0175266 -0.0192852 0.0332068 0.0175279 -0.00305821 0.0286624 0.0175279 0.0170443 0.0163732 0.0175266 0.0287164 -0.000661071 0.0224946 -0.0373702 -0.00825996 0.0200617 -0.0366336 -0.0296985 0.0224922 -0.023172 -0.0370976 0.022494 -0.00109469 -0.0357102 0.0224824 0.0115114 0.0628788 0.00848721 -0.00832256 0.0629577 0.0113893 -0.00330699 0.0627246 0.00907179 0.00769393 0.0358512 0.00900688 0.0128487 0.0378449 0.0169453 -0.00354681 0.0386589 0.00900716 -5.89976e-09 0.0358512 0.00900752 -0.0128488 0.0298806 0.00900722 -0.023882 0.0110711 0.0090052 -0.036608 -0.054995 -0.00133795 0.0186153 -0.052634 -0.0079986 0.0174373 -0.0525903 0.0079992 0.0173805 -0.0509573 0.0079995 0.0142764 -0.050941 0.00799936 -0.0142211 -0.0519379 -0.0020017 -0.0167453 -0.0525903 -0.0079992 -0.0173805 -0.0516612 -0.0115375 -0.00943745 -0.0437311 -0.00805027 0.0294296 -0.0397111 -0.00546827 0.034351 -0.0400104 0.00820875 -0.0341768 -0.0441289 -0.00500504 -0.0324964 -0.0439515 -0.00498354 0.0325186 -0.0549746 -0.00204973 -0.0274966 -0.051087 -0.00171678 -0.0281527 -0.0500928 0.00127638 -0.0324816 -0.0525198 0.00258968 -0.0274662 -0.0514089 0.00150293 -0.0156874 -0.0549675 -0.00109134 -0.0183959 -0.0503777 -0.00204917 0.0324433 -0.0555718 -0.00185698 0.0324486 -0.0524867 -0.00259018 0.0274651 -0.0524548 0.00236479 0.0174986 -0.0514086 -0.00150508 0.0156873 0.052 -0.0071325 0.00531714 0.052 -0.00606396 -0.00636396 0.0629153 -0.00450601 -0.00778513 0.052 -0.00318841 -0.00826053 0.052 0.00565507 0.00741543 0.052 -0.00314415 0.00831492 0.052 -0.0087301 -0.0014569 0.052 0.00920026 -0.00210967 0.051037 0.00645273 -0.006483 0.051 -0.0041076 0.00637481 0.051 -0.00575688 -0.00426052 0.0516244 0.00433181 0.0112753 0.0518488 -0.00602887 0.010108 0.0540741 -0.0107182 0.00345681 0.0516996 -0.0117014 -0.00748306 0.0515711 -0.00405812 -0.0107804 0.0514642 0.00411505 -0.0113823 -0.0555812 -0.00224498 -0.0324901 0.0629101 -0.00180657 0.00890325 0.0629036 -0.00748511 0.00480593 0.0629269 -0.00860335 -0.00210652 -0.0440121 -0.00791938 -0.0296442 -0.0599943 0.00796207 -0.0295993 -0.059 -0.008 -0.0295 0.0447405 0.009 -0.0274688 0.039908 0.00949275 -0.0341784 0.0191995 0.00949388 -0.0489241 0.00897164 0.00949384 -0.0517302 -0.047371 -0.008 0.0273462 -0.0470827 0.008 -0.0270809 0.00688274 0.0215017 0.0371165 0.00819051 0.0123833 0.0402576 0.00816956 0.0199824 0.0401623 -0.00817063 0.0199631 0.0401626 0.0022304 0.011804 0.0424938 0.008592 0.0215002 0.0425289 0.00173872 0.017504 0.0332006 -0.000249323 0.018888 0.0424853 -0.00524969 0.0141782 0.0424999 -0.00866294 0.0213155 0.0426163 0.0380251 -0.0106952 -0.0192583 0.0405666 -0.0104 -0.0130042 0.0336529 -0.0106961 -0.0262816 0.0472644 -0.0106997 -0.00313446 0.0424654 -0.0106982 -0.00478106 0.04936 -0.0106973 0.000276921 0.0461947 -0.0106996 0.00337384 0.0051325 -0.010698 -0.0425193 0.0207841 -0.0106976 -0.0372424 0.0141393 -0.0106977 -0.040252 0.0423817 -0.0106981 0.0051967 0.0407702 -0.0104 0.0123311 0.0334129 -0.0106986 0.026717 0.00337447 -0.0106998 -0.0461926 0.0347059 -0.0106973 0.0350988 -0.00469459 -0.0106992 -0.0426359 -0.0141393 -0.0106968 -0.0402519 -0.0264431 -0.0106996 -0.0335311 -0.0208956 -0.0106978 -0.0371873 0.00469459 -0.0106992 0.0426359 0.00313434 -0.0106995 0.0472645 -0.0322255 -0.0106988 -0.0359613 -0.00027783 -0.0106973 0.0493593 -0.0380277 -0.0106947 -0.0192523 -0.0194967 -0.0106963 0.0378789 -0.0051325 -0.0106981 0.0425193 -0.0141393 -0.0106976 0.0402519 -0.0312047 -0.0106995 0.0356374 -0.0493593 -0.0106973 -0.00027783 -0.0350988 -0.0106973 0.0347059 -0.0472645 -0.0106995 0.00313434 -0.0424654 -0.0106989 0.00478098 -0.0350492 -0.0106998 0.030277 -0.0380251 -0.0106952 0.0192583 -0.0336529 -0.0106961 0.0262816 0.0197882 -0.0065 -0.0424378 + + + + + + + + + + -0.765447 -0.596526 0.241345 -0.592535 -0.790404 0.155446 -0.982146 0.160548 -0.0980513 -0.882181 -0.469334 -0.0385164 -0.595375 -0.799615 0.0783824 -0.644913 -0.750763 -0.142974 -0.474224 -0.858211 -0.19643 -0.722322 -0.448842 -0.52611 -0.552932 0.573493 -0.604459 -0.0604798 0.444356 -0.893806 0.0349667 -0.597806 -0.800878 0.130547 -0.797624 -0.588857 0.182881 -0.732383 -0.655873 0.191327 -0.866047 -0.461905 0.451847 -0.70434 -0.547484 0.604639 0.572172 -0.554105 0.526646 -0.760283 -0.380281 -0.56732 -0.823396 0.0129491 -0.0618398 -0.837179 -0.543422 -0.418282 -0.831872 -0.364731 -0.595423 0.298207 0.746019 0.595423 -0.298207 -0.746019 0.153754 0.530434 -0.833666 -0.934961 0.21108 -0.28512 -0.488681 -0.575281 -0.655929 0.317587 0.0234451 -0.947939 -0.647571 -0.668125 -0.366415 -0.504183 0.353555 -0.787907 0.281374 -0.595424 -0.752529 -0.597565 -0.79618 -0.0949375 0.236039 -0.338816 -0.910763 -0.810912 0.338816 -0.477102 0.355412 0.79618 -0.489673 -0.987956 -0.154663 -0.00476541 -0.690834 0.530671 -0.491057 -0.104439 0.540406 -0.834898 -0.396284 -0.907144 -0.141593 0.306749 0.946629 -0.0989902 0.15449 -0.570432 -0.806685 -0.799223 -0.592066 -0.103442 -0.725769 -0.575284 -0.377237 -0.442178 -0.56859 -0.693675 -0.177942 -0.565444 -0.805363 0.10807 -0.565942 -0.817332 0.381081 -0.566244 -0.730852 0.607704 -0.566925 -0.556141 0.761796 -0.56591 -0.315299 -0.487395 0.739046 -0.465035 -0.875027 0.472516 0.105147 0.74328 -0.66135 -0.100752 -0.843207 -0.422569 0.33232 -0.341093 0.773704 -0.533888 0.665048 -0.699294 -0.262105 -0.459308 0.236729 -0.856151 0.434142 -0.80753 -0.399269 -0.915121 -0.369524 0.161262 0.734176 -0.133162 -0.665772 -0.845669 0.155927 -0.510422 -0.0732904 0.845071 -0.529607 0.266698 0.934025 -0.237634 0.40421 0.816593 -0.412057 -0.0358498 0.958349 -0.283342 -0.0355933 0.963691 -0.264638 -0.23783 0.958759 -0.15562 -0.282503 0.943145 -0.17513 -0.355907 0.932457 -0.0620881 -0.209719 0.977753 0.00425881 -0.12406 0.992125 0.0172182 -0.519393 0.754035 -0.402073 0.0402573 -0.656283 -0.75344 0.869021 0.1193 -0.480177 0.820431 -0.183026 -0.54166 0.675749 0.0891688 -0.731719 0.680146 0.0663754 -0.730066 0.455491 -0.0762397 -0.88697 0.455578 -0.0767486 -0.886881 0.240407 0.124584 -0.962644 0.138029 -0.293431 -0.945963 -0.0407755 0.134754 -0.99004 -0.202836 -0.145256 -0.968379 -0.259944 0.0693941 -0.963127 -0.4833 -0.110655 -0.868433 -0.533559 0.141269 -0.833881 -0.667246 -0.160982 -0.727233 -0.756027 0.134616 -0.640547 -0.850237 -0.147429 -0.505334 -0.876847 -0.0312372 -0.479754 -0.936545 -0.143526 -0.319819 -0.946362 0.268153 -0.180255 -0.970924 -0.236878 -0.0345706 -0.983141 0.135862 0.122374 -0.951067 -0.136471 0.277212 -0.936343 0.0924857 0.338686 0.65404 0.634004 -0.412638 0.382746 0.736495 -0.557746 0.314547 0.787939 -0.529351 0.215975 0.633785 -0.742746 -0.111537 0.742364 -0.660647 -0.136218 0.807876 -0.573394 -0.463858 0.583735 -0.6664 -0.600369 0.659497 -0.452351 -0.528273 0.798147 -0.289636 -0.725959 0.664426 -0.177542 -0.678872 0.732315 0.0533685 -0.649571 0.757246 0.0680974 -0.996419 0.0174229 0.0827348 -0.998143 0 0.0609225 -0.970396 0 -0.241521 -0.964652 -0.0177539 -0.262927 -0.800694 0.0174229 -0.59882 -0.753455 -0.0417352 -0.656174 -0.56634 0.0422074 -0.82309 -0.361738 -0.0659576 -0.929944 -0.168577 0.0662236 -0.983461 0.111861 -0.0662711 -0.991512 0.275859 0.0437411 -0.960202 0.569761 -0.0320207 -0.821186 0.560939 -0.0207846 -0.827596 0.843837 0.017423 -0.536317 0.880712 -0.0417351 -0.47181 -0.932268 -0.117522 0.342148 -0.887766 0.411703 -0.205843 0.884407 -0.0289081 -0.46582 0.863329 0.0503328 -0.502125 0.619033 -0.0229516 -0.78503 0.597714 0.0164277 -0.801541 0.356204 0.00751699 -0.934378 0.331865 0.0442349 -0.942289 -0.035959 -0.0288501 -0.998937 -0.0324479 -0.0354571 -0.998844 -0.327202 0.0837646 -0.941234 -0.463581 -0.102059 -0.880157 -0.644393 0.0830633 -0.76017 -0.783716 -0.0621962 -0.617997 -0.824096 0.0186669 -0.566143 -0.931023 0.00969225 -0.364832 -0.937986 0.0366346 -0.344732 -0.997438 -0.0037183 -0.0714343 0.884507 -0.0166301 -0.466231 0.857067 0.0314895 -0.514242 0.78351 -0.0309191 -0.620609 0.706235 0.0250203 -0.707535 0.65627 -0.0231707 -0.75417 0.552302 0.0114872 -0.833565 0.506554 -0.0198594 -0.86198 0.392042 0.016155 -0.919805 0.339546 -0.0189759 -0.940398 0.197237 0.0164461 -0.980218 0.160966 -0.01926 -0.986772 -0.0230935 -0.0198952 -0.999535 -0.0597577 0.0153985 -0.998094 -0.206343 -0.0244882 -0.978173 -0.254519 0.0129443 -0.966981 -0.382586 -0.0226325 -0.923643 -0.443664 0.0235154 -0.895885 -0.545758 -0.0251113 -0.837567 -0.637458 0.0260927 -0.770043 -0.690401 -0.0231115 -0.723058 -0.80441 0.0214759 -0.593687 -0.90943 0.00661582 -0.415805 -0.967685 -0.0206066 -0.251321 -0.981296 0.0286106 -0.190368 -0.997136 -0.0304959 -0.0692125 -0.997342 0.0326235 0.065153 -0.993203 -0.0164279 0.115228 -0.954112 -0.0232199 0.298549 -0.953717 0 0.300706 -0.95397 -0.000280468 0.299902 -0.991445 -0.000119764 0.130526 -0.991477 -0.000197303 0.130285 -0.999048 -0.000100528 -0.0436189 -0.999062 0 -0.043305 -0.976296 0 -0.21644 -0.976107 -0.000290255 -0.217291 -0.92388 -0.000121105 -0.382683 -0.924025 0 -0.382332 -0.843585 0 -0.536995 -0.842909 -0.000402742 -0.538056 -0.736919 -0.000291638 -0.675981 -0.737085 -0.000213639 -0.6758 -0.609176 -0.000109097 -0.793035 -0.609015 -0.000171334 -0.793159 -0.461485 -0.000200242 -0.887148 -0.460933 -0.000402054 -0.887435 -0.300029 -0.000434156 -0.95393 -0.301065 -9.95021e-05 -0.953604 -0.129268 -0.000422236 -0.99161 -0.129608 -0.000308103 -0.991565 0.0436189 -0.000123787 -0.999048 0.0432303 0 -0.999065 0.21644 0 -0.976296 0.217344 -0.000308371 -0.976095 0.382683 -0.000123824 -0.92388 0.382324 0 -0.924028 0.536997 0 -0.843584 0.538067 -0.000406197 -0.842902 0.675978 -0.000290971 -0.736922 0.675304 0 -0.73754 0.793023 0 -0.609192 0.793901 -0.000461739 -0.608046 0.887286 -0.000313401 -0.46122 0.886832 0 -0.462093 0.631505 0.0254081 -0.774956 -0.398224 -0.0246966 -0.916956 -0.119341 -0.104298 -0.98736 0.109724 0.160408 -0.980933 0.296202 -0.105467 -0.949284 0.604429 0.0697028 -0.793604 -0.954575 -0.0741611 0.288593 -0.97594 0.0338513 0.215397 -0.98128 -0.0397127 -0.188448 -0.982165 -0.0561765 -0.179435 -0.89766 0.0563492 -0.437072 -0.800708 -0.054878 -0.596536 0.892995 0.0249013 -0.449376 0.866025 -0.00114412 -0.5 0.681386 -0.00248167 -0.731921 0.663798 -0.0175546 -0.747706 0.313743 0.0143207 -0.9494 0.290948 -0.000986262 -0.956738 -0.0357188 -0.00248427 -0.999359 0 0.0202777 -0.999794 -0.25871 -0.0290187 -0.965519 -0.449467 0.0248685 -0.892951 -0.5 -0.00113939 -0.866025 -0.731914 -0.00247138 -0.681393 -0.706961 0.0203234 -0.706961 -0.86566 -0.0290306 -0.499789 -0.949198 0.0249095 -0.313691 -0.979744 -0.0294211 -0.19808 -0.998831 0.0355269 0.0327711 -0.971338 -0.0376076 0.234708 0.4263 0.803451 -0.415614 -0.341407 0.800254 -0.492986 0.816214 -0.00422015 -0.577734 0.584964 0.141977 -0.798536 -0.102725 0.191758 -0.976051 0.740564 0.49671 -0.452597 -0.810695 0.0723422 -0.580982 -0.782252 0.17968 -0.596487 -0.889788 0.454546 0.0408087 -0.971683 0.223229 -0.0774627 -0.564184 0.467826 -0.68032 -0.863112 -0.353815 -0.36035 -0.182421 0.410931 -0.893229 0.0371424 -0.0922968 -0.995039 0.684652 0.16124 -0.710812 -0.659189 -0.298974 0.689989 0.948041 -0.00357415 -0.318129 0.95302 0.000866878 -0.302907 0.99007 -0.000975395 -0.140572 0.990517 -6.01758e-07 -0.137387 0.884629 4.15776e-05 -0.466296 0.884669 8.20761e-05 -0.466219 0.783885 4.05978e-05 -0.620906 0.783942 8.34222e-05 -0.620834 0.656446 4.92841e-05 -0.754373 0.656464 6.05313e-05 -0.754357 0.506654 4.24916e-05 -0.86215 0.506726 8.16732e-05 -0.862107 0.339607 4.05634e-05 -0.940567 0.339689 8.12865e-05 -0.940538 0.160996 4.04483e-05 -0.986955 0.161074 7.75134e-05 -0.986942 -0.0230985 4.59562e-05 -0.999733 -0.0231967 0 -0.999731 -0.206405 0 -0.978467 -0.205913 0.00024173 -0.97857 -0.382683 1.54108e-05 -0.92388 -0.382549 8.37233e-05 -0.923935 -0.54593 4.16376e-05 -0.837831 -0.545855 8.33833e-05 -0.83788 -0.690585 4.25256e-05 -0.723251 -0.690651 0 -0.723188 -0.811724 0 -0.584042 -0.811549 0.000144408 -0.584285 -0.90522 3.94543e-05 -0.424943 -0.905182 8.133e-05 -0.425024 -0.96789 4.02267e-05 -0.251374 -0.967865 8.76623e-05 -0.251472 -0.9976 4.24605e-05 -0.0692442 -0.997606 0 -0.0691535 -0.993337 0 0.115243 -0.993372 0.00014621 0.114941 -0.955248 4.07018e-05 0.295806 -0.955274 8.1185e-05 0.295723 -0.884629 4.05089e-05 0.466296 -0.88467 8.22803e-05 0.466217 -0.783885 5.90349e-05 0.620906 -0.783807 0 0.621005 -0.656446 0 0.754373 -0.656617 0.000108911 0.754224 -0.506654 4.25329e-05 0.86215 -0.506726 8.16732e-05 0.862107 -0.339607 4.05634e-05 0.940567 -0.33967 7.1863e-05 0.940545 -0.160996 6.67332e-05 0.986955 -0.160855 0 0.986978 0.0230985 0 0.999733 0.0228964 9.72547e-05 0.999738 0.206405 4.46738e-05 0.978467 0.206327 8.20466e-05 0.978483 0.382683 4.0833e-05 0.92388 0.382604 8.12229e-05 0.923913 0.54593 4.03687e-05 0.837831 0.545842 8.96938e-05 0.837888 0.690585 4.85655e-05 0.723251 0.690661 0 0.723179 0.811724 0 0.584042 0.811528 0.000161033 0.584313 0.90522 3.57966e-05 0.424943 0.905179 8.13317e-05 0.425031 0.96789 4.02267e-05 0.251374 0.967867 8.24936e-05 0.251462 0.9976 3.27818e-05 0.0692442 0.997593 7.95624e-05 0.0693439 0.993337 4.00593e-05 -0.115243 0.993348 8.17625e-05 -0.115154 0.955248 4.06363e-05 -0.295806 0.955275 8.33931e-05 -0.295719 0.797585 -1.38845e-07 -0.603206 0.797548 -1.25523e-05 -0.603256 0.858883 -0.0115034 -0.512042 0.888064 0.00232021 -0.459713 -0.494866 0.000897912 0.868969 -0.49265 -1.70017e-07 0.870228 -0.306278 -4.18116e-07 0.951942 -0.306279 -1.68543e-07 0.951942 -0.109921 -3.70442e-07 0.99394 -0.109921 -2.26363e-07 0.99394 0.0908657 -5.03779e-07 0.995863 0.353435 -0.00600931 0.93544 0.287995 0.00646387 0.95761 0.0987003 -0.0023118 0.995115 0.382684 -0.000218359 0.923879 0.382137 -2.29773e-07 0.924106 0.493227 -4.19299e-07 0.8699 0.493226 -1.32515e-07 0.869901 0.690361 -3.49834e-07 0.723465 0.69036 -1.77947e-07 0.723466 0.845862 -4.19326e-07 0.533401 0.845862 -2.20907e-07 0.533402 0.950354 -5.63088e-07 0.31117 0.950354 -1.7644e-07 0.311172 0.997535 -3.37519e-07 0.0701758 0.997535 -2.64158e-07 0.0701761 0.655741 -4.34203e-07 -0.754986 0.655742 -1.81226e-07 -0.754985 0.451969 -3.36833e-07 -0.892033 0.45197 -2.09106e-07 -0.892033 0.220941 -3.58445e-07 -0.975287 0.220942 -1.31078e-07 -0.975287 -0.0234094 -3.00599e-07 -0.999726 -0.0234091 -2.16713e-07 -0.999726 -0.26635 -4.86952e-07 -0.963877 -0.266349 -2.75427e-07 -0.963877 -0.382684 -4.39537e-07 -0.92388 -0.383178 -0.00038616 -0.923675 -0.964357 -0.000861985 -0.264604 -0.963709 -3.6279e-07 -0.266957 -0.889696 -2.60054e-07 -0.456553 -0.889697 -4.7672e-07 -0.456552 -0.780548 -2.36842e-07 -0.625096 -0.780548 -2.96404e-07 -0.625095 -0.635663 -1.16462e-07 -0.771967 -0.639932 -0.00146686 -0.76843 -0.47349 0.00647127 -0.880776 -0.408549 -0.00702818 -0.912709 -0.925216 0.00907744 0.379332 -0.923638 0.0240245 0.382514 -0.93043 -0.000363388 0.36647 -0.926911 -0.00361481 0.375265 -0.920899 0.0034736 0.389785 -0.916956 -0.00036771 0.398988 -0.920902 -0.00601542 0.389748 -0.92388 -9.48694e-09 0.382683 -0.926796 -0.00416509 0.375543 0 -1 0 1.33615e-05 -1 -1.62747e-05 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.645154 -0.0140691 -0.763923 -0.841611 -0.139239 -0.521827 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.228179 -0.0382777 0.972867 0.0518591 -0.0563805 0.997062 -0.460571 -0.863186 0.206842 0 -1 0 -0.185428 -0.294278 -0.937559 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.780897 -0.0743623 -0.620218 0.909193 0.334715 -0.247658 0.944935 0.0760152 0.318309 0.560885 0.292435 0.774526 0.911069 -0.111841 0.396793 0.254422 -0.0828283 0.96354 -0.144254 0.430927 0.890782 -0.830902 0.390503 0.396369 0.00644332 0.999979 -0.00021267 -0.0167366 0.99986 0.000830048 -0.797945 0.164858 -0.579746 -0.00902994 0.999958 0.00145911 0.00650081 0.999979 -5.32339e-05 0.52603 0.563999 0.636552 -0.0346873 0.998718 0.0368649 0.581276 0.813138 0.03042 -0.0073603 0.0497591 -0.998734 -0.0114057 0.999792 -0.0169119 -0.935934 0.242167 0.255702 -0.579811 0.138493 0.802894 -0.54018 0.048393 0.840157 -0.0653047 -0.104246 0.992405 0.181796 0.213143 0.959959 0.797942 0.0315325 0.601909 0.979128 0.165248 -0.118332 0.87748 0.474902 0.0670537 0.0130341 0.999542 0.0273157 0.550241 0.824928 0.129334 0.442072 0.483161 -0.75573 -0.0643719 0.327782 -0.942558 -0.804935 0.308404 -0.506919 -0.829829 0.369373 0.418268 0.128028 0.943874 -0.304483 -0.0698077 0.992866 0.0966663 -0.743749 0.516672 0.42413 -0.109379 -0.240649 0.96443 0.298764 0.85055 0.432787 0.811375 -0.551514 0.193655 -7.25737e-07 -1 3.0061e-07 0 -1 0 -5.49687e-07 -1 7.36287e-07 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1.78458e-05 -1 -4.30836e-05 0 -1 0 -0.000514519 -0.999996 0.00266454 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.00157154 -0.999997 0.00183817 0 -1 0 0 -1 0 2.05553e-05 -1 4.3812e-05 -0.00242781 -0.999995 -0.00207069 -0.000359891 -0.999997 -0.00234609 -0.00100314 -0.999999 -0.00084576 0 -0.999999 -0.00110889 0.000320403 -0.999999 -0.0010536 0.000658075 -1 -0.000741258 -8.53524e-07 -1 6.69549e-07 2.22335e-06 -1 3.27246e-08 0.000948275 -1 0.000280719 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 8.79403e-07 -1 -9.25405e-08 0.000881473 -0.999999 0.00072221 -0.891616 0.0234833 0.452183 -0.866025 -0.00114412 0.5 -0.681386 -0.00248167 0.731921 -0.706961 0.0203126 0.706961 -0.499789 -0.0290278 0.86566 -0.313682 0.0248959 0.949202 -0.258819 -0.00114525 0.965925 0.00480801 -0.00235339 0.999986 0 0 1 0.249927 0 0.968265 0.258817 -0.00406001 0.965918 0.484548 -0.00213372 0.874762 0.504986 0.00796871 0.863091 0.706774 -3.96939e-05 0.707439 0.707033 -0.000224369 0.707181 0.873751 -0.00769291 0.486312 0.866025 0 0.5 0.965272 0 0.261246 0.965925 -0.00114198 0.258819 0.999358 -0.00247723 -0.0357291 0.999794 0.020317 0 0.965519 -0.029029 -0.25871 0.000759531 -0.999931 0.0116882 0.00320292 -0.999882 0.0150402 -0.00485718 -0.999865 0.0156928 -0.00371368 -0.999887 0.0145476 -0.0100137 -0.999895 0.0104516 -0.0108268 -0.999885 0.0106446 -0.0114235 -0.999913 0.00659175 -0.0165532 -0.999851 0.00500446 -0.0136766 -0.999906 -0.000102022 -0.0170339 -0.999841 -0.00519608 -0.0134062 -0.999907 -0.00257456 -0.0128985 -0.999842 -0.0121989 -0.0134699 -0.999819 -0.0134657 -0.00901295 -0.999719 -0.0219043 -0.00780418 -0.999957 -0.00510322 -0.0066794 -0.999922 -0.0105746 -0.0015329 -0.999918 -0.0126823 -0.00177132 -0.999915 -0.0129369 0.00420943 -0.999897 -0.0137327 0.00416838 -0.999898 -0.0136908 0.010238 -0.99989 -0.0106926 0.0230285 -0.999631 -0.014398 0.024833 -0.999608 -0.0129077 0.0244561 -0.999618 -0.0129091 0.0181887 -0.999834 -0.000488233 0.0173306 -0.999849 -0.00162797 0.0113729 -0.999919 0.00569704 0.0109951 -0.999927 0.00508264 0.00855981 -0.999894 0.0118091 0.00756314 -0.999933 0.0088016 0.00538239 -0.999898 0.0132467 0.996436 0.00150721 0.0843417 0.263401 -0.958677 -0.107509 -0.853125 0.0744485 0.516367 -0.708177 -0.117094 0.696257 -0.586186 0.0785669 0.806358 -0.325893 -0.0435548 0.944403 -0.301177 -0.0792678 0.950268 0.995532 -0.0114615 0.0937246 0.912833 -0.0129601 0.408128 0.908802 0 0.417227 0.737154 0 0.675725 0.753893 -0.0459761 0.655387 0.000290539 -1 -0.000570945 0.00197176 -0.999997 0.00154376 0.00156447 -0.999999 -0.000428852 0.000973386 -1 0.000163552 0.000862741 -1 0.0004715 0.000809034 -1 0.000492051 0.00055413 -0.999999 0.000930266 0.000747214 -0.999999 0.000806774 0.00082304 -0.999999 0.000820859 0.000352323 -0.999999 0.00101626 -0.000323613 -1 0.000697032 -0.00136424 -0.999998 0.00130731 0.00289808 -0.999982 0.00518877 -0.0049119 -0.999974 0.00530028 -0.0029915 -0.999863 0.0163068 -0.00939822 -0.99987 0.0130886 -0.0162335 -0.999771 0.0139279 -0.0156298 -0.999827 0.0101154 -0.0211456 -0.999738 0.00872177 -0.018138 -0.999829 0.00357119 -0.0252018 -0.999681 -0.00144896 -0.0251919 -0.999683 0.000365922 -0.0116585 -0.999926 -0.00358644 -0.0072705 -0.999921 -0.0102173 -0.00687254 -0.999975 -0.00168461 -0.00102757 -0.999996 -0.0028123 -5.843e-05 -1 -0.00100147 0.000688821 -0.999999 -0.00103034 0.00102038 -0.999999 -0.000580809 0.000870037 -0.999999 -0.000667557 0.000916485 -1 -8.24057e-05 0.00029367 -1 -0.000605872 -0.00143468 -0.999997 -0.00210951 -0.00241393 -0.999996 -0.00161465 0.00045618 -1 -0.000669856 0.00010168 -1 -0.000430143 -0.00066595 -1 -0.000707537 8.74598e-05 -1 -0.000882013 0.953717 0 -0.300706 0.953996 -0.000309909 -0.299818 0.991445 -0.000124053 -0.130526 0.991482 -0.000214766 -0.130243 0.999062 -0.000109618 0.0432918 0.999063 -0.000109022 0.0432899 0.976189 -0.000236215 0.216922 0.976097 -0.000373474 0.217335 0.924131 -0.00026895 0.382076 0.92401 -0.000365622 0.382367 0.843902 0.000316836 0.536497 0.842894 -0.000307915 0.538079 0.737277 -0.000123799 0.675591 0.737081 -0.000216173 0.675804 0.608762 -0.000110078 0.793353 0.609036 0 0.793143 0.461748 0 0.887011 0.460927 -0.000308222 0.887438 0.300706 -0.000123726 0.953717 0.301077 0 0.9536 0.130526 0 0.991445 0.129605 -0.000309161 0.991566 -0.0436189 -0.000124024 0.999048 -0.0432295 0 0.999065 -0.21644 0 0.976296 -0.21732 -0.00030014 0.9761 -0.382683 -0.00012253 0.92388 -0.382328 0 0.924027 -0.5373 0 0.843392 -0.538024 -0.000286018 0.84293 -0.675591 -0.000120645 0.737277 -0.675312 0 0.737532 -0.793353 0 0.608762 -0.793866 -0.000280714 0.608093 -0.887011 -0.000119892 0.461748 -0.886837 0 0.462082 -0.00379249 -0.999993 0.000511351 0.00595291 -0.999978 -0.0030083 0.00348253 -0.999993 0.00134574 0.00291543 -0.99999 -0.00331708 0.00520592 -0.999982 -0.0029141 0.00432765 -0.999989 0.00200164 0.0261355 -0.999614 0.00944979 0.018646 -0.999424 0.0283697 0.0602974 -0.99561 0.071596 0.00633875 -0.999979 0.00111129 0.00471672 -0.999986 -0.00236252 0.0408939 -0.999055 0.0146951 0.0688765 -0.997325 -0.0244738 3.96383e-05 -1 9.07579e-05 7.59079e-05 -1 0.000118813 0.000147105 -1 0.000140447 0.000309484 -1 2.7394e-05 -1.85489e-05 -1 0.000120877 -0.00111476 -0.999999 0.000848391 -0.00128692 -0.999999 0.000574833 -0.00159481 -0.999996 0.00235279 -0.00396481 -0.999989 -0.00248912 -5.00781e-05 -1 0.000417089 -0.00053989 -1 -0.000265645 -0.00117265 -0.999999 -2.92331e-05 -0.00384934 -0.999989 -0.00257648 -0.00449899 -0.99997 -0.00622871 -0.00499091 -0.999959 -0.00757795 -0.0049924 -0.999959 -0.00758032 -0.0504489 -0.998473 -0.0225182 -0.00138208 -0.999982 -0.00577742 0.0236891 -0.998709 -0.0449349 0.000503364 -0.999991 -0.00430555 0.00204901 -0.999995 0.00239458 0.0045946 -0.999982 -0.00395058 -0.00171318 -0.999977 -0.00659672 -0.000919098 -0.999997 0.00215462 0.00155972 -0.999997 0.00159283 -0.00484208 -0.999987 0.00152668 -0.00929462 -0.999949 0.00405678 0.00141897 -0.999999 0.000190469 0.00655684 -0.999813 0.0182171 0.0126166 -0.999725 0.0197479 0.00214936 -0.999932 0.0114918 0.00294711 -0.999982 0.00518234 0.000478697 -1 0.000457032 0.000445548 -1 0.000529035 -0.000245115 -1 0.000304339 -5.52225e-05 -1 0.000796196 0.000521246 -0.999992 0.00388343 0 1 0 -0.00134202 0.999993 -0.00363346 -0.00169192 0.99999 -0.00414177 0 1 0 0 1 0 -0.000349501 1 2.71148e-05 -0.000133199 1 0.00017638 -0.00656848 0.99997 0.0041708 0 1 0 -0.00132528 0.999997 0.00216931 0.00199994 0.999997 0.00113163 -0.000694107 0.999995 0.00308317 -0.000851789 0.999995 0.00309767 -0.000581663 0.999978 0.00653765 0.000958477 0.999993 0.00351997 0.00562107 0.999975 0.00427665 0 1 0 0 1 0 0.000118461 1 0.000320727 0.000855656 0.999999 0.00100878 0.00566701 0.999966 0.00600355 0.000197048 1 7.09234e-05 7.67146e-05 1 0.000264071 0 1 0 0.0310001 0.999519 -0.000620261 0.00383582 0.999989 0.00270384 0.00496946 0.999986 0.00175921 0 1 0 0.000888728 0.999999 -0.000817341 0.000819565 0.999998 -0.0016703 0.00529529 0.999985 0.00130609 0.00406153 0.999977 -0.00552922 0.0021316 0.999998 0.000406277 0.00251889 0.999996 -0.00151173 0 1 0 0.00217261 0.999992 -0.00348263 0.00492279 0.999984 -0.00268171 -0.000873468 0.999999 -0.00117241 0.00183323 0.999993 -0.00325534 0.00150849 0.999994 -0.0031941 -0.00414161 0.999978 -0.0051722 0.00202318 0.999998 -0.000710698 -0.00245763 0.999996 -0.00143789 -0.00376596 0.999989 -0.00276205 -0.00759024 0.999971 0.000424649 -0.00287078 0.999987 0.00419159 -0.00638312 0.999979 -0.000546546 -1.08459e-05 1 0.000202988 -0.00021321 1 4.39361e-05 -0.000186862 1 -7.76124e-06 -0.000316684 1 6.7635e-05 -0.000249514 1 -0.000245939 0 1 0 -0.00124291 0.999999 -0.000349343 -0.000899295 0.999997 0.00240514 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 2.25851e-05 1 -1.82896e-05 0.000655195 1 -0.000530583 -2.94958e-05 1 0.000159929 0.000558644 1 -3.23464e-05 0 1 0 -7.75276e-06 1 -5.40397e-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.11925 0.983361 0.137039 0.776798 0.290178 0.558912 0.892129 0.284068 0.351299 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.11925 0.983361 -0.137039 -0.776798 0.290178 -0.558912 -0.892129 0.284068 -0.351299 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.025303 0.992458 -0.119948 -0.85526 0.445409 0.264843 -0.79335 0.3677 0.485173 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.87593 0.0471805 0.480126 -0.783636 -0.0251791 0.620709 -0.706329 0.0251158 0.707438 -0.65627 -0.0231707 0.75417 -0.529202 0.0187332 0.848289 -0.506621 -0.0112527 0.862095 -0.339348 -0.0390922 0.939848 -0.233599 0.0527208 0.970903 -0.160966 -0.01926 0.986772 0.0230935 -0.0198952 0.999535 0.0597577 0.0153985 0.998094 0.206343 -0.0244882 0.978173 0.254519 0.0129443 0.966981 0.382586 -0.0226325 0.923643 0.443664 0.0235154 0.895885 0.545758 -0.0251113 0.837567 0.637458 0.0260927 0.770043 0.690401 -0.0231115 0.723058 0.80441 0.0214759 0.593687 0.911287 0.0402554 0.409798 0.967577 -0.0254299 0.251293 0.992284 0.0387972 0.117759 0.997552 -0.00982153 0.0692413 0.992797 -0.0329867 -0.115181 0.97349 0.0491261 -0.22339 0.955123 -0.0161829 -0.295768 0.00656154 0.999975 0.00280812 0.00724528 0.999961 -0.00501595 0.000566436 1 0.000425431 0.000631335 1 0.000242765 -0.000427503 1 0.000258381 0.000188264 1 0.00035744 0.000201463 1 0.00033333 -0.000188264 1 -0.00035744 -9.71912e-05 1 -0.000523798 0.014301 0.999863 -0.00838679 -0.00106283 0.999999 -0.00035445 0.000374164 1 0.000295046 0.000641011 1 0.000310199 0 1 0 0 1 0 -0.000374164 1 -0.000295046 -2.89625e-05 1 -0.000275443 0.0153787 0.999871 -0.00461369 0 1 0 -0.000466317 1 0.00024561 -1.44507e-05 1 -0.000401437 0.00013335 1 -0.000425582 0 1 0 -0.000483658 1 0.00021993 0 1 0 0.000168132 1 -0.000411562 0.000288896 1 -0.000226303 -0.584409 0.0424588 0.810347 -0.378049 -0.026409 0.925409 -0.331865 0.0442349 0.942289 0.035959 -0.0288501 0.998937 0.0324479 -0.0354571 0.998844 0.327202 0.0837646 0.941234 0.463581 -0.102059 0.880157 0.677272 0.123027 0.725374 0.783609 -0.0643623 0.617912 0.932565 0.0627207 0.355513 0.930852 0.0503173 0.361916 0.998935 -0.0289213 -0.0359589 0.995697 0.0503237 -0.0778096 -0.722234 -0.0137534 0.691512 -0.657216 -0.0542274 0.751749 -0.81796 0.244566 0.5207 -0.011909 0.999811 -0.0153602 -0.00828519 0.99994 -0.00721547 -0.0119252 0.999927 -0.00174049 -0.0131717 0.999907 -0.00359009 -0.0160637 0.999871 0.00098046 -0.0129964 0.999915 -0.000608642 -0.00683906 0.99997 0.00366378 -0.010303 0.999888 0.0108672 -0.0082522 0.999892 0.0121751 -0.00835387 0.999879 0.0131348 -0.00621423 0.999843 0.016621 -0.00158284 0.9999 0.0140299 0.000533378 0.999859 0.0167576 0.00574479 0.999874 0.0147685 0.00740661 0.99984 0.0162538 0.0130064 0.999801 0.0151423 0.0117142 0.999879 0.0102017 0.0174318 0.999825 0.00682952 0.0152986 0.999874 0.00416981 0.0172716 0.99985 -0.00105419 0.0176774 0.999843 -0.00130359 0.0141603 0.999871 -0.00758589 0.0147321 0.999856 -0.00844183 0.00919955 0.999866 -0.0135728 0.00897459 0.999886 -0.0121234 0.00621423 0.999843 -0.016621 0.00158284 0.9999 -0.0140299 -0.000533378 0.999859 -0.0167576 -0.00574479 0.999874 -0.0147685 -0.00740661 0.99984 -0.0162538 0.970496 0.042305 -0.237379 0.997282 -0.0415051 -0.06087 0.980607 0.0407011 0.191713 0.964652 -0.0177539 0.262927 0.800694 0.0174229 0.59882 0.753455 -0.0417352 0.656174 0.565844 0.0424049 0.823421 0.36173 -0.0662712 0.929924 0.168241 0.066064 0.98353 -0.111861 -0.0662711 0.991512 -0.275859 0.0437411 0.960202 -0.569761 -0.0320207 0.821186 -0.560939 -0.0207846 0.827596 -0.861657 0.0205784 0.507073 -0.88129 -0.0207847 0.472119 -0.685073 0.606746 0.403155 -0.414293 0.807063 0.420726 -0.417407 0.676049 0.607231 -0.214109 0.642095 0.736119 -0.100648 0.75272 0.650602 0.125004 0.671086 0.730765 0.168047 0.750696 0.638917 0.441207 0.631916 0.637196 0.504833 0.774336 0.381508 0.484288 0.806373 0.339453 0.836863 0.521723 0.16573 0.606962 0.779137 -0.156663 0.577366 0.799789 -0.164272 0.00141771 0.999999 -0.000421941 -5.17231e-05 1 -4.24553e-05 0.000829727 0.999999 -0.00113898 0.000338935 1 0.000345764 -0.00162449 0.999998 -0.00138001 -0.00182408 0.999997 -0.00129673 -0.00104035 0.999999 -0.000267479 0.000438953 1 0.000305428 -0.000810029 0.999999 0.000643627 0.00147458 0.999999 0.000552315 -0.00142672 0.999999 0.000364044 0.000992555 0.999999 0.00126316 -0.000927722 0.999999 0.000509864 0.000561655 1 -0.00022147 -0.000227584 1 -8.67524e-05 -0.807852 -0.1717 0.563821 -0.792415 0.059929 0.607031 -0.572042 -0.0911837 0.81514 -0.546633 0.0800746 0.833535 -0.317587 -0.0234451 0.947939 -0.282955 0.00831575 0.959097 -0.249607 0.135278 0.958852 -0.0829616 -0.160985 0.983464 0.0407719 0.135397 0.989952 0.187131 -0.117196 0.975319 0.259362 0.096265 0.960971 0.395602 -0.153851 0.905444 0.524605 0.22929 0.819888 0.632372 -0.23473 0.738246 0.755936 0.135494 0.64047 0.844237 -0.117861 0.522851 0.88048 0.073262 0.468389 0.922788 0.000540591 0.385308 0.952699 0.0620128 0.29752 0.94927 -0.245034 0.197089 0.990034 0.13469 0.0411208 0.987477 -0.116971 -0.105868 0.967158 0.157748 -0.199302 0.942263 -0.119624 -0.312778 0.667021 0.535117 0.518395 -0.034699 -0.759644 0.649413 0.172771 -0.40011 -0.900035 -0.423384 -0.0329239 -0.905352 -0.374063 0.0244167 -0.927082 0.384238 0.0562735 0.921517 0.326914 -0.0521391 0.943615 0.410343 -0.00605469 0.911911 0.116385 -0.98949 -0.0858107 -0.895932 0.127389 0.425533 0.851693 0.184819 0.490367 -0.130516 0.851197 0.508359 0.0732904 0.845071 0.529607 -0.181743 0.930565 0.317834 -0.173037 0.940518 0.292376 0.0218708 0.981436 0.19054 0.019426 0.97208 0.233845 0.269759 0.942643 0.196607 0.835331 -0.440272 -0.329216 0.735649 0.363406 0.571626 -0.746874 -0.596268 0.294354 0.927052 0.249327 0.280018 -0.694192 -0.332422 0.63843 -0.423249 -0.60552 0.673947 0.498197 0.379111 0.779791 0.924333 -0.0105249 -0.381442 0.923335 -0.00353386 -0.383978 0.926072 -0.00260609 -0.377338 0.926257 -0.00244686 -0.376884 0.92388 2.58417e-08 -0.382683 0.922416 0.0118108 -0.386018 0.921054 0.00329497 -0.38942 0.918498 0.000981687 -0.395425 0.977546 0.0105237 -0.210459 0.995633 -0.0191302 0.0913764 0.949338 0.0217767 0.313502 0.964222 -0.000473489 0.265094 0.89505 -0.000391525 0.445966 0.887923 0.00476185 0.459967 0.780456 -0.00179439 0.625208 0.782293 -0.000612036 0.622911 0.637141 -0.00143185 0.770746 0.640067 -0.000147076 0.768319 0.474122 0.00136682 0.880458 0.469612 -0.000156983 0.882873 0.385006 0.00482135 0.922902 0.382576 -0.000335332 0.923924 0.381724 8.69228e-05 0.924276 0.382251 -0.0004443 0.924058 0.337733 -0.12698 0.932638 0.266327 0.0128031 0.963798 0.215698 0 0.97646 0.0235139 0 0.999724 0.0229212 -0.00016244 0.999737 -0.225023 -0.00131992 0.974353 -0.219955 0.000148194 0.97551 -0.451463 -0.00040882 0.89229 -0.452509 -0.000749278 0.89176 -0.656609 -0.000564546 0.754231 -0.656197 -0.000405539 0.75459 -0.976486 -0.0700865 0.203869 -0.799454 -0.00102225 0.600726 -0.798302 -0.000407521 0.602258 -0.925371 0.0299959 0.377875 -0.887535 0.00609929 0.4607 -0.934652 -0.00979172 0.35543 -0.954135 0.0048237 0.299339 -0.984032 -0.012277 0.177568 -0.99049 0.000551709 0.137582 -0.497682 0.017906 -0.867175 -0.672044 -0.00719569 -0.740476 -0.687316 -0.00132331 -0.726357 -0.84601 -0.00015929 -0.533168 -0.845224 -0.000585847 -0.534412 -0.950294 -0.000598985 -0.311354 -0.950533 -0.000375548 -0.310622 -0.99769 7.85754e-05 -0.0679346 -0.997229 -0.0017809 -0.074373 -0.396379 -0.00602077 -0.918067 -0.382113 -0.000289686 -0.924116 -0.384158 0.000801119 -0.923267 -0.382305 0 -0.924036 0.334273 0.00818137 -0.942441 0.305559 -0.00672505 -0.95215 0.490325 0.0117938 -0.87146 0.554052 -0.00995398 -0.832423 -0.292449 0 -0.956281 -0.287992 0.00144813 -0.957632 -0.0909971 -7.94806e-07 -0.995851 -0.089008 -0.000630893 -0.996031 0.113523 -0.00143257 -0.993534 0.117161 -0.00267029 -0.993109 0.709622 0.00544402 -0.704562 0.84668 -0.00930122 -0.532022 0.000115314 -1 0.000233616 -8.08359e-05 -1 0.000152581 0.000256946 -1 0.000621043 0.156963 -0.382751 0.91042 -0.414524 -0.861102 -0.294403 0.171015 -0.365145 -0.915108 -0.853795 -0.383269 0.352334 0.870196 -0.41213 0.270014 0.291994 -0.945719 -0.142674 -0.189567 -0.97883 -0.0771726 0.560972 0.506749 0.654612 -0.000111658 -1 -0.000328805 -0.000353108 -1 -0.00084644 -0.192823 -0.900121 -0.390642 0 -1 0 -0.471237 -0.551066 0.688667 0.263238 -0.869356 0.418242 0.109264 -0.940497 0.321757 0 -1 0 0 -1 0 0.951181 -0.236259 -0.198586 -0.585865 -0.213825 -0.781691 -6.60057e-05 -1 -0.000194475 -4.87177e-05 -1 -0.000118799 -4.09902e-05 -1 -0.000114164 -3.85285e-06 -1 -0.00016454 0.00760982 -0.999498 -0.0307518 0.00724129 -0.999463 -0.0319648 0.014865 -0.999459 -0.0293384 0.0118106 -0.999558 -0.0272827 0.0192493 -0.999569 -0.0221707 0.0381421 -0.998856 -0.0288471 0.0207814 -0.999593 -0.0195335 0.00822456 -0.999957 -0.00426033 0.00864649 -0.999959 -0.00274622 0.0140497 -0.999899 -0.00194429 0.0389783 -0.999239 -0.00166432 0.0309613 -0.999518 0.00217582 0.0295801 -0.999516 0.00968529 0.0514392 -0.998116 0.0334343 0.051805 -0.998123 0.0326683 0.0399542 -0.999145 0.0105934 8.00167e-05 -1 8.38537e-05 8.20921e-05 -1 8.17342e-05 9.17447e-05 -1 0.000256614 0.00214359 -0.999972 0.00718142 0.00218034 -0.999972 0.00720947 0.00082291 -0.999959 0.00905448 -0.00427874 -0.999263 0.0381511 -0.00421932 -0.999263 0.0381524 -0.0203724 -0.997785 0.0633194 -0.00298705 -0.99962 0.0274165 -7.6065e-05 -1 0.000269083 -0.000330172 -1 0.00011984 -0.0285097 -0.999557 0.00849406 -0.0320226 -0.999448 -0.00889068 -0.161913 -0.982945 -0.0871909 -0.165885 -0.982464 -0.0851241 -0.203058 -0.965569 -0.162618 -0.0608381 -0.998124 0.00688034 -0.0244484 -0.99927 -0.0293535 -0.0313201 -0.997813 -0.0582174 -0.00858069 -0.999958 0.00336133 -0.246085 -0.609122 0.753931 -0.453004 0.2523 0.855063 0.381796 -0.205295 0.901158 0.380345 -0.0658628 0.922497 0.69583 -0.455749 0.55508 0.551752 0.391938 0.736176 0.591882 -0.674069 -0.441935 0.762259 0.508436 -0.400568 0.0109318 0.0772217 -0.996954 -0.0754564 -0.834072 -0.546471 -0.376171 -0.0945552 -0.921713 -0.384382 -0.0107841 -0.923111 -0.964342 0.0162722 -0.264157 -0.428662 -0.578403 -0.694045 -0.846088 -0.401465 0.350658 -0.846391 -0.0277118 0.53184 0.779788 0.542877 0.311793 0.495911 0.587171 0.639768 0.105949 0.554329 0.825527 0.815832 -0.568211 0.107493 0.730917 -0.566187 0.381042 0.442386 -0.566776 0.695025 0.178087 -0.565637 0.805195 -0.108487 -0.56871 0.815352 -0.378158 -0.578009 0.72312 -0.597919 -0.586104 0.546787 -0.747203 -0.58837 0.309045 0.987956 0.154663 0.00476541 -0.409958 -0.166497 -0.89678 -0.215534 0.976496 0.00113004 0.00170193 0.41239 0.911006 -0.845535 -0.00529541 -0.533893 -0.891178 0.124327 -0.436284 -0.108769 0.992958 0.0469493 0.419599 0.176081 0.890468 0.180177 0.966714 0.18166 0.321032 0.918978 -0.228951 -0.880603 -0.360575 -0.307449 0.57878 -0.0216994 -0.815195 -0.213709 0.913558 -0.346034 0.1701 0.892771 0.417164 0.982963 -0.012121 0.183403 -0.556167 0.0887092 0.826323 0.185455 -0.553789 -0.811741 -0.164424 0.549666 0.819044 0.0540973 0.728359 0.683057 0.104439 -0.540406 0.834898 0.834575 -0.550888 0.00256185 0.80032 0.189879 0.568713 0.699908 0.607001 -0.376402 0.138173 -0.886922 -0.440769 0.583526 -0.709042 0.395925 0.367527 -0.924884 0.0975366 -0.355412 0.79618 0.489673 0.810912 0.338816 0.477102 -0.236039 -0.338816 0.910763 0.597565 -0.79618 0.0949375 0.131111 -0.666319 -0.73405 0.185277 0.444512 0.876403 -0.291782 -0.55308 0.780363 0.927398 0.309036 -0.210784 0.654526 -0.659118 0.370351 -0.789882 0.586896 0.177874 0.564601 -0.326979 0.757833 0.589164 -0.462491 0.662562 -0.153754 -0.530434 0.833666 0.425057 -0.826471 0.369151 -0.0397138 -0.827128 0.560609 -0.402865 -0.829727 0.386334 0.486825 -0.859907 -0.153495 0.867347 -0.484428 -0.114188 0.817911 0.574263 -0.0352667 0.24134 -0.596548 0.765432 0.272512 -0.500322 0.821836 0.278656 -0.797378 0.535294 0.487764 -0.598343 0.635666 0.581567 -0.389834 0.714009 0.522326 -0.705758 0.478624 0.832201 -0.223374 0.507489 -0.0995646 0.183594 0.977947 -0.0385151 -0.46939 0.88215 0.0783842 -0.799605 0.595389 -0.14481 -0.743214 0.653194 -0.196005 -0.858874 0.473198 -0.464239 -0.569223 0.678577 -0.513556 -0.293984 0.806122 -0.478624 -0.705758 0.522326 -0.744755 -0.325668 0.582478 -0.716159 -0.430272 0.549529 -0.466757 -0.850353 0.242978 0.189051 -0.704415 0.684148 -0.00727829 -0.17934 0.98376 -0.28118 0.575261 0.768123 -0.734882 0.497999 0.460374 -0.845842 0.498712 0.189308 0.367834 -0.468516 0.803238 -0.798759 0.58042 -0.15842 -0.49223 0.562156 -0.664598 0.707398 0.535617 0.461198 0.47204 0.53095 0.703754 -0.365858 -0.480239 -0.797194 0.949733 0.182744 -0.25419 -0.204157 -0.705312 -0.678863 -0.055166 -0.219629 -0.974023 0.179371 0.52563 -0.831588 0.65168 -0.708691 -0.270316 0.719797 0.530009 -0.44831 -0.386957 -0.0508707 0.920693 0.941264 0.329398 -0.0742885 0.543863 0.776727 -0.317661 0.23003 0.822439 0.52027 0.309578 0.0438972 -0.94986 0.78302 -0.041696 -0.620597 0.646709 0.0324959 0.762044 0.226575 -0.0216854 0.973752 0.679647 0.0490019 -0.731901 0.354265 -0.056296 0.933449 0.290429 -0.0449643 0.95584 -0.163414 0.871992 -0.461439 -0.511999 0.773833 -0.37288 -0.331252 0.921533 -0.202608 -0.484375 0.842128 0.237067 0.964818 -0.0687391 -0.253775 0.0179809 -0.473865 0.880414 -0.0340907 -0.584814 0.81045 0.0427986 -0.850203 0.524713 -0.0613026 -0.985277 0.159598 0.0407953 -0.993635 -0.105 -0.0194172 -0.81232 -0.582889 -0.0209669 -0.810744 -0.585026 0.0183606 -0.281064 -0.959513 -0.0374394 -0.159536 -0.986482 0.524017 -0.831418 0.184798 0.81948 -0.572154 -0.0330567 -0.969992 -0.228425 0.0832973 0.364462 -0.930694 0.0312376 -0.944334 -0.323617 0.0592037 0.972395 -0.232134 0.0236855 0.87584 -0.4643 0.131642 -0.0584861 -0.994556 -0.0862455 -0.983146 0.169257 -0.0691052 0.978842 -0.171103 -0.112211 -0.301857 -0.947867 0.102131 0.546277 0.833054 -0.0871976 0.0380085 0.930805 0.363534 0.866588 0.45972 0.19412 0.808089 0.49401 -0.320853 0.182617 0.11718 -0.976176 0.157084 -0.981216 -0.111978 0.513241 -0.857653 -0.0318557 0.822035 0.528225 -0.212689 -0.0583815 -0.824995 0.562117 0.041572 -0.967926 0.247772 -0.167268 -0.966461 -0.194868 0.0559424 -0.679046 0.731961 -0.0406143 -0.112733 0.992795 -0.0112479 -0.0751604 0.997108 -0.0021294 -0.0782348 -0.996933 0.00146532 -0.0734291 -0.997299 -0.0179046 -0.688987 -0.724552 0.534405 -0.347222 -0.770615 0.663363 0.0903758 0.74282 0.805582 -0.487233 0.337106 -0.287105 0.0547457 0.956333 -0.824797 -0.0584491 0.5624 -0.967631 0.0319155 0.250343 -0.569833 -0.00970115 0.821703 -0.714267 0.0440577 0.698486 -0.524941 0.0229573 0.850829 0.176361 -0.939115 0.29489 -0.492664 0.657695 -0.569842 -0.294683 0.910959 -0.288645 0.124484 -0.161913 -0.978922 0.873651 0.153119 0.461832 0.0991981 0.168467 -0.980703 0.802188 -0.519885 -0.293621 0.981734 -0.0367548 0.186673 0.754465 0.0827005 -0.65111 0.993411 -0.106205 0.0430765 0.0913123 0.092622 0.991506 0.230868 -0.237403 -0.943578 0.834077 0.0692196 0.547288 0.498624 0.114606 -0.859209 0.477936 -0.210943 0.85269 0.863058 -0.0863447 -0.49767 0.956456 -0.275732 0.0957264 0.927494 -0.0277704 -0.372805 0.914669 -0.242562 0.323332 0.637196 0.0665526 -0.767823 0.982552 -0.159582 -0.0955296 0.562849 0.0169514 0.826386 0.954956 -0.00935513 -0.2966 0.968798 -0.0842696 -0.233085 0.956048 0.0477479 -0.289295 0.0374061 -0.00169661 -0.999299 0.0849737 0.00915178 -0.996341 0.204499 -0.0171159 -0.978717 0.167236 -0.00146012 -0.985916 0.330642 -0.00546528 -0.943741 0.295628 0.00519136 -0.955289 0.438463 0.00173238 -0.898747 0.46081 -0.00680211 -0.887473 0.580227 0.000553684 -0.814455 0.594288 -0.00586352 -0.804231 0.705332 0.000148106 -0.708877 0.713582 -0.00410131 -0.70056 0.811442 -1.08775e-06 -0.584433 0.815009 -0.00228089 -0.579444 0.893513 0.00228614 -0.449032 0.89643 -0.000382564 -0.443184 0.948401 0.00184653 -0.317069 -0.962319 -0.0973031 0.253919 -0.911759 0.0530202 0.407289 -0.772781 -0.00649103 0.63464 -0.814066 -0.126408 0.566849 -0.906087 0.0837591 0.414717 -0.713238 -0.0173156 0.700708 -0.811209 0.49215 0.315799 -0.778825 -0.485358 -0.397316 -0.714732 0.0240147 -0.698986 -0.722078 -0.0152198 -0.691645 -0.821766 -0.037879 -0.568564 -0.902068 -0.09474 -0.421067 -0.927593 0.275948 -0.25184 -0.082679 0.00173937 -0.996575 -0.0982119 -0.00456869 -0.995155 -0.0879845 0.00332419 0.996116 -0.102039 -0.00271409 0.994777 -0.256387 0.000440037 0.966574 -0.272501 -0.00602991 0.962137 -0.416913 0.00696693 0.90892 -0.448814 -0.00496065 0.893611 -0.696702 0.000256356 0.717361 -0.580707 -0.00769995 0.814077 -0.563493 0.000637644 0.82612 -0.982516 -0.000833007 0.186178 -0.993095 0.00511761 0.117198 -0.996237 -0.00819064 0.0862834 -0.996028 -0.00818906 -0.0886649 -0.992678 0.0063154 -0.120628 -0.876831 0.375099 -0.30078 -0.696656 -0.000216223 -0.717405 -0.58061 -0.00766197 -0.814146 -0.563836 0.000585776 -0.825887 -0.44568 -0.00477892 -0.895179 -0.415715 0.00779107 -0.909462 -0.257606 -0.000732172 -0.96625 -0.248781 0.00282888 -0.968556 0.10035 -0.00288614 0.994948 0.116358 -0.021447 0.992976 0.335784 0.00281435 0.941935 0.341287 -0.0043057 0.939949 0.525825 -0.0479907 0.849238 0.640598 0.0596026 0.76556 0.687202 -0.00999187 0.726397 0.81887 -0.046056 0.572128 0.877651 0.0422008 0.477438 0.918174 -0.0261263 0.395316 0.973154 0.0123132 0.229827 0.979205 -0.0204453 0.20184 0.997302 -0.0623868 -0.0386902 0.999748 -0.0224646 0 0.979152 -0.0229379 -0.20183 0.972088 0.0112929 -0.234343 0.918174 -0.0261267 -0.395316 0.877652 0.0422051 -0.477437 0.81887 -0.0460575 -0.572128 0.687202 -0.00999126 -0.726397 0.640598 0.0596059 -0.765559 0.525825 -0.0479918 -0.849238 0.343945 -0.00491136 -0.938977 0.289282 0.0622081 -0.955221 0.138805 -0.0403407 -0.989498 0.207211 0.625184 0.752468 0.375201 -0.640687 0.669884 0.602121 0.485405 0.633903 0.515388 -0.801753 0.302602 0.588692 0.797328 0.133079 0.49349 -0.861359 -0.120531 0.798652 0.49425 -0.343324 0.51961 -0.293867 -0.802276 0.0754483 -0.576248 -0.813785 0.140958 -0.101852 0.984762 0.480605 0.112676 0.869668 0.512852 -0.112676 0.85105 0.776791 0.0962136 0.622365 0.802034 -0.207556 0.560055 0.903528 0.20941 0.373878 0.95073 -0.20941 0.228607 0.986869 0.154663 0.0465692 0.986869 -0.154663 -0.0465692 0.95073 0.20941 -0.228607 0.903528 -0.20941 -0.373878 0.802034 0.207556 -0.560055 0.776791 -0.0962135 -0.622365 0.512852 0.112676 -0.85105 0.480605 -0.112676 -0.869668 0.140958 0.101852 -0.984762 0.0861689 0.642654 0.761295 0.0824511 0.659653 0.747034 0.3821 -0.653016 0.653888 0.532999 0.70162 0.472907 0.811475 -0.183503 0.554829 0.826542 0.534859 0.175366 0.615567 -0.46376 -0.637184 0.32746 0.811928 -0.483262 0.269769 -0.461275 -0.845252 0.184434 -0.00976034 -0.982796 0.198613 0.0697488 -0.977593 0.480231 -0.03555 -0.876421 0.505241 0.243914 -0.827791 0.742106 -0.272754 -0.612278 0.791212 0.306273 -0.529321 0.938607 -0.190752 -0.287457 0.969925 0.0588929 -0.236172 -0.117603 -0.0369312 0.992374 -0.0997113 -0.0800256 0.991793 -0.331786 -0.0433053 0.94236 -0.380257 0.389615 0.838812 -0.610654 -0.336462 0.716865 -0.703094 0.309427 0.640245 -0.891205 -0.24072 0.384458 -0.932318 0.122883 0.340122 -0.995572 -0.0928058 0.0149636 -0.992328 0.121986 -0.0201018 -0.934919 -0.099204 -0.340711 -0.917913 0.130931 -0.374557 -0.75153 -0.105806 -0.651158 -0.751169 -0.0946951 -0.653282 -0.559448 0.194401 -0.805746 -0.454803 -0.27253 -0.847869 -0.296641 0.203097 -0.933143 -0.141093 -0.156443 -0.977557 -0.0836242 0.0835652 -0.992987 0.139235 -0.0590686 0.988496 0.0922304 -0.0285875 0.995327 0.850571 -0.00514164 0.525836 0.602253 -0.0355902 0.797512 0.710076 0.0103023 0.70405 0.738697 -0.0290327 0.673412 0.850216 0.00139079 0.526432 0.848589 -0.00250842 0.529046 0.982709 -0.0231703 0.1837 0.999985 -0.0004814 0.00547313 0.999976 -0.00700362 0 0.98269 -0.0239801 -0.183697 0.978887 -0.00276903 -0.204386 0.848937 -0.00255051 -0.528489 0.579741 -0.0111223 -0.814725 0.602387 -0.0286404 -0.79769 0.671555 0.0128649 -0.740843 0.738997 -0.00559915 -0.673685 0.729211 -0.018496 -0.684038 0.850188 0.00823278 -0.526414 0.843726 -0.00678811 -0.536731 0.0922668 0.00530676 -0.99572 0.0578999 -0.0457058 -0.997276 0.108897 -0.0210866 0.993829 0.24474 0.00145579 0.969588 0.273653 -0.00845142 0.961791 0.413084 0.00176586 0.910691 0.445719 -0.00936181 0.895124 0.561815 0.00299331 0.827257 0.550304 -0.00518187 0.834948 0.929675 8.16007e-05 0.368381 0.932469 -0.00274838 0.36124 0.977672 0.00296927 0.210116 0.97545 -0.0034969 0.220192 0.926427 -3.95101e-05 -0.376475 0.932458 -0.00549651 -0.361236 0.974313 0.00482522 -0.225147 0.523169 0.00599844 -0.852208 0.44572 -0.00913632 -0.895126 0.404993 0.00115502 -0.914319 0.273653 -0.00845121 -0.961791 0.244124 0.00166568 -0.969743 0.135292 -0.0139116 -0.990708 0.00255867 -0.297101 -0.954843 0.125085 0.131284 -0.983422 0.34964 -0.250309 -0.902827 0.506359 0.407475 -0.759977 0.642945 -0.317688 -0.696919 0.893097 0.108036 -0.436699 0.977451 -0.127581 -0.168264 0.868259 0.45616 0.195048 0.752463 -0.401222 0.522322 0.606753 0.400256 0.686765 0.463489 -0.382937 0.799085 0.297533 0.25406 0.920287 -0.104438 0.225209 0.968697 -0.0168735 0.999745 0.0150191 -0.0195366 0.998888 0.0429131 -0.0237264 0.999427 0.0241245 -0.0288418 0.999522 0.0111591 -0.0250226 0.998359 0.0515177 -0.0346481 0.997981 -0.0532269 -0.042417 0.998931 -0.0183815 -0.0663603 0.996241 -0.0556735 0.123264 0.992236 0.0165242 0.0610872 0.99725 0.0419493 0.0316013 0.999426 0.0122103 0.0299279 0.994103 0.104229 0.0252704 0.994756 0.0991075 -0.0566924 0.998012 0.0275348 -0.089506 0.995984 -0.00197657 -0.0409583 0.999015 -0.0170824 -0.030779 0.995437 -0.0903233 -0.00479314 0.997229 -0.0742392 0.00879632 0.999006 -0.0436991 0.0537853 0.994439 -0.0905407 0.0606389 0.997609 -0.0331547 0.0310988 0.99931 -0.0202909 0.0201153 0.999794 -0.00274719 0.0165869 0.999754 0.0147014 0.067634 0.996816 0.0422389 0.0318849 0.998149 0.0517801 0.0725123 0.993705 0.085394 -0.281374 0.0147077 0.959485 -0.320107 0.0643874 0.945191 -0.488507 -0.0257599 0.87218 -0.58479 0.0564396 0.809219 -0.751965 0.0665373 0.655837 -0.652729 -0.0337616 0.756839 -0.999523 0.0118946 -0.0284849 -0.98753 0.019074 0.156274 -0.971687 -0.0539632 0.230027 -0.94112 0.0354264 0.336212 -0.862351 -0.0209784 0.505876 -0.861074 -0.0242814 0.5079 -0.908691 0.0489268 -0.414592 -0.954654 -0.0507992 -0.293352 -0.976039 0.027732 -0.215821 -0.998899 -0.00647383 -0.0464639 -0.654636 -0.0244492 -0.755549 -0.714781 0.089453 -0.693604 -0.84871 -0.0648918 -0.524862 -0.099736 0.100083 -0.989968 -0.156729 0.00148539 -0.987641 -0.425179 0.0196233 -0.904897 -0.439771 -0.00769714 -0.898077 0.193813 -0.107203 -0.975164 0.737183 0.0626966 -0.672778 0.68754 -0.00759404 -0.726107 0.566332 0.0215923 -0.823895 0.522239 -0.028247 -0.852331 0.310775 0.0943098 -0.945793 0.922048 0.082927 -0.378087 0.837585 -0.0620591 -0.54277 0.98538 0.0666629 0.156789 0.997917 -0.0391919 -0.0512345 0.999434 0.0299706 -0.015303 0.952123 -0.0467735 -0.302117 0.838895 0.0865147 0.537374 0.939981 -0.050598 0.337454 0.937789 -0.0361398 0.345321 0.619371 0.0560285 0.783097 0.777225 -0.0512072 0.627136 0.325565 0.0660952 0.943207 0.282673 0.0128151 0.959131 -0.0578355 0.998252 0.0121971 -0.0626779 0.979756 0.190129 0.00405691 0.999965 0.00737576 0.00399813 0.999975 0.00576503 -0.00417185 0.999982 -0.0043719 -0.00553265 0.999971 -0.00517638 -0.00562749 0.999972 -0.0048655 -0.0130673 0.999896 -0.00604247 -0.0173153 0.999843 -0.00371388 -0.0146302 0.999893 -0.000536596 -0.0146398 0.999893 -0.000533647 -0.0187192 0.999821 0.00287576 -0.0132508 0.999878 0.00821663 -0.00510663 0.999985 0.00187502 -0.00615229 0.999975 0.00339243 -0.00485447 0.999974 0.00526633 -0.00577737 0.99996 0.00680309 -0.00526585 0.999974 0.00500161 -0.00195833 0.999637 -0.0268836 -0.0116853 0.999806 -0.0158396 -0.0031898 0.999975 -0.00631224 0.00243324 0.99998 -0.00591676 0.00252879 0.99995 -0.00972024 0.0036595 0.999937 -0.0106068 0.00437947 0.999961 0.00760331 0.00458655 0.999984 0.00318225 0.00629393 0.999973 0.00370772 0.00728078 0.99997 0.0026878 0.00811731 0.99996 0.00362985 0.0144835 0.999892 0.00232749 0.0163561 0.999866 -0.000796817 0.0166182 0.999862 -0.000718204 0.029701 0.999371 -0.0193916 0.00564387 0.999982 -0.00220454 0.00511512 0.999972 -0.00554562 0.00365868 0.999988 -0.00327639 0.00398115 0.999974 -0.00594552 -0.0247009 0.204908 0.978469 -0.320256 -0.386184 0.865042 -0.504586 0.411408 0.759037 -0.642945 -0.317688 0.696919 -0.904754 0.157802 0.395625 -0.845155 -0.310694 0.43495 -0.995373 -0.095111 -0.0136444 -0.900675 0.164747 -0.402049 -0.681617 -0.157206 -0.714622 -0.635606 0.162517 -0.754714 -0.37046 -0.142133 -0.91791 0.556814 -0.0486847 0.829209 0.713249 0.314284 0.626499 0.590542 0.792356 0.153076 0.779305 0.586441 -0.220843 0.511949 0.775633 -0.369191 -0.726046 0.462304 -0.50905 -0.574497 0.800063 -0.172776 -0.988351 -0.139294 -0.0613144 -0.469192 0.848347 0.245289 -0.675944 0.260908 0.689222 -0.454803 0.712007 0.534976 -0.2748 0.823538 0.496256 -0.225002 0.319438 0.920507 0.151116 0.987784 0.0380288 0.41818 0.895133 -0.154476 0.677025 -0.267918 -0.685461 0.189333 0.958544 -0.212945 0.0637528 0.976075 -0.207879 -0.0147895 0.986903 -0.160637 -0.339846 0.893888 -0.292352 -0.0555671 0.998249 -0.0202732 -0.960256 -0.15354 0.233095 0.522551 0.849861 0.0683897 0.556849 0.82578 -0.089478 -1 -0.000669206 0.00017803 -0.999999 0.000539609 -0.00100398 -0.0504209 -0.0251538 -0.998411 0.0189689 0.00758827 -0.999791 -0.0176725 -0.0710765 -0.997314 0.00121412 -0.0263112 -0.999653 -0.00673231 0.0101869 -0.999925 2.97546e-05 0.00238152 -0.999997 -0.00105969 0.00134715 -0.999999 -1 -3.53591e-05 0.000277273 -0.999999 0.000462941 0.000993879 0.118113 0.107751 0.987137 -0.011558 0.0289434 0.999514 -0.0631717 -0.0912779 0.99382 -0.0192661 0.0585377 0.998099 -0.00126026 0.0229046 0.999737 0.00157388 0.0146263 0.999892 -0.00099337 0.00178741 0.999998 -0.0186761 -0.0152362 0.999709 -0.139235 -0.0590686 -0.988496 -0.0922304 -0.0285875 -0.995327 -0.850577 -0.00352318 -0.525839 -0.602232 -0.0365543 -0.797484 -0.718461 0.021559 -0.695234 -0.738973 -0.00984291 -0.673663 -0.850216 -0.00137367 -0.526432 -0.849707 -0.00247834 -0.52725 -0.982709 -0.0231703 -0.1837 -0.999985 -0.0004814 -0.00547313 -0.999976 -0.00700362 0 -0.98269 -0.0239801 0.183697 -0.978886 -0.00276884 0.204386 -0.848936 -0.00255052 0.528489 -0.55148 0.00263785 0.834184 -0.550503 0.00291677 0.834828 -0.601992 -0.0461548 0.797167 -0.738939 0.013801 0.673631 -0.717894 -0.0292169 0.695539 -0.850177 0.00974494 0.526407 -0.843127 -0.00727 0.537665 -0.0922668 0.00530676 0.99572 -0.0578999 -0.0457058 0.997276 -0.108897 -0.0210866 -0.993829 -0.24474 0.00145585 -0.969588 -0.273653 -0.00845127 -0.961791 -0.413084 0.00176601 -0.910691 -0.445719 -0.00936178 -0.895124 -0.558372 0.0026114 -0.829586 -0.548351 -0.00411082 -0.836238 -0.929675 8.15662e-05 -0.368381 -0.932469 -0.00274838 -0.36124 -0.977672 0.00296927 -0.210116 -0.97545 -0.00349734 -0.220192 -0.926427 -3.95102e-05 0.376475 -0.932458 -0.00549651 0.361236 -0.974313 0.00482527 0.225146 -0.445719 -0.00934358 0.895124 -0.412568 0.00172657 0.910925 -0.273653 -0.00845131 0.961791 -0.244123 0.00166563 0.969743 -0.135292 -0.0139116 0.990708 0.00117144 -0.999999 -0.00100035 -0.00318405 -0.997943 -0.0640221 -0.00154206 -0.999999 -0.000129069 0.0177373 -0.997828 0.0634389 0.0561802 -0.998417 -0.00261941 -0.000557902 -1 0.000227361 -0.00044543 -1 -0.000440489 -0.00624635 -0.999972 -0.00421635 -0.00265056 -0.999979 -0.00592642 -0.003274 -0.999968 0.00732827 -0.000235823 -1 0.000564073 0.00323561 -0.999995 -0.000735443 -0.0102641 -0.99994 0.00382636 0.0289777 -0.99941 -0.0184182 0.0298158 -0.999539 -0.00580736 0.00056971 -0.999999 -0.00133351 0.00304681 -0.999978 -0.00590986 0.00504678 -0.999959 -0.00757254 0.00305089 -0.999968 -0.00744502 -0.00390453 -0.999947 -0.00955881 -0.00161187 -0.999992 0.0036013 -0.00075628 -0.999999 0.00129696 0.0040122 -0.999992 0.000461122 0.00655075 -0.99997 -0.00420096 0.00575717 -0.99995 -0.00816 0.00535917 -0.999887 0.0140464 0.000231649 -1 0.000556944 -0.000440489 -1 0.00044543 -0.0093397 -0.999857 0.0141175 -0.0129059 -0.999897 0.00620846 -0.0124977 -0.999836 -0.0130791 0.000146264 -0.999999 0.00108269 5.39075e-05 -1 0.000645847 0.00982634 -0.999948 0.00284212 0.00282104 -0.999985 0.00464849 -0.00683569 -0.999943 -0.00820877 0.000629722 -0.99998 -0.00623004 -0.000799773 -0.999999 -0.00147267 -0.000384289 -1 0.000109222 0.0363316 -0.997646 0.0581574 -0.000834981 -0.99919 0.0402312 0.00565771 -0.999982 0.00196229 0.00393097 -0.999981 0.00466953 0.000516438 -1 -0.000216155 -0.000370082 -1 9.69908e-05 -0.00592691 -0.999906 -0.0124027 -0.00628855 -0.999971 -0.00439244 -0.00308613 -0.999944 0.0101025 0.000259238 -0.999845 0.0176211 -0.0155829 -0.999774 0.0144546 -0.00409254 -0.999991 0.00104831 0.0026929 -0.999962 -0.00828578 0.002084 -0.999962 -0.00847509 0.00442054 -0.999987 -0.00258929 -0.0210551 -0.999225 -0.0332726 0.00369855 -0.999383 -0.0349155 -0.0068275 -0.999974 -0.00235722 -0.00114177 -0.999998 -0.001496 -9.97983e-06 -1 -0.000866556 0.00259699 -0.999933 0.0112901 -0.00168941 -0.999906 0.0136079 -0.000991911 -0.999991 0.00408931 -0.0012421 -0.999999 0.00107113 -0.017631 -0.999796 0.00983444 0.00326385 -0.999963 -0.00790639 -0.00177813 -0.999966 -0.00805931 -0.00924008 -0.999923 -0.00829895 -0.000738819 -1 -0.000607208 -0.00212763 -0.999927 0.011866 -0.00295813 -0.999918 0.0124597 0.00417962 -0.999947 0.00942291 -0.00908859 -0.999929 0.00769623 0.0199008 -0.99955 0.0224265 0.0216196 -0.99963 0.0165123 0.00730292 -0.999968 -0.00324522 -0.00233797 -0.999989 0.00407962 -0.00312699 -0.999987 0.00410507 0.00302001 -0.999975 0.00633857 0.00485771 -0.999964 0.00688795 0.0084774 -0.999918 0.00960024 -0.0042347 -0.999943 0.00975245 0.0205664 -0.999482 0.0247575 -0.00209389 -0.999998 -7.21966e-05 -0.00419935 -0.999987 0.00274669 0.00998168 -0.999945 0.0032924 0.00815665 -0.999951 0.00555953 -0.186522 -0.934033 0.304617 0.188405 0.952785 0.238127 -0.125058 -0.97956 -0.157554 -0.191662 -0.98132 -0.0166137 -0.17321 -0.984683 -0.0199238 -0.11801 -0.979739 0.161819 -0.182964 -0.982942 0.0186998 -0.174599 -0.984425 0.0205553 0.00852402 -0.947122 -0.320762 0.0804429 -0.992466 -0.0924184 -0.0966538 -0.989104 0.111043 -0.10861 -0.989656 0.0937317 -0.0475715 -0.717763 -0.69466 -0.028828 -0.706032 -0.707593 0.0519485 -0.847439 -0.528345 0.0946815 -0.942531 -0.320422 0.198736 -0.967497 -0.156379 -0.192062 -0.97411 0.119258 -0.101846 -0.954763 -0.279383 0.153223 -0.879906 -0.449764 0.000337825 -0.999999 -0.000991634 0.372907 -0.925815 -0.0617023 0.204851 -0.974336 0.0933067 -0.209221 -0.977227 -0.0354166 0.483153 -0.871768 0.0811462 0.775973 -0.627176 -0.0672064 0.453373 -0.883256 -0.119628 0.0200643 -0.994936 -0.0984864 -0.0898152 -0.989229 -0.115582 0.13216 -0.873722 0.468129 0.260856 -0.960038 0.101395 0.0535985 -0.983259 -0.17415 0.127424 -0.777396 0.61597 0.195429 -0.658843 0.726453 -0.328388 -0.933269 0.145501 0.0271862 -0.983132 0.180865 -0.0392288 -0.963729 -0.263986 0.000569292 1 -0.000205568 0.0244034 0.999679 -0.00687089 0.00017836 1 0.000154687 -0.000123725 1 4.87436e-05 -0.000272863 1 -9.96183e-05 -0.000519771 1 0.00031385 -0.00082492 1 1.20618e-05 -0.000350764 1 -0.000399701 -0.000211235 1 9.4678e-05 -0.00223853 0.999996 0.00186618 6.9488e-05 1 9.40049e-05 0.00122743 0.999999 0.000124043 0.000624446 1 0.000503123 0.000718503 1 0.000507632 0.000644106 1 0.000652271 0.000613215 1 0.000652771 0.000733419 1 -0.000382297 -0.000470964 1 -0.000704821 -0.000194781 1 -0.000364072 0.000475565 1 5.72956e-05 0.000427464 1 0.000563731 0.000274631 1 0.00092814 0.00037734 1 0.000926889 0.00163334 0.999997 0.00208352 8.44725e-05 0.999992 0.00399475 -0.00329542 0.999994 0.00140125 -0.000550955 1 0.000642678 -0.000547754 1 0.000723522 -0.000357466 1 0.000867491 -0.000300106 1 0.000842588 -0.000322277 1 0.0008038 -0.0015568 0.999999 0.000787803 -6.64956e-05 0.999992 0.00393123 -0.00013217 1 -0.000894608 7.9789e-05 1 -0.000936763 0.000207796 1 -0.000771321 0.000176882 1 -0.000948393 0.000260567 1 -0.000885049 0.000302028 1 1.65457e-05 0.00030899 1 -0.000585363 0.000840501 0.999999 -0.000691228 0.000768992 0.999999 -0.000770697 0.000742327 1 -0.000569169 0.000419524 1 -0.000549538 0.967296 0.15273 0.202516 0.930959 -0.167193 0.324594 0.910203 0.0994954 0.402035 0.818371 -0.146284 0.55576 0.732782 0.255912 0.630507 0.572584 -0.265997 0.775495 0.517358 0.154699 0.84167 0.291808 0.11383 0.949679 0.239055 -0.115784 0.964078 0.00425108 0.99999 -0.00135026 -0.000903255 1 -0.000395625 -3.27335e-05 1 2.61474e-05 0.000400454 0.999999 -0.00127107 0.00039372 0.999999 -0.00126702 0.000901665 1 0.000318692 0.000100042 0.999999 0.00102609 -0.000720244 1 -0.000307254 -0.000572089 0.999999 -0.000948163 0.000317574 1 -0.000499958 0.000468268 1 0.000375201 0.00191472 0.999998 0.000559949 0.000659323 1 -0.000160713 -0.00238459 0.999996 0.00118843 -0.00173625 0.999999 0.000300083 -4.47534e-05 1 0.000205893 0.000101624 1 -0.000232445 8.01107e-05 1 -0.000217583 -3.95797e-05 1 -0.000478346 -0.000269236 0.999999 -0.00144917 -0.000461489 1 -0.000820652 -0.000916866 0.999999 -0.00107275 -0.000687701 1 -0.000515363 -0.00355852 0.999994 0.000188563 0.00317845 0.999995 0.000255376 -0.0861689 0.642654 -0.761295 -0.0824511 0.659653 -0.747034 -0.3821 -0.653016 -0.653888 -0.532999 0.70162 -0.472907 -0.811689 0.0309068 -0.583272 -0.945739 0.254859 -0.201556 -0.663355 -0.0753723 0.744499 -0.32746 0.811928 0.483262 -0.269769 -0.461275 0.845252 0.00163928 -0.999998 -0.00131339 0.0012762 -0.999999 -0.000528088 0.00609142 -0.999976 -0.00336762 0.0193696 -0.999812 -0.000914029 0.0092527 -0.999947 0.00449882 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.0213436 -0.904131 0.426722 0.0854872 -0.984285 0.154513 5.29088e-05 -1 9.56293e-05 -0.000250032 -1 0.00045244 -0.00163928 -0.999998 0.00131339 -0.0012762 -0.999999 0.000528088 -0.00609142 -0.999976 0.00336762 -0.0193696 -0.999812 0.000914029 -0.0092527 -0.999947 -0.00449882 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0213436 -0.904131 -0.426722 -0.0854872 -0.984285 -0.154513 -5.29088e-05 -1 -9.56293e-05 0.000250032 -1 -0.00045244 -0.140958 -0.101852 -0.984762 -0.480605 0.112676 -0.869668 -0.512852 -0.112676 -0.85105 -0.776791 0.0962136 -0.622365 -0.802034 -0.207556 -0.560055 -0.903528 0.20941 -0.373878 -0.95073 -0.20941 -0.228607 -0.986869 0.154663 -0.0465692 -0.986869 -0.154663 0.0465692 -0.95073 0.20941 0.228607 -0.903528 -0.20941 0.373878 -0.802034 0.207556 0.560055 -0.776791 -0.0962135 0.622365 -0.512852 0.112676 0.85105 -0.480605 -0.112676 0.869668 -0.140958 0.101852 0.984762 0 1 0 0 1 0 0 1 0 0 1 0 0.0213436 0.904131 0.426722 -0.0854872 0.984285 0.154513 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.00319637 0.999994 -0.00159622 0.00751625 0.999894 -0.0124728 0.000297281 0.999857 -0.016928 -0.0194608 0.899635 -0.436208 0.0590125 0.944642 -0.322754 -0.00227468 0.999993 -0.00310201 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.302366 -0.542655 -0.783645 -0.581436 0.535951 -0.612118 -0.591289 -0.674884 -0.441486 -0.887103 0.415733 -0.200538 -0.761433 -0.642559 -0.0856599 -0.69464 0.665883 0.272168 -0.39561 -0.865928 0.306042 -0.664416 0.160434 0.72994 -0.248682 0.480508 0.840993 -0.0630671 -0.827985 0.557193 0.0125138 -0.998005 -0.0618839 0.0271358 -0.99933 -0.0245488 0.00649477 -0.999975 -0.00279196 0.014615 -0.999887 -0.00339391 0.00928281 -0.999955 0.00209846 0.102129 -0.994013 0.0388297 0.113833 -0.991843 0.0573511 0.00517175 -0.999971 0.00555706 0.00741611 -0.999897 0.0123066 0.00208167 -0.999971 0.00727551 -0.00165024 -0.991749 0.128182 -0.0399468 -0.990067 0.134802 -0.0340672 -0.992033 0.121288 -0.068264 -0.994845 0.074996 -0.0558861 -0.99619 0.0669427 -0.00701806 -0.999971 0.00283076 -0.014615 -0.999887 0.00339391 -0.00928281 -0.999955 -0.00209846 -0.102129 -0.994013 -0.0388297 -0.135365 -0.986554 -0.0915856 -0.00502057 -0.999973 -0.00539789 -0.0019248 -0.999934 -0.0113197 -0.0159663 -0.994369 -0.104762 -0.175992 -0.914788 -0.363579 -0.15738 -0.981463 -0.109366 -0.518466 0.850458 -0.088962 -0.309097 -0.948318 0.0717791 -0.181869 0.97454 0.131129 0.0704448 0.960203 0.270273 0.225206 -0.899788 0.373717 0.367712 0.885529 0.283947 0.518466 0.850458 0.088962 0.309097 -0.948318 -0.0717791 0.250045 0.95526 -0.157976 0.363876 -0.876811 -0.314321 0.342103 -0.123527 -0.931508 -0.000366415 -1 -0.00085573 -0.000560018 -1 -0.000391273 -0.0548916 -0.997367 -0.0474012 -0.0956334 -0.994565 -0.0411746 -0.0735922 -0.997173 -0.0151693 -0.030692 -0.999512 0.00579715 -0.0379858 -0.999253 0.00717482 -0.0244553 -0.999699 -0.00198687 0 -1 0 0 -1 0 -0.0256711 -0.999621 0.00990617 -0.0562733 -0.996642 0.0594829 -0.0609475 -0.993276 0.0984337 -0.0260182 -0.997135 0.0710304 -0.00631311 -0.999207 0.0393005 -0.0237352 -0.996315 0.0824151 0.0135253 -0.980347 -0.196819 0.032563 -0.998253 -0.0493083 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.030692 -0.999512 -0.00579715 0.0735922 -0.997173 0.0151693 0.0956334 -0.994565 0.0411746 0.0428922 -0.997867 0.0492169 0 -1 0 0 -1 0 0 -1 0 0.0142103 -0.999829 0.0118318 0.0181354 -0.998412 0.0533325 0.0126426 -0.995292 0.0960955 -0.0570627 0.0673071 -0.996099 -0.143379 -0.0237034 -0.989384 -0.340098 -0.00403496 -0.940381 -0.336139 0.0009883 -0.941812 -0.527862 -0.0484931 -0.847945 -0.684874 -0.0094152 -0.728601 -0.640705 0.0567248 -0.765689 -0.81887 -0.0460562 -0.572128 -0.918182 -0.0257692 -0.39532 -0.878634 0.0439366 -0.475469 -0.979383 -0.00738793 -0.201877 -0.976899 0.00991141 -0.213472 -0.994555 -0.104106 -0.00474517 -0.979914 -0.0115307 0.199087 -0.918182 -0.0257693 0.39532 -0.976898 0.0099152 0.213475 -0.81887 -0.0460577 0.572128 -0.878635 0.0439407 0.475469 -0.687202 -0.00999142 0.726397 -0.526282 -0.0239019 0.849974 -0.67663 0.00658613 0.736294 -0.124413 0.0230286 0.991963 -0.145268 -0.0040154 0.989384 -0.343564 -0.047293 0.937938 -0.453173 0.0433228 0.890369 -0.00153183 -0.999999 -0.000356046 -0.00140497 -0.999999 -0.000262635 -0.00147692 -0.999999 -0.000572162 -0.00121747 -0.999999 -0.000668624 -0.0012973 -0.999999 -0.000803254 -0.00117912 -0.999999 -0.00107491 -0.000904933 -0.999999 -0.00103229 -0.000951478 -0.999999 -0.00125996 -0.000771526 -0.999999 -0.00154943 -0.000913045 -0.999998 -0.00161562 -0.000659087 -0.999997 -0.00231645 -0.000764371 -0.999997 -0.00232743 -0.00033519 -0.999993 -0.00361729 0.000395144 -0.999991 -0.0042643 0.00170845 -0.999994 -0.00306661 0.000404362 -0.999999 -0.00142119 0.000799751 -0.999998 -0.00160612 0.00104277 -0.999999 -0.00121519 0.000812682 -0.999999 -0.00107616 0.00125609 -0.999999 -0.00114508 0.00140353 -0.999999 -0.000806178 0.00127256 -0.999999 -0.000787938 0.00123632 -0.999999 -0.00080263 0.0020837 -0.999997 -0.000807228 0.00318494 -0.999995 -0.000595368 0.00410317 -0.999992 0 0.00385531 -0.999992 0.000720683 0.00172628 -0.999998 0.00135359 0.00151499 -0.999999 0.000586909 0.00123605 -0.999999 0.000699961 0.0012973 -0.999999 0.000803254 0.00117912 -0.999999 0.00107491 0.000904933 -0.999999 0.00103229 0.000951478 -0.999999 0.00125996 0.000771525 -0.999999 0.00154943 0.000876958 -0.999998 0.00159874 0.000641517 -0.999997 0.0022547 0.000654745 -0.999997 0.00225597 0.00027903 -0.999995 0.00301123 -0.00115305 -0.999995 0.00299772 -9.69678e-05 -0.999999 0.00104645 -0.000340395 -0.999999 0.00119636 -0.000356945 -0.999999 0.00117343 -0.000727224 -0.999999 0.00146046 -0.00139915 -0.999998 0.00143053 -0.000812682 -0.999999 0.00107617 -0.00125609 -0.999999 0.00114508 -0.00141039 -0.999999 0.000790408 -0.00123573 -0.999999 0.000765133 -0.00161298 -0.999999 0.000624871 -0.0015394 -0.999999 0.000308344 -0.00159279 -0.999999 0.000297743 -0.0019041 -0.999998 0 0.939965 -0.0180314 0.340796 0.0874572 -0.000183187 0.996168 0.0456526 0.0203069 0.998751 0.169144 -0.0117169 0.985522 0.950329 0.00195673 0.311242 0.893536 -5.66089e-05 0.448992 0.89618 0.00251593 0.443683 0.811671 -0.00231014 0.584111 0.814554 -0.000159535 0.580087 0.713707 -0.00413991 0.700432 0.70533 0.000178423 0.70888 0.594605 -0.00593768 0.803996 0.580204 0.000638291 0.814471 0.461223 -0.006766 0.887258 0.437434 0.0021742 0.899248 0.33564 -0.00625598 0.941969 0.277552 0.0102125 0.960656 -0.656094 0.533996 0.533282 0 1 0 -0.000730857 0.999997 -0.00234917 -0.451647 0.867348 0.209098 -0.0450355 0.996756 0.066702 -0.0669857 0.997719 0.00839274 -0.00021176 1 -1.38891e-05 -0.00331187 0.999994 0.00106298 -0.000322459 -0.999999 -0.00106125 -0.00251461 -0.999993 0.00270795 -0.00556876 -0.999881 -0.014397 -0.0134199 -0.99991 -0.00068057 -0.0220407 -0.999739 0.00599399 -0.00311773 -0.999995 0.0011318 -0.00308769 -0.999995 0.00108606 0.00327969 -0.999994 -0.00151204 -0.00344462 0.999994 -0.000257648 -0.00307036 0.999995 -0.0011558 -0.00305666 0.999995 -0.00112648 -0.0010952 0.999999 0.000337903 -0.00324627 0.999991 -0.00288879 -0.0777638 0.996228 -0.0385148 -0.00248991 0.99999 -0.0036751 -2.90959e-05 1 -0.000125045 -0.000918129 -0.999997 0.0023492 0.00511573 -0.999619 -0.027119 0 -1 0 -0.860328 -0.347683 -0.372763 -0.000169209 -1 -0.000172606 0.000284501 -1 0.000204196 -0.00332057 -0.999994 -0.00117289 0.0181661 -0.999808 -0.00728729 -0.995859 -0.0277216 0.0865777 -0.966829 -0.0894726 0.239241 -0.158779 0.0599716 0.985491 -0.955882 -0.0657555 -0.286297 -0.837953 0.0165434 -0.545492 -0.242142 0.1751 0.95431 -0.989996 -0.135698 -0.0386429 -0.58152 0.0455176 -0.812258 -0.980199 -0.184957 0.070725 -0.948393 -0.119403 0.293758 -0.967404 -0.236427 -0.0907277 -0.889509 -0.105397 -0.444595 0.144173 0.0204708 0.989341 -0.839459 -0.448217 0.307263 -0.977274 -0.198364 0.0747534 0.0728742 -0.564899 0.821936 -0.789894 0.313649 0.526965 -0.0809367 -0.400145 -0.912871 0.483807 -0.66686 0.56677 0.43533 0.899899 -0.0258687 0.209809 -0.973504 -0.0909398 0.988305 0.126377 0.085333 0.487183 -0.66582 -0.565098 0.572789 -0.657771 -0.489132 0.312192 -0.899739 -0.30497 0.046769 -0.774517 -0.630822 -0.566394 -0.664648 -0.487279 -0.542786 -0.649201 -0.532842 -0.463736 -0.740759 -0.486029 -0.174977 -0.98005 0.0942636 -0.668408 -0.726183 0.160902 -0.995876 0.035813 -0.0833538 -0.885601 0.454862 -0.0938652 -0.469022 -0.726956 0.501551 -0.56124 -0.617479 0.551116 -0.56297 -0.667625 0.487177 0.713226 -0.4942 -0.497066 0.75929 -0.641621 0.108638 0.369366 0.869273 -0.328532 0.116168 -0.979826 -0.162621 0.10594 -0.994139 -0.0215521 -0.249947 -0.950751 -0.183302 0.00339195 -0.999949 0.00948737 -0.522928 0.0311859 -0.851806 -0.336544 -0.02554 -0.941321 0.569833 -0.00970115 -0.821703 0.714267 0.0440577 -0.698486 -0.951212 -0.00646713 -0.308471 0.00374464 -0.999991 -0.00198557 0.173593 -0.397528 0.90102 -0.179966 -0.980952 -0.0731091 -0.0237511 -0.980144 -0.196862 0.0938871 -0.981717 -0.165581 -0.972508 0.0102532 -0.232643 -0.925954 -0.033361 -0.376159 -0.119775 0.00916976 -0.992759 0.0111572 0.0459675 -0.998881 -0.0310348 -0.99951 -0.00418125 -0.0254011 -0.975348 -0.219205 0.181094 -0.977312 -0.109847 0.0933032 -0.916857 0.388159 2.2064e-06 -1 9.17905e-06 -0.249261 -0.967854 -0.0335824 -0.115025 -0.0380067 -0.992635 0.23252 0.0357641 -0.971934 0.853796 -0.0531082 -0.517892 0.997418 0.0709414 0.0111264 -0.0923815 -0.995724 0.000528227 0.0235015 -0.996833 -0.0759671 0.0811379 -0.996333 -0.0271701 0.0644748 -0.996636 0.050592 0.0229197 -0.996994 0.0740149 0.851806 0.0311859 -0.522928 0.94779 -0.0310554 -0.31738 0.786681 0.00916915 0.617292 0.698426 0.0459673 0.714204 0.307241 -0.00653902 -0.951609 0.0743522 -0.996615 -0.0350836 0.0874227 -0.995694 0.030835 0.0278708 -0.995293 0.0928143 -0.0836186 -0.994035 -0.0700161 -0.0635499 -0.995079 0.0760269 0.94204 -0.0464496 0.332268 0.658915 0.0636489 0.74952 0.287491 -0.0273894 0.957392 0.895882 0.0100572 -0.444178 -0.10594 -0.994139 0.0215521 0.249947 -0.950751 0.183302 -0.00339195 -0.999949 -0.00948737 0.522928 0.0311859 0.851806 0.336544 -0.02554 0.941321 0.951212 -0.00646713 0.308471 0.0793454 -0.994516 -0.0681397 0.0507771 -0.995293 0.0825467 -0.0823147 -0.995025 0.0561274 -0.0726074 -0.996634 -0.0380582 0.447534 -0.0337091 0.893631 -0.885768 0.00418237 -0.464109 0.0923815 -0.995724 -0.000528227 -0.0235015 -0.996833 0.0759671 -0.0811379 -0.996333 0.0271701 -0.0644748 -0.996636 -0.050592 -0.0229197 -0.996994 -0.0740149 -0.851667 0.0311762 0.523156 -0.947788 -0.0311278 0.317379 -0.786681 0.00917277 -0.617292 -0.698624 0.0459063 -0.714015 -0.307241 -0.00654528 0.951609 -0.431198 -0.0242751 -0.901931 -0.332414 0.0103213 -0.943077 -0.895917 -0.0112954 0.444079 -0.949249 0.050308 0.310477 0.331758 -0.0365575 -0.942656 0.460051 0.00758364 -0.88786 0.901795 -0.0218587 -0.431611 0.939648 0.0102049 -0.34199 -0.417803 -0.011714 -0.908462 -0.314119 0.023644 -0.949089 0.943819 -0.0206799 0.329816 0.910125 0.00932814 0.41423 0.32451 -0.0138214 -0.945781 0.431237 -0.0242616 0.901912 0.332414 0.0103296 0.943077 0.906016 -0.00194027 -0.423239 0.94755 -0.0111828 0.319411 -0.901795 -0.0218587 0.431611 -0.939648 0.0102049 0.34199 -0.93218 -0.0427975 -0.359456 -0.324512 -0.0138281 0.94578 -0.94755 -0.0111828 -0.319411 -0.534405 -0.347222 0.770615 -0.663363 0.0903758 -0.74282 -0.805582 -0.487233 -0.337106 0.0816783 0.471976 0.87782 0.00905297 0.891045 0.453825 0.0134947 0.89794 0.439912 -0.00517975 0.986479 -0.163803 0.0207504 0.998655 -0.0475234 -0.00582251 0.98303 0.183354 0.00908682 0.876078 -0.482085 -0.00250885 0.864536 -0.502564 0.0766183 0.429634 -0.899747 -0.0397373 0.640475 -0.766951 0.017636 0.865292 -0.500958 0.999998 -0.00024971 0.00186923 0.996689 0.0494022 0.0645721 0.998092 0.0488531 0.037767 0.999999 -0.000895486 -0.000851759 0.999994 0.000502169 -0.0033548 0.999996 0.000884749 -0.0028082 0.999907 0.0110598 -0.00803857 0.999885 0.0151332 0.000930546 0.999451 -0.0326086 -0.00585617 0.946606 -0.168032 -0.275141 0.937287 -0.281746 -0.205211 0.979969 -0.198923 -0.00949829 0.999998 0.000410096 -0.00214907 0.999985 -0.00159369 0.00527749 0.999982 -0.00269696 0.00531975 0.999934 0.009888 -0.00591984 0.999885 -0.0125335 -0.00848326 0.999871 -0.016025 -0.000786226 0.999985 -0.000921259 0.00531338 -0.763444 -0.64127 -0.0769747 -0.714742 0.674602 0.184544 -0.795719 -0.491322 0.354166 -0.292948 0.0168015 -0.955981 -0.218149 0.413749 -0.883868 -0.737523 0.628441 -0.247227 -0.944957 0.310129 0.104285 -0.888543 -0.0258078 -0.458066 -0.884585 -0.0310228 -0.465347 -0.632429 -0.0880645 -0.769596 -0.876998 0.0363712 -0.479116 -0.230355 -0.132709 -0.964015 0.0180519 1.39646e-05 -0.999837 -0.144757 0.122345 -0.981874 -0.152906 -0.0243738 -0.98794 -0.940757 -0.00566001 -0.339035 -0.992615 -0.0132966 0.120574 -0.913148 0.014865 0.407356 -0.880629 0.0458461 0.471583 -0.677069 0.0696657 0.732615 -0.884126 -0.0413652 0.465415 -0.0246834 0.0002182 0.999695 -0.0348997 -0.0054383 0.999376 -0.144761 -0.109515 0.983387 -0.487161 -0.039408 0.872423 -0.151009 0.0927006 0.984176 -0.99054 0.00481368 -0.13714 -0.992333 0.00242167 -0.123573 -0.95141 -0.000972519 0.307925 -0.368685 -0.00330439 -0.929548 -0.70661 -0.00516468 0.707584 -0.396383 0.00299168 0.91808 -0.356144 -0.675716 0.645422 0.875935 -0.319034 -0.361877 -0.294489 -0.0291899 0.955209 -0.610902 0.478151 -0.631007 -0.0899864 0.995549 -0.0279956 0.820672 -0.431789 -0.37424 -0.897093 -0.239249 -0.371463 -0.0821731 0.996442 0.0187584 0.335412 0.936863 -0.0989239 0.0365677 0.9917 -0.123266 0.852421 0.0479179 0.520655 -0.919849 0.103045 0.378496 -0.956181 -0.286567 0.0599794 0.718748 0.687066 -0.106494 0.129842 0.986197 0.102743 -0.990291 0.113552 -0.0801842 0.0305316 0.183165 -0.982608 -0.0305418 0.600555 -0.799 -0.0190936 0.585037 -0.810782 0.0207089 0.973089 -0.229496 -0.0209449 0.986939 -0.15973 0.0181867 0.878535 0.477332 -0.03952 0.81027 0.584722 0.0300896 0.550332 0.834404 -0.0244673 0.15372 0.987812 -0.020981 0.159625 0.986955 0.96052 -0.0782085 -0.266992 1 0 0 1 0 0 1 0 0 0.958527 0.0438233 0.281611 0.884649 -0.457026 0.0923238 0.350796 0.410301 -0.841781 0.942759 0.329536 -0.0511027 -0.803703 0.571411 0.165985 0.961712 0.046258 0.270131 0.999935 -0.010072 -0.00539607 0.999996 -0.00294598 0.000456847 0.949575 0.00596747 0.313483 0.268182 -0.962951 0.0283365 0.120013 -0.990771 0.0629971 0.26449 -0.378254 -0.887113 -0.4915 0.765044 0.416096 0.00359224 -0.716125 -0.697963 -0.00311405 -0.699498 -0.714627 0.00366955 -0.700244 0.713894 -9.44802e-05 -0.709667 0.704537 0.00291509 0.700161 -0.713979 -0.00031198 0.707727 -0.706485 0.00380793 0.71604 0.698048 0 0.707217 0.706997 -0.916844 0.0760375 -0.391937 -0.90144 -0.425394 -0.0802895 -0.901243 0.425922 0.0796956 -0.917222 -0.0763975 0.390982 0.47092 -0.663832 0.581001 0.504522 0.808098 -0.304031 0.240936 0.413225 -0.878177 -0.997565 0.0480003 -0.0505901 -0.344159 -0.0923359 -0.93436 -0.920659 0.0191227 0.3899 -0.988955 -0.0591141 -0.13592 0.113919 0.214166 0.970132 -0.0112418 0.992506 -0.121679 0.00192501 0.275241 0.961374 -0.0605746 0.997975 0.0194178 0.66417 -0.677532 0.315957 0.978676 0.00803547 -0.205253 0.984384 0.000504031 -0.176031 -0.962309 0.020178 -0.271209 -0.980448 0.000108798 -0.196776 -0.979518 0.00843733 -0.20118 0.250359 0.787319 0.563426 -0.743978 0.486459 0.458099 0.00134158 0.00166756 0.999998 0.00851685 -0.012134 -0.99989 -0.00479073 -0.000479047 0.999988 -0.00384179 -0.991574 -0.129481 -0.89855 0.363093 -0.246521 0.196697 -0.962733 0.185624 -0.941264 -0.329398 0.0742885 0.336813 -0.633962 -0.696168 0.422722 0.896412 -0.133238 -0.425815 0.895309 0.130784 0.399198 -0.0554336 0.915187 -0.439671 0.887741 -0.136402 0.439245 0.887976 0.136246 0.426214 0.895094 -0.130951 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + + + + + + + + + + + +
diff --git a/descriptions/deep_robotics/x30_description/meshes/l_thigh.dae b/descriptions/deep_robotics/x30_description/meshes/l_thigh.dae new file mode 100755 index 0000000..0cd3ee5 --- /dev/null +++ b/descriptions/deep_robotics/x30_description/meshes/l_thigh.dae @@ -0,0 +1,63 @@ + + + + + VCGLab + VCGLib | MeshLab + + Y_UP + 周四 11月 23 02:57:46 2023 + 周四 11月 23 02:57:46 2023 + + + + + + + + + -0.03284 0.02575 0.0380382 -0.00493975 -0.02525 0.0573558 -0.0483868 -0.02525 0.0399535 -0.0548546 -0.02525 0.0304719 -0.0621296 -0.02525 0.00880166 -0.0626935 -0.02525 -0.00266199 -0.0611599 -0.02525 -0.0140366 -0.0575802 -0.02975 -0.0249416 -0.0481813 -0.02975 -0.0405697 -0.036078 -0.02525 -0.0513414 -0.026123 -0.02975 -0.0570539 -0.000169368 -0.02525 -0.0627442 0.00751925 -0.02525 -0.0622979 0.0187405 -0.02525 -0.0598862 0.0187405 -0.02975 -0.0598862 0.0293349 -0.0297504 -0.0554716 0.0444568 0.02575 -0.0228821 0.0478095 0.02575 -0.0146372 0.0384193 0.02575 -0.0322973 0.046777 0.01975 -0.018161 0.0234564 0.02575 -0.0441565 0.0040773 0.02575 -0.00968681 0.0152556 0.02575 -0.0476158 0.0152556 0.01975 -0.0476158 -0.00367792 0.02575 -0.0500884 -0.0039647 0.02575 -0.00972992 -0.0196378 0.02575 -0.0461765 -0.0441565 0.02575 -0.0234564 -0.00968576 0.02575 -0.00407727 -0.0499954 0.02575 -0.00432888 -0.0476158 0.02575 -0.0152556 -0.0444568 0.02575 0.0228821 -0.0478096 0.02575 0.0146372 -0.0152556 0.02575 0.0476158 -0.0234564 0.02575 0.0441565 -0.0319799 0.0197502 0.0371914 0.0181609 0.01975 0.0467771 0.0146372 0.02575 0.0478096 0.0476158 0.02575 0.0152556 0.0441565 0.02575 0.0234564 0.0459181 0.01975 0.0202346 0.0228821 0.02575 0.0444568 0.00367797 0.02575 0.0500888 0.0166245 -0.02525 -0.0550443 0.0245944 -0.0181632 -0.0519715 0.055636 -0.02525 -0.0145219 0.0325146 -0.0297498 -0.0632455 0.00221091 -0.02975 -0.088816 -0.00395358 -0.02975 -0.0626253 0.00751925 -0.02975 -0.0622979 0.0143782 -0.0298308 -0.0864577 -0.0152941 -0.02975 -0.0608576 -0.0620485 -0.02975 -0.0378395 -0.036078 -0.02975 -0.0513414 -0.0403847 -0.0302591 0.0480356 -0.04825 -0.0302182 0.0401593 0.0125173 -0.0300159 0.061488 -0.0310941 -0.0303203 0.0545221 -0.0100298 -0.0301813 0.0619453 -0.0207434 -0.030158 0.0592294 0.0496437 -0.0302287 0.0383706 -0.0688365 -0.02375 -0.0364627 -0.0687482 -0.02375 -0.0125475 -0.0679049 -0.02375 0.00013944 -0.0624056 -0.0299788 -0.0090544 -0.0617591 -0.0301514 0.0123599 -0.0627459 -0.02375 0.0240381 -0.0550116 -0.0302099 0.030187 -0.048622 -0.02375 0.0452771 -0.0414396 -0.023788 0.051905 -0.0272907 -0.02375 0.0606684 -0.0177872 -0.02375 0.0644012 -0.00624931 -0.02373 0.0669167 0.0150957 -0.0236808 0.0656496 0.00146383 -0.0302536 0.0627453 0.0227302 -0.0298266 0.0589281 0.0421444 -0.0301888 0.0464979 0.0338799 -0.0301752 0.0528427 0.0471537 -0.0236411 0.047223 0.0316221 -0.0237495 0.0590738 0.0551815 -0.0237485 0.0376092 0.0679534 -0.0236521 0.0161124 0.0613829 -0.0240111 0.0282318 0.0620569 -0.0299578 0.00984177 0.0625802 -0.0298612 -0.00454782 0.0611914 -0.0300919 -0.0134822 0.0771002 -0.02375 -0.0268227 0.0727413 -0.0259 -0.0190901 0.0475918 -0.0252176 -0.0587309 0.0372309 -0.0266663 -0.0654376 0.0607158 -0.02525 -0.0158478 0.0574526 -0.02525 -0.00403936 0.0268805 -0.02525 -0.05083 -0.00133634 -0.02525 0.0608802 -0.0608802 -0.02525 -0.00133633 -0.0141969 -0.02525 0.0557198 0.0529794 -0.02525 0.0223481 0.0602111 -0.0252802 0.0176689 0.0624032 -0.02525 0.00658817 0.050108 -0.02525 0.0377723 0.0560679 -0.0252773 0.0281771 0.0490597 -0.02525 0.0299899 -0.0575802 -0.02525 -0.0249416 0.0293516 -0.02525 0.0494443 0.0573038 -0.02525 0.00523229 -0.0520741 -0.02525 -0.0350121 -0.0557171 -0.02525 -0.0142077 -0.0608924 -0.02525 0.000547165 -0.0600412 -0.02525 0.00222744 -0.0403002 -0.02525 0.0480984 -0.00300229 -0.02525 0.0600088 0.033563 -0.02525 0.0530197 0.0402915 -0.02525 0.0445596 0.0370697 -0.02525 0.0440463 -0.0594872 -0.02525 0.0199708 0.0216596 -0.02525 0.0532645 0.0134844 -0.02525 0.0558965 -0.0152941 -0.02525 -0.0608576 -0.0445596 -0.02525 0.0402915 -0.026123 -0.02525 -0.0570539 -0.0134844 -0.02525 -0.0558965 0.0625733 -0.02525 -0.00470604 0.0425245 -0.02525 0.0461436 0.0235141 -0.0252833 0.0581778 0.0127031 -0.02525 0.0614507 0.0014806 -0.02525 0.0627325 -0.00978989 -0.02525 0.0619816 -0.0251597 -0.02525 0.0577355 0.0134844 0.01975 0.0558965 0.0557171 0.01975 0.0142077 0.0557171 -0.02525 0.0142077 0.0490597 0.01975 0.0299899 -0.0223275 -0.02525 0.052988 -0.0299616 -0.02525 0.049077 -0.0494443 -0.02525 0.0293515 -0.0532646 0.01975 0.0216596 -0.0532646 -0.02525 0.0216596 -0.0558965 0.01975 0.0134844 -0.0558965 -0.02525 0.0134844 -0.0490597 -0.01825 -0.0299899 -0.0509376 -0.02525 -0.0269877 -0.0557171 0.01975 -0.0142077 -0.0249535 -0.02525 -0.0519644 0.0749082 -0.02375 -0.0313043 0.0786116 -0.0237499 -0.0217114 0.078995 -0.0237407 -0.0169834 0.0782984 0.0199876 -0.011058 0.0782898 -0.0237594 -0.0114039 0.0759044 0.0193885 -0.00308741 0.0768079 -0.023677 -0.0058322 0.0696265 0.018249 0.0124658 0.0736952 -0.02375 0.00292818 0.0655762 0.0176589 0.0206842 0.0404783 0.0156276 0.0531284 0.0379758 -0.0238208 0.0550444 0.0267249 0.0152668 0.0615632 0.024677 -0.0236983 0.0625147 0.00446935 -0.0236911 0.0672432 -0.0143173 -0.02375 0.0653701 -0.0165644 0.0159993 0.06479 -0.0237431 -0.02375 0.0622515 -0.0326856 -0.02375 0.057798 -0.0253196 0.016385 0.0616783 -0.0331934 0.0168588 0.0575127 -0.0412306 0.017397 0.0521112 -0.053142 -0.0237264 0.0402283 -0.0554426 0.0187517 0.0372364 -0.0576362 -0.02375 0.0340304 -0.0595136 -0.02375 0.0308998 -0.0590255 0.019144 0.0319072 -0.06549 -0.0237711 0.015671 -0.0673905 -0.02375 0.00460652 -0.0669881 0.0209297 0.0076761 -0.0688941 0.0225187 -0.0174423 -0.0689425 -0.02375 -0.0304863 -0.0689694 0.0230336 -0.027312 0.0734546 -0.02375 -0.0337041 0.070035 0.0219376 -0.0385578 0.0680421 -0.0237548 -0.0411893 0.0577526 -0.0237503 -0.0526915 0.0491189 0.0235239 -0.061352 0.0479086 -0.02375 -0.0625364 0.0368214 -0.02375 -0.0731071 0.0378499 0.0240076 -0.0721437 -0.0539307 -0.0237572 -0.0894371 -0.0597591 -0.0237739 -0.0878564 -0.0599062 0.0242171 -0.0877244 -0.0648283 0.0242186 -0.0831718 -0.0665527 -0.0237498 -0.078267 -0.0683333 -0.02375 -0.0509146 -0.0637649 -0.0237529 -0.0846357 -0.0649866 -0.0237579 -0.0826963 -0.0609334 -0.0297505 -0.078087 -0.0485717 -0.02975 -0.0839374 0.0237571 -0.02375 -0.0851147 0.0243676 -0.027399 -0.0792656 -1.76871e-05 -0.023755 -0.0946351 0.0100165 -0.0237901 -0.0935939 0.0145603 -0.0237637 -0.0918866 0.018764 -0.02375 -0.0892443 0.009832 0.0242254 -0.0936748 0.00588211 0.01975 -0.0944544 0.00299127 0.0302068 -0.0886546 0.0146621 0.0242034 -0.0918355 0.0193243 0.0242102 -0.088874 0.0251616 0.0242073 -0.0838604 0.0149773 0.0302074 -0.0851176 0.0547352 0.0302073 -0.0449307 0.057573 0.0230011 -0.0528603 0.0660424 0.022325 -0.0435411 0.0733713 0.0215767 -0.0338463 0.0643757 0.0302073 -0.0321207 0.0766941 0.0211559 -0.0279348 0.0787346 0.0206889 -0.0215853 0.0789445 0.0203501 -0.0165891 0.0681871 0.0302073 -0.0133056 0.0729255 0.0188039 0.00485889 0.0473486 0.0302073 0.0253775 0.0602706 0.0169981 0.030105 0.0540001 0.0164204 0.0391521 0.0477617 0.0159763 0.0465679 0.0333897 0.0154028 0.0580615 0.0235645 0.0302073 0.0465324 0.018682 0.0302073 0.0487336 0.00829666 0.0302073 0.051863 0.020019 0.0151963 0.0642314 -0.00468882 0.0155667 0.0671299 0.00791591 0.0153056 0.0668922 -0.0181804 0.0302073 0.0496546 -0.0499263 0.0181543 0.0440296 -0.0624264 0.0197161 0.0249789 -0.0648422 0.0202769 0.0177378 -0.0592227 0.0302073 -0.00149768 -0.0681926 0.021674 -0.00333002 -0.0618309 0.0302073 -0.0280966 -0.0687032 0.02363 -0.0413129 -0.0620832 0.0302073 -0.0495123 -0.0680903 0.0240473 -0.0559621 -0.066511 0.0242088 -0.0783793 -0.0671845 0.0242065 -0.0713206 -0.0626643 0.0242063 -0.0858264 -0.0545159 0.0242225 -0.0893745 0.000559124 0.0242164 -0.0946878 0.0282117 0.0302073 0.0438719 -0.0408302 0.0302073 0.0361743 -0.0300952 0.0302073 0.0439014 -0.0607443 0.0302107 -0.0794429 -0.0534992 0.0302073 -0.0834615 -0.0472052 0.0302073 -0.0372761 -0.00498514 0.0302073 0.0523639 0.0366256 0.0302073 -0.064631 -0.0555271 0.0302075 0.0146895 -0.0499795 0.0302073 0.0256935 0.0588266 0.0302073 0.00734949 0.0422632 0.0302073 0.0315805 0.0533986 0.0302073 0.0165602 0.0647741 0.0302073 -0.00461159 -0.0156493 0.0302073 -0.0728648 0.0693017 0.0302075 -0.0223799 0.0346358 0.0302073 0.0390664 -0.0526056 0.0282073 -0.0754077 -0.0183637 0.0302073 -0.0812837 -0.0559439 0.0302054 -0.0368913 -0.052864 0.0282073 -0.0352876 -0.0556851 0.0302064 -0.0781537 -0.017779 0.0282072 -0.0748544 -0.00561697 -0.01825 -0.094107 -0.00368047 0.01975 -0.050056 -0.0314747 0.01975 -0.0375799 -0.00561697 0.01975 -0.094107 -0.0187597 0.01975 -0.0461332 -0.0500318 0.01975 -0.00432678 -0.0136192 0.01975 -0.0040889 -0.0379974 0.01975 -0.0327925 0.0573674 0.0197499 0.00489045 0.0607475 0.01975 -0.00102596 0.0595677 0.01975 -0.00269666 0.0529794 0.01975 0.0223481 0.0323216 0.01975 0.0384406 0.0216596 0.01975 0.0532646 -0.0141969 0.01975 0.0557198 -0.0205511 0.01975 0.0458102 -0.0384384 0.01975 0.0323188 0.0234564 0.01975 -0.0441565 0.0385471 0.01975 -0.0614033 0.0233699 0.01975 -0.0529789 0.0326135 0.01975 -0.0609466 0.0268805 0.01975 -0.05083 0.0473547 0.0197501 -0.0549814 -0.0529207 0.01975 -0.0895308 0.0124932 0.01975 -0.0759211 -0.0459181 0.01975 -0.0202347 -0.0600073 0.01975 -0.00300542 -0.0574167 0.01975 0.0041894 -0.0494443 0.01975 0.0293515 -0.046777 0.01975 0.018161 -0.0440909 0.01975 0.0370074 -0.0439937 0.01975 0.0421039 -0.0223275 0.01975 0.052988 -0.0299614 0.01975 0.0490771 -0.00488072 0.01975 0.0573674 0.00418936 0.01975 0.0574168 0.000547174 0.01975 0.0608924 -0.00133634 0.01975 0.0608802 0.0293516 0.01975 0.0494443 0.0434443 0.01975 0.0426705 0.0574219 0.01975 -0.00420343 0.055636 0.01975 -0.0145219 0.0688655 0.01975 -0.0216353 0.0651324 0.01975 -0.0170006 -0.00643475 0.01975 -0.0122145 0.00975535 0.01975 -0.00395548 -0.0534771 0.01975 -0.0214907 -0.0642387 0.01975 -0.0404169 -0.0640763 0.01975 -0.0654135 0.0166245 -0.01825 -0.0550443 0.0233523 -0.01825 -0.0538124 -0.0293516 -0.01825 -0.0494443 -0.0414409 -0.01825 -0.044411 0.00208185 -0.01825 -0.0607239 0.00587794 -0.01825 -0.0944646 0.0234086 -0.01825 -0.064858 -0.0642392 -0.01825 -0.0404172 -0.0371244 -0.01825 -0.0440102 -0.018393 -0.01825 -0.0546322 -0.00418936 -0.01825 -0.0574167 -0.0529208 -0.01825 -0.0895387 -0.05301 0.01975 -0.07635 0.0601042 -0.02525 0.002894 0.0609472 -0.02525 0.00100954 0.0601146 0.01975 0.00287768 0.0606278 -0.02525 -0.001389 0.0609472 0.01975 0.00100954 0.00486792 -0.02525 -0.0573885 -0.0440178 -0.02525 -0.0444774 -0.0437375 -0.01825 -0.0417755 -0.0608802 0.01975 -0.00133633 -0.0608924 0.01975 0.000547166 -0.0600329 0.01975 0.00224012 -0.0445627 0.01975 0.0402817 -0.0439937 -0.02525 0.0421039 -0.0426705 -0.02525 0.0434443 -0.0408805 -0.02525 0.0440306 -0.0426705 0.01975 0.0434443 -0.0408805 0.01975 0.0440306 -0.00300543 0.01975 0.0600073 0.000547174 -0.02525 0.0608924 0.00222744 -0.02525 0.0600412 0.00224012 0.01975 0.0600329 0.0403064 0.01975 0.0445568 0.0421038 -0.02525 0.0439937 0.0421038 0.01975 0.0439937 0.0434443 -0.02525 0.0426705 0.0440306 -0.02525 0.0408805 0.0440337 0.01975 0.0408656 0.00412508 -0.02525 0.0574291 -0.0379251 0.01975 0.043552 -0.0379225 -0.02525 0.0435536 -0.0440462 -0.02525 0.0370697 -0.0574291 -0.02525 0.00412507 -0.0573708 0.01975 -0.00486902 -0.0573576 -0.02525 -0.00493318 -0.0599988 -0.02525 -0.003018 -0.0435278 -0.01825 -0.0376855 -0.0435254 -0.02525 -0.0376916 -0.0371182 -0.02525 -0.0440125 -0.00412131 -0.02525 -0.0574297 0.00486712 -0.01825 -0.0573895 0.0435253 -0.02525 0.0376917 0.0435621 0.01975 0.0376374 0.0371244 0.01975 0.0440102 -0.0534607 -0.0182498 -0.0214581 -0.0640756 -0.01825 -0.0654098 -0.0530137 -0.01825 -0.0763422 0.0124915 -0.01825 -0.0759242 0.0234146 0.01975 -0.064848 0.0293348 -0.02525 -0.055471 0.0314687 0.01975 -0.0595061 0.0686007 0.01975 -0.0234561 0.0652241 0.01975 -0.0316553 0.0616301 -0.0229201 -0.0383165 0.0597785 0.01975 -0.0410217 0.0529978 0.01975 -0.049472 0.0535401 -0.0225937 -0.0489948 0.0368353 0.01975 -0.0620782 0.0369481 -0.0244459 -0.0620993 0.0345942 0.01975 -0.0619982 0.0345606 -0.0259551 -0.0620799 0.0667969 0.01975 -0.0177849 0.0682742 0.01975 -0.0194721 0.0685172 -0.023926 -0.0197269 0.0325108 -0.0277785 -0.0609151 0.0413127 -0.023435 -0.0595958 0.046562 -0.0228814 -0.0555719 0.0614117 -0.0250195 -0.0441392 0.0659987 -0.023272 -0.0300069 0.0661894 -0.0252711 -0.017315 0.0687152 -0.0234512 -0.0231594 -0.0500332 0.01975 0.00368214 0.0500041 0.02575 0.00432893 -0.00432679 0.01975 0.0500365 0.00390604 0.01975 0.0145109 -0.0125215 0.01975 0.00673889 -0.0130227 0.01975 -0.00749876 -0.00390605 0.01975 -0.0145109 -0.0322973 0.02575 -0.0384193 -0.0128972 0.01975 0.00391526 -0.0380185 0.02575 -0.0328171 0.00967969 0.01975 0.00409159 0.00965879 0.02575 0.0040772 0.0500365 0.01975 0.0043268 0.0386589 0.02575 0.0318802 0.0379998 0.01975 0.0327954 0.00396579 0.02575 0.00973191 0.00645514 0.01975 0.0122352 0.0322972 0.02575 0.0384193 0.00368055 0.01975 0.0500569 -0.00407727 0.02575 0.00968576 -0.00409161 0.01975 0.00967971 -0.0501007 0.02575 0.00367703 -0.0132679 0.02575 0.00391548 -0.0131189 0.02575 0.00732934 -0.0384149 0.02575 0.0322918 0.0384406 0.01975 -0.0323216 0.0500884 0.02575 -0.00367794 0.050056 0.01975 -0.00368048 0.00971662 0.02575 -0.0039574 0.00409167 0.01975 -0.0096803 0.00432893 0.02575 -0.0500041 0.0043268 0.01975 -0.0500365 0.0328171 0.02575 -0.0380185 0.0327925 0.01975 -0.0379974 -0.00432892 0.02575 0.0500041 -0.0621118 -0.0252598 0.0105391 -0.0408019 -0.0252595 0.048001 -0.01134 -0.0252635 0.0619706 0.0311236 -0.0252603 0.0547723 0.048001 -0.0252604 0.0408019 0.0590598 -0.02575 0.0219305 0.0483498 -0.0497496 0.0223745 0.0525685 -0.0497498 -0.0089427 0.0182928 -0.0497499 0.0501436 0.012472 -0.0497499 0.0577567 0.0123736 -0.01075 -0.0395915 0.00501166 -0.01825 -0.0429653 0.0129034 -0.01825 -0.0412867 0.0204415 -0.01075 -0.0360935 0.0275906 -0.01075 -0.0309733 0.0334998 -0.01075 -0.0244612 0.0416079 -0.0182495 -0.0126095 -0.00551207 -0.0151928 0.0521547 -0.00115254 -0.0125112 0.0575338 -0.00541636 -0.00977076 0.0522102 -0.0594005 0.0139585 -0.0472106 0.0148709 -0.009506 -0.0524337 0.0154562 -0.0086659 -0.0619011 -0.0534498 0.0166888 -0.0108806 -0.0459455 0.0167495 -0.0293887 -0.0239169 0.0167473 -0.0489797 0.032914 0.0165421 -0.0434696 0.0507581 0.01625 -0.0198393 -0.0390751 0.0163589 -0.0381246 -0.0014629 0.0127492 -0.0547141 0.0574314 0.0166146 -0.00377076 -0.00456418 0.016709 0.0542952 -0.0422345 0.01175 0.0390192 -0.0268709 -0.0281671 0.0466122 0.0148243 -0.0345515 0.0510673 0.0118865 -0.0332296 0.0570213 -0.0533985 -0.0271755 0.0124743 -0.054738 -0.0498111 0.0311892 -0.0452104 -0.0497796 0.0346653 -0.0601353 0.0143429 -0.00053428 -0.033754 -0.040079 -0.0471955 -0.0368256 -0.0502604 -0.0481244 0.0582883 -0.040079 0.00622116 0.0593755 -0.0497594 0.00976678 0.033765 -0.049916 0.0471433 0.0482817 -0.02125 -0.0143051 0.00619427 -0.02265 -0.05044 -0.0292317 -0.02125 -0.0420527 -0.0418893 -0.02125 -0.0283839 -0.0482623 -0.02265 -0.0159156 -0.0480923 -0.02125 -0.0149296 0.0202269 -0.0144556 -0.0317245 -0.0121849 -0.0144406 -0.0355903 -0.0264209 -0.014442 -0.026779 0.0517084 -0.0349268 0.0300562 0.0479832 -0.03403 0.0318681 0.0461031 -0.0497499 0.0313807 0.0578382 -0.0497495 -0.0131664 0.0530989 -0.0226501 0.000344104 0.052258 -0.02265 -0.00941864 0.0453267 -0.02265 -0.0276604 0.0268236 -0.0348559 -0.0456334 0.0239762 -0.02265 -0.0473788 0.022651 -0.0497498 -0.0481917 -0.0179799 -0.0349447 -0.0500025 -0.0233602 -0.02265 -0.0476856 -0.0449644 -0.02265 -0.0282455 0.0394724 -0.02265 -0.0355182 0.0322738 -0.02265 -0.0421665 0.0392449 -0.0497482 -0.0357693 0.0135092 -0.0497516 -0.0514425 -0.0045567 -0.02265 -0.0529041 0.00312489 -0.0497623 -0.0530937 -0.0299496 -0.0497506 -0.043933 -0.0424239 -0.0497499 -0.0321734 -0.0390087 -0.02265 -0.0360268 0.0543543 -0.05075 0.0318529 0.0211645 -0.0252604 0.0593381 0.0211632 -0.05075 0.059339 0.0105391 -0.0252604 0.0621118 -0.000479132 -0.0498165 0.0629948 -0.0485279 -0.0252595 0.0401728 -0.0593433 -0.0499228 0.0211434 -0.0108016 -0.0123104 0.0564199 -0.00223343 -0.021303 0.0574258 5.74033e-05 0.0110927 0.0574754 -0.00559308 -0.0105312 0.0572273 -0.0052241 0.016581 0.0572902 -0.03448 -0.02525 0.046015 -0.0382527 0.0167034 0.0428787 -0.0422345 -0.02525 0.0390192 0.0417252 -0.02525 0.0395633 0.0338807 -0.02525 0.046458 0.0481932 -0.02525 0.0313635 0.0481932 0.01675 0.0313635 0.0530713 -0.02525 0.0221289 0.0561986 0.01675 0.0121643 0.0048507 -0.02525 0.057295 0.0151342 -0.02525 0.0554726 0.0249185 -0.02525 0.0518201 0.0346867 0.0167348 0.0459627 -0.025588 -0.02525 0.0514927 -0.0563515 0.01675 0.0114349 -0.0533536 0.01675 0.0214392 -0.0485956 0.01675 0.0307362 -0.0257359 -0.0107649 -0.028354 0.0322585 -0.0107643 -0.0203017 0.0202552 -0.0107646 -0.0322877 -0.0224058 -0.0107556 0.0309853 -0.0362367 -0.0107608 0.0132735 0.017039 0.0141563 -0.0519224 0.0194076 0.00963255 -0.0509356 0.024253 -0.01825 -0.0488062 -0.0298651 0.00749671 -0.0455675 -0.0297983 0.0112634 -0.045633 -0.0276149 0.0127509 -0.0472742 -0.0395482 0.0055 -0.0374992 -0.0456788 0.0055 -0.0297271 -0.0513267 0.00549951 -0.0188475 -0.0503023 -0.01825 -0.0209744 -0.0456788 -0.01825 -0.0297271 -0.0395482 -0.0055 -0.0374992 -0.0236184 -0.01825 -0.0491164 -0.0281354 -0.0127443 -0.0469212 0.0535154 0.0167185 -0.0104462 0.0460602 -0.01825 -0.0291326 0.0402544 0.0166807 -0.0367943 0.0400309 -0.01825 -0.0369834 0.0246104 0.0167213 -0.0486272 -0.0532665 -0.01825 -0.0115297 0.0380263 -0.01215 -0.0128729 0.0244088 -0.01435 -0.0318736 0.00933441 -0.01435 -0.0390459 0.0404469 -0.0212479 -0.0040088 0.000985528 -0.021248 -0.0407004 0.0160712 -0.0163722 -0.0373445 0.00394261 -0.0164713 -0.0401746 -0.0231258 -0.0212475 -0.0335066 -0.0368911 -0.01625 -0.0167123 0.0165345 -0.0121346 -0.0346423 -0.00132048 -0.0120907 -0.0380207 -0.024851 -0.0121316 -0.0310369 -0.0348594 -0.01215 -0.0191471 -0.0359851 -0.0107654 -0.0125623 0.00919835 0.0160034 -0.0749484 -0.0509166 0.0159188 -0.075336 0.0113601 -0.0497817 -0.0619656 0.0318529 -0.05075 -0.0543543 0.0407968 -0.05075 -0.0480028 0.0620845 -0.05075 -0.00939394 0.0590216 -0.0507499 0.0220658 0.0480027 -0.05075 0.0407968 0.0374181 -0.0476792 0.0472496 0.0407873 -0.0497926 0.0480597 0.0324167 -0.0507584 0.0541671 0.0105324 -0.05075 0.0621112 -0.0113417 -0.05075 0.0619707 -0.0108238 -0.0461009 0.0580335 -0.00653354 -0.049739 0.0559975 -0.0222864 -0.0507499 0.0589585 -0.0619684 -0.0498125 -0.0113477 -0.0595311 -0.05075 -0.00651399 -0.0482085 -0.0498254 0.0406346 -0.0480027 -0.05075 -0.0407968 -0.035179 -0.0498036 -0.0449982 -0.0324032 -0.0498156 -0.0541715 0.0339333 -0.012137 0.017233 0.00188618 -0.0116604 0.0379212 -0.0373009 -0.0121555 0.0113083 -0.00850646 -0.0107435 -0.037325 -0.0311046 -0.01075 -0.0274425 -0.0360108 -0.01075 -0.0205867 -0.0394295 -0.01075 -0.0128804 0.00411582 -0.01075 -0.0412753 0.0150239 -0.0107448 0.0388375 0.0388292 -0.0107648 0.00311257 0.0406037 -0.01075 -0.00848105 0.0379035 -0.01075 -0.0168498 0.00246923 -0.0107545 -0.0381695 0.000657508 0.00643594 -0.0557762 -0.00265911 0.00875 -0.0557131 0.00401167 0.00523697 -0.0605009 0.00408128 -0.00434265 -0.055634 -0.00144542 -0.0127391 -0.0558212 0.000369776 -0.00747581 -0.0557797 -0.0093896 0.00875 -0.0549805 0.054561 -0.0182502 -0.000285998 0.0534114 -0.01825 -0.0108383 0.05057 -0.01825 -0.0203206 0.0327133 -0.0182496 -0.0286366 0.0213167 -0.01825 -0.0376389 0.032681 -0.01825 -0.0436142 0.0125086 -0.0182515 -0.0531272 0.032561 -0.01825 0.0437039 0.0400372 -0.01825 0.0369766 0.0461499 -0.01825 0.0289902 0.0506911 -0.01825 0.0200166 0.053506 -0.01825 0.0103613 0.0432326 -0.0182497 0.00451726 0.0145746 -0.01825 0.0525151 0.0101411 -0.01825 0.0535363 0.00737252 -0.0212484 0.0400101 -0.0335481 -0.0164458 0.0229625 0.0244095 -0.0164318 0.0321781 0.0337802 -0.0164689 0.0225947 -0.00607116 -0.016501 0.0402265 0.0133583 -0.0163904 0.0384292 -0.032751 -0.0164925 -0.0235976 -0.0244081 -0.0164276 -0.0324873 -0.00905445 -0.0164225 -0.0396306 0.0272943 -0.01625 -0.0299211 0.0325556 -0.0164459 -0.0238974 0.0384457 -0.0163919 -0.0132366 0.0404885 -0.0164772 0.00489712 -0.038824 -0.0164401 0.0112742 -0.0406213 -0.0164386 -0.00262527 0.0153989 -0.01435 0.0370754 0.0378563 -0.01435 0.0133647 0.0400193 -0.01435 -0.00318829 0.0374118 -0.0144477 -0.00396264 0.031988 -0.0144516 -0.0198046 0.0352627 -0.01435 -0.01919 0.0044652 -0.0144365 -0.0373508 0.000259331 -0.01325 -0.0400175 -0.0153989 -0.01435 -0.0370754 -0.0291475 -0.01435 -0.0276068 -0.0378563 -0.01435 -0.0133647 -0.0354246 -0.0144444 -0.0126629 -0.0374118 -0.0144477 0.00396264 -0.0400193 -0.01435 0.0031883 -0.0352627 -0.01435 0.01919 -0.0213987 -0.01435 0.034386 -0.0158781 -0.01215 0.0368727 0.0291475 -0.01435 0.0276068 -0.00158603 -0.0135759 0.0400454 -0.0113382 -0.0121555 0.0364309 -0.0295029 -0.01215 0.0272267 -0.0380263 -0.01215 0.0128729 -0.0399747 -0.01215 -0.00370671 -0.00882758 -0.01215 -0.0391636 0.0158781 -0.01215 -0.0368727 0.0295029 -0.01215 -0.0272267 0.037007 -0.0121527 -0.0116355 0.0399747 -0.01215 0.00370671 0.035011 -0.01215 0.0196454 0.0239937 -0.01215 0.0321872 0.00990352 -0.0121328 0.0386616 -0.032113 -0.01825 -0.0440341 -0.0102553 -0.01825 -0.0538864 -0.0405131 -0.01825 0.0364546 -0.0330218 -0.01825 0.0279401 -0.0509463 -0.01825 0.0193579 -0.0403629 -0.0182496 0.0161097 -0.0536358 -0.01825 0.00966697 -0.0545259 -0.0182507 -0.000763469 -0.0395482 -0.01825 -0.0374992 -0.0411178 -0.01825 -0.0134319 -0.0203363 -0.0170065 0.0506502 -0.0246084 -0.01825 0.0486279 -0.0465218 -0.01825 0.0283897 -0.0331247 -0.01825 0.0432782 0.0239761 -0.01825 0.0489428 0.0239761 0.01625 0.0489428 0.0399676 0.016715 0.0370575 0.0461498 0.0167042 0.0289909 0.0506911 0.0166756 0.0200169 0.0203614 -0.010753 0.0328142 -0.025588 0.01675 0.0514927 -0.0544995 0.0167125 -0.00036278 -0.0505289 0.016693 -0.0205368 -0.0536362 0.016697 0.00966624 -0.0426629 0.0136103 0.0424136 -0.0246191 0.0167225 0.0486218 -0.0321573 0.0167582 0.0477142 0.0151342 0.01675 0.0554726 -0.0158519 0.01675 0.0552718 -2.19924e-05 0.0158474 0.0598527 0.0249185 0.01675 0.0518201 0.0530713 0.01675 0.0221289 0.0574496 0.016726 0.00410112 0.0544986 0.0165022 0.000357455 0.0089444 0.0167472 -0.0538025 0.0533527 0.0167739 -0.0214409 0.0485984 0.0168217 -0.03073 0.0354507 0.0167131 -0.0453984 -0.00476417 0.0165876 -0.0543035 -0.0408433 0.01675 -0.0409413 -0.0323915 0.0165319 -0.0438554 -0.0617582 0.0167384 -0.0428681 -0.0508766 0.0167471 -0.062331 0.0485956 -0.02525 -0.0307362 0.0422345 0.01175 -0.0390192 0.0438513 0.0167423 -0.037297 0.0097894 -0.0252324 -0.0567613 0.025588 -0.02525 -0.0514927 -0.00956901 -0.0252483 -0.0569557 -0.0461792 -0.0252361 -0.0345414 -0.0530433 -0.0252496 -0.0222229 -0.0561986 0.01675 -0.0121643 -0.0574719 0.01175 -0.00179845 0.0563515 0.01675 -0.0114349 0.0612418 -0.0502413 -0.03448 0.0619012 -0.04475 -0.0348173 0.0634957 -0.0477542 -0.0305005 -0.0590598 -0.02575 -0.0219305 -0.0590219 -0.05075 -0.022068 -0.0543479 -0.0497826 -0.0318585 -0.0211434 -0.0498283 -0.0593433 0.000693827 -0.0498037 -0.0629878 0.0481374 -0.0498252 -0.0407068 -0.0510471 -0.0055 -0.0623321 -0.0456788 -0.0055 -0.0297271 -0.0513196 -0.00549982 -0.0185058 -0.0524909 -0.0348777 0.00853919 -0.052258 -0.02265 0.00941864 -0.0496496 -0.0348445 0.0189107 -0.0496375 -0.02265 0.0188607 -0.0239762 -0.02265 0.0473788 0.0449644 -0.02265 0.0282455 -0.0394724 -0.02265 0.0355182 -0.0322738 -0.02265 0.0421665 -0.0392449 -0.0497477 0.0357693 0.00810227 -0.0355291 0.0526933 0.0317246 -0.02265 0.0425812 0.0424239 -0.0497499 0.0321734 0.0493889 -0.02265 0.0195024 0.0510938 -0.04955 0.014458 0.0521315 -0.02265 0.0100951 0.0525721 -0.04955 0.00746864 -0.0294137 -0.04975 0.0518479 -0.0582214 -0.03485 0.0129119 -0.0122798 -0.03485 -0.0577763 0.0318797 -0.0329263 -0.0496499 0.050195 -0.0497497 -0.0178869 0.0519126 -0.03485 0.0268342 0.0174311 -0.0497499 0.056347 -0.0220116 -0.0497495 0.0483958 -0.0431477 -0.0350465 -0.0310917 0.022034 -0.0349631 -0.0483708 0.0495832 -0.0226522 -0.0190309 0.0581173 -0.0345534 -0.0130019 0.0481745 -0.0352394 0.0225268 0.0431477 -0.0350465 0.0310917 -0.0308529 -0.0497503 0.0440606 -0.014437 -0.0212491 0.0385031 -0.0355418 -0.02125 0.0368741 -0.0390371 -0.0212489 0.0120694 -0.0403744 -0.0212475 -0.00523448 -0.0347548 -0.0212475 -0.0212037 -0.0123099 -0.0212476 -0.0385982 -0.00554003 -0.02125 -0.050516 0.0174547 -0.0212476 -0.0367808 0.0142133 -0.02125 -0.0487908 0.0339856 -0.0212474 -0.0230622 0.0355418 -0.02125 -0.0368741 0.0500808 -0.02125 0.00526044 0.0442556 -0.02125 0.0240251 0.0208569 -0.0212481 0.0350991 -0.00906577 -0.02125 0.0504057 -0.031988 -0.0144516 0.0198046 -0.0202269 -0.0144556 0.0317245 -0.0044652 -0.0144366 0.0373508 0.0121848 -0.0144406 0.0355903 0.0264209 -0.014442 0.026779 0.0354246 -0.0144444 0.0126629 -0.0105391 -0.0252604 -0.0621118 -0.0211646 -0.0252604 -0.0593381 -0.0299038 -0.0252477 -0.0494661 -0.0543539 -0.0252603 -0.0318525 -0.0576361 -0.0252513 -0.000393512 -0.0629983 -0.0252601 -0.000406623 0.0563515 -0.02525 -0.0114349 0.0621048 -0.0252597 -0.0105651 0.0533536 -0.02525 -0.0214392 0.0422345 -0.02525 -0.0390192 0.0485241 -0.0252597 -0.0401771 0.03448 -0.02525 -0.046015 0.0219221 -0.0252592 -0.0590618 0.000406631 -0.0252633 -0.0629983 0.0576361 -0.0252513 0.000393493 0.0561986 -0.02525 0.0121643 0.0619698 -0.0252545 0.0113455 0.0543539 -0.0252603 0.0318525 0.0401873 -0.0252604 0.0485139 -0.000406623 -0.0252604 0.0629983 -0.00776808 -0.025156 0.0569802 -0.0563515 -0.02525 0.0114349 -0.0533536 -0.02525 0.0214392 -0.0593381 -0.0252597 0.0211646 -0.0485956 -0.02525 0.0307362 -0.0547614 -0.0252597 0.031147 -0.0318547 -0.0252594 0.0543524 -0.021922 -0.0252592 0.0590618 -0.0158519 -0.02525 0.0552718 0.0148622 -0.02265 -0.0509777 0.0250253 -0.02265 -0.04423 0.0400465 -0.02265 -0.0312864 0.0482623 -0.02265 0.0159156 0.0350609 -0.02265 0.0373317 0.0390087 -0.02265 0.0360268 0.0233602 -0.02265 0.0476856 0.0142002 -0.02265 0.051166 0.0045567 -0.02265 0.0529041 -0.00524199 -0.02265 0.0528406 -0.00619427 -0.02265 0.05044 -0.0148622 -0.02265 0.0509777 -0.0453267 -0.02265 0.0276604 -0.0489709 -0.02265 0.0135798 -0.0531112 -0.0227063 -0.000700959 -0.0521315 -0.02265 -0.0100951 -0.0493889 -0.02265 -0.0195024 -0.0312864 -0.02265 -0.0400465 -0.0317246 -0.02265 -0.0425812 -0.0135798 -0.02265 -0.0489709 -0.0142002 -0.02265 -0.051166 0.00524199 -0.02265 -0.0528406 -0.0505989 -0.02125 -0.000327911 -0.0482817 -0.02125 0.0143051 -0.0400465 -0.02265 0.0312864 -0.0250253 -0.02265 0.04423 0.0152887 -0.02125 0.0484646 0.0135798 -0.02265 0.0489709 0.0316928 -0.02125 0.0391322 0.0505189 -0.02265 -0.00841173 -0.0584441 -0.0397586 -0.00807996 -0.0474723 -0.0462225 0.0337289 -0.0471788 -0.0492385 0.0375779 0.0476988 -0.0398844 -0.0346655 -0.0303931 -0.0348591 0.0434298 -0.0318942 -0.0325889 0.050328 -0.0227491 -0.0350578 0.0481145 -0.0546911 -0.0345905 0.017514 -0.0457267 -0.0348474 -0.0271247 -0.0487354 -0.03485 -0.0321251 -0.0480028 -0.0348978 -0.0226381 -0.0523058 -0.03485 -0.0284167 -0.00837763 -0.0350245 -0.0524644 -0.0141695 -0.0348569 -0.0511873 -0.0175375 -0.03485 -0.0562137 0.0309744 -0.0496892 -0.0442874 0.0524118 -0.0348552 -0.00866633 0.052745 -0.0338326 -0.0145456 0.0499301 -0.03485 -0.0178748 0.0555615 -0.03485 -0.0176649 0.0455658 -0.0348472 0.0273629 0.0180038 -0.0349312 0.0499852 0.0171098 -0.03485 0.0569647 -0.040743 -0.0497927 -0.0481009 0.0118872 -0.04975 0.0610169 0.0619673 -0.0498365 0.0113524 0.0457432 -0.0497728 -0.0370812 0.0485922 -0.0497971 -0.0341412 0.0222772 -0.0507499 -0.0589632 0.0309902 -0.04975 -0.0515176 0.053099 -0.0497491 0.000345566 0.0581813 -0.0497497 -0.0218039 -0.0250859 -0.0497499 0.0501408 0.062996 -0.049884 0.000448594 -0.0407786 -0.049855 0.0480158 0.0510661 -0.04975 0.0312804 -0.0144693 -0.04975 0.0605853 -0.062111 -0.0498467 0.0105201 -0.0105201 -0.0498616 -0.062111 0.0324172 -0.0497737 0.0534148 -0.0629948 -0.0498036 -0.000479385 0.0569076 -0.0497601 0.0074983 -0.0140827 -0.0313379 -0.0548184 -0.0483149 -0.0268586 -0.0283137 0.049871 -0.0306455 0.0272797 0.0285327 -0.0284065 -0.045573 -0.0269773 -0.0349206 0.0518285 -0.0574314 0.0166146 0.00377076 -0.0491853 0.0055009 -0.0753124 -0.0510039 -0.00678963 -0.0623318 -0.0578745 -0.0134174 -0.0623764 -0.0612099 0.016734 -0.0623964 -0.0580921 0.0136698 -0.0623778 -0.0510471 0.0055 -0.0623321 -0.0566296 -0.00982753 -0.0623683 -0.0595856 -0.00848964 -0.0623875 0.0231443 -0.0136754 -0.0618513 0.00422848 -0.0053242 -0.0619739 0.0200895 0.010999 -0.0618712 0.0154562 0.0133341 -0.0619011 0.00914409 0.00733389 -0.061942 0.0177708 -0.0140074 -0.0618859 -0.0640455 -0.0163892 -0.0624159 -0.0641695 0.01275 -0.0434886 -0.0529489 0.0137278 -0.0226766 -0.0208358 -0.01675 -0.0692431 0.0420611 0.0143222 0.0428828 0.0601353 0.0143429 0.000534281 0.0428925 0.0136543 -0.0423044 -0.0404494 0.0166786 0.036522 0.042176 0.016561 0.039373 0.0574719 0.01175 0.00179845 0.000927903 0.0167493 -0.056891 -0.0301211 -0.0212489 0.0275433 -0.0201985 -0.0164701 0.0353925 0.0383343 -0.0212501 0.0144217 0.0316628 -0.0212489 0.0255117 0.0535061 0.0166754 0.010362 0.0325591 0.0166979 0.0437058 0.0145952 0.0167076 0.0525075 0.00463813 0.0166731 0.0543013 -0.0152612 0.016697 0.0523216 -0.0331252 0.0165181 0.043278 -0.0465226 0.016689 0.0283888 -0.0509468 0.0167185 0.019357 -0.0573684 0.0163425 -0.00467557 -0.0438347 0.0167463 0.037319 0.00745706 0.00552984 -0.061953 0.00025011 0.00875058 -0.0545055 0.000296015 0.0113057 -0.0749963 -0.0145053 0.0127549 -0.0524915 0.000521885 -0.00627709 -0.0749965 -0.0211158 -0.01275 -0.0694679 -0.00942492 -0.01275 -0.0548926 0.069529 -0.050451 -0.0122327 0.069928 -0.0448452 -0.0132384 0.062374 -0.04475 -0.00949834 0.0543563 -0.0447552 -0.0319679 0.0652674 -0.0505508 -0.0169785 0.0591692 -0.05075 -0.0252633 0.0590791 -0.0449016 -0.0219663 0.0542796 -0.0507512 -0.0321384 0.00910683 0.0157316 -0.0619424 -0.0299011 -0.00706822 -0.0455669 -0.0318288 -0.00550047 -0.0443107 -0.0306765 -0.00550531 -0.0751225 -0.0321575 0.0055 -0.07471 -0.0313833 0.00550188 -0.0447107 -0.0510384 0.00722533 -0.0623321 -0.0278706 -0.0127426 -0.0751752 -0.029829 -0.0107464 -0.0456076 0.00665166 -0.01675 -0.0619582 0.00912913 -0.0154407 -0.0619421 0.00917775 -0.0156352 -0.0749347 -0.0492342 -0.0167407 -0.0752982 -0.0492007 -0.0167496 -0.0623201 -0.0510384 -0.0150247 -0.0623321 0.0212529 -0.0192453 -0.0618635 -0.0640441 0.0138915 -0.0624161 -0.0513471 0.0167449 -0.0276147 -0.0640073 0.013632 -0.0421209 -0.0611878 -0.0192474 -0.0623978 -0.0641738 -0.0161161 -0.0424153 -0.0533717 -0.01525 -0.0234191 -0.0616624 -0.0192352 -0.0425435 0.0231507 0.013598 -0.0618513 -0.0561986 -0.02525 -0.0121639 -0.0514976 -0.0192508 -0.0281285 -0.0168734 -0.020106 -0.0553129 -0.00340974 -0.0200646 -0.057515 -0.0362132 -0.020372 -0.0450916 0.00803159 -0.0192655 -0.0582991 -0.0229721 -0.01925 -0.0545336 0.0214996 -0.0192137 -0.0535092 0.0231002 -0.01525 -0.0539595 0.0230955 0.0164441 -0.0530152 0.0238261 -0.0175525 -0.0523606 0.020212 0.0167493 -0.061769 0.0190894 -0.00907767 -0.0510645 0.0172319 -0.0141534 -0.0517158 0.0161269 0.00845845 -0.0618968 0.0151119 0.0090598 -0.0523988 -0.0594039 -0.00807096 -0.0464809 -0.0613688 -0.0125061 -0.0473627 -0.0569845 -0.0128351 -0.0472881 -0.0618365 -0.0115079 -0.062402 -0.0567625 0.00984612 -0.0463492 -0.057789 0.00830758 -0.0623758 -0.0617267 0.0111933 -0.0624013 -0.0609797 0.00883978 -0.047314 -0.0209024 0.01675 -0.0691369 -0.0211154 0.01275 -0.0692138 -0.00016773 -0.0127409 -0.0749698 0.000431782 0.00713945 -0.0749967 -0.0296176 -0.0104023 -0.0751933 -0.00184556 0.0127513 -0.0749766 -0.0508625 -0.00550398 -0.0753281 -0.0276578 0.0127494 -0.0751739 -0.0296031 0.011147 -0.075193 -0.0509507 -0.014931 -0.0749072 -0.0297351 0.00686708 -0.0751968 0.00673266 -0.01675 -0.0744579 -0.0509468 0.00731968 -0.0752505 -0.0484662 0.01675 -0.0748157 0.00673266 0.01675 -0.0744579 0.00852607 0.00475077 0.0538146 0.00467684 0.00475 0.054299 -0.0053802 0.00475 0.0542338 0.00192078 0.00475 0.0379362 -0.015254 0.00475 0.0523217 -0.00851781 0.00875012 -0.0373155 -0.0030228 0.00875 -0.0380802 -0.000568391 -0.020927 0.0527151 -0.0116616 -0.0178773 0.0515475 -0.00267354 -0.0170121 0.0405981 -0.0103738 -0.01075 -0.0401619 0.00246983 0.00875 -0.0381708 -0.0147433 0.00875 -0.0469492 -0.0146908 -0.01825 -0.0469679 0.00987442 -0.01825 -0.0521302 0.0104968 0.00875037 -0.053276 0.0033323 -0.01075 0.0413459 -0.0112026 -0.01075 0.0399384 -0.0177824 -0.01825 0.0498579 0.00403892 -0.01825 0.0430544 0.015067 -0.0182497 0.0406623 0.0281485 -0.0107461 0.030684 0.0282738 -0.0182497 0.0329622 0.0383455 -0.0182497 0.0203847 0.0373982 -0.0107462 0.0183091 0.0415559 -0.0107462 0.00304565 -0.0122315 -0.01825 0.041491 -0.022296 -0.0107441 -0.0351942 -0.0221714 -0.0107437 0.0352086 -0.0243291 -0.0182497 0.0359483 -0.0316659 -0.01075 0.0267929 -0.0381117 -0.0107441 0.0168464 -0.0416672 -0.0107436 0.000375628 -0.0434427 -0.0182496 -0.00119241 -0.0349043 -0.0182496 -0.0258916 -0.0113885 -0.0182497 -0.0417154 -0.0226457 -0.0182495 -0.0369942 -0.00904763 0.00475 0.0366871 0.00784532 -0.01825 0.0522427 -0.0180212 0.00475 0.0502134 0.0104643 -0.0497689 -0.0565839 0.0106653 -0.04525 -0.0572281 -0.0491209 -0.0497414 -0.0206263 -0.0521315 -0.04955 -0.0100951 -0.0525529 -0.0497497 0.00878412 -0.057045 -0.049773 -0.00960245 -0.0514003 -0.0497499 -0.0265623 -0.0556233 -0.0497499 0.0176992 -0.0581442 -0.0497499 0.0128594 -0.0514903 -0.0497494 -0.0303625 -0.050195 -0.0497497 0.0178869 -0.0481754 -0.04975 -0.0319197 -0.045218 -0.0497479 0.0278788 -0.0200992 -0.0497499 -0.0492544 -0.0357685 -0.0497497 -0.0392473 -0.0321314 -0.0497499 0.049347 -0.0177164 -0.04975 -0.0531933 -0.0157486 -0.0497493 -0.0577608 -0.011642 -0.0497499 -0.0570392 -0.0135092 -0.049752 0.0514425 -0.00389968 -0.049751 0.0530425 -0.00946666 -0.04975 -0.0531377 0.00951672 -0.04975 0.0531622 0.0270179 -0.0322407 -0.0517904 0.0317903 -0.0497409 0.0427757 0.045218 -0.0497478 -0.0278788 0.0515498 -0.0497494 0.0263469 0.0565098 -0.0497499 -0.0174393 0.00913458 -0.00721325 -0.0619421 0.00905831 0.00561139 -0.0749336 0.00915294 -0.00570422 -0.0747026 -0.00682261 -0.0463737 0.061065 0.00521184 -0.0459778 -0.0591958 0.0629969 -0.0252601 0.000423579 0.0593374 -0.0252597 -0.0211656 0.0547617 -0.0252596 -0.0311453 0.0408018 -0.0252595 -0.0480011 0.0318547 -0.0252594 -0.0543524 0.0113399 -0.0252591 -0.0619706 -0.0311235 -0.0252603 -0.0547723 -0.0401873 -0.0252603 -0.0485139 -0.0480011 -0.0252604 -0.0408019 -0.0619698 -0.0252545 -0.0113455 -0.021263 -0.0507771 -0.0480019 -0.0297214 -0.0508103 -0.0432774 -0.0497581 -0.05125 0.0167447 0.0480469 -0.0508305 0.0211635 0.0433485 -0.05125 0.0296168 0.0519883 -0.0508364 -0.00731513 0.0497581 -0.05125 -0.0167447 0.0458442 -0.0507543 -0.0255875 0.0334917 -0.0508321 -0.0404302 0.00719148 -0.0508234 -0.0520056 0.0608701 -0.05725 0.0122617 0.0547514 -0.0637461 0.00886905 0.0546938 -0.0787541 0.00901637 0.0352299 -0.0837528 0.0429835 0.0302202 -0.05375 0.0465988 -0.010007 -0.07725 0.0545017 -0.0135276 -0.07875 0.0541802 -0.00633371 -0.0622387 0.0550973 -0.0441694 -0.08575 0.0334398 -0.0456145 -0.07725 0.0314626 -0.0452148 -0.0637492 0.0321518 -0.0428234 -0.05725 0.0351944 -0.0430756 -0.0637492 0.0349631 -0.0551817 -0.0637485 -0.00573642 -0.054878 -0.05375 -0.00758695 -0.0556657 -0.0824109 -0.00182094 0.0597786 -0.05075 0.00961232 0.0573688 -0.0537085 0.00588769 0.0499897 -0.0507491 -0.0387298 -0.0076457 -0.053724 0.0569402 -0.00533313 -0.050749 -0.0627874 0.0159255 -0.0507489 -0.0609813 -0.0603513 -0.0507475 0.0187008 -0.0601393 -0.05075 -0.0187688 -0.0505953 -0.05375 -0.0375382 -0.0404279 -0.0507485 0.0482939 -0.0318529 -0.05075 0.0543543 -0.0219967 -0.050749 0.0590292 0.0624303 -0.0537469 0.0101841 0.0548231 -0.05375 0.0314436 0.040301 -0.053749 0.0487154 0.0150586 -0.0507478 0.0613607 -0.00694093 -0.0507465 0.0628242 0.0603891 -0.05375 -0.0188301 0.0627933 -0.0507491 -0.00504016 0.0380971 -0.05075 -0.0501758 -0.0527084 -0.08575 0.021352 -0.0540584 -0.0847655 0.0222033 0.0547906 -0.0854898 -0.0224227 -0.0500405 -0.0774989 -0.0293249 0.0484646 -0.0857433 0.0299438 -0.0392277 -0.0854703 0.0445686 -0.0190519 -0.0856811 0.0551802 -0.038032 -0.0857502 0.0423712 -0.0331962 -0.0837499 0.04496 0.020742 -0.0853187 -0.0541666 0.0398256 -0.0852784 -0.0432238 0.0373575 -0.0855903 -0.0439159 -0.0520775 -0.0827495 -0.0027094 0.0436311 -0.0824912 -0.0283186 -0.016699 -0.0821711 0.049459 0.0103305 -0.0823697 -0.0510306 0.0522881 -0.0825941 0.00116952 0.0133006 -0.082749 0.0504921 -0.0417742 -0.0822633 0.0312607 -0.0504252 -0.0822441 0.0140761 -0.031201 -0.0823148 -0.0419579 0.0133999 -0.0853246 -0.060502 -0.0477104 -0.08435 -0.0167057 -0.0447422 -0.08575 -0.0218262 0.00505458 -0.08575 0.0502972 0.00742598 -0.08435 0.0500022 0.0286535 -0.08435 0.0412144 0.0434476 -0.08575 0.0258393 0.0501748 -0.08435 0.00146398 0.0337606 -0.08575 -0.0382706 0.0410581 -0.08435 0.0336253 -0.00214035 -0.0843582 0.0530794 -0.00807306 -0.0857465 0.0521945 -0.0319605 -0.08575 0.042367 -0.0258908 -0.08435 0.0459051 -0.0439026 -0.0843543 0.0298846 -0.00384055 -0.08575 -0.0530043 0.0177054 -0.08435 -0.048785 0.00226039 -0.0848554 0.0558035 0.00688425 -0.0657466 0.0249505 -0.00774941 -0.0571007 -0.011119 -0.0097599 -0.0632581 -0.00723244 -0.0110503 -0.0573096 0.00615738 -0.00806784 -0.0632655 0.00909096 0.00588119 -0.0594725 0.0108313 0.0108629 -0.063423 0.00477093 -0.00119246 -0.0632544 -0.0121567 -0.00317353 -0.0627505 -0.0149943 0.0282395 -0.0627649 0.00103532 0.000329719 -0.063597 -0.028086 -0.0222512 -0.0627579 -0.0174228 -0.0272692 -0.0627593 0.00656382 -0.00244082 -0.0627717 0.0279341 0.0167223 -0.07725 -0.0224581 0.010592 -0.0627568 -0.0261281 0.021782 -0.07725 -0.0175939 0.0212814 -0.0627662 -0.0185957 0.026251 -0.0627572 -0.00986217 0.0242485 -0.0627604 0.0145096 0.0142597 -0.0628348 0.0243967 0.00493271 -0.0638419 0.0276173 -0.0129386 -0.0637447 0.0251269 -0.0106938 -0.0772501 0.0261115 -0.0194051 -0.07725 0.0201851 -0.0278879 -0.0627741 -0.00457379 -0.0236452 -0.0772501 -0.0153972 -0.0161915 -0.07725 -0.0228437 -0.011116 -0.0628036 -0.0259806 0.00384684 -0.07725 -0.0277365 0.0221509 -0.077267 0.0308703 0.0368583 -0.0772626 0.00966594 0.0342185 -0.0772752 -0.0172606 0.0256997 -0.0797205 -0.0285234 -0.0341949 -0.0772682 -0.0176295 -0.0380154 -0.0772673 0.00261164 -0.015635 -0.0797296 0.0201614 -0.023621 -0.0797293 0.00964272 -0.0201295 -0.07875 -0.0156542 -0.0153945 -0.0796971 -0.0203682 -0.00960555 -0.07875 -0.0236217 -0.00316451 -0.07875 -0.0253029 0.0099109 -0.07875 -0.0234952 0.0236754 -0.0797199 -0.0095324 0.0253029 -0.07875 -0.00316451 0.0252775 -0.0797159 0.00346011 -0.0097123 -0.0797346 0.0236123 0.00331093 -0.0797313 0.0253042 0.00960555 -0.07875 0.0236217 0.0154277 -0.0797296 0.0203204 0.0256896 -0.06575 -0.000440022 0.0203307 -0.07875 -0.015392 0.015497 -0.0796866 -0.0202892 0.0099109 -0.06575 -0.0234952 0.00328454 -0.0796219 -0.0253168 -0.00365675 -0.06575 -0.0252071 -0.0201295 -0.06575 -0.0156542 -0.0252597 -0.06575 -0.00349219 -0.0156542 -0.06575 0.0201295 -0.00349219 -0.07875 0.0252597 -0.0117399 -0.0657022 0.00205862 0.0110241 -0.0653394 -0.00306985 0.0394025 -0.044302 -0.0685594 0.0344515 -0.0507877 -0.0669985 0.0306586 -0.0443044 -0.0624208 0.037769 -0.0827302 -0.00480911 0.0191035 -0.0827499 0.0330938 0.00487246 -0.0772784 0.0380748 0.00344213 -0.0827499 0.0380564 -0.00918739 -0.0772697 0.0368681 -0.0334335 -0.0782374 0.0185067 -0.0344663 -0.0827497 0.0172468 -0.00438894 -0.0773461 -0.0378497 0.00712132 -0.07475 -0.0515101 -0.0119671 -0.07475 -0.0506042 -0.0163446 -0.0824891 -0.0493994 -0.0475367 -0.0784501 -0.0212162 -0.0506329 -0.0747721 -0.0118487 -0.0492842 -0.07475 0.0165853 -0.0514925 -0.07475 0.00724693 -0.0453975 -0.07475 0.0253588 -0.0331712 -0.07475 0.0400458 -0.0326675 -0.0827499 0.0405529 -0.0251831 -0.0784436 0.0455809 -0.016465 -0.07475 0.0493245 -0.00712132 -0.07475 0.0515101 -0.0038929 -0.0827494 0.0519202 0.00246488 -0.07475 0.0519415 0.0292743 -0.0821707 0.0432081 0.0294394 -0.07475 0.042864 0.0429357 -0.07475 0.0293348 0.0506333 -0.0747732 0.0118476 0.0475367 -0.0784501 0.0212162 0.0519474 -0.07475 0.00233819 0.0492842 -0.07475 -0.0165853 0.0514925 -0.07475 -0.00724693 0.0399648 -0.07475 -0.0332688 0.0120441 -0.0857522 -0.0391324 -0.0276243 -0.08575 -0.0310573 -0.0406035 -0.08575 -0.00888876 -0.0130843 -0.08575 0.039452 0.0126039 -0.08575 0.0396081 0.0284911 -0.08575 -0.0303521 0.000700693 -0.088177 -0.0410377 -0.0397386 -0.0881787 0.0107124 -0.018629 -0.0881739 0.0367003 -0.00209075 -0.0881721 0.0411047 0.0291483 -0.0881694 0.0290581 0.0384474 -0.0881686 0.0146901 0.0410985 -0.088168 -0.00221802 0.0154794 -0.0881897 0.0360518 0.0341411 -0.0881915 0.0193326 0.0386821 -0.0866941 -0.00124066 0.0270202 -0.086692 -0.0293617 -0.00786194 -0.0882025 -0.0380759 0.0121956 -0.0882644 -0.0381118 -0.0231234 -0.0882035 -0.0312554 -0.0341056 -0.0881913 -0.0186617 -0.0397598 -0.0883436 -0.00649259 -0.0371096 -0.0857511 -0.0110316 -0.0131317 -0.0857406 0.0364353 0.0261102 -0.0857508 0.0285846 0.00208922 -0.0855339 0.0356273 0.0340316 -0.0855206 0.0108733 0.0327127 -0.0854636 -0.014545 0.0248798 -0.085371 -0.0256116 -0.0350428 -0.0855399 0.00761677 -0.0176801 -0.0855746 0.0310986 -0.00858009 -0.0847035 0.0347306 -0.00797721 -0.0847154 -0.0348824 -0.0102483 -0.0797499 -0.0342131 -0.0205944 -0.07975 -0.0289157 -0.0222352 -0.0847138 -0.0280384 -0.0290949 -0.0855473 -0.0207422 -0.0349023 -0.0855421 -0.00824764 -0.0343828 -0.0797499 0.00965627 -0.0293434 -0.0855787 0.0204741 -0.0267734 -0.0797709 0.0234547 0.012986 -0.0855296 0.0333066 0.00123946 -0.0797499 0.0356886 0.0164976 -0.0797735 0.0315348 0.0260469 -0.0855249 0.0244696 0.0284519 -0.0797782 0.0213764 0.0357811 -0.08539 0.000882977 0.0292757 -0.0797499 -0.0199871 0.0284079 -0.0844386 -0.0508416 0.0302947 -0.0827542 -0.0429454 0.0311452 -0.08575 -0.044568 0.024836 -0.0845079 -0.0503165 0.0323142 -0.0509832 -0.0635587 0.0378127 -0.0507321 -0.0584631 0.041841 -0.0450315 -0.0625917 0.0413666 -0.0507411 -0.0620583 0.0412375 -0.0505836 -0.0646479 0.0383466 -0.050892 -0.0673305 -0.00660996 -0.05375 -0.055105 -0.0159068 -0.05725 -0.0531716 0.0213327 -0.05375 -0.0512364 -0.0159068 -0.06225 -0.0531716 0.0213327 -0.05875 -0.0512364 -0.0159068 -0.06375 -0.0531716 -0.00660996 -0.06375 -0.055105 -0.0275586 -0.0687733 -0.0482461 -0.00660996 -0.06875 -0.055105 0.00760764 -0.06875 -0.0551709 0.0213327 -0.06875 -0.0512364 -0.00248858 -0.07475 -0.052441 -0.0212644 -0.07475 -0.0480008 -0.0297225 -0.07475 -0.0432762 -0.0433485 -0.07475 -0.0296168 -0.0480525 -0.07475 -0.0211473 -0.0480522 -0.0507808 -0.0211491 -0.045834 -0.07475 0.0256026 -0.0403517 -0.0507974 0.0335864 -0.0334902 -0.07475 0.0404309 -0.0254908 -0.07475 0.0458963 -0.0166233 -0.07475 0.0497987 -0.00718979 -0.07475 0.0520054 -0.00719272 -0.0507615 0.0520055 0.021263 -0.0507771 0.0480019 0.0433485 -0.07475 0.0296168 0.0511201 -0.07475 0.0119576 0.0524473 -0.050756 0.00236373 0.045834 -0.07475 -0.0256026 0.0334657 -0.0749633 -0.0404253 0.0254908 -0.05125 -0.0458963 0.0318421 -0.0366208 -0.0681472 0.034921 -0.0544659 -0.0703168 0.0343658 -0.03675 -0.0700377 0.0444079 -0.03675 -0.0628579 0.0436066 -0.03675 -0.066357 0.0434913 -0.03675 -0.0593871 0.0297021 -0.0507592 -0.0655153 0.0299017 -0.05075 -0.0598458 0.0363698 -0.03675 -0.0554903 0.0410667 -0.03675 -0.05674 0.0410667 -0.05075 -0.05674 0.0313691 -0.0565359 -0.0683184 0.0166403 -0.0508121 -0.0497946 -0.0368527 -0.0507633 -0.0374194 -0.0623247 -0.05075 -0.00897517 -0.0334916 -0.0508321 0.0404303 0.00248687 -0.0507802 0.0524415 0.0120805 -0.0507527 0.0510917 -0.0433479 -0.0507521 -0.0296186 0.0297214 -0.0508103 0.0432775 0.0371678 -0.0509414 0.0370788 -0.0166251 -0.050779 0.0497986 -0.0120805 -0.0507527 -0.0510917 -0.00248685 -0.0507802 -0.0524416 -0.0458442 -0.0507543 0.0255875 -0.0519883 -0.0508364 0.00731513 -0.0524472 -0.0509108 -0.00236195 -0.0254927 -0.0507525 0.0458958 0.0511219 -0.0507892 0.011951 -0.0548406 -0.0787505 -0.0292161 -0.0540319 -0.0838645 -0.0298667 -0.0550321 -0.08225 -0.0291179 -0.0547115 -0.08225 -0.0108474 -0.0546188 -0.07875 -0.0104792 -0.0555543 -0.08575 0.00262702 0.0588469 -0.07875 -0.0208002 0.0623125 -0.0787498 0.00360117 0.0557589 -0.07875 0.00338108 0.0586494 -0.08375 -0.0209265 0.0554535 -0.0828868 0.00354448 0.0528118 -0.07875 -0.0179761 0.0530839 -0.08225 -0.0175563 0.0536681 -0.0830486 0.014298 0.0535827 -0.0837499 -0.0161529 0.0509914 -0.08575 0.0235643 -0.0101073 -0.0787502 -0.0612892 -0.0285113 -0.07875 -0.0478587 -0.033782 -0.08375 -0.0520782 -0.0285351 -0.08225 -0.048129 -0.0289704 -0.0837483 -0.0474581 0.00314623 -0.0792382 0.0554793 0.00473839 -0.07875 0.0617087 -0.00423876 -0.0837347 0.0618259 -0.00775477 -0.0822754 0.0549561 -0.0395017 -0.0787466 0.0391819 0.0521306 -0.0787506 0.0339681 0.040448 -0.0787492 0.0471332 0.0455369 -0.08375 0.0323638 0.0519827 -0.0822504 0.0338917 0.0460452 -0.08225 0.0319451 0.0462968 -0.07875 0.0306082 0.0378794 -0.07875 0.0407017 0.030201 -0.08225 0.0469935 0.0288625 -0.0837474 0.0474411 0.011402 -0.08375 0.054693 0.0522209 -0.06375 -0.0335349 0.0555666 -0.06375 -0.00442785 0.061839 -0.0637499 0.00426883 0.0519688 -0.06375 0.0198854 0.0415152 -0.06375 0.046608 0.0226864 -0.06375 0.0508086 -0.0280336 -0.06375 0.0554801 -0.0309449 -0.06375 0.0465563 -0.0192931 -0.0622806 0.0522744 -0.0136799 -0.06375 0.0604497 -0.0532818 -0.06375 -0.0162686 -0.0409841 -0.06375 -0.0378664 -0.0590043 -0.06375 -0.0184535 0.00434287 -0.06375 -0.061924 0.00760764 -0.06375 -0.0551709 0.0130504 -0.0625849 -0.0607523 0.0556971 -0.06225 -0.00120212 0.0446594 -0.06225 0.0427488 0.0402339 -0.06225 0.0385338 0.0321518 -0.0637492 0.0452148 0.0259349 -0.06225 0.0495593 -0.0130316 -0.0622501 0.0604464 -0.0402339 -0.06225 -0.0385338 -0.0405743 -0.0629956 -0.0470353 -0.0608701 -0.0622501 -0.0122617 0.0423647 -0.06225 -0.0359399 0.00492374 -0.06225 -0.0557895 -0.0339471 -0.06225 -0.0518641 0.0524889 -0.06875 -0.0180324 0.0518139 -0.0679994 -0.0342626 0.0555666 -0.06875 -0.00442785 0.0607155 -0.06875 -0.0146172 0.061839 -0.0687499 0.00426883 0.054257 -0.06875 0.0118785 0.0415152 -0.06875 0.046608 0.0373848 -0.06875 0.0411691 0.00220447 -0.06875 0.0557557 0.0334582 -0.0675522 0.052535 0.0146172 -0.06875 0.0607155 0.0261723 -0.06875 0.0491795 -0.0378665 -0.06875 0.0409841 -0.0506205 -0.06875 -0.0360761 -0.0532818 -0.06875 -0.0162686 -0.0409841 -0.06875 -0.0378665 0.0377756 -0.06875 -0.0495996 -0.0159068 -0.06875 -0.0531716 0.0556971 -0.06725 -0.00120211 0.0497205 -0.06725 -0.0253264 0.0446594 -0.06725 0.0427488 0.0562139 -0.06725 0.0265314 0.0402339 -0.06725 0.0385338 0.0119294 -0.06725 0.061005 0.0012021 -0.06725 0.0556971 -0.0045686 -0.0674508 0.0619494 -0.012495 -0.06725 0.0541885 -0.0470353 -0.0680006 0.0405743 -0.0544722 -0.06725 -0.030542 -0.0527333 -0.06725 -0.018147 0.046211 -0.0672517 -0.0408963 0.0213327 -0.06725 -0.0512364 0.00492377 -0.06725 -0.0557895 -0.033596 -0.0672502 -0.0526035 0.00455477 -0.06725 -0.0619606 0.0246464 -0.06725 -0.0568907 -0.0159068 -0.06725 -0.0531716 -0.0281931 -0.0637529 -0.0479593 0.0623125 -0.07375 0.00360117 0.0491796 -0.07375 -0.0261723 0.055546 -0.07375 0.00267592 0.0546061 -0.07375 -0.00992108 0.0575634 -0.07375 0.0239304 0.0415152 -0.07375 0.046608 0.0373848 -0.07375 0.0411691 0.00220447 -0.07375 0.0557557 -0.00360117 -0.07375 0.0623125 -0.0378665 -0.07375 0.0409841 -0.0590043 -0.07375 -0.0184535 -0.0532818 -0.07375 -0.0162686 -0.0409841 -0.07375 -0.0378664 0.00760764 -0.07375 -0.0551709 0.00434287 -0.07375 -0.061924 -0.00660996 -0.07375 -0.055105 0.0213327 -0.07375 -0.0512364 0.0130504 -0.0725849 -0.0607523 -0.0159068 -0.07375 -0.0531716 0.05012 -0.07225 -0.0244562 0.0608701 -0.0722501 0.0122617 0.0402339 -0.07225 0.0385338 0.0446594 -0.07225 0.0427488 0.0527333 -0.07225 0.018147 0.0012021 -0.07225 0.0556971 0.00109993 -0.07225 0.0621614 -0.0134403 -0.07225 0.0609522 -0.0385338 -0.07225 0.0402338 -0.0405743 -0.0729956 -0.0470353 -0.0402339 -0.07225 -0.0385338 0.0423647 -0.07225 -0.0359399 0.0376532 -0.07225 -0.0494162 0.00492376 -0.07225 -0.0557895 0.00251655 -0.07225 -0.0624574 -0.0159068 -0.07225 -0.0531716 0.0246464 -0.07225 -0.0568907 0.0555535 -0.0772513 -0.00365777 0.0554068 -0.0772501 -0.0289986 0.0513998 -0.07725 -0.021313 0.0402339 -0.07725 0.0385338 0.0527333 -0.07725 0.018147 0.0253264 -0.07725 0.0497205 0.00339719 -0.0772505 0.0555922 -0.0254934 -0.07725 0.049751 -0.0544822 -0.0772503 -0.0304893 -0.0456276 -0.07725 -0.0315971 0.0213327 -0.07725 -0.0512364 0.000529831 -0.0772501 -0.0556957 -0.0159068 -0.07725 -0.0531716 -0.0275586 -0.0737733 -0.0482461 0.054257 -0.07375 0.0118785 0.048381 -0.07375 0.0274858 0.0261723 -0.07375 0.0491795 -0.0162686 -0.07375 0.0532818 -0.0414579 -0.0772506 0.0368946 -0.0491796 -0.07375 0.0261723 -0.0546061 -0.07375 0.00992107 -0.0532059 -0.07725 0.0171527 -0.055546 -0.07375 -0.00267592 -0.0527333 -0.07725 -0.0181471 0.0342743 -0.07725 -0.0436523 0.0429105 -0.0772475 -0.0354637 0.0467649 -0.06875 -0.0299661 0.0556971 -0.07225 -0.00120213 0.048381 -0.06875 0.0274858 0.0253265 -0.07225 0.0497205 -0.0162686 -0.06875 0.0532818 -0.0172493 -0.07225 0.0530662 -0.0497205 -0.07225 0.0253264 -0.0527333 -0.07225 -0.0181471 0.0424503 -0.06875 -0.0361715 0.0508086 -0.06375 -0.0226864 0.0409841 -0.06375 0.0378664 0.0530662 -0.06725 0.0172492 0.0253265 -0.06725 0.0497205 0.00220449 -0.06375 0.0557557 -0.0243645 -0.06725 0.0498661 -0.0385338 -0.06725 0.0402338 -0.0497205 -0.06725 0.0253265 -0.0556972 -0.06725 0.00120209 -0.0552593 -0.06375 0.00652672 -0.0402339 -0.06725 -0.0385338 0.0352446 -0.06375 -0.0432771 0.0346384 -0.0672514 -0.0440228 0.0491795 -0.05875 -0.0261723 0.0513998 -0.06225 -0.021313 0.0514157 -0.06225 0.0212747 0.0299661 -0.05875 0.0467649 0.00420179 -0.0587572 0.0555398 0.00992108 -0.06225 0.0546061 -0.0387037 -0.06225 0.0401358 -0.0315971 -0.05875 0.0456276 -0.0411691 -0.05875 0.0373848 -0.0491795 -0.05875 0.0261723 -0.0555398 -0.0587572 0.0042018 -0.0527333 -0.06225 -0.018147 -0.0532714 -0.0586865 -0.0160324 0.0424503 -0.05875 -0.0361715 0.0522209 -0.05875 -0.0335349 0.0558724 -0.0587487 -0.00180995 0.061839 -0.0587499 0.00426883 0.054257 -0.05875 0.0118785 0.0606385 -0.05875 0.013213 0.0498661 -0.05875 0.0243645 0.0423802 -0.0587194 0.0361768 0.0532683 -0.05875 0.0325964 0.0409113 -0.0587499 0.0463664 0.0180324 -0.05875 0.0524889 -0.0360761 -0.05875 0.0506205 -0.0179241 -0.05875 0.0595313 -0.0153848 -0.0587194 0.053521 -0.0409841 -0.05875 -0.0378664 0.0342743 -0.0605 -0.0436523 -0.028926 -0.05875 -0.0473829 -0.00660996 -0.05875 -0.055105 0.00434287 -0.05875 -0.061924 0.00760763 -0.05875 -0.0551709 -0.0159068 -0.05875 -0.0531716 0.044573 -0.0572156 -0.0330792 0.0428397 -0.05725 0.0453932 0.0540162 -0.05725 0.0130846 -0.00323424 -0.05725 0.0618938 -0.0122617 -0.0572501 0.0608701 -0.0470353 -0.0580006 0.0405743 -0.030542 -0.05725 0.0544722 -0.0544722 -0.05725 -0.030542 -0.0606777 -0.0572501 -0.0126692 0.0246464 -0.05725 -0.0568907 0.0213327 -0.05725 -0.0512364 0.00492374 -0.05725 -0.0557895 -0.033596 -0.0572502 -0.0526035 -0.024738 -0.05725 -0.0496818 0.0532615 -0.0572493 -0.0170663 0.0554868 -0.0537809 -0.00213067 0.0476249 -0.05725 0.0287759 0.0145616 -0.0537493 0.0538033 0.00992108 -0.05725 0.0546061 0.0264186 -0.05725 0.0490582 -0.0254934 -0.05725 0.049751 -0.0381799 -0.0538379 0.0402811 -0.0490864 -0.0572512 0.0263758 -0.0546061 -0.05725 0.00992107 -0.0477211 -0.0572487 -0.0287112 0.0347934 -0.05725 -0.043605 0.0470506 -0.0572656 -0.0404217 0.0334581 -0.0575522 0.052535 -0.00385732 -0.0587499 0.0617147 0.0607471 -0.0831566 0.0134603 0.0411578 -0.0824406 0.0463277 -0.0608185 -0.083546 -0.0125471 -0.0608701 -0.0772501 -0.0122617 0.0470506 -0.0722656 -0.0404217 -0.0470353 -0.0730006 0.0405743 -0.0608701 -0.0722501 -0.0122617 -0.0608701 -0.0672501 -0.0122617 0.0470506 -0.0622656 -0.0404217 -0.0249242 -0.0623884 -0.057001 0.0518251 -0.0853445 0.0302588 -0.0115316 -0.0851474 -0.0546693 -0.00748718 -0.0854711 -0.0578079 0.0352354 -0.0849413 -0.0397585 0.0463044 -0.0853094 -0.0409586 0.0427802 -0.08575 -0.0373619 0.0471896 -0.08575 -0.0232907 0.053068 -0.08575 -0.000469277 0.0453089 -0.08575 0.0276322 0.0233499 -0.08575 0.0477413 -0.0494571 -0.0857509 0.019467 -0.0525633 -0.0857527 -0.00463724 -0.0547508 -0.0837641 -0.00900608 -0.0497202 -0.08575 -0.0283382 -0.0449264 -0.0857528 -0.0284477 -0.0460056 -0.0857499 -0.032476 -0.0277505 -0.08575 -0.0448054 -0.0243119 -0.08575 -0.050072 -0.00241932 -0.08575 -0.0558157 0.011409 -0.0857192 -0.0553428 0.0555543 -0.08575 -0.00262703 0.00776566 -0.0857082 0.0563823 0.0239627 -0.08575 0.0502411 0.0560102 -0.0787477 -0.0266926 0.0473597 -0.0830343 -0.0288932 -0.0623125 -0.0787498 -0.00360117 -0.0533143 -0.0805 0.016815 -0.0559354 -0.07875 -0.00137264 -0.0535084 -0.08375 0.0167357 -0.0584211 -0.08225 0.021181 -0.0624125 -0.08225 -0.00196354 0.0527855 -0.07875 0.0171448 0.0550619 -0.0822504 0.0288114 -0.0442689 -0.07875 -0.033759 -0.0522928 -0.0787509 -0.0337769 -0.0520657 -0.0837496 -0.0339594 -0.0414786 -0.08225 -0.0460525 -0.0129874 -0.0840793 0.0541764 -0.018569 -0.0825645 0.0583467 -0.0390455 -0.07875 0.0484727 -0.0334093 -0.07875 0.0447823 -0.0497748 -0.07875 0.0252954 -0.0519585 -0.0829079 0.0333463 -0.0387736 -0.0829504 0.0487793 -0.0497861 -0.0829899 0.0252809 0.0334778 -0.08575 0.0246352 0.027732 -0.08575 0.0413423 0.0497297 -0.08575 0.00228105 0.0471312 -0.08575 -0.0160282 0.0403912 -0.08575 0.00558412 0.0393582 -0.08575 -0.0121852 -0.0336884 -0.08575 -0.0366516 -0.00800436 -0.08575 -0.0404163 -0.0173528 -0.08575 -0.0471013 0.000198646 -0.08575 -0.0497816 0.0225519 -0.0857482 -0.0473426 -0.0176793 -0.08575 0.0469797 -0.0327094 -0.08575 0.037528 -0.0309994 -0.08575 0.0271401 -0.0393582 -0.08575 0.0121852 -0.0441506 -0.08575 0.0229994 -0.0494994 -0.08575 0.00529714 0.00228011 -0.0829012 -0.0553423 -0.00593707 -0.0827454 -0.0613889 0.0299475 -0.07875 0.0467763 0.0138792 -0.08375 0.060766 0.033782 -0.08375 0.0520782 0.0103494 -0.08225 0.0547939 -0.0280366 -0.0857759 0.0267867 -0.0378594 -0.0857436 0.0094946 -0.0290477 -0.0857511 -0.025594 -0.0156205 -0.0858731 -0.0350251 -0.00438753 -0.0857753 -0.0369875 0.0346985 -0.0858079 -0.017027 0.0356993 -0.0857509 0.0149792 0.00790079 -0.0857511 0.0382742 -0.0148097 -0.0881673 -0.0384017 0.0366485 -0.0882583 -0.0185471 0.0148091 -0.0881706 0.0384015 -0.00715627 -0.0881843 0.0383709 -0.0324476 -0.0882905 0.0246102 -0.0365959 -0.0881929 0.0127794 -0.0321438 -0.0881813 -0.0262833 0.0375901 -0.0827499 0.00686453 0.0340795 -0.0827499 -0.0172838 0.043154 -0.0827497 0.0293917 0.0495047 -0.0827491 -0.0165942 -0.0431461 -0.0827492 -0.0294025 -0.0334306 -0.08275 -0.0185078 0.0312336 -0.08275 0.0220138 -0.0225696 -0.0827499 -0.0308343 -0.0026804 -0.0827496 -0.0521391 -0.00434952 -0.0827502 -0.0382613 -0.0128555 -0.0827499 0.0359844 -0.0238656 -0.08275 0.0295708 -0.038112 -0.0827499 -0.00276005 -0.0544722 -0.06225 -0.030542 -0.0506205 -0.06375 -0.0360761 -0.0601141 -0.06225 0.0169212 -0.0265314 -0.06225 0.0562139 -0.043177 -0.06225 0.0447325 -0.046608 -0.0637498 0.0415152 0.033596 -0.0622502 0.0526035 0.0294208 -0.06375 0.0547692 0.0102845 -0.06375 0.0613037 0.0119294 -0.06225 0.061005 -0.0045686 -0.0624508 0.0619494 0.0575634 -0.06375 0.0239304 0.060828 -0.06225 0.015931 0.0542768 -0.06225 -0.031747 0.0617978 -0.06225 -0.0017525 0.0607155 -0.06375 -0.0146172 -0.0522209 -0.06375 0.0335349 -0.0508086 -0.06375 0.0226864 -0.0607155 -0.06375 0.0146172 -0.0618616 -0.06238 -0.00365567 -0.0519567 -0.06225 0.0335273 -0.0532059 -0.06225 0.0171527 -0.0590043 -0.06875 -0.0184535 -0.0405743 -0.0679956 -0.0470353 -0.0617978 -0.06725 0.00175249 -0.0179241 -0.06875 0.0595313 -0.0134403 -0.06725 0.0609522 -0.0347017 -0.06725 0.0515724 -0.0360761 -0.06875 0.0506205 0.0608652 -0.0680044 0.0124106 0.0554801 -0.06875 0.0280336 0.0585098 -0.06725 -0.0209887 0.0617978 -0.06725 -0.0017525 0.0376532 -0.06725 -0.0494163 -0.0518139 -0.0680044 0.0342625 -0.0590531 -0.06875 0.0194076 -0.0623125 -0.06875 -0.00360118 -0.0491795 -0.06875 0.0261723 -0.0557557 -0.06875 0.00220447 -0.0585098 -0.06725 0.0209887 -0.0544722 -0.07225 -0.030542 -0.0506205 -0.07375 -0.0360761 -0.0585098 -0.07225 0.0209887 -0.0179241 -0.07375 0.0595313 -0.0360761 -0.07375 0.0506205 -0.0347017 -0.07225 0.0515724 0.0342625 -0.0730044 0.0518139 0.0194076 -0.07375 0.0590531 0.0209887 -0.07225 0.0585098 0.0562139 -0.07225 0.0265314 0.0585098 -0.07225 -0.0209887 0.0576248 -0.07375 -0.0237821 0.0617978 -0.07225 -0.0017525 -0.0590531 -0.07375 0.0194076 -0.0518139 -0.0730044 0.0342625 -0.0623125 -0.07375 -0.00360117 -0.0617978 -0.07225 0.00175249 -0.0556971 -0.07225 0.00120212 -0.0520837 -0.0781334 0.033678 -0.0608275 -0.07725 0.0110476 -0.0554673 -0.0772889 -0.000666769 -0.0618938 -0.07725 -0.00323424 -0.0602962 -0.07875 -0.0140592 -0.0526566 -0.08225 -0.0332587 -0.0404468 -0.0837498 -0.0471124 -0.0405743 -0.0779956 -0.0470353 -0.0585311 -0.0787505 0.0210075 -0.0587506 -0.08375 0.0205299 -0.0623289 -0.0837499 -0.00396823 -0.056582 -0.0773291 0.0252961 -0.0169281 -0.0774379 0.059474 -0.0410715 -0.0772508 0.0465136 0.0105715 -0.0787501 0.0611661 0.0205989 -0.0772494 0.0586859 0.0330627 -0.0784513 0.0529934 0.0106375 -0.08225 0.061282 0.033596 -0.0822502 0.0526035 0.0534916 -0.07725 0.0313473 0.0446594 -0.07725 0.0427488 0.0553897 -0.0787503 0.02862 0.0611413 -0.0772496 0.0134166 0.0623901 -0.07725 0.00180558 0.0623289 -0.0837499 0.00396822 0.0624125 -0.08225 0.00196353 0.0585485 -0.08225 -0.0206309 0.0561622 -0.0823801 -0.0259881 0.0379697 -0.0773672 -0.0493679 0.0470981 -0.0772471 -0.0405011 0.00251657 -0.06225 -0.0624574 -0.0146172 -0.06375 -0.0607155 -0.0294208 -0.06875 -0.0547692 -0.0102845 -0.06875 -0.0613037 -0.0119294 -0.06725 -0.061005 -0.0330627 -0.0734513 -0.0529934 -0.0209887 -0.07225 -0.0585098 -0.0102845 -0.07375 -0.0613037 -0.0101683 -0.08225 -0.0614232 -0.033596 -0.0822502 -0.0526035 -0.0138792 -0.08375 -0.060766 -0.00549899 -0.077274 -0.0617191 0.00455477 -0.07725 -0.0619606 -0.0205989 -0.0772494 -0.0586859 -0.0330627 -0.0784513 -0.0529934 0.0380971 -0.05375 -0.0501758 0.0377755 -0.07375 -0.0495996 0.0350851 -0.07375 -0.0431807 0.0437459 -0.0581848 -0.0598212 0.0377265 -0.0629879 -0.0495269 0.0342743 -0.0705 -0.0436523 0.0246571 -0.0795165 -0.0568871 0.0213327 -0.07225 -0.0512364 0.0213327 -0.06375 -0.0512364 0.0213327 -0.06225 -0.0512364 0.0251556 -0.05375 -0.0577598 -0.0585098 -0.05725 0.0209887 -0.0623901 -0.05725 -0.00180559 0.0119294 -0.05725 0.061005 0.0146172 -0.05875 0.0607155 0.0562139 -0.05725 0.0265314 0.0585098 -0.05725 -0.0209887 0.0607155 -0.05875 -0.0146172 0.0623521 -0.05725 0.0015122 0.0377263 -0.0579879 -0.049527 -0.0518139 -0.0580044 0.0342626 -0.0607155 -0.05875 0.0146172 -0.0617147 -0.0587499 -0.00385733 -0.0590043 -0.05875 -0.0184535 -0.0506205 -0.05875 -0.0360761 -0.0405743 -0.0579956 -0.0470353 -0.0294208 -0.05875 -0.0547692 -0.0119294 -0.05725 -0.061005 -0.0102845 -0.05875 -0.0613037 0.00455477 -0.05725 -0.0619606 -0.0136692 -0.0627501 0.00539254 -0.0144597 -0.0572946 0.00165646 -0.0113161 -0.0573701 0.00984099 0.0136644 -0.0570618 0.000522013 0.0116158 -0.0572572 0.00887723 0.00421455 -0.0573411 0.0139535 0.00531716 -0.0627566 0.0138762 -0.00535362 -0.0627273 0.0139034 0.00786676 -0.06326 -0.0092304 -0.0234952 -0.06575 -0.0099109 -0.00960555 -0.06575 -0.0236217 -0.00852164 -0.06575 -0.00772525 -0.015392 -0.06575 -0.0203307 -0.0220278 -0.06575 0.0132258 -0.0034585 -0.06575 0.0114432 -0.0253029 -0.06575 0.00316451 -0.00349218 -0.06575 0.0252597 0.0234952 -0.06575 0.00991089 0.0184764 -0.06575 0.0178541 0.0156542 -0.06575 -0.0201295 0.00762847 -0.06575 0.00879107 0.0222964 -0.0657489 -0.0131274 0.00485302 -0.06575 -0.00978029 0.00349219 -0.06575 -0.0252597 -0.0099109 -0.06575 0.0234952 0.0346832 -0.0797498 -0.00847757 0.0218786 -0.0797319 0.0134957 0.0349638 -0.0797499 0.00724216 0.00317738 -0.0797499 -0.0353581 0.024832 -0.07975 -0.0255007 0.011029 -0.0797538 -0.0342417 -0.0291918 -0.07975 -0.0205755 -0.023521 -0.0797296 -0.00988414 -0.0351983 -0.0797499 -0.00604532 -0.0142087 -0.0797499 0.0327628 -0.0203204 -0.0797295 0.0154277 -0.0256953 -0.079732 -0.000748286 0.0402435 -0.05375 0.0382207 0.0348375 -0.0537488 0.0478892 0.0289434 -0.05375 0.0559578 -0.00827862 -0.0537425 0.062671 0.013208 -0.05375 0.0618047 0.00143027 -0.05375 0.0554826 -0.0230632 -0.05375 0.0509835 -0.0347935 -0.05375 0.0528287 -0.0516185 -0.0537507 0.0365047 -0.0450902 -0.0536512 0.0369068 -0.049363 -0.0537515 0.0260141 -0.0554846 -0.0537503 0.00330019 -0.0609071 -0.05375 0.0168699 -0.0566497 -0.05375 -0.00712245 -0.051963 -0.0537509 -0.0201255 -0.0581765 -0.05375 -0.0246934 -0.0629167 -0.05375 -0.00579013 -0.0384153 -0.0537504 -0.0500699 -0.0376907 -0.0537712 -0.0409503 0.00755375 -0.05375 -0.0552047 0.0102583 -0.05375 -0.0623511 -0.0216596 -0.05375 -0.0513327 -0.0261923 -0.05375 -0.0572971 -0.0101916 -0.05375 -0.0623731 0.0547713 -0.05375 0.0100287 0.048381 -0.05375 0.0274858 0.0510116 -0.0537503 -0.0224365 0.0501895 -0.0537469 -0.0384524 0.034627 -0.05375 -0.0438755 -0.0361836 -0.0507503 -0.0513418 -0.0436224 -0.0507488 -0.0454459 0.0622203 -0.05075 0.0106797 0.0251556 -0.05075 -0.0577598 -0.0226608 -0.0507486 -0.0590094 0.00684154 -0.05075 -0.0626678 -0.0512058 -0.0507711 -0.0115466 -0.0629651 -0.05075 0.00209728 -0.0542124 -0.050748 -0.0324525 -0.0511495 -0.0507538 0.0369948 -0.0483492 -0.0507501 0.0340894 0.0289434 -0.05075 0.0559578 0.0413179 -0.0507493 0.0479598 0.0557109 -0.0507485 0.0298204 0.0593644 -0.0507479 -0.0216372 0.0404349 -0.0507748 -0.0334961 0.0433797 -0.05075 -0.05919 0.0355094 -0.05075 -0.0554336 -0.0210619 -0.07475 -0.0475436 -0.0120822 -0.07475 -0.0510908 -0.0294394 -0.07475 -0.042864 -0.0368144 -0.07475 -0.0367247 -0.0371684 -0.07475 -0.0370778 -0.0429357 -0.07475 -0.0293348 -0.0511201 -0.07475 -0.0119576 -0.0519474 -0.07475 -0.00233819 -0.0524469 -0.07475 -0.00236068 -0.0519877 -0.07475 0.00731661 -0.0497581 -0.07475 0.0167447 -0.0399648 -0.07475 0.0332688 -0.0403491 -0.07475 0.0335887 0.00248858 -0.07475 0.052441 0.0119671 -0.07475 0.0506042 0.0120822 -0.07475 0.0510908 0.0210619 -0.07475 0.0475436 0.0212644 -0.07475 0.0480008 0.0297225 -0.07475 0.0432761 0.0371684 -0.07475 0.0370778 0.0368764 -0.0771275 0.0367271 0.0480525 -0.07475 0.0211473 0.0524469 -0.07475 0.00236067 0.0519877 -0.07475 -0.00731661 0.0497581 -0.07475 -0.0167447 0.0453975 -0.07475 -0.0253588 0.0403491 -0.07475 -0.0335887 0.0255568 -0.0752144 -0.0458436 0.0167571 -0.0754704 -0.0497236 -0.00246488 -0.07475 -0.0519415 0.00718979 -0.07475 -0.0520054 -0.00318362 -0.07725 -0.0278184 -0.0100018 -0.07725 -0.0261527 0.0106118 -0.07725 -0.0259112 0.00850098 -0.0772552 -0.0370121 0.0254731 -0.07725 -0.0116242 0.0257576 -0.07725 -0.0195449 0.0275636 -0.07725 -0.00492408 0.0276528 -0.0772501 0.0056116 0.0297034 -0.0772651 0.0238017 0.0234638 -0.07725 0.0152791 0.0163166 -0.0772501 0.0230203 0.00320823 -0.0772501 0.0280335 -0.0201256 -0.0772598 -0.0323399 -0.0281381 -0.0772501 -0.00210154 -0.02567 -0.0772501 0.011714 -0.0239467 -0.0772603 0.0297257 0.00525195 -0.06275 0.0208968 0.0126963 -0.06275 0.00731285 0.00857787 -0.0627536 -0.012124 0.0147923 -0.0627515 -0.00105562 -0.0137889 -0.0627485 -0.00526113 -0.0234371 -0.0627567 0.0157886 0.00476287 -0.0573026 -0.0112736 -0.00200638 -0.0612523 0.0118282 -0.0111827 -0.0572162 -0.00592882 0.0112753 -0.05706 -0.00729833 -0.000209423 -0.0573324 -0.0145491 0.0133375 -0.058 -0.0607742 0.0246464 -0.05875 -0.0568907 0.02471 -0.06375 -0.0570013 0.0246464 -0.06225 -0.0568907 0.0130504 -0.0675849 -0.0607523 0.0247108 -0.06875 -0.057001 0.02471 -0.07375 -0.0570013 0.0247265 -0.07725 -0.05703 0.0252103 -0.0857492 -0.056858 0.00371445 -0.08375 -0.0618194 0.0125284 -0.0772494 -0.0608417 0.00434287 -0.06875 -0.061924 0.0312315 -0.03675 -0.0582995 0.0436528 -0.0410414 -0.0627712 0.0397053 -0.0366741 -0.0698611 0.02942 -0.0365924 -0.0627471 0.0343989 -0.044275 -0.0574449 0.0406072 -0.04425 -0.0575483 0.0332107 -0.04425 -0.0684157 0.010168 -0.0855665 -0.0341924 0.010809 -0.0827496 -0.0367817 0.0219507 -0.0827374 -0.0472522 -0.00210425 -0.0772495 0.0622331 0.00482317 -0.0824946 0.0616895 0.0102886 -0.07875 0.0550024 0.00775486 -0.0853869 0.0594907 -0.00304033 -0.07875 -0.0566828 0.00960389 -0.0780726 -0.0548507 -0.0113865 -0.0805 -0.0547312 0.0314201 -0.0844868 -0.0480928 0.0342123 -0.0854099 -0.0527954 -0.0522598 -0.08435 0.00682121 -0.0498152 -0.08435 0.00617231 -0.0511591 -0.0843485 -0.0126291 -0.043079 -0.0843533 -0.0304215 -0.0292177 -0.08435 -0.0438627 -0.0315307 -0.08435 -0.0395118 -0.00994778 -0.08435 -0.0492006 -0.0113281 -0.08435 -0.0514712 0.00294709 -0.08435 -0.0511945 0.0343319 -0.08435 -0.0370487 0.0460913 -0.0843475 -0.0254987 0.0472473 -0.08435 -0.0169513 0.0521756 -0.08435 -0.00743798 0.0446202 -0.08435 0.0237571 0.0513226 -0.08435 0.0119836 0.0211982 -0.08435 0.048252 -0.0161037 -0.08435 0.0475429 -0.0323462 -0.08435 0.0383846 -0.0441252 -0.08435 0.0239295 0.0268176 -0.08275 -0.0273136 0.0169951 -0.0846765 -0.0550303 0.0411907 -0.0843225 -0.0413696 0.0268161 -0.0792503 -0.0446014 0.0333707 -0.050737 -0.0598792 -0.033525 -0.08225 0.0448232 -0.0233561 -0.0772642 0.0575534 -0.0227242 -0.0835142 0.0576632 -0.0430962 -0.0811402 0.0445099 -0.0227413 -0.08225 0.051034 -0.0227204 -0.07875 0.0511549 -0.0401026 -0.0827438 0.0384083 -0.0228606 -0.0840787 0.0510015 0.0493304 -0.0805 0.0254316 0.0525217 -0.0837699 0.033717 0.0504324 -0.08375 0.0241881 -0.0435979 -0.08225 -0.0348107 -0.0417795 -0.08375 -0.0365446 -0.0503923 -0.08225 -0.0243507 -0.0503328 -0.07875 -0.0242495 -0.0503328 -0.08375 -0.0242495 0.0502067 -0.0805 -0.0236547 0.0527367 -0.0857504 -0.0210792 -0.0574484 -0.0841272 0.0238251 -0.0314637 -0.07725 -0.0455915 -0.0314637 -0.07225 -0.0455915 -0.0360997 -0.0772556 -0.0422048 -0.0314637 -0.06725 -0.0455915 -0.0332886 -0.0572496 -0.0443867 0.0441694 -0.08575 -0.0334398 0.0455441 -0.0786247 -0.031682 0.051712 -0.0722501 -0.0343713 0.051712 -0.05725 -0.0343713 0.0452148 -0.0637492 -0.0321518 0.0331235 -0.0507501 0.0468641 0.00914549 -0.05075 -0.0562933 0.0353638 -0.0827954 -0.0511084 0.0417111 -0.0505595 -0.0689597 0.0267262 -0.0828953 -0.0561004 0.0445313 -0.0555518 -0.0631693 0.0362386 -0.0824655 -0.0503106 -0.020945 -0.0167501 -0.0626368 -0.0201822 -0.0190007 -0.0626338 -0.0211658 0.01675 -0.064215 -0.00889506 -0.0165 -0.286879 0.0180432 -0.0168264 -0.301285 -0.014209 0.017 -0.309634 0.0130456 0.0168821 -0.312884 0.0201816 0.0164986 -0.292991 0.0038387 0.024 -0.313212 -0.0126034 0.024 -0.298669 -0.00150072 0.024 -0.287421 0.0122967 0.022 -0.295019 0.0126736 -0.022 -0.296074 0.0109625 -0.024 -0.293019 -0.006654 -0.022 -0.288525 -0.00837901 0.022 -0.292917 -0.00737642 0.022 -0.307479 -0.00114104 0.022 -0.311067 0.0027832 0.017 -0.310131 0.0101243 0.017 -0.297223 -0.00413904 0.022 -0.289769 -0.00265195 -0.017 -0.310166 0.00983825 -0.022 -0.304874 0.00265175 -0.017 -0.289847 -0.000613382 -0.022 -0.28924 -0.00983845 -0.022 -0.295139 0.0175782 0.00234322 -0.0618874 0.014909 -0.000802118 -0.0619047 -0.061972 0.0092468 -0.0623405 -0.0553629 0.0103572 -0.0623602 -0.056772 -0.00831935 -0.0623692 0.0165411 -0.00731575 -0.0668942 0.0141541 -0.00954606 -0.0619096 -0.0204985 0.019 -0.0644947 -0.0177084 0.0190405 -0.185597 -0.0175348 0.0192628 -0.212388 -0.0173996 0.0200346 -0.233201 -0.0484546 0.0199244 -0.230857 -0.0494524 -0.019 -0.0761705 -0.0211501 -0.0190005 -0.0635834 -0.0486595 -0.0191061 -0.199203 -0.0176027 -0.0191292 -0.20191 -0.0510438 -0.01475 -0.062832 -0.0494886 0.01675 -0.0626056 -0.0624413 -0.0190002 -0.0629235 0.00598915 -0.019 -0.0785821 0.0231492 -0.016083 -0.0619423 0.0210811 -0.0184981 -0.0618647 -0.0640356 -0.0172901 -0.0624358 -0.0494524 0.019 -0.0761705 0.0219936 0.018334 -0.0658757 0.0231487 0.0161062 -0.0619033 -0.050235 -0.016266 -0.0803273 -0.0494789 -0.01575 -0.262962 -0.0510438 0.01475 -0.062832 -0.0495648 0.015584 -0.262962 0.0091603 -0.01475 -0.0624419 -0.0552375 0.0154093 -0.076073 -0.0536982 -0.011 -0.0775995 0.0120083 -0.0123237 -0.0781782 0.0119425 -0.0128467 -0.0669239 0.0150779 -0.0160759 -0.0749103 0.0231894 -0.0162489 -0.0668511 0.0218524 -0.018455 -0.0658801 -0.057216 -0.0160154 -0.067893 -0.050931 -0.018715 -0.076794 -0.0639996 -0.0171203 -0.0673583 -0.0521424 0.0179683 -0.0773034 -0.0624383 0.0184391 -0.0666281 0.0145065 0.0159666 -0.0755389 0.0120086 0.0119703 -0.078178 -0.0145497 0.0164351 -0.155628 0.00361879 0.0163112 -0.0799783 0.00431592 0.0155229 -0.0799737 -0.0153486 -0.0157371 -0.163068 0.0036232 -0.0162795 -0.0799782 -0.0161536 -0.016338 -0.163908 -0.016747 -0.019008 -0.16742 0.0131247 0.024 -0.301963 -0.000202697 0.024 -0.269435 0.0098456 0.0240263 -0.291024 -0.00934208 0.0234346 -0.30947 -0.0526075 -0.0152071 -0.207244 -0.0522474 0.0164989 -0.262947 -0.0524425 0.0161802 -0.232768 -0.0531248 0.0165619 -0.0777193 -0.0534415 0.015 -0.0778529 -0.0508145 0.0187386 -0.0768544 -0.0490716 0.019 -0.135321 -0.0524007 -0.0177353 -0.0773583 -0.0503076 -0.0188042 -0.135329 0.00286895 0.0165 -0.0799832 -0.0143326 0.0165 -0.290563 0.0065234 0.0168182 -0.282899 -0.0485154 0.0165 -0.274895 -0.048247 -0.0165 -0.26297 -0.0151508 -0.0164999 -0.314722 -0.0494305 -0.0165 -0.0803221 0.00286895 -0.0165 -0.0799832 -0.0414776 -0.0165 -0.28438 -0.0503746 -0.0164989 -0.272091 0.0168414 -0.0165006 -0.313149 0.00649403 -0.0165005 -0.320362 0.0119761 -0.0169534 -0.286421 0.0181189 -0.0165023 -0.288514 0.0213066 -0.0165046 -0.301198 0.00661776 -0.016505 -0.276446 -0.0486507 0.0164446 -0.262967 -0.0414776 0.0165 -0.28438 -0.00925187 -0.024 -0.290874 0.0132544 -0.024 -0.303674 -0.000626033 -0.024 -0.313745 -0.0135333 -0.024 -0.302453 -0.046676 -0.024 -0.269737 0.0191103 -0.0235919 -0.291634 0.000626061 -0.024 -0.286268 -0.00556459 0.0164976 -0.320657 -0.0144015 0.0165001 -0.315593 0.00985298 0.0164999 -0.319515 0.0200852 0.0168544 -0.308381 0.00663685 0.0165 -0.276656 0.00978405 0.016333 -0.0804956 0.00512259 -0.01675 -0.0769683 0.00441288 0.01675 -0.0799729 0.00441288 -0.015 -0.0799729 -0.052247 -0.0165 -0.262946 -0.048247 0.0165 -0.26297 -0.0490514 -0.016266 -0.262965 -0.0497471 0.01475 -0.262961 -0.0497471 -0.01475 -0.262961 0.00957673 -0.016641 -0.0806039 -0.0125205 0.0165508 -0.165603 0.00598915 0.019 -0.0785821 0.00115739 0.015 -0.106519 -0.00253773 0.015 -0.119591 -0.00729576 0.019 -0.123054 -0.00205169 0.0172446 -0.114654 -0.0148266 0.0186271 -0.162379 -0.0501443 0.0188203 -0.199194 -0.0526599 0.0151056 -0.199165 -0.0486595 0.019106 -0.199182 -0.0485197 0.0194517 -0.22084 -0.0507615 0.019096 -0.230053 -0.0484047 0.0206675 -0.238599 -0.0523929 0.0165415 -0.199225 -0.0515074 0.0179149 -0.199209 -0.0528735 0.0162425 -0.135345 -0.0506683 0.0235173 -0.263965 -0.0519747 0.0217127 -0.267739 -0.01391 0.0232593 -0.313584 -0.0440053 0.0201084 -0.281448 -0.044843 0.0230178 -0.278888 -0.0256845 0.024 -0.296483 -0.00321387 0.0235338 -0.320758 0.0109163 0.0237851 -0.317589 -0.0140781 0.0209276 -0.315888 0.0208941 0.0224981 -0.297258 0.017521 0.0227326 -0.289049 -0.0485511 -0.0195539 -0.223788 -0.0504482 -0.0186855 -0.207184 -0.0485087 -0.0201151 -0.233334 -0.048441 -0.0221553 -0.248307 -0.0490715 -0.019 -0.135321 -0.0513735 -0.019058 -0.23507 -0.0524076 -0.0165025 -0.199246 -0.0515276 -0.0178942 -0.199231 -0.0531693 -0.0164402 -0.0777827 -0.0518462 -0.0223283 -0.265173 -0.0482766 -0.0215865 -0.275599 -0.0461705 -0.0234403 -0.275704 -0.0147313 -0.0231534 -0.312784 -0.0416935 -0.0204573 -0.284112 -0.014157 -0.0204448 -0.315859 -0.00773028 -0.023992 -0.317247 -0.00558755 -0.016683 -0.320871 0.0107284 -0.0235156 -0.318508 0.0203394 -0.0234871 -0.304759 0.00784805 -0.018535 -0.0793404 0.00841977 -0.015 -0.0846612 -0.00975476 -0.0150006 -0.150386 0.00115739 -0.015 -0.106519 -0.00186102 -0.0172723 -0.114198 -0.00453547 -0.019 -0.111968 -0.00253773 -0.015 -0.119591 -0.0486507 -0.0164446 -0.262967 0.00423774 -0.0156937 -0.0799742 -0.0489304 -0.01675 -0.0803186 0.00441288 -0.01675 -0.0799729 -0.0498494 0.0164403 -0.0803247 -0.0494305 0.0165 -0.0803221 -0.0489304 0.01675 -0.0803186 0.00482795 -0.022 -0.287646 -0.0100893 -0.022 -0.305074 0.000613208 -0.022 -0.310772 -0.00482726 -0.022 -0.312367 0.00665383 -0.022 -0.311487 0.00901701 -0.022 -0.294092 0.010773 0.022 -0.30048 0.00499434 0.022 -0.309781 0.0115661 0.022 -0.306511 -0.0111725 0.022 -0.299624 0.00579659 0.022 -0.290913 0.00376816 0.022 -0.287283 -0.00975476 0.0150006 -0.150386 -0.00047172 -0.0164987 -0.257509 0.0066992 0.0215918 -0.276826 -0.0110235 -0.016003 -0.229096 -0.0126225 0.0151085 -0.167953 -0.0162204 -0.0193006 -0.214603 -0.0484992 -0.0209012 -0.240377 -0.0161443 -0.0196729 -0.226324 -0.0485921 -0.0193006 -0.214812 -0.0483095 -0.0238242 -0.262662 -0.0483554 -0.0234853 -0.258049 -0.0173327 0.021402 -0.243524 -0.00254104 0.023854 -0.262962 -0.0483158 0.0237953 -0.262135 -0.00374114 0.0233425 -0.256363 -0.0483859 0.0230885 -0.254569 -0.0487828 0.0190256 -0.180077 -0.0114369 -0.0151025 -0.158589 -0.0141451 -0.0182066 -0.165451 -0.0126262 -0.0159894 -0.166482 -0.0122707 -0.0156043 -0.222273 -0.014831 -0.0188934 -0.206134 -0.0130711 -0.0173473 -0.20614 -0.00962244 -0.021402 -0.243474 -0.0133794 -0.0186692 -0.226208 -0.0128805 -0.0202806 -0.234923 -0.00254143 -0.0238539 -0.26296 -0.00493203 -0.0233338 -0.256287 0.00157528 -0.024 -0.274225 -0.00404794 -0.0235753 -0.258758 -0.000759279 -0.0228695 -0.259737 0.00637187 -0.0222352 -0.277303 -0.0114369 0.0151025 -0.158589 -0.015565 0.0195917 -0.227278 -0.0122708 0.0156368 -0.222274 -0.0131431 0.0174585 -0.205071 -0.00864006 0.0213765 -0.243472 -0.000316141 0.0222222 -0.259786 -0.0118961 0.0176819 -0.22609 0.0048517 0.017 -0.290376 -0.00278339 0.017 -0.289882 0.00963027 0.017 -0.304858 0.0168119 0.017 -0.296549 -0.0152247 0.017 -0.28864 -0.00963046 0.017 -0.295154 -0.0101245 0.017 -0.30279 -0.0048519 0.017 -0.309637 -0.00550023 0.0168382 -0.317238 -0.000471456 0.0165 -0.257513 -0.00281569 -0.0159531 -0.258383 -0.00281583 0.0156255 -0.258383 -0.0151227 0.0145 -0.167969 -0.0149347 -0.0145 -0.164918 -0.0537626 -0.0107916 -0.0673494 -0.0617725 -0.00913102 -0.0674018 -0.0640143 0.0162482 -0.0674159 -0.0603001 0.00748802 -0.0673924 -0.0608828 0.00126614 -0.0673961 -0.0578011 -0.00085656 -0.0673762 -0.0537729 0.0128369 -0.0673497 -0.0574928 0.0156085 -0.067372 0.0119412 0.0118475 -0.0669239 0.0147938 0.000216696 -0.0669055 0.0156303 0.016157 -0.0668964 0.0196707 -0.000215693 -0.066874 0.0231893 0.0162491 -0.0668512 0.0187437 0.00766141 -0.0668799 0.0101595 -0.017 -0.302658 0.00497618 -0.017 -0.309573 -0.0115628 -0.017 -0.28493 0.00956661 -0.017 -0.29503 -0.0049764 -0.017 -0.29044 0.00221262 -0.0169145 -0.319204 -0.0095668 -0.017 -0.304983 -0.0101597 -0.017 -0.297355 -0.0168119 -0.017 -0.303464 0.00512259 0.01675 -0.0769683 0.00853195 -0.0167489 -0.0768918 0.00856842 0.0166428 -0.0768501 -0.00469003 0.0165 -0.259079 -0.0133639 0.0145 -0.229975 -0.0171224 0.0165 -0.167982 -0.0154994 0.0162741 -0.226209 -0.0144034 0.0145 -0.226194 -0.0147705 0.0145 -0.222289 -0.0120893 -0.0145 -0.149838 -0.0151231 0.0152819 -0.165925 -0.0122709 0.015 -0.150607 -0.0151227 -0.0145 -0.167969 -0.0147705 -0.0145 -0.222289 -0.0167705 -0.0165 -0.222302 -0.0171224 -0.0165 -0.167982 -0.0153272 -0.0161784 -0.226596 -0.0144034 -0.0145 -0.226194 -0.0133639 -0.0145 -0.229975 -0.0596897 -0.0146843 -0.0623882 -0.0614086 -0.00886489 -0.0623993 0.0201717 -0.00888876 -0.0618705 0.0170499 -0.0157706 -0.0656327 0.015866 0.014512 -0.0618982 0.0198321 0.00872504 -0.0618727 -0.0507988 -0.016748 -0.0623809 0.0080363 -0.0167516 -0.0620116 -0.021447 0.0186709 -0.0621641 -0.0218667 0.0172141 -0.0621511 -0.0609159 0.0137579 -0.0623961 0.0189675 -0.00154114 -0.0618784 0.0150168 0.00863808 -0.0619039 -0.0580396 0.00217822 -0.0623776 -0.0601036 -0.00226164 -0.0623909 -0.0508329 -0.0156349 -0.0628308 0.00965218 0.0172475 -0.0619388 -0.0508899 0.0155197 -0.0628311 0.00915678 0.0167469 -0.0624453 -0.0617128 0.0189967 -0.0627789 -0.0640426 0.0157484 -0.0629167 0.0191857 0.0189757 -0.0619958 0.0191606 -0.019 -0.0623771 + + + + + + + + + + 0.680366 -0.182984 -0.709661 -0.608405 0.000320516 0.793627 -0.589154 -0.00390989 0.808012 -0.574666 0.00259262 0.818384 0.807574 -0.000907543 -0.589765 0.43231 -0.375624 0.819765 0.802433 0.00669548 0.596704 -0.640791 0.00721356 0.767682 0.570028 -1.10816e-07 -0.821625 0.570051 5.94944e-06 -0.821609 0.70964 -0.00312798 -0.704558 0.707543 -0.00977855 -0.706603 0.826102 -0.00058672 -0.56352 0.827665 0.00603444 -0.56119 0.914909 -0.00577975 -0.403619 0.929188 0.114836 -0.351316 0.968905 -0.0931535 -0.229227 0.998 0.0398175 -0.0490891 0.994553 0.100049 -0.0292217 0.98394 -0.11943 0.13266 0.947218 0.078073 0.310937 0.956838 0 0.290621 0.877417 0 0.479729 0.852288 0.104258 0.512577 0.753976 -0.14031 0.641742 0.65312 0.0517729 0.755483 0.664822 0 0.747002 0.497711 0 0.867343 0.497711 -7.18023e-07 0.867343 0.331406 -7.81059e-07 0.943488 0.331406 0 0.943488 0.123773 0 0.992311 0.153197 -0.102871 0.982827 -0.0577891 0.07489 0.995516 -0.028531 -8.27505e-07 0.999593 -0.210122 -8.09361e-07 0.977675 -0.210123 0 0.977675 -0.384683 0 0.923049 -0.384631 -0.000141963 0.92307 0 -1 0 0 -1 0 0 -1 0 -0.841778 -0.00519388 0.539799 -0.859891 0.0657985 0.506219 -0.924575 -0.0617029 0.37597 -0.977889 0.0488584 0.203337 -0.975295 0.00516191 0.220847 0.00682346 0.000387051 -0.999977 0.00692207 -0.000275845 -0.999976 0 -1 0 0 -1 0 -1.45388e-07 -1 -8.17382e-08 -0.213531 -0.00519354 0.976922 -0.216253 0 0.976337 -0.388663 0 0.92138 -0.388663 0 0.92138 -0.548345 0 0.836252 -0.550664 0.00519359 0.834711 -1.05579e-07 -1 4.54023e-08 -1.1645e-07 -1 5.00769e-08 0.520701 0.0823459 0.849759 0.237852 0.0418189 0.970401 0.251768 0.00510827 0.967774 -4.67273e-08 -1 8.31164e-08 0 -1 0 8.35412e-07 -1 3.52398e-07 0.977082 -0.0058616 0.212782 0.966039 0.0660379 0.249815 0.919625 -0.0617032 0.387921 0.835253 0.0488569 0.547691 0.845799 0.00516239 0.533476 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.213532 -0.00519356 -0.976922 0.251487 0.0685772 -0.965428 0.387825 -0.0656052 -0.919395 0.54587 0.0335784 -0.837197 0 -1 0 0 -1 0 0 -1 0 -0.539799 -0.00519388 -0.841778 -0.506219 0.0657979 -0.859891 -0.375972 -0.0617032 -0.924574 -0.203379 0.0488321 -0.977882 -0.220904 0.00509458 -0.975282 -0.976922 -0.00519355 -0.213532 -0.965986 0.0657978 -0.250084 -0.919625 -0.0617027 -0.387922 -0.836491 0.0475424 -0.545914 -0.845884 0.0115823 -0.533242 0 -1 0 0 -1 0 -1.60601e-07 -1 4.50089e-08 -0.522069 0.00580194 0.852884 -0.195616 0.000122133 0.980681 -0.195546 0 0.980695 -0.359744 0 0.933051 -0.379943 0.0263655 0.924634 -0.446716 0 0.894676 -0.98535 -3.52961e-09 0.170545 -0.985315 -4.81184e-05 0.170749 5.65868e-07 -1 8.94472e-06 0 -1 0 8.41364e-06 -1 -2.18086e-05 7.82997e-06 -1 -3.72042e-05 -2.12482e-06 -1 -7.80214e-05 -0.00861854 -0.999911 0.0102234 0 -1 0 1.1418e-07 -1 -1.6463e-07 -2.68789e-08 -1 -4.68409e-08 0.0221431 -0.999725 -0.00767113 0 -1 0 2.26285e-06 -1 1.14938e-05 8.37912e-06 -1 9.41489e-06 3.16078e-05 -1 -1.21721e-05 0.22345 -0.924667 -0.308321 -0.239382 -0.117853 -0.963746 0.275797 -0.795072 0.540182 0.221861 -0.971122 0.0877428 0.22974 -0.96852 0.095855 -0.47965 -0.0617878 -0.875282 0.618723 -0.536866 0.573547 -0.669947 -0.742177 -0.0185541 -0.664735 -0.746721 -0.0231441 -0.663575 -0.748017 -0.0117753 -0.65219 -0.758023 0.00706364 -0.696572 -0.717344 -0.0143433 -0.713055 -0.699504 0.0473966 -0.686515 -0.722805 0.0790582 -0.761271 -0.648191 0.0177588 -0.821357 -0.55296 0.140027 -0.771455 -0.583178 0.254482 -0.73598 -0.617948 0.276539 -0.748954 -0.560893 0.352798 -0.717592 -0.547595 0.430351 -0.668843 -0.561567 0.487126 -0.700543 -0.532953 0.474553 -0.648564 -0.494887 0.578318 -0.578063 -0.526506 0.623406 -0.624558 -0.473287 0.62123 -0.496791 -0.503625 0.706796 -0.488068 -0.481261 0.728133 -0.410884 -0.484563 0.772252 -0.346611 -0.525929 0.776698 -0.344819 -0.527566 0.776385 -0.29079 -0.516083 0.805667 -0.225157 -0.54691 0.806346 -0.0598795 -0.587049 0.807334 -0.156727 -0.543591 0.824588 -0.204276 -0.56273 0.801003 -0.0232365 -0.557936 0.829559 0.205862 -0.594441 0.777342 0.104635 -0.575434 0.811127 0.119435 -0.59794 0.792592 0.25924 -0.547866 0.795385 0.532324 -0.484152 0.694427 0.541623 -0.56484 0.622575 0.397135 -0.518396 0.75733 0.414304 -0.622135 0.664304 0.36633 -0.553939 0.747632 0.695707 -0.53871 0.475167 0.661947 -0.500087 0.558335 0.568091 -0.783039 0.253226 0.54665 -0.816115 0.187433 0.399252 -0.916803 0.00836694 0.404871 -0.906323 0.121074 0.350381 -0.936117 -0.0302965 0.342724 -0.938576 0.0401917 0.332386 -0.942926 -0.0202671 0.333845 -0.94229 -0.025249 0.306566 -0.947525 -0.0906324 0.253367 -0.9594 -0.123923 0.217376 -0.967166 -0.131675 0.216164 -0.967424 -0.131772 0.265343 -0.944994 -0.191256 0.291794 -0.92007 -0.261395 0.287571 -0.921836 -0.25985 0.317982 -0.893185 -0.317974 0.305447 -0.896696 -0.320371 0.347819 -0.870026 -0.349393 0.462754 -0.729634 -0.503481 0.416167 -0.842315 -0.342506 0.403975 -0.85294 -0.330602 0 -1 0 9.24061e-07 -1 -5.75058e-07 -6.121e-07 -1 -1.74139e-07 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1.5174e-07 -1 -6.6314e-08 6.82974e-08 -1 -3.42523e-07 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 2.08623e-07 -1 -2.9547e-08 0 -1 0 0 -1 0 2.13549e-08 -1 -3.67875e-07 0 -1 0 2.97162e-07 -1 2.52928e-07 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.00536756 -0.999984 -0.00183978 -0.00533893 -0.999984 -0.00179554 -0.00401104 -0.999986 -0.00351968 0 -1 0 -3.46044e-05 -0.999996 0.00282394 -0.00478516 -0.999983 -0.00343855 -0.00449168 -0.999987 -0.00230388 0 -1 0 0 -1 0 0 -1 0 -0.640913 -0.00492419 -0.767597 0 -1 0 0 -1 0 0 -1 0 6.3496e-09 -1 2.01958e-07 3.17311e-07 -1 -1.7809e-07 -1.34497e-06 -1 -4.2725e-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 6.55175e-07 -1 -6.90429e-08 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.000138136 -0.999977 -0.00671443 -0.00194244 -0.99998 -0.00603341 -0.00321202 -0.999995 -0.000451794 0 -1 0 -4.81862e-08 -1 -3.86317e-07 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 3.55704e-08 -1 -3.88425e-07 -5.80136e-08 -1 -3.54287e-07 0 -1 0 0 -1 0 0 -1 0 -0.986252 -0.0165354 0.16442 -0.988141 0.00379478 0.153501 -0.999885 -0.00200625 -0.0150591 -0.998172 0.0485638 -0.0359721 -0.979071 -0.0619597 -0.19386 -0.849344 0.0158158 -0.527602 -0.741066 -0.0115544 -0.671333 -0.734887 0.00791266 -0.678143 -0.608715 -0.0100613 -0.793325 -0.608934 -0.010674 -0.793149 -0.456658 0.00258981 -0.889639 -0.289747 0.00382499 -0.957096 -0.113476 -0.0033347 -0.993535 -0.112972 -0.00215134 -0.993596 0.0664776 -0.00276347 -0.997784 0.0694567 0.00396862 -0.997577 0.266281 -0.00585712 -0.963878 0.244903 -0.0738821 -0.966729 0.410942 0.0937559 -0.906828 0.534619 -0.0934067 -0.839915 0.572466 0.000633601 -0.819928 -0.572976 3.96038e-05 -0.819572 -0.573131 0 -0.819464 -0.444816 0 -0.895622 -0.444815 7.41434e-08 -0.895622 -0.306456 7.8801e-08 -0.951885 -0.306457 0 -0.951885 -0.161409 0 -0.986888 -0.161596 -3.95027e-05 -0.986857 -0.984672 6.83775e-05 -0.174417 -0.984731 7.20572e-09 -0.174084 -0.947833 1.31944e-08 -0.318766 -0.947833 1.31944e-08 -0.318766 -0.889781 1.88909e-08 -0.456388 -0.889781 0 -0.456388 -0.811968 0 -0.583701 -0.812079 -3.957e-05 -0.583548 0.174151 2.50712e-05 -0.984719 0.174033 0 -0.98474 0.318489 0 -0.947927 0.318489 7.84734e-08 -0.947926 0.455957 7.36781e-08 -0.890002 0.455959 3.54605e-07 -0.890001 0.819521 2.05813e-05 -0.573049 0.819465 2.3723e-08 -0.573129 0.895621 1.84119e-08 -0.444817 0.895621 1.84119e-08 -0.444817 0.951885 1.26848e-08 -0.306455 0.951885 1.26848e-08 -0.306455 0.986888 6.68105e-09 -0.161409 0.986857 -3.95015e-05 -0.161595 0.955812 0.000663794 0.293977 0.822125 -0.000215151 0.569307 0.81155 0.0324855 0.58338 0.887953 -0.0417713 0.458033 0.934912 0.0607807 0.349635 0.98468 3.94951e-05 0.174372 0.984713 -7.20993e-09 0.174186 0.954831 -1.22997e-08 0.29715 0.572974 0.000231443 0.819573 0.546664 0.0423864 0.836279 0.427204 -0.056471 0.90239 0.323794 0.056471 0.944441 0.19221 -0.0423029 0.980442 0.161596 -0.000257228 0.986857 -0.0962908 0.00043497 -0.995353 -0.0960272 0.00333892 -0.995373 0.898304 -0.00275688 -0.439366 0.871793 0.00208703 -0.489871 0.855316 -5.52077e-05 -0.518107 0.952067 0.00103487 -0.305887 0.958951 -0.00184882 -0.283567 0.996725 -0.00252852 -0.0808258 0.999121 0.00151893 -0.0418849 0.993244 9.98687e-05 0.116042 0.992105 -0.00118701 0.125404 0.966396 -0.00222299 0.25705 0.957695 0.00175169 0.287779 0.936344 0.00100641 0.351083 0.942288 -0.00156853 0.334801 0.917489 -0.00202018 0.397756 0.916821 -0.00153406 0.399294 0.896904 0.00267124 0.442218 0.879088 0.00207161 0.476654 0.871438 -0.00413604 0.490488 0.834069 -0.00257521 0.551654 0.821818 0.00228678 0.569745 0.765307 -0.00221434 0.643661 0.767574 -0.00118133 0.640959 0.669211 0.00201657 0.74307 0.648662 -0.00418297 0.761065 0.571138 0.00363834 0.820846 0.535543 -0.00234334 0.844505 0.465079 0.00189188 0.885267 0.443939 -0.00144995 0.896056 0.369671 0.00326167 0.929157 0.310956 -0.00470813 0.950413 0.214781 0.00842761 0.976626 0.148305 -0.00420684 0.988933 0.0190053 0.00731854 0.999793 -0.0304256 -0.00421363 0.999528 -0.188278 0.0021492 0.982114 -0.193193 0.0033959 0.981155 -0.268944 -0.00114918 0.963155 -0.339494 0.00124178 0.940607 -0.334879 0.0003027 0.942261 -0.407522 -0.00296583 0.91319 -0.469712 0.000852634 0.882819 -0.467623 0.000361961 0.883928 -0.558425 -0.00115558 0.829554 -0.557857 -0.00132348 0.829936 -0.67817 -0.000237306 0.734905 -0.680735 0.000618034 0.73253 -0.74505 -0.00333463 0.667 -0.77619 0.00236978 0.630495 -0.809561 -0.00249896 0.58703 -0.857588 0.00546537 0.514309 -0.830001 -0.00365364 0.55775 -0.904656 0.000286749 0.426142 -0.897772 -0.00293544 0.440451 -0.950202 0.000237897 0.311636 -0.948621 -0.000895677 0.316412 -0.977935 0.00458186 0.208858 -0.985564 -0.00275257 0.16928 -0.998758 0.00211752 0.0497727 -0.997797 -0.00125274 0.0663234 -0.993434 0.00108844 0.114403 -0.994048 0.00202495 0.108926 -0.999939 -0.00200592 0.01083 -0.999971 -0.0010874 0.00757201 -0.999842 0.000630312 -0.0177425 -0.998264 -0.00114359 -0.0588876 -0.999127 0.000667372 -0.0417801 -0.999394 -0.000750064 -0.034796 -0.99982 0.000870975 -0.0189726 0.816097 -0.000314988 -0.577915 0.810345 -0.00159907 -0.58595 0.780481 0.00196263 -0.625177 0.745302 -0.00168439 -0.666724 0.740061 0.000413588 -0.67254 0.708677 0.000173822 -0.705533 0.707143 -0.00038819 -0.707071 0.691657 0.000387949 -0.722226 0.690048 -0.0002604 -0.723764 0.676701 0.00027909 -0.736258 0.678408 -0.000652055 -0.734685 -0.101202 0.000206319 -0.994866 -0.0971871 0.000112262 -0.995266 -0.261743 -0.00193404 -0.965136 -0.292721 0.00173277 -0.956196 -0.566885 0.000528485 -0.823797 -0.626606 -0.00496935 -0.779321 -0.775087 0.00209958 -0.631851 -0.846123 -0.00249215 -0.532982 -0.942799 4.03924e-05 -0.333363 -0.943537 -0.000171634 -0.331267 -0.997881 -0.00373661 -0.06496 -0.995478 0.000644302 -0.0949862 -0.249386 -0.812449 -0.527004 -0.172526 -0.745301 -0.64402 -0.414513 -0.753271 -0.510649 -0.602634 -0.700971 -0.381408 -0.703485 -0.666211 -0.247532 -0.728385 -0.683525 -0.0474207 -0.0675594 -0.707729 -0.703247 -0.0678578 -0.706845 -0.704106 0.451863 -0.820479 -0.350191 0.0732797 -0.68047 -0.729102 0.128052 -0.717009 -0.685201 0.271705 -0.646257 -0.713112 0.422534 -0.611386 -0.669083 0.494563 -0.630748 -0.597967 0.522568 -0.697815 -0.489874 0.102617 -0.0791889 -0.991564 -0.0310335 0.064127 -0.997459 0.651559 0.000759709 -0.758598 0.637333 -0.00149491 -0.770587 0.351738 -0.000226483 -0.936098 0.35588 0.000239916 -0.934532 0.532155 -0.000227785 -0.846647 0.536183 0.000254341 -0.844102 0.204784 -0.000863089 -0.978807 0.19337 0.000242519 -0.981126 0.108202 0.0771533 -0.991131 -0.0300823 -0.0878878 -0.995676 -0.0634395 0.720865 -0.690166 0.0777759 0.691623 -0.718059 0.18766 0.748472 -0.636061 0.251366 0.715782 -0.651514 0.394469 0.675877 -0.622563 0.47317 0.687789 -0.550506 0.482522 0.712176 -0.50988 0.481854 0.712779 -0.50967 0.50705 0.703534 -0.497935 0.509211 0.722213 -0.468095 0.514807 0.718082 -0.468328 0.547945 0.707286 -0.446658 0.553753 0.720892 -0.416741 0.575556 0.709882 -0.405959 0.603845 0.704097 -0.373656 0.624613 0.714193 -0.31589 0.636033 0.707916 -0.307112 0.706461 0.685358 -0.176628 0.709431 0.704545 0.0179654 0.687054 0.721687 0.0844076 0.690932 0.711614 0.12735 0.657764 0.70758 0.25822 0.65686 0.711099 0.250746 0.645257 0.705224 0.293773 0.63005 0.710556 0.313283 0.628853 0.706677 0.32427 0.614072 0.705753 0.353311 0.6083 0.708141 0.35848 0.595858 0.704785 0.38501 0.580398 0.710311 0.398243 0.551379 0.701174 0.452035 0.556409 0.710381 0.431008 0.520216 0.706434 0.479924 0.489811 0.714852 0.499071 0.455106 0.705881 0.54278 0.420946 0.711435 0.56273 0.390157 0.704583 0.59274 0.350345 0.709069 0.611947 0.318566 0.704928 0.633713 0.290029 0.708546 0.643309 0.255655 0.705357 0.661144 0.202567 0.712083 0.672239 0.159566 0.698989 0.697103 0.0265287 0.710133 0.703568 0.0279731 0.70948 0.70417 -0.140754 0.714288 0.685552 -0.112409 0.704487 0.700758 -0.211093 0.701313 0.680882 -0.30454 0.713786 0.630687 -0.295811 0.709333 0.639799 -0.407356 0.716787 0.565931 -0.362246 0.705365 0.609293 -0.451936 0.700788 0.551951 -0.564474 0.703799 0.431319 -0.52689 0.714726 0.45995 -0.518255 0.705841 0.482908 -0.613439 0.703328 0.359196 -0.622397 0.717049 0.313787 -0.658087 0.701369 0.273868 -0.685742 0.702119 0.191799 -0.677049 0.719524 0.154567 -0.697118 0.706144 0.124048 -0.695439 0.714412 0.0773289 -0.686537 0.723972 0.0673192 -0.705897 0.707052 0.0422748 -0.707839 0.706179 0.0166209 -0.699639 0.714449 0.00824198 -0.710807 0.70332 -0.00970171 -0.699071 0.714372 -0.0311882 -0.704246 0.709133 -0.0341822 -0.725462 0.684795 -0.0689962 -0.719814 0.647042 -0.251403 -0.568413 0.677706 -0.466498 -0.391716 0.726071 -0.565137 -0.319449 0.751997 -0.576587 -0.20822 0.705096 -0.677852 -0.0678336 0.707018 -0.703935 0.00073825 1 0.000472117 8.57737e-09 1 1.49821e-08 -3.50729e-07 1 4.1696e-07 -9.12552e-06 1 0.000164335 -1.1674e-07 1 -1.06859e-06 -7.76255e-07 1 -7.44122e-07 -1.96717e-05 1 -6.55544e-06 7.25712e-09 1 1.60969e-08 -4.88555e-06 1 1.05268e-06 6.73046e-06 1 -1.39565e-06 -0.000232212 1 -0.000369983 4.1403e-08 1 6.59673e-08 0.000850966 1 2.98043e-05 6.34224e-05 1 0.000118651 0.000314969 1 -3.71043e-06 4.23177e-06 1 -5.11683e-05 3.4616e-06 1 -1.73429e-06 -2.79363e-06 1 7.7708e-06 -1.64669e-05 1 -0.000111137 1.61706e-05 1 -3.20804e-05 -2.64141e-07 1 1.98786e-07 3.06536e-06 1 -2.32654e-06 2.32179e-05 1 3.13029e-07 -3.96713e-08 1 1.36e-07 8.49086e-08 1 -2.9108e-07 1.27649e-08 1 1.0465e-08 1.35422e-08 1 9.29203e-09 1.40757e-08 1 8.29503e-09 -2.07075e-06 1 8.71416e-07 -1.21608e-07 1 -4.77399e-08 -1.69082e-05 1 2.35812e-05 1.01287e-08 1 1.35403e-08 1.16687e-08 1 1.18894e-08 0.046394 0.831617 0.553409 -0.00472426 0.954733 0.297426 -0.776712 0.577934 0.250423 -0.423464 0.824436 -0.375478 -0.423332 0.824548 -0.375381 -0.0330614 -0.656101 -0.753948 0.543002 0.839725 0.00342647 0.542299 0.840178 0.00349388 9.05438e-07 1 2.37966e-07 -0.0959697 -0.00212055 -0.995382 -0.0961265 -0.000733647 -0.995369 0 -1 0 0 -1 0 0 -1 0 -1.08758e-08 -1 -4.18058e-08 -1.62112e-08 -1 -4.32674e-08 5.06543e-08 -1 -1.19058e-07 0 -1 0 0 -1 0 -1.54852e-07 -1 6.97686e-07 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1.15898e-07 -1 -1.61914e-07 5.15479e-08 -1 -9.25391e-07 -9.08486e-08 -1 -2.3284e-07 -2.69436e-07 -1 -2.33276e-07 -1.59349e-05 -1 -4.24249e-06 0 -1 0 1.21905e-06 -1 -4.53751e-07 3.9622e-05 -1 -4.22157e-06 9.16635e-06 -1 -1.30538e-05 -1.52462e-05 -1 -1.32001e-05 8.69347e-06 -1 1.41344e-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 3.83497e-06 -1 -2.95061e-05 0 -1 0 0 -1 0 4.70754e-07 -1 -4.91806e-07 1.84707e-05 -1 1.87141e-05 3.37528e-05 -1 -1.54214e-06 -1.97169e-06 -1 5.65186e-06 0 -1 0 0 -1 0 0 -1 0 -1.11909e-05 -1 -9.49878e-06 3.89437e-07 -1 5.90811e-07 1.0329e-10 -1 -4.22884e-08 4.51726e-08 -1 -6.84739e-08 2.98425e-07 -1 1.53118e-07 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1.06017e-07 -1 -1.37727e-06 3.06605e-07 -1 1.62143e-07 0 -1 0 -2.42625e-08 -1 -1.57024e-07 1.09885e-05 -1 2.62209e-06 0 -1 0 3.67042e-06 -1 -3.65255e-06 0 -1 0 1.57251e-07 -1 -1.56596e-07 5.48753e-08 -1 -5.46468e-08 5.52776e-08 -1 -5.45199e-08 -2.50524e-07 -1 -4.4364e-08 -8.56386e-08 -1 -1.39235e-07 0 -1 0 0 -1 0 0 -1 0 -2.13976e-06 -1 -1.38646e-08 -6.85403e-07 -1 -3.58426e-07 -2.51858e-07 -1 -3.56316e-07 -2.28131e-07 -1 -3.47432e-07 3.33523e-07 -1 5.07938e-07 5.52482e-07 -1 6.97811e-07 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1.12173e-07 -1 -2.18739e-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 -2.39885e-07 -1 1.82951e-07 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 2.53551e-08 -1 -1.0532e-07 4.97159e-07 -1 4.84239e-07 7.23062e-09 -1 -9.25807e-07 0 -1 0 0 -1 0 -0.999987 0.000158439 -0.00509806 -0.999993 0.000546142 -0.00376307 0.869333 -4.90469e-05 -0.494226 0.869297 -6.70141e-06 -0.494291 0.999979 -1.30001e-05 0.00649795 0.999979 1.6702e-05 0.0065431 0.00983336 0.998509 -0.0537046 0 1 0 1.09625e-05 1 -1.59586e-05 4.24461e-08 1 4.29495e-08 4.55046e-08 1 3.96527e-08 2.30184e-08 1 3.29252e-08 -3.92539e-09 1 4.22736e-08 1.57886e-07 1 1.11091e-09 0 1 0 -3.2369e-07 1 1.25947e-08 6.18979e-08 1 1.17373e-07 1.8027e-08 1 5.4356e-07 -7.33179e-08 1 7.23295e-08 -2.11956e-08 1 1.08025e-07 -6.16963e-08 1 3.36953e-07 -6.65433e-08 1 3.33602e-07 0 1 0 4.93986e-09 1 7.45601e-08 1.72051e-08 1 3.63426e-08 -1.01077e-07 1 1.53341e-07 0.702927 7.92163e-05 0.711262 0.702927 7.92539e-05 0.711262 -0.711889 -2.61073e-05 0.702292 -0.711969 -7.29186e-05 0.702211 0.999975 -9.51056e-05 0.007036 0.999977 -2.77544e-06 0.00676998 -0.94187 1.36094e-05 0.335978 -0.94187 1.30341e-05 0.335977 -0.591011 -0.000156071 -0.806663 -0.91283 6.27304e-05 -0.40834 -0.913393 1.26374e-08 -0.40708 -0.991245 -4.09882e-09 0.132032 -0.99522 0.00186132 0.0976404 -0.816852 -0.0024794 0.576841 -0.728427 1.74573e-05 0.685123 -0.766011 0.0616813 0.639862 -0.0672185 -0.000390995 0.997738 -0.0924311 0.0245929 0.995415 0.725284 -0.272992 0.632012 0.997305 -0.0120067 -0.0723796 0.998688 0.000388114 -0.051206 0.577203 -0.000118462 0.816601 0.885719 3.86394e-05 0.464221 0.886148 -1.43859e-08 0.463403 0.999979 -2.01145e-10 0.00647934 0.999979 -1.92764e-10 0.00647934 0.89208 1.34436e-08 -0.451877 0.891662 -3.86439e-05 -0.452701 0.587741 0.000118449 -0.809049 0.954554 2.36752e-06 -0.298039 0.954537 2.46773e-08 -0.298092 0.711674 5.81568e-08 -0.70251 0.711673 0 -0.702511 0.311278 0 -0.950319 0.31128 7.86714e-08 -0.950318 -0.159217 8.17282e-08 -0.987244 -0.159855 -4.29935e-05 -0.98714 0.815244 3.76447e-05 -0.579117 0.463461 2.82168e-06 -0.886117 0.463403 7.33591e-08 -0.886148 0.00649113 8.27825e-08 -0.999979 0.00648915 0 -0.999979 -0.451885 0 -0.892076 -0.452707 -3.8582e-05 -0.891659 -0.809046 0.000118471 -0.587745 0.169283 -0.000118449 -0.985567 -0.298055 3.86503e-05 -0.954549 -0.298936 0 -0.954273 -0.702506 0 -0.711677 -0.702506 0 -0.711677 -0.95032 0 -0.311276 -0.950606 -3.85456e-05 -0.3104 -0.987679 0.000118408 0.156496 -0.801883 0.000981775 -0.59748 0.989776 0.00117997 0.142628 0.987543 0.000103455 0.157351 0.597484 0.000982491 -0.80188 0.587037 -0.000982354 0.80956 -0.9895 0.000983035 0.144529 0.157348 -0.000982602 -0.987543 -0.828646 -0.0118917 0.559646 0.883999 0 0.467489 0.883999 3.84971e-08 0.467489 0.884184 -4.01463e-05 0.467139 -0.929528 6.98223e-05 0.36875 -0.924659 -0.00205799 0.380791 -0.885092 0.00189668 0.465412 -0.86449 -0.0056469 0.502618 -0.68594 0.00267601 0.727654 -0.698574 -0.000882708 0.715537 -0.779945 -0.00293566 0.625841 -0.797022 0.0037044 0.603939 -0.252552 2.00252e-08 -0.967583 -0.252553 -1.47239e-07 -0.967583 -0.23344 -0.445262 -0.864435 -0.258918 0.000667703 -0.965899 -0.498316 0.00437564 0.866984 -0.366769 -0.00138103 0.930311 0.0356955 -0.00181285 0.999361 0.00844751 -0.000456772 0.999964 0.46891 -0.00192336 0.883244 0.863114 0.00395341 0.504994 0.782893 -0.00127889 0.622155 0.494366 -0.000491977 0.869254 -0.752337 -0.000343151 -0.658778 -0.720213 0.0024771 -0.693749 -0.426285 -0.00368975 -0.904581 -0.989589 -0.00163365 0.143911 -0.998369 0.00547871 -0.0568202 -0.964604 -0.003829 -0.263674 0.845406 -0.40712 0.34575 0.614466 -0.514924 0.597733 0.722799 -0.527032 0.446989 -0.11885 -0.831352 0.542889 0.459914 -0.720893 0.518452 -0.292912 -0.735183 0.611316 -0.299471 -0.811196 0.502273 -0.398665 -0.794698 0.457735 -0.522969 -0.686913 0.504632 -0.452603 -0.833303 0.317423 -0.609301 -0.73837 0.289071 -0.674656 -0.694704 0.249451 -0.739913 -0.595058 0.313743 -0.243526 -0.72788 -0.641004 -0.400283 -0.904336 -0.148154 -0.275043 -0.407276 -0.870906 0.841454 -0.00572916 -0.540299 0.859776 0.065977 -0.506392 0.924575 -0.0617042 -0.37597 0.977703 0.048212 -0.204384 0.975576 0.0107861 -0.219399 0 -1 0 0 -1 0 0 -1 0 -0.00582823 0.0023782 0.99998 -0.00623923 -0.000387627 0.99998 0.711848 0.00079434 -0.702333 -0.711693 -0.00218749 0.702487 -0.711506 -0.000387385 0.702679 -0.99998 0.00239514 -0.00582758 -0.99998 -0.000387559 -0.00624135 0.999965 -0.00427824 0.00713154 0.99998 0.000395618 0.00634341 -0.702464 0.000100596 -0.711719 -0.702397 -0.000456144 -0.711785 0.702007 -0.00239518 0.712166 0.702283 0.000194902 0.711897 0.00653283 -0.00234456 -0.999976 0.00624189 -0.000388015 -0.99998 -0.00627728 0.000782198 0.99998 -0.00647376 -0.000436144 0.999979 -0.712126 -0.0042775 0.702039 -0.71158 0.000389461 0.702605 0.711658 -0.00206391 -0.702523 0.711517 -0.00074706 -0.702668 -0.999966 -0.0041132 -0.00710554 -0.99998 0.000389662 -0.00634623 0.99998 0.00240133 0.00582639 0.99998 -0.000387636 0.00624111 -0.70203 -0.00245418 -0.712143 -0.702333 0.000387871 -0.711849 0.702595 -0.000388155 0.71159 0.703132 0.00476641 0.711043 -0.580717 0.503857 -0.63945 0.548083 0.189119 0.814763 -0.876216 0.481823 0.00964016 0.834004 -0.546606 -0.0752333 0.574194 0.506575 0.643182 0.590532 0.195184 -0.783055 -0.98941 -0.0611467 0.131643 -0.993713 -0.103207 0.0433997 0.428895 0.889155 0.159536 -0.193632 0.980187 -0.0417246 -0.183306 0.982291 -0.0387715 -0.944759 -0.00797834 -0.327669 -0.219804 -0.543421 0.810173 -0.542968 0.142138 0.827637 0.194074 0.237646 -0.951767 0.202497 0.229488 -0.952014 0.387203 0.229208 -0.893049 0.387203 0.229208 -0.893049 0.566758 0.229208 -0.791359 0.610165 0.176098 -0.772456 0.710012 0.284237 -0.644277 0.850665 0.184793 -0.492159 0.863723 0.155611 -0.479341 0.912434 0.284238 -0.294402 0.981044 0.175999 -0.0810957 0.975451 0.199832 -0.0925374 -0.160057 -0.980384 0.115021 0.160057 0.980384 -0.115021 0.90237 0.196366 -0.383627 0.659704 -0.550083 0.512054 0.338439 -0.932056 -0.129347 -0.39382 -0.906652 -0.151289 -0.812288 -0.331254 0.480062 0.951971 -0.291834 -0.0926546 0.56164 -0.824891 0.0641503 -0.834201 -0.548016 -0.0615314 -0.996015 -0.0562656 0.0692002 0.234662 -0.0527963 -0.970642 0.916907 -0.395328 -0.0547487 0.801608 -0.597814 0.00657894 -0.412318 -0.910588 0.0286774 -0.893669 -0.435562 -0.107899 0.932285 -0.341325 -0.119753 -0.869652 -0.480264 -0.114243 -0.446129 -0.883382 0.143546 -0.053679 0.911158 -0.408546 0.126334 -0.988763 -0.0799273 -0.540451 -0.827944 0.149737 0.994908 -0.0495254 -0.0877757 0.259858 -0.215422 0.941311 -0.0640403 0.99583 0.0649714 -0.148848 0.985517 0.0812481 -0.193295 0.98111 0.00780496 -0.455448 -0.854127 0.251066 0.759278 0.495356 -0.422042 0.999982 0.00557842 -0.00238689 0.441806 -0.762825 -0.472129 -0.760835 -0.300332 0.575265 0.945304 -0.220649 0.240237 0.11387 -0.338437 0.934074 0.751177 -0.560888 0.348047 -0.349765 -0.756932 0.552013 0.676319 -0.697662 -0.236349 0.710516 -0.47606 -0.518203 -0.710516 0.47606 0.518203 -0.192065 0.083312 0.97784 -0.230088 0.701518 0.674487 0.538833 0.179462 -0.823075 0.497621 0.104965 0.86102 -0.875262 0.22499 0.42813 -0.717976 -0.0279219 0.695507 -0.664422 0.190103 0.722775 0.776929 0.0128461 0.629457 -0.635668 -0.769747 0.0584509 -0.871057 0.286757 0.398786 -0.666794 -0.643204 0.376397 -0.479639 0.678317 0.556626 -0.358429 -0.678223 0.641516 -0.259563 0.559558 0.787097 -0.0721109 -0.55956 0.825647 0.0614038 0.559558 0.826513 0.250977 -0.66589 0.702567 0.382679 0.526385 0.759259 0.729849 -0.102658 0.675857 0.84167 -0.375517 0.388045 0.958612 -0.232338 0.164564 -0.605291 0.00840254 -0.79596 -0.273275 0.0339619 -0.961336 -0.0248838 -0.0453363 -0.998662 0.841021 0.00572618 -0.540972 -0.447303 -0.0543514 -0.89273 -0.0201843 0.0333933 -0.999238 -0.625285 0.0199288 -0.780142 -0.998373 3.31888e-07 0.0570182 -0.996285 -0.00726738 0.0858115 -0.965542 0.00387048 0.26022 -0.963394 -0.00198808 0.268081 -0.896834 -0.00157103 0.442364 -0.895107 -3.5359e-06 0.445851 -0.531928 -0.00300386 0.846784 -0.496323 0.00834993 0.868098 -0.367224 -0.016999 0.929977 -0.346299 -0.00308707 0.938119 -0.335042 0.000567968 0.942203 0.214358 -0.0314986 0.976247 0.177376 -0.00126463 0.984142 0.296926 -0.000913119 0.9549 0.355115 -0.0207235 0.934593 0.380535 -0.00774187 0.924734 0.835396 -0.0614796 0.546199 0.79408 0.00622201 0.607782 0.891782 -0.0141769 0.452244 0.892161 -0.0146199 0.451482 -0.801905 -0.00159933 0.59745 -0.797311 0.00109954 0.603568 -0.67847 -0.00111235 0.734627 -0.593936 0.036932 0.803664 -0.711222 -0.136445 0.689599 -0.190111 -0.00734552 0.981735 -0.157038 0.00304502 0.987588 -0.0064802 -0.00882675 0.99994 0.0716294 0.0133218 0.997342 0.475286 0.00626044 0.879809 0.520893 -0.00846042 0.85358 0.627191 0.00222906 0.778862 0.668869 -0.00836117 0.743333 0.728307 0.00565086 0.685227 0.77619 -0.00817294 0.630446 0.900991 -0.00907897 0.433743 0.96003 -0.00211228 0.27989 0.961481 0 0.274871 0.994607 -3.59084e-09 0.103717 0.995607 5.8968e-05 0.0936272 0.995579 -7.34647e-05 0.0939239 0.964226 -2.21848e-05 0.265082 0.964217 -3.79595e-05 0.265116 0.903546 0.000938947 0.42849 0.90262 2.1521e-05 0.430437 0.815434 2.23496e-05 0.57885 0.815321 -6.15926e-05 0.579009 0.709417 -9.38375e-05 0.704789 0.702456 0.00400235 0.711716 0.589449 -0.000540356 0.807805 0.568169 0.00928271 0.82286 0.416748 -0.000441732 0.909022 0.417596 1.14662e-05 0.908633 0.25258 2.25797e-05 0.967576 0.252332 -8.78332e-05 0.967641 0.0807241 -4.34649e-05 0.996736 0.0799568 -0.000374916 0.996798 -0.0935834 0.000137676 0.995611 -0.0938667 1.12544e-05 0.995585 -0.265048 2.23374e-05 0.964235 -0.265349 -0.000111895 0.964152 -0.428416 0.00246458 0.903579 -0.433672 3.80966e-05 0.901071 -0.578851 2.16474e-05 0.815433 -0.579 -5.69147e-05 0.815328 -0.704781 -0.00023963 0.709425 -0.711733 0.00395117 0.702439 -0.822838 -1.50457e-05 0.568277 -0.822583 0.00019473 0.568644 -0.909017 -0.000148735 0.41676 -0.909032 -0.00016566 0.416726 -0.967576 -1.21795e-05 0.252579 -0.967696 -0.00022401 0.252118 -0.996736 -9.26444e-05 0.0807242 -0.996788 -0.000377227 0.080088 -0.206696 -0.00614377 0.978386 0.274482 -0.42636 0.861903 0.0108716 -0.0136167 0.999848 -0.0254538 -0.0787058 0.996573 -0.0662475 0.00586256 0.997786 -0.186481 0.00640877 0.982438 -0.153114 -0.000206598 0.988209 -0.0369394 -0.0018134 0.999316 -0.999984 0.00456187 0.00327551 -0.793104 -6.13249e-08 0.609086 -0.753397 -0.0176267 0.657329 -0.669843 -0.00473002 0.742488 -0.695992 -7.22958e-08 0.71805 0.660166 -0.00369728 0.75111 0.660522 -0.00382103 0.750797 0.998439 -0.0197179 0.0522628 0.992625 -0.00019806 0.121223 0.785131 -0.00564453 0.619304 0.799516 0 0.600645 0.884214 0 0.467081 0.884214 0 0.467081 0.954115 0 0.299439 0.954115 -1.65876e-08 0.299439 0.988177 -6.79951e-09 0.153319 0.0405682 0.000390605 0.999177 0.127302 0.0118667 0.991793 0.174503 -7.73898e-09 0.984657 0.34973 -1.55101e-08 0.936851 0.34973 0 0.936851 0.51342 0 0.858138 0.514271 0.000246818 0.857628 -0.621505 0.00267556 0.783405 -0.524491 -0.00543878 0.851399 -0.498592 0 0.866837 -0.361843 0 0.932239 -0.361843 0 0.932239 -0.221693 0 0.975116 -0.994138 -0.00587965 0.107963 -0.990218 -2.7978e-09 0.139528 -0.957916 -6.36511e-09 0.287048 -0.957916 -1.24407e-08 0.287048 -0.890194 -2.02045e-08 0.455582 -0.890194 -1.65876e-08 0.455582 -0.810292 -2.59895e-08 0.586026 0.789615 -0.613553 0.00779486 0.26425 -0.821331 0.505556 0.198672 0.711935 0.673556 -0.248161 -0.613927 0.74934 -0.155854 0.534545 0.830645 -0.39689 -0.00759364 0.917835 -0.301492 -0.280686 0.911218 -0.322299 -0.00104092 0.946637 -0.30891 0.00222285 0.951089 -0.399984 0.000487519 0.916522 -0.373879 0.0178383 0.927306 -0.344338 0.0745573 0.93588 -0.287712 0.00177103 0.957716 -0.238942 -0.012452 0.970954 -0.186762 0.00057827 0.982405 -0.188466 0.0280548 0.981679 -0.227732 -0.004903 0.973711 -0.0920259 0.012531 0.995678 -0.119029 0.0422137 0.991993 -0.0346053 -0.13568 0.990148 0.167882 0.0390202 0.985035 0.36921 0.05428 0.92776 0.511087 -0.0199196 0.859298 0.592144 0.0196391 0.805593 0.516117 -0.115394 0.84871 0.571152 0.00416446 0.820834 0.66199 0.00238751 0.749508 0.650611 0.0153852 0.759255 0.785143 0.00146302 0.619313 0.786039 3.98593e-05 0.618177 0.887509 0.00718239 0.460735 0.956883 -0.0245246 0.289436 0.887988 0.00610268 0.459827 0.953958 0.0181476 0.29939 0.893353 -0.0156701 0.449082 0.884215 0 0.467081 0.785144 0 0.619314 0.785144 0 0.619314 0.660171 0 0.751115 0.661637 0.00151734 0.749823 0.601314 -0.0155184 0.798862 0.554555 0.0056903 0.832128 0.546812 0.00147135 0.837254 0.333721 0.120654 0.934919 0.391537 -0.045215 0.919051 0.511822 0.0788197 0.855468 0.995054 -0.00189134 0.0993129 -0.995885 -0.00346497 0.0905642 -0.994117 0.00174082 0.108299 -0.959511 -0.000306291 0.281672 -0.957915 0.00121895 0.287048 -0.890193 -0.00150183 0.455581 -0.850099 -0.0259259 0.525984 -0.793103 0.00177482 0.609085 -0.672801 0.00029723 0.739824 -0.66985 0.00139897 0.742495 -0.527629 1.8132e-06 0.849475 -0.524498 0.00100197 0.851411 -0.404948 -0.000541748 0.91434 0.993222 0.00305202 0.11619 0.963169 5.7611e-05 0.268897 0.969081 0.00828584 0.246605 -0.926551 -0.360067 0.108883 -0.894253 0.360067 0.265825 -0.802159 -0.360067 0.476332 -0.70882 0.360067 0.606569 -0.539068 -0.360067 0.761418 -0.400826 0.360067 0.842431 -0.147932 -0.436584 0.887418 0.136418 0.436582 0.889261 0.403681 -0.449333 0.796957 0.558717 0.172284 0.811267 0.688045 -0.438107 0.578494 0.835096 0.204589 0.510644 0.860255 -0.422778 0.284993 0.925062 0.360067 0.120882 0.445458 -0.893729 0.0530678 0.780082 -0.552214 0.294163 0.414933 -0.870555 0.264508 0.467278 -0.770868 0.432913 0.24411 -0.885984 0.394262 0.272763 -0.763229 0.585732 0.0499987 -0.880815 0.470814 0.021307 -0.812993 0.581883 -0.213981 -0.773308 0.596831 -0.0797376 -0.923967 0.374068 -0.632377 -0.458898 0.624109 -0.314134 -0.869873 0.380317 -0.69124 -0.682716 0.236826 -0.290388 -0.942538 0.165221 -0.68923 -0.720728 0.0742528 -0.974784 -0.194777 0.108895 -0.924904 0.21488 0.313655 -0.861616 -0.173654 0.476931 -0.750357 -0.110102 0.651799 -0.626081 0.197148 0.754424 -0.550236 -0.0598462 0.832862 -0.231278 0.0467222 0.971765 -0.227373 0.0336348 0.973227 0.0409419 -0.134328 0.990091 0.155311 0.105376 0.982229 0.424056 -0.0933685 0.90081 0.420526 -0.0792656 0.903811 0.725891 0.0480095 0.686132 0.72853 0.0373423 0.683995 0.851223 -0.0992779 0.515329 0.938151 0.104318 0.330138 0.963199 -0.0882909 0.253876 -0.50878 -0.848977 0.142759 -0.395443 0.848136 0.352547 -0.578099 0.575019 0.578925 0.60748 -0.608644 0.510413 0.389588 -0.885607 0.252826 0.915723 0.395035 0.0734812 0.999898 -0.0134809 -0.00481486 0.999965 0.00443719 0.00712896 0.999999 -0.000662659 0.00136009 0.99999 0.00241251 0.00370648 0.00617814 -0.00150207 -0.99998 0.00736126 0.000318569 -0.999973 -0.00101612 0.0121307 -0.999926 -0.045168 -0.00977302 -0.998932 0.00603016 -0.00126708 -0.999981 0.00685984 0.000674477 -0.999976 0.00764441 -0.0172809 -0.999821 0.00645382 -0.00378546 -0.999972 0.00737531 0.00297713 -0.999968 0.00631714 -0.0029947 -0.999976 -0.262424 -0.0405901 -0.964099 0.00593094 -0.00179938 -0.999981 0.00741758 -0.00887619 -0.999933 0.00608102 0.00752155 -0.999953 0.0023902 -0.00439645 -0.999988 0.0101862 0.0166613 -0.999809 0.0324669 0.0234286 -0.999198 -0.999634 -0.0176658 -0.0204742 0.00180066 -0.999995 0.00268716 -3.50107e-05 -1 4.92997e-05 -0.0139545 -0.999889 0.00524142 -0.170919 -0.985154 0.0160509 0.000341034 -1 -6.265e-05 0.0590027 -0.997383 -0.0417839 0.648325 -0.754205 0.104162 0.0358755 -0.999294 -0.0111854 0.043479 -0.999022 -0.00798737 0.0887342 0.991337 -0.0968413 -0.00884839 -0.999912 0.009935 -0.0306286 -0.99953 0.00146754 -6.36329e-05 -1 -4.51896e-05 0.130473 -0.166665 -0.977343 0.032195 -0.993082 -0.11292 -0.343453 -0.570044 -0.746384 -0.0806869 -0.947497 -0.309418 0.202564 -0.645904 -0.736054 0.115862 -0.314611 -0.942123 0.454418 -0.604618 -0.654173 -0.527877 -0.721081 0.448763 0.189691 -0.899277 -0.394105 -0.696035 -0.624466 -0.354369 -0.342686 0.0292733 0.938994 0.516325 -0.654533 -0.552264 0.180696 -0.975385 -0.126383 -0.309251 -0.950556 -0.0284288 0.0905122 -0.968155 -0.233416 0.656626 -0.714025 0.24292 0.171765 -0.983697 0.053264 -0.11797 -0.980306 -0.158377 -0.114866 -0.972502 0.202598 -0.376457 0.925545 -0.0405834 -0.312536 0.882818 -0.350648 -0.0305665 -0.959217 -0.281014 0.11196 0.000670782 -0.993712 0.113145 -0.00027019 -0.993578 0.24134 0.937843 -0.249411 0.761667 0.256944 -0.594847 -0.0018052 0.999998 -0.00108975 0.00221678 0.999989 0.00414282 0.00358865 0.999982 0.00483269 0.00311713 0.999993 0.00205513 0.00266426 0.999995 0.0019066 0.00428606 0.999989 0.0019014 0.00447393 0.99999 -0.000132719 0.291635 0.883951 -0.365486 0.00307825 0.999995 3.76668e-05 0.0063485 0.999979 -0.00133926 0.00448635 0.999987 -0.00231656 0.00114063 0.999999 -0.00118542 0.00193244 0.999994 -0.00293436 0.00183736 0.999994 -0.00292908 -0.000264039 0.999999 0.00129489 -0.000338016 1 0.000779603 -0.106617 0.971185 -0.213148 -0.000912585 0.999997 -0.00217213 -0.00165564 0.999995 -0.00283059 -0.00119288 0.999999 -0.00113892 -0.00187195 0.999997 -0.00140198 -0.00686206 0.999975 -0.00187185 -0.0068104 0.999977 0.000233405 -0.0028907 0.999995 0.000833364 -0.00314985 0.999995 0.00101632 -0.00391261 0.99999 0.00226367 -0.00266284 0.999993 0.00263665 -0.0023821 0.999995 0.00216156 -0.00266041 0.99999 0.00371488 -0.00068824 0.999992 0.00381144 0.332336 0.498168 -0.800863 0.0397211 -0.000569488 -0.999211 -0.816598 -0.266148 -0.512184 0.0235211 -0.000234299 -0.999723 -0.0161595 0.00411779 -0.999861 -0.115592 -0.0015311 -0.993296 -0.108208 -0.00388634 -0.994121 -0.00012623 1 -0.000174054 0 1 0 -3.35709e-05 1 9.8034e-06 2.6473e-05 1 4.04294e-05 5.8199e-07 1 3.52704e-05 1.63849e-05 1 3.31229e-05 5.01868e-07 1 -1.40191e-07 4.42095e-05 1 8.09536e-06 4.18014e-05 1 1.06264e-05 4.54392e-05 1 -1.36163e-05 3.55701e-05 1 -2.50864e-05 3.1362e-05 1 -1.60504e-05 3.10802e-05 1 -2.36317e-05 2.56301e-05 1 -2.84097e-05 -1.48919e-05 1 -2.83225e-05 0 1 0 0 1 0 -8.1577e-05 1 -0.000123129 1.10418e-05 1 2.90599e-05 1.7875e-05 1 2.17079e-05 1.23385e-05 1 2.0219e-05 1.66464e-05 1 1.84996e-05 1.79923e-05 1 1.45558e-05 1.88969e-05 1 1.44636e-05 2.22184e-05 1 1.14513e-05 2.21398e-05 1 8.8146e-06 2.51937e-05 1 7.34503e-06 3.59064e-05 1 -1.14871e-05 0.000511597 1 -0.000142909 -2.28842e-05 1 2.76504e-05 -9.17804e-08 1 2.26793e-06 0 1 0 0.127418 0.132279 -0.982989 0.0659839 0.289023 -0.955046 0.992744 0.0925965 -0.0767157 0.989643 -0.0650238 -0.127979 0.906119 -0.107802 -0.409057 0.857844 0.140658 -0.494286 0.666415 -0.207491 -0.716127 0.565861 0.15512 -0.809777 0.315337 -0.2206 -0.922983 -0.339942 0.115107 -0.933375 -0.126057 -0.163125 -0.978519 -0.710943 -0.109049 -0.694743 -0.663243 0.0358476 -0.747545 -0.486296 -0.162049 -0.858636 -0.855092 0.0648592 -0.514403 -0.899311 -0.274091 -0.340756 -0.970046 0.21599 -0.111168 -0.142761 -0.988441 -0.0510351 0.0761382 -0.992193 -0.0987736 -0.44024 -0.896347 -0.0524435 -0.668869 -0.698928 -0.253207 -0.384465 -0.890015 -0.245072 -0.467 -0.75899 -0.453701 -0.258401 -0.871232 -0.417354 -0.26777 -0.842295 -0.467802 -0.0582237 -0.833981 -0.548713 -0.0507512 -0.795923 -0.603267 -0.0539833 -0.796634 -0.602047 0.181194 -0.844041 -0.504741 0.161012 -0.864542 -0.47607 0.440411 -0.785479 -0.43481 0.345694 -0.861044 -0.372959 0.589969 -0.781703 -0.202179 0.38294 -0.907373 -0.173295 0.64307 -0.76127 -0.0832376 -0.0289421 0.960737 -0.275947 0.0251472 0.993044 -0.115027 -0.0160976 0.999528 -0.0261616 -0.0233949 0.999149 -0.0339698 -0.0282051 0.999437 -0.0181587 -0.0329624 0.999253 -0.0201558 -0.0374327 0.999288 -0.00467159 -0.0360278 0.99934 -0.00470792 -0.0415674 0.999038 0.0139843 -0.0328308 0.999413 0.00975933 -0.0379351 0.998592 0.0370914 -0.024494 0.99948 0.0209606 -0.0227942 0.997477 0.0672354 -0.0102619 0.999715 0.0215678 0.0843587 0.953 0.290988 0.0374497 0.933605 0.356342 -0.0412839 0.98788 0.149632 0.0160976 0.999528 0.0261617 0.0233949 0.999149 0.0339698 0.028205 0.999437 0.0181587 0.032962 0.999253 0.0201557 0.0374322 0.999288 0.0046716 0.0360278 0.99934 0.00470792 0.0415673 0.999038 -0.0139842 0.0328308 0.999413 -0.0097592 0.0379351 0.998592 -0.0370913 0.0293131 0.999213 -0.0267437 0.0111884 0.999334 -0.034729 0.069553 0.926344 -0.370203 0.92655 -0.360068 -0.108883 0.894253 0.360066 -0.265825 0.80216 -0.360067 -0.476332 0.65327 0.46692 -0.596007 0.511093 -0.466516 -0.721905 0.236469 0.404965 -0.883225 -0.15108 0.299493 -0.942061 -0.389895 -0.360012 -0.847569 -0.529154 0.360067 -0.768341 -0.7009 -0.360067 -0.615704 -0.795918 0.360067 -0.486688 -0.890733 -0.360067 -0.277393 -0.925062 0.360068 -0.120882 0.0953216 -0.811756 -0.576165 -0.0298465 -0.955097 -0.294785 -0.00106495 -0.999998 0.00150421 -0.000634356 -1 0.000654423 -0.00330659 -0.999993 0.00196349 -0.00601669 -0.999982 0.00070699 -0.000715415 -1 -0.000237009 0.00581155 -0.999889 0.0137242 -0.0635063 -0.884066 0.463027 -0.0869326 -0.889867 0.447861 0.0731848 -0.997211 -0.0146671 -0.00615904 -0.999943 0.00869948 -0.00149961 -0.999999 0.000550928 0.00151786 -0.999999 -0.000901387 0.00228597 -0.999997 -0.000268634 -0.00122838 -0.999999 0.000411162 -0.00709851 -0.999972 -0.00221068 -0.00355791 -0.999987 -0.00379253 -0.00204824 -0.999996 -0.00179927 0.0159844 -0.755419 -0.655047 0 1 0 2.07033e-05 1 1.3958e-05 0 1 0 -5.37849e-06 1 -3.43497e-05 1.64529e-06 1 -5.20996e-05 0.125949 0.70398 -0.698963 -4.66677e-06 1 2.58986e-05 -1.61105e-05 1 2.56464e-05 -1.97037e-05 1 2.13346e-05 -2.09478e-05 1 -1.84305e-05 0 1 0 1.13003e-06 1 3.39367e-05 -3.34509e-05 1 1.65931e-05 -3.55182e-05 1 9.85743e-06 -3.36399e-05 1 5.98785e-06 -0.000100338 1 -5.66182e-05 -9.61382e-05 1 5.19016e-05 -1.03897e-05 1 -6.16986e-05 -3.49413e-05 1 -2.86814e-05 -2.36868e-05 1 -2.69499e-05 -3.08412e-05 1 -2.40876e-05 -4.37776e-05 1 1.22532e-05 0 1 0 0 1 0 -0.177217 -0.0176172 -0.984014 -0.124849 -0.000206606 -0.992176 0.000674008 0.000202464 -1 0.00648059 0.00468936 -0.999968 0.181433 -0.00733353 -0.983376 0.190115 0.000105836 -0.981762 0.367679 0.00021284 -0.929953 0.996378 0.000220281 -0.0850294 0.996316 8.09895e-06 -0.0857636 0.963579 4.00797e-06 -0.267424 0.963583 8.8409e-06 -0.267408 0.898033 2.97736e-06 -0.439928 0.898044 1.01114e-05 -0.439906 0.801906 3.97784e-06 -0.59745 0.801262 -0.000305958 -0.598313 0.67847 0.000180861 -0.734628 0.678017 4.87688e-06 -0.735046 0.531931 2.49477e-06 -0.846788 0.531962 1.31959e-05 -0.846768 0.427859 -2.85909e-05 -0.903846 0.355082 -0.0111292 -0.934769 -0.224472 -0.0039719 -0.974473 -0.210376 -8.71929e-05 -0.977621 -0.355192 7.40333e-06 -0.934794 -0.355216 0 -0.934784 -0.520911 0 -0.853611 -0.52086 1.75314e-05 -0.853642 -0.668892 3.21651e-06 -0.743359 -0.667887 0.000392402 -0.744263 -0.794095 -0.000174626 -0.607793 -0.793713 8.341e-06 -0.608293 -0.892256 5.25468e-06 -0.45153 -0.892256 5.47432e-06 -0.451531 -0.960032 4.00106e-06 -0.27989 -0.960029 7.6576e-06 -0.279902 -0.995127 3.95885e-06 -0.098602 -0.995115 4.1141e-05 -0.0987228 -0.327372 -0.922791 -0.203186 -0.00126232 0.999999 -0.000259118 0.00329093 0.999959 -0.00847864 0.00566128 0.999955 -0.00767857 0.00766771 0.999968 0.00207435 -0.168193 0.985375 0.0273472 -0.38594 0.904972 0.179096 0.211622 -0.977073 0.0233189 0.0164857 0.999849 0.00541897 -0.0278207 0.999605 0.00394019 0.134139 0.857373 0.496909 -0.576816 0.792949 0.196252 0.00734075 0.999798 -0.018698 0.0153092 0.999862 -0.00646651 0.0103982 0.999941 -0.00311574 0.00907555 0.999948 -0.00464467 0.0212803 0.999748 -0.00716589 0.0165066 0.999799 -0.011383 0.0172655 0.999784 -0.0116113 0.0374154 0.999158 -0.0168185 0.0443411 0.9931 -0.108566 0.00719184 0.999766 -0.0203984 0.00746317 0.998988 0.0443528 0.00211287 0.999844 -0.017523 0.00909145 0.999829 -0.0161253 0.00376166 0.988649 0.150199 0.107346 0.992024 0.0660631 -0.441806 0.762825 0.472128 0.0394139 0.998806 0.0288597 -0.00919343 0.999928 -0.00767269 0.387386 0.893345 0.227745 -0.021687 0.991376 0.129241 -0.00585244 0.999895 -0.0132236 -0.00499464 0.999898 -0.0133796 -0.00483406 0.999928 -0.0109662 -0.0052671 0.999922 -0.0113739 -0.0266023 0.99964 0.00360281 -0.0138991 0.999876 -0.00734214 -0.0196095 0.999722 -0.0131031 -0.0187664 0.999807 -0.00588945 0.0507855 0.998608 -0.0142481 -0.113677 0.993058 0.0302324 -0.0477977 0.998614 -0.0220299 -0.0243316 0.999678 -0.00724087 -0.0247944 0.999666 -0.0072579 -0.0183755 0.997765 0.0642405 -0.0452244 0.998556 0.0290005 -0.0860514 0.855284 -0.510965 0.455448 0.854127 -0.251066 -0.00471333 0.999821 0.0183285 -0.00929941 0.999943 0.00517765 -0.0170773 0.999854 0.000259739 0.00107134 0.999998 0.00176944 0.937271 -0.151395 -0.314012 0.0217621 0.997273 -0.0705192 0.00930544 -0.997944 0.0634213 -0.000192961 1 -4.50738e-05 0.128523 0.990078 0.0568016 7.69345e-05 1 -0.000171673 0.0916003 0.977001 0.192557 0.0601557 0.993152 0.100148 0.00148204 0.999973 0.00715446 1.42662e-05 1 4.34154e-05 0.000105217 1 0.000402971 0 1 0 7.95813e-06 1 4.1331e-05 -4.01816e-05 1 0.000127148 7.36992e-05 1 0.000484781 -0.000822045 1 0.000138691 -0.000734496 1 3.59874e-05 -0.000112447 1 0.000210736 -2.66133e-05 1 0.000129177 0.999984 0.00456184 -0.00327487 0.793104 0 -0.609086 0.753737 -0.0174819 -0.656944 0.669843 -0.00458513 -0.742488 0.685049 0 -0.728497 0.314597 -0.102177 -0.94371 0.442579 0.000200904 -0.896729 0.0100685 -0.119074 -0.992834 -0.161079 0.0853174 -0.983247 -0.339477 -0.187757 -0.921685 -0.461421 0.181961 -0.868321 -0.661046 -0.208795 -0.72071 -0.953945 0.016184 -0.299545 -0.955392 -2.31495e-06 -0.29534 -0.988017 -8.65662e-07 -0.154345 -0.997894 -0.0167848 -0.0626651 -0.992625 -0.000198072 -0.121225 0.524498 0.000377561 -0.851411 0.524773 0.000288517 -0.851242 0.410933 -0.00872197 -0.911624 0.994138 -0.0058797 -0.107963 0.990218 2.7978e-09 -0.139528 0.957916 6.36511e-09 -0.287048 0.957905 9.25304e-06 -0.287084 0.890194 8.31341e-07 -0.455582 0.89018 8.57659e-06 -0.45561 0.810429 3.28977e-05 -0.585836 0.895814 -0.13361 -0.423869 -0.995609 0.000137883 -0.0936089 0.967568 -0.00242345 -0.252601 0.904273 0.00551464 -0.426919 0.909008 -0.00131447 -0.416777 0.82282 0.00686961 -0.568261 0.998047 -9.96937e-05 -0.0624613 0.996678 0.0093352 -0.0809085 0.966812 -0.000632247 -0.255486 -0.99557 -4.57713e-05 -0.0940202 -0.964226 -2.86947e-05 -0.265082 -0.964242 -8.51178e-07 -0.265023 -0.903547 0.000990329 -0.428488 -0.902429 -0.000116558 -0.430838 -0.815434 -5.91873e-05 -0.57885 -0.815431 -6.1638e-05 -0.578854 -0.709249 -9.38837e-05 -0.704958 -0.702456 0.00392674 -0.711716 -0.588511 -0.000283585 -0.80849 -0.568167 0.00947583 -0.822858 -0.416748 -0.000523827 -0.909022 -0.417392 -0.000167059 -0.908727 -0.252579 -1.23034e-05 -0.967576 -0.25212 -0.00022386 -0.967696 -0.0807248 -9.25817e-05 -0.996736 -0.0779378 -0.00133859 -0.996957 0.0935839 0.000669311 -0.995611 0.0953939 -0.000122861 -0.99544 0.265048 2.2905e-05 -0.964235 0.265168 -3.25482e-05 -0.964202 0.428415 0.00247631 -0.903579 0.433693 3.79656e-05 -0.901061 0.578851 2.15283e-05 -0.815433 0.579009 -6.16946e-05 -0.815321 0.70495 -9.38791e-05 -0.709257 0.711712 0.00394359 -0.70246 0.814842 -0.000327046 -0.579684 0.81305 0.00614342 -0.582162 6.7343e-05 1 -0.000154552 -2.53686e-05 1 -9.76601e-05 0.000642135 1 -0.000297303 2.99587e-08 1 2.36311e-08 2.42945e-05 1 -3.97149e-06 6.60584e-05 -1 -1.0905e-05 -5.527e-05 -1 6.4199e-05 0.000140115 -1 -4.94628e-05 0.000163788 -1 -7.58796e-05 -2.99587e-08 -1 -2.36311e-08 -0.999969 0.0034439 -0.00706735 -0.999854 0.0169935 0.00199195 0.997242 -0.00537708 -0.0740264 0.996388 -0.0129398 -0.083931 0.964463 0.00063477 -0.264216 0.963577 -0.00205188 -0.267424 0.89803 -0.00269411 -0.439926 0.897998 -0.00263578 -0.439992 0.895107 -3.43968e-06 -0.445851 0.531922 -0.00568361 -0.846774 0.522554 0.00112605 -0.852606 0.367212 -0.0188228 -0.929947 0.342359 -0.000804662 -0.939569 0.337328 0.000695874 -0.941387 -0.228397 -0.0469573 -0.972435 -0.177376 -0.0011332 -0.984143 -0.323126 -0.00909047 -0.946312 -0.355119 -0.0201248 -0.934604 -0.361282 -0.0170058 -0.932302 -0.835887 -0.061964 -0.545393 -0.794086 0.00482705 -0.607786 -0.880397 -0.00909908 -0.474151 -0.892032 -0.0223929 -0.451417 0.801905 -0.00159926 -0.59745 0.797311 0.00109972 -0.603568 0.67847 -0.00111229 -0.734627 0.636537 0.0182693 -0.77103 0.701872 -0.0517595 -0.71042 0.190111 -0.0073456 -0.981735 0.164241 0.000787352 -0.98642 0.00648029 -0.00712733 -0.999954 -0.0365408 0.0062999 -0.999312 -0.479112 0.00997966 -0.877697 -0.520897 -0.00739266 -0.853587 -0.668876 -0.00695967 -0.743341 -0.706011 0.0117135 -0.708104 -0.77619 -0.00817307 -0.630446 -0.936716 0.00627269 -0.350035 -0.959998 -0.00835844 -0.279881 -0.978346 0.00418075 -0.206932 -0.995093 -0.00665965 -0.0987168 -0.997276 -6.7182e-06 -0.0737589 0.271626 -0.0458818 -0.961309 0.676781 0.0326848 -0.735459 -0.659926 0.00134093 -0.751329 0.589014 0.000204537 0.808123 0.793706 -0.0562077 -0.605699 0.886884 0.00622577 -0.46195 0.801697 -0.0256054 -0.597181 0.998054 0.0577081 -0.023628 0.719444 -0.0510872 0.692669 0.425001 0.0284446 0.904746 -0.873338 -0.0132956 0.486933 0.916201 0.069011 0.394732 0.284292 -0.065193 0.956519 -0.172909 0.0412812 0.984072 -0.410998 -0.079092 0.908199 -0.998586 0.0530886 -0.00261756 -0.0372444 0.0127584 0.999225 -0.874594 -0.0483563 0.482439 -0.954816 0.0143226 0.296851 -0.997691 0.0263416 -0.0626009 -0.75511 -0.00305109 0.655591 -0.990276 -0.0207806 -0.137555 -0.99179 -0.01613 -0.126858 0.738178 0.0512399 -0.672657 -0.49319 -0.0413982 -0.868936 0.971626 -0.0268635 0.234994 0.975475 -0.0208342 0.219124 0.0345574 -0.0143365 -0.9993 0.927065 -0.118055 -0.355827 0.0439555 -0.0711446 0.996497 -0.181622 0.00673077 0.983345 0.851688 -0.0958791 0.515203 0.997467 0.00242967 0.071091 -0.804984 0.0324462 0.592409 0.553077 0.0331623 0.83247 -0.993682 -0.0177545 0.11082 -0.0707031 -0.00206729 0.997495 -0.995645 -0.0121873 0.0924269 -0.210227 -0.0614325 -0.975721 0.156057 0.0119557 -0.987676 0.606624 0.0105625 0.794919 0.269191 0.0561854 -0.961446 5.14836e-05 -1 -0.000101009 5.02474e-05 -1 -8.49931e-05 9.73256e-05 -1 -5.76435e-05 0.00010371 -1 -5.85432e-05 9.67443e-05 -1 -8.7348e-05 0.000224672 -1 -3.55779e-05 0.000263382 -1 4.50868e-05 0.000223138 -1 7.71231e-05 0.000238607 -1 0.000110008 0.000180114 -1 0.000168129 0.000179624 -1 0.000166336 9.47831e-05 -1 0.000226953 4.67502e-05 -1 0.00046224 5.99286e-05 -1 0.00016776 -1.92493e-05 -1 0.000220399 -2.58107e-05 -1 0.000209671 -0.000133366 -1 0.000238698 -0.000133721 -1 0.000169823 -0.000273037 -1 0.000154126 -0.000207095 -1 4.64736e-05 -0.000239368 -1 2.19152e-05 -9.51843e-05 -1 -0.000127942 6.06753e-06 -1 1.88359e-06 -8.23837e-05 -1 5.6421e-05 -9.10968e-05 -1 -1.73856e-05 -0.000136649 -1 -0.000113635 -7.62126e-05 -1 -0.00027601 -7.07451e-05 -1 -0.000124552 4.78817e-05 -1 -0.000235627 -5.90992e-06 -1 -7.51092e-05 -0.000582962 0.999997 -0.00223522 -0.000658547 0.999998 -0.00186733 -0.00097812 0.999997 -0.00215023 -0.00141867 0.999997 -0.00204896 -0.00144684 0.999996 -0.00235317 -0.00296685 0.999991 -0.003005 -0.00386145 0.999989 -0.00274466 -0.0031814 0.999995 -0.000677084 -0.00162562 0.999998 -0.000888832 -0.000806992 1 -0.00021703 -0.000773338 1 2.02856e-05 -0.00163281 0.999999 0.000360378 0.00164105 0.999999 -6.40497e-05 0.00170545 0.999999 -0.000100137 0.00177052 0.999998 -0.000530553 0.0016455 0.999999 -0.000429939 0.0016648 0.999998 -0.000852008 0.00151769 0.999999 -0.000686897 0.00148747 0.999998 -0.00114235 0.00136953 0.999999 -0.000954702 0.00128339 0.999998 -0.00142258 0.00115138 0.999999 -0.00110498 0.000992484 0.999998 -0.00161075 0.000914502 0.999999 -0.00127096 0.00127358 0.999999 -0.000484092 0.00158207 0.999993 -0.00330987 0.00131109 0.999988 -0.00473896 -0.000766452 0.999985 -0.00535734 -0.000126716 0.999996 -0.00269003 7.3918e-05 0.999997 -0.00235881 0.00164273 0.999999 -0.000364305 0.000773333 1 -2.02835e-05 0.000812413 1 0.000255154 0.00154345 0.999998 0.000858409 0.00160872 0.999998 0.000849799 0.0015865 0.999998 0.00112974 0.00142816 0.999998 0.00112652 0.00137557 0.999998 0.00139298 0.00119742 0.999998 0.00136237 0.00111627 0.999998 0.0016113 0.00092635 0.999998 0.00154832 0.000812276 0.999998 0.00178808 0.000634327 0.999998 0.00169922 0.0004984 0.999998 0.00191127 0.000316395 0.999998 0.0017853 0.000159431 0.999998 0.00197067 0.00723334 0.999938 0.00849141 -0.00163208 0.999999 6.30757e-05 -0.00172104 0.999999 0.000113008 -0.00178676 0.999998 0.000535605 -0.00164597 0.999999 0.000422482 -0.0016657 0.999998 0.000852471 -0.00151959 0.999999 0.00068848 -0.00148926 0.999998 0.00114372 -0.00134555 0.999999 0.000915039 -0.00125773 0.999998 0.00139413 -0.0011454 0.999999 0.00112401 -0.000992414 0.999998 0.00161097 -0.000914422 0.999999 0.00127114 -0.000686906 0.999998 0.00176972 -0.000664167 0.999999 0.00137391 -0.00906734 0.999886 -0.0120849 -0.0046085 0.999823 0.0182298 -0.00216137 0.999798 0.0199808 1.62751e-07 -1 -8.40451e-07 1.80866e-07 -1 -5.48455e-07 -2.3533e-07 -1 7.84033e-08 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.00114439 -0.999999 0.000308691 0.000114504 -1 0.000197764 -3.05138e-06 -1 -5.27012e-06 -1.57265e-05 -1 -1.53535e-06 1.03607e-05 -1 6.56741e-06 3.26932e-07 -1 -1.02686e-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 -4.88579e-07 -1 -6.16756e-08 0.146951 -0.982308 -0.116085 0.505359 -0.862081 -0.037807 0.479174 -0.864893 0.149508 -0.0106972 -0.999918 -0.00711107 0 -1 0 0.134702 -0.989983 -0.0423085 0.412972 -0.886442 0.208986 0.386971 -0.805655 0.448523 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1.07521e-07 -1 -8.18144e-07 -6.17433e-08 -1 -8.31083e-07 -7.62661e-08 -1 -4.23152e-07 5.04119e-09 -1 -7.77891e-07 0.915408 -0.37552 -0.144959 0.874554 -0.202141 -0.440789 0.666794 -0.643205 -0.376396 0.47964 0.678316 -0.556627 0.282912 -0.783291 -0.553549 0.266283 0.526386 -0.807473 -0.0729624 -0.173709 -0.98209 -0.0768274 -0.254843 -0.963926 -0.460669 0.25484 -0.8502 -0.493217 -0.0715917 -0.866956 -0.536269 -0.716618 -0.445952 -0.728897 0.516555 -0.449311 -0.669955 -0.712674 -0.207979 -0.857436 0.508408 -0.0795356 -0.776929 -0.0128461 -0.629457 -0.728437 -0.565143 -0.387289 0.664422 -0.190103 -0.722775 0.717976 0.0279219 -0.695507 0.875262 -0.22499 -0.42813 -0.672628 -0.38192 -0.633805 -0.0286389 -0.99958 0.0043315 -0.0554054 -0.998295 0.0183739 0.0240673 -0.998992 0.0378793 0.000334769 -1 0.00032231 0.00236998 -0.999947 -0.0100412 -0.0396434 -0.998917 0.0243756 -0.031129 -0.999466 -0.00996919 0.0187252 -0.999728 -0.0139124 0.713468 -0.511619 -0.478759 0.237661 -0.551464 0.799628 -0.930018 -0.252551 -0.266992 -0.551161 -0.227089 -0.802903 0.233761 -0.897546 -0.373855 0.465611 -0.875977 -0.125976 -0.0812856 -0.981161 -0.175258 -0.0112154 -0.953591 0.300896 -0.175812 -0.971635 0.158162 -0.251774 -0.967 -0.0390026 -0.772078 -0.316497 -0.551112 0.193874 -0.978275 0.0734213 0.644009 -0.651952 0.400262 -0.676129 -0.394268 0.622417 0.209739 -0.927512 0.309403 -0.119854 -0.992784 -0.00380919 -0.294997 -0.953212 0.0660667 0.566874 -0.672901 0.475245 0.775805 -0.378711 0.504684 0.19905 -0.890468 -0.4092 -0.304148 -0.485107 -0.819857 -0.115492 -0.657904 -0.744194 -0.130473 0.166665 0.977343 -0.966499 -0.155523 -0.204186 -0.308514 -0.936853 -0.164697 -0.358706 -0.909285 -0.211022 -0.325827 -0.92361 -0.201943 -0.600166 -0.790034 0.125086 -0.896669 0.318304 0.307681 -0.223188 -0.958542 0.177158 -0.17216 -0.929461 0.326287 -0.230547 -0.891688 0.389538 -0.212068 -0.919864 0.329966 -0.00327719 -0.999991 0.00252239 -0.00202534 -0.999998 -0.00045693 -0.023662 -0.99972 -0.000916449 0.000202125 -1 3.13172e-05 0.000330983 -1 0.000806321 0.00622433 -0.99997 -0.00468588 -0.00812727 -0.999967 0.000962054 -0.00100097 -0.999904 0.0137954 -0.0107111 -0.99994 0.00209801 -0.00776544 -0.999963 0.00368526 -0.00603156 -0.999953 -0.00759766 -0.0161448 -0.999863 0.00363272 -0.00085393 -1 0.000216946 -0.000203067 1 0.000105438 -0.00163559 -0.999999 -0.000220587 -1.77495e-06 -1 -3.00276e-05 0.000693057 -0.999999 -0.00119009 0.000546891 -0.999995 0.00304244 -0.00126964 -0.999991 0.00411824 -6.97458e-05 -0.999997 0.00237582 -0.00337752 -0.999994 0.000263082 -6.86462e-05 -0.999997 -0.00258081 0.00553073 -0.999984 0.000962363 0.00501459 -0.999976 -0.00468455 0.00571636 -0.99998 -0.00266649 -0.00344172 -0.999992 0.00189698 0.000681422 -0.999998 0.00176006 -0.012991 -0.999912 -0.00276428 -0.00208134 -0.999995 -0.00249879 0.0338094 -0.999301 -0.0159678 0.00335381 -0.999994 0.00123832 -0.000243452 -0.999996 0.00294363 -0.00229011 -0.999956 -0.00908689 0.00408918 -0.999988 -0.00260191 0.0313291 -0.999376 -0.0163284 0.039821 -0.999181 -0.0071466 0.000200589 -0.99999 -0.0045503 0.00515726 -0.999987 5.27686e-06 0.00540142 -0.999915 0.0118336 0.0118118 -0.99993 -0.000411073 -0.0937091 -0.995597 0.00244984 -0.000985581 -0.999995 -0.0030271 3.78979e-05 -0.999992 0.00409182 -0.000498565 -0.999993 0.00361367 -0.00291761 -0.999969 0.00731815 0.000421731 -1 0.000518861 0.0145868 -0.999768 -0.0158694 0.0218082 -0.999066 -0.0373055 0.00234465 -0.999992 0.00317571 0.0280382 -0.999588 -0.00616935 -0.00387024 -0.999769 0.0211587 0.00521629 -0.999472 0.0320722 0.0130253 -0.9999 0.00547215 -0.00967654 -0.999918 0.00839009 -0.00392576 -0.999988 -0.00309267 0.0242048 -0.998407 -0.0509748 -0.000599603 -0.999996 -0.00275003 0.0070074 -0.999698 0.0235632 0.0151 -0.999701 -0.0192081 -0.000988248 -0.99999 0.00442776 0.000976149 -0.999992 0.0039451 0.00804749 -0.999916 0.0101947 0.00530842 -0.999973 -0.00499295 0.00411131 -0.999991 0.00107185 0.00737252 -0.999882 0.0135067 0.00666461 -0.999953 -0.00706552 0.00325602 -0.99999 0.00303499 -0.0067822 -0.999939 0.00867483 0.000133585 -0.999996 0.00270547 0.00533491 -0.999973 0.00509451 0.00375965 -0.999936 0.0106357 0.00821172 -0.999965 0.00159274 0.00720423 -0.999971 0.00231703 0.0051405 -0.999987 -0.000540616 0.00429768 -0.999987 0.00261093 0.00429367 -0.999987 0.00262096 0.192065 -0.083312 -0.97784 -0.653055 0.179952 -0.73562 0.963886 -0.254703 -0.077779 -0.884759 0.293547 0.361983 -0.0479577 -0.61011 -0.790864 -0.687681 0.549258 -0.474773 0.999984 -1.82098e-05 0.00558767 0.99998 -0.000235359 0.00632783 -0.989856 0.00501467 -0.141982 -0.999339 -0.0334662 -0.0141907 0.00648616 5.33165e-07 -0.999979 0.00634368 -1.47669e-05 -0.99998 0.00648114 1.1629e-06 -0.999979 0.0064805 4.82695e-07 -0.999979 0.00645201 0.000499576 -0.999979 0.0064358 6.43593e-05 -0.999979 0.00648057 1.23775e-07 -0.999979 0.00648131 4.40187e-08 -0.999979 0.00648025 -2.40604e-08 -0.999979 0.00648018 0 -0.999979 0.0064821 -2.47994e-06 -0.999979 0.00648098 1.74513e-06 -0.999979 0.00648067 -2.10929e-07 -0.999979 0.00648105 -5.24327e-07 -0.999979 0.00632353 0.000368845 -0.99998 0.00646647 9.69548e-06 -0.999979 0.00629498 -5.21056e-06 -0.99998 0.00632459 -1.86103e-05 -0.99998 0.00647642 -5.88402e-06 -0.999979 0.00647912 -7.4179e-06 -0.999979 0.00647806 -4.87957e-06 -0.999979 0.00652394 1.33299e-06 -0.999979 0.00645629 -7.04334e-06 -0.999979 0.0064804 -1.60817e-05 -0.999979 0.00648048 -1.83714e-05 -0.999979 0.0064829 -4.224e-06 -0.999979 0.0152413 0.017454 -0.999732 -0.00872922 0.0179659 -0.999801 0.0138318 0.0194163 -0.999716 0.00647367 -3.45206e-06 -0.999979 0.00648134 -4.26543e-07 -0.999979 0.00648209 -2.27383e-09 -0.999979 -0.394193 0.119013 -0.911289 0.00649735 -1.19818e-05 -0.999979 0.00647782 8.56153e-06 -0.999979 0.00647917 2.10648e-07 -0.999979 0.00648204 -2.20352e-07 -0.999979 0.0065189 -3.46393e-05 -0.999979 0.00650315 6.031e-05 -0.999979 0.00642256 6.73468e-06 -0.999979 -0.999935 0.00904659 -0.00691013 -0.999936 0.00418355 -0.0104727 -0.999979 -8.89233e-05 -0.00641787 -0.999978 4.59779e-05 -0.00662555 -0.869253 1.60536e-05 0.494367 -0.869282 -2.69188e-05 0.494317 -0.000182454 -1 -0.000682982 -0.000154231 -1 -0.000815346 -8.20449e-06 -1 3.09572e-05 0 -1 0 -0.95544 -0.2925 0.0397217 -0.449314 -0.405515 0.796037 -0.449229 -0.746488 -0.490866 0.64196 -0.319638 0.696935 0.950289 -0.311209 0.00996209 -0.843493 0.452297 0.289737 0.576816 -0.792949 -0.196252 0.760835 0.300332 -0.575265 -0.441806 0.762825 0.472128 -0.64196 0.319638 -0.696935 -0.921081 -0.227202 -0.316211 -0.193602 -0.898426 -0.394143 -0.064277 0.996436 -0.0546165 0.086543 -0.996238 0.00441652 0.999979 0 0.00642985 0.99998 0.000838001 0.00621788 0.999502 -0.0308329 0.00672193 0.999833 -0.0176305 0.00475937 -0.99945 -0.0325691 -0.00630024 -0.559398 -0.828833 0.0104763 0.421158 0.226256 0.878313 -0.421158 -0.226256 -0.878313 -0.917014 -0.395532 -0.0513752 4.41906e-05 -1 5.43097e-05 7.53268e-05 -1 2.01315e-05 3.73291e-05 -1 -0.000106925 -0.000365769 -1 0.000439423 0.000366757 -1 0.000149869 0.999782 0.0195161 0.00736993 -0.994357 0.106081 -0.00125357 0.00103439 0.999999 6.94544e-05 -7.13401e-05 0.999999 0.00137811 -0.000357868 1 0.000287176 -0.00138146 0.999999 -0.000184782 0.000226969 1 -0.000181925 -0.353154 0.0311009 -0.935048 -0.317395 -0.0201306 -0.94808 0.356335 -0.000933806 0.934358 0.441358 0.12793 0.888165 0.734976 -0.17007 -0.656419 0.746623 0.642751 0.171537 0.00582643 0.999889 -0.0136961 0.00410067 0.999911 0.0126948 0.756431 0.33001 -0.564718 0.812574 -0.27669 0.512997 0.626832 -0.00128178 -0.779153 0.0923313 -0.99088 -0.0981406 0.293734 0.955633 0.0220368 -0.636338 0.759958 -0.132431 -0.41982 0.906047 0.0531947 -0.984365 -0.176066 0.00511605 -0.373112 -0.927315 -0.0295599 0.635729 -0.771878 0.00723597 0.56261 -0.826722 -0.000821014 0.977266 0.211523 -0.0144535 0.640077 0.767942 0.0238164 0.489538 -0.871891 -0.0125781 0.798997 -0.601114 0.0162778 -0.718463 -0.695491 -0.0101754 0.801295 0.598222 0.00754487 0.766916 0.641617 0.0129421 -0.94333 0.325827 -0.062974 0.415291 -0.909685 0.00269132 0.467113 -0.884071 0.0149799 -0.684374 -0.72913 0.00126851 -0.726614 -0.68697 -0.0101888 -0.309319 0.949095 -0.0594991 0.0025277 -0.99999 0.00369773 6.16597e-05 -0.999985 -0.00544945 -0.000339295 -0.999999 0.00132192 -0.00233075 -0.999997 0.00055981 -4.97316e-05 -1 -8.51864e-05 -0.984591 0.174829 0.00401708 -0.808931 0.587835 0.00898021 -0.707937 0.705991 -0.0200375 -0.697088 0.599355 0.393499 -0.707029 -0.706992 -0.0164651 -0.778815 -0.627244 0.00356463 -0.993362 0.00442241 0.114943 -0.697252 -0.578801 0.422881 0.946574 -0.321377 -0.0267439 0.922119 -0.380384 -0.0707402 0.712087 0.669568 -0.211214 -0.489285 0.805791 0.333618 -0.954158 -0.00117394 -0.299302 -0.950584 0.00591578 0.31041 -0.870219 -0.0865958 -0.484995 -0.498004 -0.780222 0.378477 0.488443 0.802116 -0.343559 0.332157 -0.14245 -0.932405 -0.0477241 -0.262443 -0.963767 -0.174171 -0.919091 -0.353463 -0.739507 0.0611569 -0.670365 -0.0961033 0.814418 -0.572265 -0.120426 0.0448893 -0.991707 -0.324161 0.878809 -0.350164 0.594524 -0.323689 -0.736048 0.91688 0.0120235 -0.398982 -0.936297 0.348365 -0.0446065 0.916155 0.397137 0.0542364 0.881425 0.462561 0.0955396 -0.53868 0.839487 0.0713075 -0.106922 0.991495 -0.074201 0.986011 0.135712 0.0967728 0.0303859 0.181958 -0.982837 -0.943957 0.32725 0.0430498 0.0754758 0.996224 -0.0429015 0.43345 0.89999 0.0462556 -0.214072 0.973557 -0.0797487 0.587969 0.803145 0.0961763 -0.173164 -0.981131 -0.0860021 0.0325953 -0.386079 -0.92189 0.0135672 -0.418175 -0.908265 0.00477332 0.520484 -0.853858 0.005363 0.561355 -0.827558 -0.604104 0.080203 0.792859 -1.84636e-10 1 2.84896e-08 -0.00019724 1 3.32505e-05 -8.3884e-08 1 -9.00584e-09 5.35587e-09 1 -2.76579e-08 1.46627e-07 1 2.84218e-08 0.0962793 -0.000430104 0.995354 0.137823 0.0140861 0.990357 0.0371692 0.00588995 0.999292 0.0164985 6.69057e-05 0.999864 -0.939049 0.119408 -0.32238 0.0907162 0.626381 0.774221 -0.559128 0.818458 -0.132295 -0.12179 -0.00800409 0.992524 -0.0945659 -0.00851492 0.995482 -0.102186 0.00911236 0.994724 -0.841509 0.0283543 -0.539498 -0.832489 -0.0012348 -0.55404 -0.832073 -0.000900817 -0.554666 -0.835286 -0.00075514 0.549815 -0.839891 0.000713561 0.542755 -0.843446 -0.00201329 0.53721 -0.846578 0.00429141 0.532248 0.883057 4.48427e-06 0.469265 0.883511 -0.000845112 0.468409 0.883254 -0.000462664 0.468894 0.883358 -9.94905e-05 0.468698 0.353823 0.0315123 0.934781 0.921388 -0.00158795 -0.38864 0.923298 -0.00041175 -0.384084 0.92333 -0.000484301 -0.384007 0.923862 -0.0011879 -0.382725 -0.833298 -0.000104918 -0.552823 -0.8333 -0.000107033 -0.552821 -0.83329 -0.000135362 -0.552836 0.203765 0.23566 0.950234 0.206174 0.232306 0.95054 0.49264 0.208278 0.844942 0.509894 0.257694 0.820732 0.765001 0.198761 0.612591 0.773921 0.257719 0.57847 0.936762 0.19807 0.288521 0.932155 0.258104 0.25391 -0.384529 0.23742 0.892059 -0.373628 0.236348 -0.896963 -0.407692 0.204888 0.889836 -0.641363 0.255655 0.723391 -0.659592 0.228758 0.715967 -0.816893 0.228676 0.529522 -0.832696 0.19904 0.516721 -0.943101 0.262892 0.20359 -0.966092 0.1926 0.171963 -0.952409 0.258899 -0.160896 -0.956406 0.228651 -0.181677 -0.889733 0.229308 -0.394706 -0.880182 0.180619 -0.438926 -0.780689 0.280007 -0.558677 -0.650304 0.17669 -0.738841 -0.657091 0.204614 -0.72551 -0.376145 0.232621 -0.896885 -0.990793 0.13448 -0.0156058 0.490401 0.0449644 -0.870336 -0.291043 0.0117621 -0.956638 0.353049 -0.147416 -0.923918 0.0485128 -0.998309 0.0320152 0.969514 -0.0630359 -0.236788 0.108947 -0.324806 0.939485 -0.366315 0.0589681 -0.92862 0.00892166 -0.0320694 -0.999446 -0.00353727 -0.0454134 0.998962 0.368673 0.098043 0.924374 -0.994618 0.0350433 -0.0975055 -0.778655 -0.0159903 0.627248 0.356512 0.927766 0.110228 0.727467 -0.6808 0.0854609 -0.419995 -0.766858 0.485318 -0.428894 0.889156 -0.159535 -0.00632623 0.999879 0.0142455 0.431909 -0.890792 -0.141227 -0.3091 -0.925769 -0.217734 -0.431907 -0.890792 0.141227 -0.210983 -0.901552 0.377743 -0.932611 -0.169251 -0.318732 0.980521 -0.00183757 0.196405 0.977096 -0.0264357 0.211149 0.975689 -0.0382717 0.215793 -0.103105 0.977657 -0.183183 -0.197684 0.941392 -0.273317 -0.9668 0.0579679 -0.248873 0.974195 -0.0217455 0.224658 -0.974823 0.0209554 -0.221992 -0.0847337 0.954651 -0.285415 -0.953211 0.0811018 -0.291224 -0.0940221 0.614619 -0.783201 -0.909558 -0.382458 0.162576 0.993564 -0.0986297 0.0556988 -0.194398 0.660851 0.724904 0.994667 -0.00280776 0.103098 0.985902 0.0858077 0.143647 -0.390051 0.83735 0.383021 -0.522452 -0.764885 0.376822 0.997741 -0.0665088 -0.009449 0.99866 -0.0458069 0.0240772 -0.522451 -0.764885 0.376822 -0.0490461 0.932184 0.358648 -0.971745 0.230405 0.0512346 0.919573 0.284279 0.271238 0.996223 -0.0868333 6.36733e-05 -0.021529 0.767771 0.640363 -0.167984 0.963167 0.209976 0.0632107 0.797817 0.599576 0.993757 0.0807511 0.0769806 0.555265 -0.249208 0.793459 0.640819 -0.039796 0.76666 -0.724238 -0.0733019 -0.685643 0.636008 0.0108001 0.771607 0.559287 -0.0070365 0.828944 0.822249 0.276243 -0.49759 0.52748 -0.638907 -0.559967 0.573424 -0.0155287 0.819112 -0.508148 0.110972 -0.854091 0.214915 0.964411 -0.154027 0.239655 0.446139 -0.862279 0.60298 0.0529357 0.795998 0.55738 -0.0063754 0.830233 0.775508 0.224498 0.590074 0.304204 0.470323 -0.828406 0.0850817 0.973109 -0.214055 0.193126 0.930878 -0.310111 0.542985 0.000313819 0.839742 0.575354 -0.00205662 0.817902 -0.564236 0.00526943 -0.825597 0.553655 -0.00769113 0.832711 -0.63934 0.763654 -0.0898718 -0.883331 -0.465668 0.0536701 0.595528 -0.0586092 0.801194 0.668503 0.0867178 0.738636 -0.288286 0.932182 0.218923 -0.288285 0.932182 0.218924 0.667855 0.0374376 0.743349 -0.752085 -0.124987 -0.647106 0.664648 0.0475555 0.745642 -0.416429 0.893848 0.166201 -0.188335 0.98078 -0.0509988 0.711535 0.0342414 0.701816 -0.743487 -0.0709238 -0.664979 0.667092 0.0287798 0.744419 0.0522132 0.516966 0.854412 -0.212331 0.0845056 0.973537 -0.187503 0.00691497 0.98224 -0.131794 0.00236483 0.991274 0.0827927 0.0192685 -0.996381 0.323458 -0.848827 0.418171 0.796877 0.465669 -0.38489 -0.194892 0.0135301 0.980731 -0.171787 -0.0125387 0.985054 0.305675 -0.207293 -0.929297 0.358503 -0.932183 0.0501012 0.751031 -0.325887 -0.574238 -0.211249 -0.108193 0.971426 -0.0311223 -0.0572351 0.997876 -0.104608 0.0133157 0.994424 -0.574336 0.328133 -0.749978 -0.0386741 -0.00997973 0.999202 -0.175372 -0.984392 0.0147064 -0.0771641 -0.00155018 0.997017 -0.646644 -0.455999 -0.611487 -0.662561 -0.465667 -0.586657 -0.072148 -0.0092602 0.997351 -0.0937704 0.0101915 0.995542 -0.0697237 -0.00763298 0.997537 -0.763308 0.132268 -0.632349 -0.823655 0.000250708 0.567091 -0.830216 -0.00638397 0.557406 -0.815994 0.043438 0.576427 0.174542 -0.977315 0.119961 -0.827809 -0.0102594 0.560917 0.833189 0.0130543 -0.552834 -0.575181 0.234486 0.783699 0.862282 0.446134 0.239654 0.862281 0.446136 0.239655 0.897476 0.0789915 -0.433933 -0.832837 -0.00717054 0.553472 0.943147 -0.101601 0.316468 0.860994 0.0155036 -0.508378 -0.811283 0.176112 0.557499 0.732322 0.0426196 -0.679624 -0.806611 0.0214673 0.590693 -0.7599 -0.00722238 0.65 -0.31097 -0.877186 -0.365845 -0.829425 -0.117158 0.546194 -0.777896 0.148289 0.610646 -0.203748 0.972851 -0.10976 -0.817809 0.00081544 0.575489 0.833998 0.00732838 -0.551719 -0.838534 -0.0135303 0.544682 0.0035385 -0.446051 -0.895001 0.0035385 -0.446051 -0.895001 -0.758347 -0.0114268 0.651751 -0.786496 0.0176391 0.617344 -0.756602 -0.00962464 0.653805 -0.769592 -0.0139666 0.638383 -0.982616 -0.159452 -0.0950891 -0.997659 -0.049172 -0.0475289 -0.996882 -0.00864707 -0.0784257 -0.998667 0.0216535 -0.0468651 -0.971618 0.0702287 -0.225892 -0.98861 -0.150247 -0.00870488 0.785259 -0.192743 0.588403 -0.322096 0.734607 0.597165 0.457541 0.624894 0.632585 -0.96629 0.0336759 -0.255244 -0.571043 -0.455894 0.682694 -0.967508 0.041405 -0.249427 0.457541 0.624894 0.632586 0.457541 0.624893 0.632586 -0.96926 0.0537298 -0.240099 -0.98639 -0.0575207 -0.154031 0.511341 0.765228 -0.391096 -0.998451 0.000999418 -0.0556257 -0.989087 0.00277285 -0.147307 -0.99601 -1.95087e-06 -0.0892413 -0.971703 0.0171801 -0.235579 -0.104718 0.980539 0.166066 0.469583 -0.598341 0.649215 0.586657 -0.465667 -0.662561 0.0490463 0.932183 -0.358649 0.997324 0.0722857 0.0109216 -0.994004 0.0144049 -0.108395 -0.997146 -0.0109705 -0.0746914 0.326764 0.137537 -0.935045 0.354058 0.312407 -0.881502 0.0317435 0.800916 -0.597935 -0.987861 0.069572 -0.138889 -0.158156 -0.717871 -0.677973 -0.14723 -0.706197 -0.692538 0.14723 0.706197 0.692538 0.158156 0.717871 0.677973 0.056106 -0.662433 -0.747017 -0.056106 0.662433 0.747017 -0.128194 0.254402 0.958565 -0.143212 0.287117 0.947129 0.143212 -0.287117 -0.947129 0.50743 -0.803908 0.310237 -0.596434 -0.394334 0.699119 0.020067 -0.170218 -0.985202 0.47713 0.11246 0.871608 0.798467 -0.528361 -0.28859 0.628329 0.740715 0.23779 -0.6534 -0.719232 0.236164 -0.877778 0.345186 -0.332194 0.906752 -0.40992 0.0988274 -0.906752 0.40992 -0.0988274 0.980325 -0.181193 -0.0783023 0.809485 -0.585886 0.038359 -0.787534 0.612942 0.0639692 -0.94734 0.317019 -0.0452348 -0.297177 -0.184748 -0.936779 -0.208474 0.205516 -0.956191 0.00969612 -0.152131 -0.988313 0.00107152 -0.103781 -0.9946 0.181541 0.103519 -0.977919 0.323636 -0.18789 -0.927339 0.294523 0 -0.955644 -0.891388 0.0661858 0.448383 -0.900037 -0.0930065 0.425773 -0.984028 0.0877205 0.154898 -0.966732 -0.240995 0.0857337 -0.989264 0.134473 -0.0572147 -0.975268 -0.0385966 -0.217629 -0.95863 -0.152454 -0.240386 -0.902399 0.18145 -0.390835 -0.848073 -0.173853 -0.500548 -0.768046 0.135079 -0.625986 -0.706919 -0.167901 -0.687076 -0.615969 0.128685 -0.777188 -0.493235 -0.00191794 -0.869894 -0.506041 0.107191 -0.855823 -0.7254 0.00097049 0.688327 -0.679668 -0.217466 0.700543 -0.570723 0.148738 0.80756 -0.428213 -0.0393916 0.902819 -0.316808 -0.413131 0.853789 -0.243995 0.0594328 0.967954 0.946667 0.0130908 0.321947 0.937207 -0.0958482 0.335344 0.779121 0.103879 0.618207 0.7618 -0.0969064 0.640524 0.542614 0.0275235 0.839531 0.537661 0 0.843161 0.362638 0 0.93193 0.347302 -0.0758739 0.934679 0.0660085 0.106029 0.99217 0.0401647 -0.0689207 0.996813 0.997296 0.0638621 0.0363538 0.880057 -0.127372 -0.457467 0.969173 0.143582 -0.200219 0.900379 -0.430478 -0.0632989 0.876698 0.0139414 -0.480838 0.696067 0 -0.717976 0.693305 -0.0204472 -0.720354 0.0143337 -0.823163 0.567625 -0.108942 -0.827934 0.550142 0.292311 -0.102355 -0.95083 -0.292311 0.102355 0.95083 0.24989 -0.934101 0.254971 0.210584 -0.84868 0.485177 0.234432 0.558944 0.795376 -0.0491821 0.968158 0.24546 0.0239547 0.999415 0.0244158 0.0416419 0.996382 0.0740929 0.891041 0.342281 0.298143 0.0856226 0.995587 -0.0384065 0.106743 0.992893 -0.0526234 0.335378 0.408361 -0.848978 -0.133122 0.552833 0.82259 -0.100506 0.984717 -0.142233 -0.887386 0.362223 -0.285203 -0.0296396 0.999552 -0.00407983 -0.0966205 0.992839 0.0702444 -0.954823 0.149017 -0.257113 0.955502 0.13021 0.264691 -0.695262 0.142777 -0.704432 -0.160979 -0.948192 -0.273894 0.0910139 -0.544631 -0.833723 0.0976576 -0.795398 -0.598168 -0.125348 -0.572006 -0.810616 -0.124614 -0.564452 -0.816006 -0.320073 0.623848 -0.712999 -0.402443 -0.665013 -0.629124 -0.801607 0.0144409 -0.597677 -0.760585 0.361035 -0.539596 -0.55753 -0.824378 -0.0977851 -0.982134 -0.16507 -0.0903581 -0.889784 -0.368786 0.268851 -0.936341 -0.182328 0.300037 -0.730259 -0.368788 0.57508 -0.762221 -0.182327 0.621109 -0.497647 -0.355122 0.79135 -0.481393 0.198356 0.853766 -0.140554 -0.229235 0.96317 -0.0969885 0.359869 0.927948 0.337891 -0.391988 0.855673 0.377251 -0.165071 0.911281 0.652665 -0.36918 0.661615 0.688471 0.35987 0.629683 0.888908 -0.391987 0.23704 0.957022 -0.165071 0.238453 0.920291 -0.368789 -0.130613 0.971045 -0.182324 -0.154368 0.792776 -0.379992 -0.476562 0.834399 0.127471 -0.536217 -0.117877 -0.881102 -0.458 -0.765368 0.298382 0.570245 -0.921595 -0.233007 0.310436 -0.821438 0.529595 0.211587 -0.759246 -0.649949 -0.0333459 -0.627632 0.758977 -0.173296 -0.668633 -0.672578 -0.317127 -0.452834 0.741903 -0.494491 -0.504521 -0.525533 -0.685035 -0.20236 0.0458252 -0.978239 -0.0884264 0.775959 -0.624554 0.245081 -0.529786 -0.81195 0.313362 0.566882 -0.761873 0.471484 -0.70492 -0.529896 0.468739 0.807463 -0.358171 0.602948 -0.76724 -0.218627 0.763185 0.638645 -0.0983938 0.826694 -0.560708 0.0467392 0.748627 0.617984 0.240111 0.774342 -0.525962 0.351794 0.693101 0.0932386 0.714785 0.67132 0.228902 0.704935 0.383064 -0.20501 0.900685 0.265856 0.572904 0.775307 -0.0124164 -0.767815 0.640551 -0.144435 -0.443298 0.884661 0.0185541 -0.982138 0.187243 0.0242833 0.167233 0.985618 0.212987 0.00382743 0.977048 0.909271 0.149448 0.388448 0.900737 0.161711 0.40314 0.794867 0.102353 -0.598089 0.87817 0.330336 -0.345972 0.477218 0.101733 -0.872876 -0.0171222 0.255566 -0.96664 -0.755116 -0.261685 -0.601099 -0.832031 0.125251 0.540404 -0.334685 -0.802528 -0.493897 -0.334688 -0.802526 -0.493899 -0.334687 -0.802527 -0.493898 -0.000378407 -0.993404 -0.114667 0.0981582 0.989304 -0.107902 -0.347929 -0.814206 -0.464772 -0.388585 0.0721959 -0.91858 0.388585 -0.0721959 0.91858 0.963385 0.121429 0.239051 -0.374564 0.185075 -0.908542 0.374564 -0.185075 0.908542 0.455918 0.439808 -0.773762 0.163096 -0.725615 -0.668493 -0.163096 0.725615 0.668493 0.471669 -0.849288 0.237145 -0.471669 0.849288 -0.237145 0.464986 0.358989 0.809268 0.83079 0.0767019 0.551275 0.953503 0.170997 0.248179 0.997019 -0.0762942 -0.0115125 0.846235 0.176067 -0.502878 0.457287 -0.198044 -0.866988 -0.789891 -0.0597866 -0.610326 -0.93385 0.342537 -0.102919 -0.941512 0.175492 0.287675 -0.810168 0.285936 0.51173 -0.521463 0.020863 0.853019 -0.30313 0.164015 0.938729 0.00967681 -0.156243 0.987671 -0.795554 0.312106 -0.519311 -0.67523 -0.0417544 -0.736424 -0.389624 0.285112 -0.87573 0.236971 -0.0499164 -0.970234 0.137546 0.759476 0.635828 -0.00453993 0.927362 -0.374137 -0.163448 0.944871 0.283732 0.260474 -0.0140928 -0.965378 0.49195 -0.0123579 -0.870536 0.575652 0.0366342 -0.816874 0.692809 -0.0259017 -0.720656 0.850527 -0.00697755 -0.525885 0.869055 0.0134757 -0.494532 0.954504 -0.015027 -0.297819 0.983376 0.0279298 -0.17942 0.999033 -0.0431375 -0.0084573 0.95759 0.0508153 0.283617 0.917189 -0.0285678 0.397428 0.734732 -0.00376825 0.678347 0.702985 0.032474 0.710463 0.356945 -0.0381823 0.933345 0.327596 -0.0128095 0.944731 0.046537 0.0250107 0.998603 -0.1368 -0.0465844 0.989503 -0.260572 0.0270437 0.965076 -0.562172 -0.0331998 0.826354 -0.66174 0.042962 0.748501 -0.80326 -0.0432587 0.594056 -0.922945 0.0344054 0.38339 -0.983369 -0.0460876 0.175673 -0.998106 0.0267139 0.0554064 -0.946677 -0.0382712 -0.319904 -0.915306 0.0319242 -0.401492 -0.706429 -0.0308832 -0.70711 -0.608724 0.0418291 -0.792278 -0.471296 -0.0258476 -0.881596 -0.237319 -0.00673081 -0.971408 -0.179049 0.0268001 -0.983475 0.0116515 -0.0225904 -0.999677 0.185568 0.0226548 -0.98237 0.916054 0.390828 -0.0899882 0.334313 0.836356 -0.434447 -0.254603 0.958014 0.131857 0.590318 0.663524 0.459631 0.123691 0.871856 0.473885 0.11961 0.877292 0.464814 -0.276274 0.679339 0.679832 -0.582754 0.679866 0.445173 -0.751157 0.653621 0.0924275 -0.289179 0.649903 -0.702853 0.0981516 0.646225 -0.756809 -0.264259 0.0431576 -0.963486 -0.49507 -0.0148294 -0.868726 -0.521767 -0.036579 -0.852303 -0.726222 0.0372688 -0.68645 -0.844743 -0.0391749 -0.533737 -0.946812 0.0272644 -0.320629 -0.977846 -0.0290419 -0.207301 -0.999561 0.0296276 0.000494309 -0.967708 -0.0238089 0.250948 -0.965646 -0.0288604 0.258252 -0.864534 0.0435028 0.500688 -0.71017 -0.0152277 0.703866 -0.725505 0.000295017 0.688217 -0.498307 -0.00431597 0.86699 -0.505602 0 0.862767 -0.265067 0 0.96423 -0.265073 3.14186e-06 0.964228 0.00159577 -0.00413561 0.99999 0.00736089 -0.00708752 0.999948 0.252553 0.00243509 0.96758 0.257526 0 0.966271 0.489932 0 0.871761 0.494376 -0.00243126 0.869245 0.705335 -0.00203813 0.708871 0.70251 0 0.711674 0.862104 0 0.506732 0.862767 -0.00062727 0.505602 0.972829 -0.00135526 0.231523 0.963995 0.0219783 0.265009 0.999533 -0.0298642 0.00647777 0.980287 0.0272521 -0.195692 0.95049 -0.0290247 -0.309396 0.868234 0.0280164 -0.495363 0.710514 -0.0239945 -0.703274 0.734749 -0.000540554 -0.678338 0.503435 -0.00128109 -0.864032 0.505602 -4.54006e-05 -0.862767 0.256683 -0.00444906 -0.966485 0.265073 -6.64646e-08 -0.964228 0.00653037 -1.63743e-09 -0.999979 -0.0297773 -0.017665 -0.9994 0.140906 -0.37306 0.917045 -0.110229 0.932836 0.343026 0.496857 0.0759268 0.864504 0.879199 0.38006 0.28734 0.595536 0.610258 -0.522419 -0.138319 -0.804065 -0.578227 0.0953815 0.689284 -0.718185 -0.472333 -0.542976 -0.694319 -0.600061 0.612684 0.51434 -0.455976 0.602708 -0.654851 0.558546 -0.23493 0.795509 0.840413 0.118221 0.528895 0.764721 0.287786 -0.576525 0.960833 -0.0502058 -0.272543 0.289777 0.296683 -0.90995 -0.571959 -0.17607 -0.801163 -0.994625 0.0877742 0.0549231 -0.926645 -0.0377943 0.374032 0.0881829 0.168936 0.981674 -0.674125 0.238384 0.699092 0.826166 0.327833 -0.458231 0.0971468 -0.000920768 -0.99527 0.303674 -0.552997 -0.775871 0.808294 0.0645873 -0.585226 0.799278 -0.0177562 -0.600699 0.958691 -0.0231483 -0.283506 0.992105 0.124458 0.0154111 0.919563 -0.0743334 0.385847 0.887637 0.101167 0.449296 0.673497 -0.0524625 0.737326 0.680958 -0.0834353 0.727554 0.379901 0.158427 0.911359 0.301056 -0.0818941 0.950083 -0.126067 0.0296209 0.991579 -0.0851249 -0.102831 0.99105 -0.430933 0.144813 0.890689 -0.503091 -0.0318023 0.863648 -0.757791 -0.0295895 0.651826 -0.763338 -0.00565766 0.645975 -0.949332 0.138508 0.282105 -0.971698 -0.156367 0.177067 -0.963742 0.195211 -0.181916 -0.954853 -0.0876543 -0.283854 -0.750301 0.00130485 -0.661095 -0.716485 0.131046 -0.685184 -0.376085 -0.0855988 -0.922623 -0.32932 0.0693173 -0.941671 0.0641235 0.0762505 -0.995025 -0.56517 0.076475 0.821422 -0.492787 -0.0797045 0.866492 -0.403887 0.0223641 0.914535 -0.527922 0.0950341 0.843959 -0.0449524 -0.0234509 0.998714 0.139308 -0.0281961 0.989848 0.318776 -0.0328447 0.947261 0.197171 0.04096 0.979513 0.447629 0.0588806 0.892279 0.48765 -0.00899993 0.872993 0.63875 -0.0568449 0.767312 0.769859 -0.0256503 0.637698 0.722207 0.0591597 0.689143 0.87493 -0.0271095 0.48349 0.990325 -0.0224603 0.136936 0.998777 -0.014044 -0.0473973 0.993745 0.0509902 -0.0993539 0.970706 -0.0709432 -0.229558 0.914295 -0.00360121 -0.405034 0.823391 -0.0471441 -0.565512 0.89056 0.077369 -0.448238 0.714513 0.0148781 -0.699464 0.706244 -0.000407952 -0.707969 0.564206 -0.016799 -0.825463 0.404864 -0.0293399 -0.913906 0.227693 -0.0248317 -0.973416 0.0449406 -0.0330512 -0.998443 0.18981 0.0262856 -0.981469 -0.139358 -0.00935567 -0.990198 -0.082581 0.0682889 -0.994242 -0.318694 -0.0398566 -0.947019 -0.415979 0.0693906 -0.906723 -0.487456 -0.0296221 -0.872645 -0.640372 -0.0213571 -0.767768 -0.769101 -0.0255396 -0.638617 -0.874966 -0.0273243 -0.483413 -0.990325 -0.0226131 -0.13691 -0.997607 -0.0503808 0.0473418 -0.972801 -0.0270825 0.230053 -0.985934 0.0651522 0.153914 -0.914 -0.0256557 0.404903 -0.823976 -0.0283616 0.565914 -0.893321 0.0324519 0.448245 -0.738896 0.0845091 0.668499 -0.737308 0.0797738 0.67083 -0.0856276 0.0266028 0.995972 -0.183388 -0.0153917 0.98292 -0.304551 0.104319 0.946766 0.228114 -0.354632 -0.906753 0.0575512 0.436345 -0.897937 -0.15838 -0.329772 -0.93068 -0.391161 0.417805 -0.820019 -0.502813 -0.478642 -0.719779 -0.736042 0.522047 -0.430939 -0.784917 -0.5385 -0.30647 -0.952043 -0.305936 0.00410469 -0.991082 0.119693 0.0585658 -0.877161 -0.140983 0.459034 -0.872842 0.0117529 0.487862 -0.614513 -0.352508 0.705771 -0.532896 0.33874 0.775421 -0.229352 -0.453215 0.861391 -0.00508378 0.547801 0.836593 0.149189 -0.328903 0.932505 0.544199 0.0794729 0.835183 0.533023 0.404589 0.743098 0.748157 -0.453676 0.484189 0.830975 0.46749 0.301551 0.966684 -0.206279 0.151564 0.90025 0.432216 -0.0523354 0.902102 -0.356001 -0.243875 0.803556 0.351072 -0.480673 0.29597 -0.87204 -0.389805 -0.727934 -0.669904 0.146083 -0.573932 -0.70994 0.408151 0.558484 -0.804428 -0.202462 0.119207 0.379869 0.917327 0.000367069 -0.40961 0.912261 0.402675 0.16111 0.901053 0.146067 -0.571271 0.80766 0.721208 0.290988 0.628637 0.508581 -0.456596 0.729976 0.891241 -0.190202 0.411718 0.801546 -0.400766 0.443746 0.94774 0.277314 -0.157755 0.721974 -0.691408 0.0266216 0.85002 -0.20962 -0.483245 0.530245 -0.221877 -0.818297 0.43141 0.424239 -0.796183 0.0752002 -0.499649 -0.862958 -0.087649 0.508341 -0.856684 -0.565073 0.531793 -0.630784 -0.392894 -0.548131 -0.738368 -0.729412 -0.451295 -0.514093 -0.945248 0.265853 -0.189286 -0.5583 0.0866073 -0.825107 -0.858967 0.0879718 -0.504416 0.110089 -0.79961 0.590342 0.138148 -0.947606 0.288025 0.727484 0.0170652 0.685912 0.67118 0.0811324 -0.736841 0.108086 0.870775 -0.479654 -0.188961 0.0363078 0.981313 -0.140242 -0.0905458 0.985968 0.285475 -0.567298 0.772449 0.0845928 -0.0950078 0.991876 0.431492 0.0761864 0.898894 0.455739 0.00667949 0.890088 0.692606 -0.102749 0.71396 0.728971 -0.00749699 0.684504 0.906828 0.00303863 0.421489 0.919742 -0.0975613 0.380205 0.998823 0.0476833 0.00883774 0.994123 -0.0951431 -0.0516378 0.913574 0.0384589 -0.40485 0.867179 -0.138218 -0.478432 0.590783 -0.124321 -0.797195 0.366385 0.0471526 -0.929268 0.183177 -0.176082 -0.967182 0.0855071 0.0231161 -0.996069 -0.208244 -0.0202332 -0.977868 -0.260451 -0.135369 -0.95595 -0.641397 -0.137814 -0.75473 -0.902031 -0.115934 -0.415812 -0.983844 0.0509357 -0.171627 -0.9865 -0.162811 0.0176046 -0.972502 0.130658 0.192793 -0.896411 -0.138085 0.421165 -0.814543 0.0596191 0.577032 -0.778463 -0.0189981 0.627403 -0.430566 -0.309727 -0.847751 -0.874153 0.01475 -0.485427 -0.967522 -0.17684 -0.180637 0.770777 0.0920886 0.630415 0.849169 0.00786073 0.528063 0.263219 -0.50195 -0.82387 -0.888867 0.0311522 -0.457104 -0.955188 0.294373 0.0310047 -0.949371 0.307145 0.0660083 -0.623224 0.481415 0.616304 -0.582962 0.490929 0.647414 0.0882388 0.418218 0.904051 0.124765 0.411149 0.90299 -0.525477 0.0619252 -0.848551 -0.365092 -0.114674 -0.923882 -0.241674 0.109352 -0.964176 -0.121861 -0.211928 -0.969658 -0.00693975 0.169865 -0.985443 0.276442 -0.047351 -0.959863 0.267377 0 -0.963592 -0.40586 0.0457203 -0.912791 -0.390549 0 -0.920582 -0.2036 0 -0.979054 -0.121861 -0.211927 -0.969658 -0.0045636 0.177438 -0.984121 0.275333 -0.0413761 -0.960458 0.267377 0 -0.963592 -0.390549 9.3458e-07 -0.920582 -0.2036 1.04207e-06 -0.979054 -0.121861 -0.211928 -0.969658 -0.00456334 0.177438 -0.984122 0.275333 -0.041375 -0.960458 0.267377 0 -0.963592 -0.389369 0 -0.921082 -0.2036 0 -0.979054 -0.121861 -0.211928 -0.969658 -0.00456334 0.177438 -0.984122 0.275333 -0.0413757 -0.960458 0.267377 0 -0.963592 -0.389368 0 -0.921082 -0.2036 0 -0.979054 -0.150261 -0.141369 -0.978487 -0.0045789 0.157335 -0.987535 0.0897783 -0.0322887 -0.995438 0.275137 0.055955 -0.959775 0.294489 0 -0.955655 -0.0449657 1.21875e-05 0.998989 -0.0450018 2.68506e-05 0.998987 0.139364 1.33237e-05 0.990241 0.139328 2.83634e-05 0.990246 0.318947 1.41456e-05 0.947772 0.318917 2.69957e-05 0.947783 0.48767 1.33409e-05 0.873028 0.487644 2.50378e-05 0.873042 0.639785 1.25582e-05 0.768554 0.634757 0.00265177 0.772707 0.770112 -0.00104876 0.637908 0.768486 2.85405e-05 0.639866 0.874215 1.42013e-05 0.485539 0.8742 2.66378e-05 0.485566 0.948548 1.32526e-05 0.316635 0.950074 -0.00195239 0.312018 0.990577 0.0011925 0.136948 0.990989 1.9387e-05 0.133942 0.998876 9.79982e-06 -0.0474012 0.998878 2.36765e-05 -0.0473671 0.973158 1.16772e-05 -0.230138 0.973151 0 -0.230166 0.914301 0 -0.405036 0.914431 0.000132832 -0.404742 0.824308 -7.6499e-06 -0.566142 0.824369 3.58373e-05 -0.566054 0.706244 9.61272e-06 -0.707969 0.706269 2.39357e-05 -0.707944 0.56413 1.21069e-05 -0.825686 0.564163 2.85026e-05 -0.825663 0.402805 1.41807e-05 -0.915286 0.402834 2.6932e-05 -0.915273 0.227763 1.34549e-05 -0.973717 0.227813 3.4136e-05 -0.973705 0.0449657 1.2e-05 -0.998989 0.0450019 2.66543e-05 -0.998987 -0.139364 1.32971e-05 -0.990241 -0.139327 2.8436e-05 -0.990246 -0.318947 1.41071e-05 -0.947772 -0.318917 2.69489e-05 -0.947783 -0.48767 1.34485e-05 -0.873028 -0.487644 2.5148e-05 -0.873042 -0.639785 1.24095e-05 -0.768554 -0.639774 1.76945e-05 -0.768563 -0.770112 8.85031e-06 -0.637908 -0.770126 0 -0.637892 -0.874215 0 -0.485539 -0.87407 0.00012311 -0.4858 -0.948548 -9.14816e-06 -0.316635 -0.948553 -1.65005e-05 -0.316618 -0.990578 3.57179e-05 -0.136948 -0.990579 3.46708e-05 -0.136946 -0.998876 1.1331e-05 0.0474012 -0.998877 2.36763e-05 0.0473707 -0.973158 1.16772e-05 0.230138 -0.973151 0 0.230166 -0.914301 0 0.405036 -0.914431 0.000132769 0.404742 -0.824308 -7.73777e-06 0.566142 -0.825403 0.00077618 0.564543 -0.704691 -0.000215714 0.709515 -0.706642 0.000903339 0.707571 -0.56519 0.000775058 0.82496 -0.564115 0.000261676 0.825696 -0.403465 0.000900604 0.914994 -0.403059 0.000725745 0.915174 -0.231871 0.00170274 0.972745 -0.227844 2.48362e-05 0.973698 -0.910567 0.0617376 -0.408725 -0.836175 0.0245673 -0.547912 -0.599712 -0.00618768 -0.800192 -0.49877 0.0192926 -0.86652 0.0328026 0.0167728 -0.999321 0.667956 0.0482778 -0.742634 0.97472 0.0100938 -0.223203 0.886403 -0.0346703 -0.461614 0.966847 0.00211464 0.255349 0.972345 0.00682438 0.233449 0.727144 0.00387261 0.686474 0.865729 0.000149105 0.500513 -0.999021 -0.02677 0.0352178 -0.924573 0.0460519 0.378211 -0.618109 -0.0280519 0.785592 -0.479445 0.0330209 0.87695 0.228825 -0.0101167 0.973415 0.257109 0 0.966382 0.737434 0 0.675419 0.367657 0.384442 -0.846778 0.948495 -0.31283 -0.0499528 0.953992 -0.299597 -0.0118285 -0.261124 -0.367705 -0.892529 -0.289108 -0.36019 -0.88695 -0.00820091 0.999785 0.0190213 -0.00645059 0.999885 0.0137453 -0.00466329 0.999983 -0.00360069 0.000108781 1 0.000371722 -0.00470118 0.999877 0.0149861 0.00961358 0.999916 0.00873727 0.00179689 0.999998 -0.000427093 -7.60548e-05 1 0.00012681 0.00599582 0.999981 0.00127545 0.00428382 0.999991 0.000783467 0.0101615 0.999515 -0.0294382 0.000212544 1 -0.000326044 -0.000204111 1 -0.000410593 2.88143e-05 1 -0.000478144 -0.00381017 0.99997 -0.00670212 0.00199048 0.999997 -0.00143504 0.000322535 1 0.00019634 0.000321235 1 0.000201321 0.00194019 0.999998 0.000173247 0.000576134 1 -0.000238332 -0.00424017 0.999781 -0.0205003 -0.00356035 0.999904 -0.0134109 -0.0231065 0.999694 -0.00883395 0.00238037 0.999825 -0.0185573 0.00202246 0.999823 -0.0187052 -0.000524299 1 0.000179023 0.000640767 1 -0.000440031 0.00734222 -0.999698 -0.0234705 -0.00364224 0.999988 0.00327358 0.00316785 0.999993 0.00213655 0.00438724 0.999989 0.00180106 0.000610743 1 -0.000311236 0.0119076 0.999893 -0.0084973 0.0117897 0.999897 -0.0082494 0.0230508 0.999566 0.0183237 0.000164823 1 -0.000623254 -0.0130857 0.999894 -0.00631818 -0.000537569 1 0.00022444 -0.00299218 0.999995 -0.000549813 -0.000535869 1 0.000188567 -0.0442683 -0.998966 0.0103959 9.23582e-05 1 0.000393667 1.40229e-05 0.999968 0.00794225 0.000154519 0.999973 0.00731464 0.00766115 0.99997 0.00129933 -0.000193369 1 -0.000111741 0.868388 0.0452512 -0.493817 0 -1 0 5.17192e-05 -1 5.05676e-05 -0.0302619 -0.999495 -0.00969611 0.00189935 -0.999815 0.0191268 0 1 0 -0.208573 0.978 0.00366036 -0.987014 -0.0890807 0.133672 0.668591 0.138718 -0.730577 -0.999651 0.0264178 0.000356028 -0.953296 0.0564443 -0.296717 -0.952166 0.0250081 -0.304557 -0.987478 -0.0486012 0.150083 -0.983453 0.132197 0.12387 -0.926299 0.264622 -0.268226 3.05645e-05 -1 3.90306e-06 0 -1 0 -1.89195e-05 -1 4.89131e-06 -0.127745 -0.990252 0.0555245 -0.0821963 0.995842 0.0392819 0 1 0 0.988798 0.0605053 -0.136447 0.990493 -0.077626 -0.113572 -0.996137 0.0753389 0.0451197 0.972392 0.0484847 0.228262 0.925715 -0.0574984 0.373827 0.987484 -0.0462613 -0.150784 0.961554 0.254776 -0.102488 0.93438 0.162234 0.317198 -0.0257606 -0.999045 -0.0352864 -0.211874 -0.933179 -0.290322 -0.147182 -0.974947 -0.166782 0.000109371 -1 0.000250556 -1.78931e-05 1 -2.47204e-05 -0.204341 0.937308 -0.282309 -0.723095 0.0679234 -0.687401 -0.878934 0.0426513 -0.475033 -0.364884 0.0741511 -0.928096 -0.330117 0.367245 -0.869571 -0.242174 -0.96681 -0.0814295 0.133224 -0.938541 0.318421 -0.254385 0.826546 0.502105 -0.126673 0.955131 0.267728 -0.0332858 -0.0524579 0.998068 -0.763254 -0.0102994 0.646017 -6.72949e-05 -1 -5.61197e-05 1.45041e-05 -1 0.000117002 -0.00235548 -0.999994 -0.00255342 0.104626 -0.974798 0.197033 -0.00385327 0.999921 0.0119443 0.754572 0.186135 0.629266 -0.237388 -0.077276 -0.968336 0.384614 0.0848916 0.919166 0.365276 -0.0490213 0.929608 0.702479 0.203977 0.681848 0.361661 0.332765 0.870901 0 -1 0 -0.000101592 -1 4.56177e-05 0.000128558 -1 -0.000157837 -0.110658 0.820378 -0.561013 7.68314e-06 -1 3.88245e-06 -0.000291665 -1 -0.000204759 0.299804 -0.952343 -0.056221 0.00256694 0.999996 0.00100277 6.34482e-06 -1 3.87609e-06 -3.06886e-05 -1 -8.98716e-05 0.386189 -0.915799 0.110315 0.000271372 -1 0.000320676 -0.0814057 -0.989605 0.118557 0 -1 0 4.003e-05 -1 -6.71146e-05 -9.28154e-05 -1 3.02807e-05 0 -1 0 0.287286 -0.888827 -0.357006 0 -1 0 -0.0153595 -0.996459 -0.082671 -0.080792 -0.974011 0.2116 0 -1 0 0.13993 -0.988031 -0.0649128 0 -1 0 0 -1 0 0 -1 0 -0.124118 -0.973555 -0.191794 -0.204626 -0.954258 -0.217989 -0.0242864 -0.973611 -0.226918 0.000251725 -1 4.30307e-05 0 -1 0 -0.161125 0.985934 -0.04443 0.0217886 0.970152 0.241516 0 1 0 3.53799e-06 1 -1.88073e-06 -0.0797375 0.986871 -0.140455 -0.199525 0.957237 0.209491 0 1 0 3.85487e-06 1 1.21284e-06 1.73404e-05 1 2.12185e-05 0 1 0 -0.0119566 0.999922 0.00375262 0.0293644 -0.213 0.976611 0.00161552 0.999533 0.0305221 -3.34479e-07 1 4.84924e-07 -0.217755 0.952722 -0.211907 0.00155027 0.999987 -0.00492452 0.0029961 0.999993 -0.00226803 -0.0479139 0.995197 -0.0853643 0 1 0 -9.97575e-06 1 1.39948e-06 0.363683 0.915156 -0.173853 -0.0365956 0.998458 -0.0417332 0 1 0 -0.0159524 0.998364 -0.0549075 0 1 0 -0.00413598 0.997244 -0.0740736 -1.92945e-06 1 -3.8281e-06 0.0237971 0.944256 0.32835 0 -1 0 0.0833011 -0.993644 -0.0757122 0 -1 0 7.68313e-06 -1 3.88246e-06 -2.42357e-06 -1 1.83479e-07 0.112797 -0.993581 -0.00853943 0.000111646 -1 4.20344e-05 4.38205e-06 -1 3.52151e-06 0.111101 -0.987559 0.111285 -0.0576201 -0.987869 0.144205 0 -1 0 0 -1 0 0 -1 0 -0.0821247 -0.996505 0.0152582 0.294004 -0.952626 0.0778813 0 -1 0 -0.0153595 -0.996459 -0.0826711 -0.0807926 -0.974011 0.211601 0 -1 0 0.298035 -0.948899 -0.103755 0.265967 -0.959525 -0.0925912 0 -1 0 0 -1 0 0 -1 0 -0.0011102 -0.999994 -0.00325121 -0.298999 -0.950727 0.0819647 -0.024281 -0.973612 -0.226913 0.00282251 -0.999994 0.00195141 0 -1 0 0 1 0 0.0369674 0.996505 -0.0749044 0.021789 0.970152 0.241517 0 1 0 0 1 0 0.0796317 0.996459 -0.0270039 -0.199525 0.957237 0.209492 0 1 0 0.0263201 0.999165 0.0312475 0 1 0 -0.010907 0.999698 0.0220435 -0.0867505 0.995799 0.0293194 2.05917e-06 1 -6.95946e-07 -1.90856e-06 1 5.24097e-06 -6.91912e-06 1 1.01783e-05 -0.0479141 0.995197 -0.0853648 0 1 0 -9.97577e-06 1 1.39947e-06 -3.66402e-05 1 0.000230938 0 1 0 -1.75802e-05 1 -2.22803e-05 0 1 0 0 1 0 -0.00413604 0.997244 -0.0740744 0 -1 0 -0.429599 -0.195182 -0.881674 1.16738e-05 -1 -3.89803e-06 -4.04631e-07 -1 1.42969e-06 0.0469023 -0.985057 -0.165721 5.5622e-06 -1 -4.1501e-07 -1.96778e-06 -1 -7.83613e-08 0.224165 -0.972609 -0.0614989 0.000116676 -1 4.34508e-05 3.50564e-06 -1 2.81721e-06 0.0750405 -0.995854 0.051413 -1.79311e-06 -1 -1.22852e-06 2.05915e-06 -1 7.50485e-06 0 -1 0 0 -1 0 -0.0821247 -0.996505 0.0152582 0.294003 -0.952626 0.0778813 0 -1 0 -0.0153595 -0.996459 -0.082671 -0.0807915 -0.974011 0.2116 0 -1 0 0.112283 -0.992561 0.0470632 0 -1 0 0 -1 0 0 -1 0 -0.0265774 -0.998964 -0.0369397 -0.0242864 -0.973611 -0.226918 0.00282161 -0.999994 0.00195079 0 -1 0 -1.15634e-05 1 1.97653e-06 0.0241371 0.96324 0.267554 0 1 0 7.79356e-06 1 -4.00867e-06 -9.46433e-06 1 -6.74311e-06 -0.199526 0.957237 0.209493 0 1 0 8.40474e-06 1 2.75832e-06 0 1 0 0.0754029 0.996459 0.0372137 0 1 0 -0.304106 0.952626 -0.0048066 -0.0867505 0.995799 0.0293194 2.05917e-06 1 -6.95945e-07 -4.01811e-06 1 6.66468e-06 -0.0479135 0.995197 -0.0853638 0 1 0 -9.97575e-06 1 1.39948e-06 0.306814 0.945706 -0.107264 0.00249157 0.999997 -0.00087107 0 1 0 -0.154869 0.979921 -0.125579 0 1 0 0 1 0 -0.00413595 0.997244 -0.0740728 0 1 0 -0.429974 -0.190822 -0.882445 -0.000313241 1 0.000149233 1.10217e-05 1 -4.91728e-06 -0.120919 0.990658 -0.063053 5.96976e-05 1 4.62447e-05 -0.165132 0.970913 0.173379 0 1 0 -5.43403e-05 1 -1.78337e-05 -1.52546e-05 1 -7.45276e-05 0.125692 0.989857 0.0662134 -7.92822e-05 1 -0.000214892 0.000764633 1 -7.48113e-06 -0.00193141 0.999995 0.00235487 -0.625657 -0.779694 0.0251169 0.0110876 0.998524 0.0531625 -0.000611474 0.999998 0.00199329 -0.0608149 0.993534 -0.0958711 -0.000116152 1 -0.000632514 -3.96433e-05 1 -2.09439e-05 -2.73923e-05 1 -2.26798e-05 0.0118742 0.999847 -0.0128271 -0.00732945 0.999955 -0.00600413 4.28522e-05 1 2.51021e-05 -0.0969226 0.991313 0.0889043 -0.152172 0.980262 -0.126218 -0.00252566 0.999981 -0.00555744 0.00196966 0.999997 0.00167981 6.34973e-06 1 1.47828e-05 0 -1 0 -0.429974 -0.190822 -0.882445 0.871625 -0.110195 -0.477626 0.936315 0.159894 -0.312649 0.963169 -0.144753 -0.226609 0.988035 0.135469 -0.0737199 0.913307 0.218248 0.343857 0.808483 -0.317242 0.495695 0.769352 0.160756 0.618268 0.263643 0.0848106 0.960885 0.258402 0.0429472 0.965082 -0.288045 -0.188039 0.938974 -0.454975 0.39309 0.799048 -0.606076 -0.257404 0.752606 -0.867633 -0.18804 0.460276 -0.914578 0.265109 0.305391 -0.968535 -0.238155 0.0722649 -0.990851 0.0492926 0.125637 -0.861819 0.128317 -0.490716 -0.838061 0.318783 -0.442755 -0.728166 -0.20529 -0.653934 0.686759 -0.0615145 -0.724278 0.886841 0.180479 -0.42537 0.945071 -0.247245 -0.213801 0.957263 -0.175891 -0.229586 0.913307 0.218248 0.343857 0.808483 -0.317242 0.495695 0.769352 0.160755 0.618268 0.263643 0.0848092 0.960885 0.239606 -0.0848095 0.967159 -0.493024 0.0848103 0.865872 -0.514458 -0.0848097 0.853311 -0.960885 0.0848094 0.263643 -0.967159 -0.0848087 0.239606 -0.861819 0.128318 -0.490716 -0.849594 -0.082784 -0.520901 0.681148 -0.064916 -0.729263 -0.701279 0.0641337 0.709996 0.85516 0.115351 -0.505366 0.961817 -0.109943 -0.250641 0.954387 -0.182319 -0.236441 0.962688 0.118671 0.243205 0.846761 -0.124117 0.517292 0.853311 -0.0848103 0.514458 0.505366 0.115351 0.855161 0.23297 -0.124116 0.964531 0.239606 -0.0848102 0.967159 -0.407972 -0.216478 0.886959 -0.332333 0.238155 0.912599 -0.542076 -0.26511 0.797415 -0.678498 0.188665 0.709962 -0.85516 0.115351 0.505366 -0.959372 -0.0989325 0.26423 -0.942904 -0.237413 0.233597 -0.991029 0.133502 -0.00625649 -0.861819 0.128317 -0.490716 -0.849594 -0.0827845 -0.520901 0.869534 -0.115174 -0.480256 0.93681 0.236951 -0.257374 0.974391 -0.0849174 -0.208209 0.961631 -0.0653457 0.26645 0.936102 0.123847 0.329203 0.840459 -0.0983083 0.532883 0.830309 -0.145629 0.53794 0.572128 -0.00416508 0.820154 0.422215 0.216493 0.880264 0.204682 -0.313899 0.927131 0.292464 0.230804 0.928006 -0.432089 0.163777 0.886835 -0.514312 -0.245189 0.821806 -0.646585 0.13472 0.750852 -0.759961 -0.0248078 0.649496 -0.878196 -0.155435 0.45234 -0.895321 0.36233 0.259069 -0.860379 0.157697 -0.484644 -0.849594 -0.0827841 -0.520901 0.681148 -0.0649163 -0.729263 0.836001 -0.0565639 -0.545805 -7.29034e-05 -1 7.27826e-05 3.58484e-07 -1 -3.57891e-07 -0.817828 -0.465861 -0.337833 -0.000219384 -1 1.73907e-05 0.171434 -0.546394 -0.819795 0 -1 0 0 -1 0 -0.00247592 -0.999996 0.00102328 -0.00398678 -0.999986 -0.00357144 0.119774 -0.984017 0.131779 6.60975e-07 -1 7.27227e-07 6.38624e-05 -0.999999 0.00126279 0.000572957 -1 0.000238306 -2.53022e-07 -1 9.73615e-08 1.50648e-06 -1 -1.74941e-06 0.00362591 -0.999987 -0.003566 -0.104969 -0.993655 0.0403914 0.234107 -0.967659 0.0939736 0 -1 0 -0.0153595 -0.996459 -0.0826711 -0.0851016 -0.97018 0.226956 0.00795625 -0.999941 0.00738546 0.36033 -0.915355 -0.179686 0.197809 -0.972181 -0.125443 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.327873 -0.944467 0.021964 -0.0148987 -0.988934 -0.147604 0 -1 0 0 -1 0 -0.460078 0.0215879 0.887616 0.543427 0.796241 -0.265872 -1.20487e-05 1 2.22302e-06 0.000208773 1 -6.3254e-05 0.0047398 0.999989 -0.000468945 -8.86669e-06 1 -6.28704e-06 -0.423603 0.897597 -0.121983 5.70442e-06 1 1.64268e-06 7.42911e-06 1 3.02597e-06 0.0268253 0.999111 0.032534 0 1 0 0 1 0 -0.2959 0.791921 -0.534139 0.242121 0.926481 -0.288116 -0.0975997 0.993282 0.0621781 0 1 0 -0.62153 -0.257266 0.739942 3.55893e-06 1 3.80573e-06 -0.711676 -0.253359 -0.65523 -0.0653339 0.992846 -0.0999371 -0.000137929 1 -0.000181176 -0.000172204 1 -5.47873e-05 0.285026 0.930446 0.230284 0.0296076 0.993585 -0.109139 0 1 0 -3.74018e-05 1 -7.29545e-05 -1.55861e-06 1 -2.6886e-05 0 1 0 -0.00914957 0.98644 -0.163864 0.000134674 -1 0.000313534 8.52788e-05 -1 0.000215802 0.866757 -0.16501 -0.470642 0.9359 0.285878 -0.20583 0.934625 0.0970848 0.342126 0.924405 -0.0608941 0.376521 0.795899 0.0504647 0.603323 0.801855 0.10267 0.588632 0.411062 0.181309 0.893396 0.312239 -0.20099 0.928499 0.126622 0.0592114 0.990182 0.13797 0.0876493 0.986551 -0.358373 -0.078723 0.930253 -0.574531 0.113511 0.810574 -0.936727 0.242491 0.252469 -0.947244 -0.0420241 0.317747 -0.987765 0.0381288 0.151218 -0.768812 0.361836 -0.52726 -0.907515 -0.0981187 -0.408399 0.73251 -0.0177786 -0.680524 0.195797 -0.808071 0.555594 -0.203069 -0.970765 0.127981 -0.784449 0.552998 -0.280773 0.42452 -0.761905 0.489166 -0.000412439 -1 -0.000603416 0.029185 -0.983712 0.177365 0.00105605 -0.999998 0.00147524 0.113468 -0.992477 0.0459924 0.0707291 -0.913122 0.401504 -0.0784836 -0.996914 0.00170245 0.14475 -0.986894 -0.0713294 -0.0195598 -0.991815 0.126178 -0.199686 -0.97854 0.0508425 0.0707934 -0.979414 0.189042 -0.201663 -0.955763 0.214126 0.0436344 0.998274 -0.0393055 0.110548 -0.993503 0.0270344 0.00641453 -0.941198 -0.337794 -0.118123 -0.992309 0.0370157 0 -1 0 -8.99126e-05 -1 2.67565e-05 -8.83146e-05 -1 2.27482e-05 0 -1 0 0.00118711 -0.999998 0.00129632 -0.00235944 -0.999997 0.000578387 0.00077275 -0.99998 0.00622728 0.321216 -0.831651 0.452965 0.151215 -0.987806 -0.0370684 3.19162e-05 -1 1.56329e-05 -0.131654 -0.938111 0.320334 0.000162619 -0.981809 0.189872 -0.000282672 -1 0.000172556 -0.000199966 -1 0.000141258 -0.378987 0.250597 -0.890825 0.378987 -0.250597 0.890825 -0.000259041 -1 3.93707e-05 -0.000542189 -1 0.000141889 -0.439327 -0.879993 -0.180568 -0.589793 -0.804442 -0.0708404 -0.00058543 -1 -0.000182138 -0.302983 -0.913352 -0.27201 -0.000593937 -1 -0.000554789 0 -1 0 -0.700244 -0.548301 -0.457193 -0.536619 -0.284193 -0.794528 -0.0304718 -0.976635 -0.212735 -0.0458463 -0.99868 -0.0231761 0.00218844 -0.999997 0.0011063 0.130952 -0.434454 -0.891124 -0.148358 -0.984943 -0.0887513 -0.0891639 -0.980568 0.174745 0.243288 -0.35562 0.902411 1.82555e-05 -1 2.10354e-05 0.170753 -0.818256 -0.548909 -0.0842526 -0.953646 -0.288898 -0.463518 -0.882075 0.084231 0.100142 -0.625061 0.774125 -0.21874 -0.595145 0.773275 -0.401302 -0.776321 0.486089 -0.240329 0.843838 0.479771 -0.0247469 -0.994405 0.102696 0.940869 -0.328872 0.0812926 0.130333 -0.946033 -0.296706 0.0911178 0.876139 -0.473369 -2.22615e-05 -1 -2.32223e-05 -0.346612 -0.937146 -0.0402194 -1.59258e-06 -1 -2.20042e-06 0.22581 -0.969409 -0.0962043 -0.361635 0.930987 -0.0498345 0.0239357 0.999705 -0.0041278 -0.00114723 -0.999999 0.000231135 0.310829 -0.947843 -0.0705675 0.232442 -0.972577 -0.00806608 0.188361 -0.973822 0.127245 -0.0245211 -0.996597 -0.0786997 0.335961 0.938135 -0.083859 0.00863995 0.998408 -0.055738 0.000233951 -0.998393 -0.0566649 -4.68469e-05 -1 -2.21235e-05 0 1 0 -0.0365707 -0.974227 0.222586 1.26002e-06 -1 -2.11344e-06 -0.204308 -0.97878 0.0157194 -0.0825693 -0.992761 0.0872282 -0.0823817 -0.992899 0.0858144 0.137871 -0.989325 0.0471931 -0.0691167 0.979915 0.187054 -0.0574181 0.99336 0.099694 -0.137871 0.989325 -0.0471931 -0.511908 -0.0266131 0.858628 -0.498909 0.0266133 0.866246 -0.500101 0.0950022 0.86074 0 -1 0 0.571004 -0.78595 -0.237144 2.61175e-06 -1 -1.08469e-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 3.20744e-06 -1 -6.88282e-07 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.000102048 -1 -8.93829e-05 0.000117379 -1 -0.000333459 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0972798 -0.941268 -0.323345 -0.0981582 -0.989304 0.107902 0.0337294 0.109454 -0.993419 0.0259856 -0.99905 0.0349811 -8.43657e-06 -1 -2.0162e-05 0.000127347 -1 -5.19459e-05 -0.000167301 -1 -0.000383266 1.74895e-05 1 2.39463e-05 0 1 0 0.011397 -0.999103 -0.0407768 0.0499899 -0.996036 -0.0735738 0.0354553 -0.998628 -0.0385427 0.0810174 -0.995562 -0.0478793 0.0541935 -0.998164 -0.0270351 0.0726821 -0.997355 0.000783641 0.0897059 -0.995962 0.00363676 0.0592288 -0.997853 0.0279423 0.0769322 -0.996126 0.0425902 0.0205345 -0.9989 0.0421578 0.00663895 -0.999175 0.0400692 -0.266962 -0.94655 0.181036 -0.0468493 -0.993844 0.100391 -0.132836 -0.990648 0.0311498 -0.382254 -0.922978 0.0446467 -0.463969 -0.880981 -0.0927702 -0.190033 -0.981528 0.0221333 -0.05602 -0.997877 -0.0332176 -0.0759088 -0.995679 -0.0534983 -0.0363295 -0.997868 -0.0542275 -0.0517597 -0.993908 -0.0972986 -0.0116182 -0.99834 -0.0564038 0.00821465 -0.994986 -0.0996735 -0.00457529 -0.999936 -0.0103873 -0.0041022 -0.999782 -0.0204606 -0.00311747 -0.99984 -0.0176143 -0.475774 -0.869228 0.134467 -0.56485 -0.804593 -0.183236 0.00636478 -0.999979 0.000960951 0.0174139 -0.999785 0.0112108 0.00358399 -0.999985 0.00411136 0.00659995 -0.999928 0.010006 0.000613219 -0.999965 0.00829847 0.000620149 -0.999994 0.00333678 -0.00214047 -0.999962 0.00845178 -0.00277651 -0.999914 0.0128201 0.00118284 -0.999962 -0.0086649 -0.0108269 -0.999895 0.00959523 0.0540088 -0.998461 0.0125978 -0.00369956 -0.999991 -0.00225827 -0.0146201 -0.99965 -0.0220717 7.87736e-05 1 -0.000250821 -1.6119e-05 1 -6.2717e-06 1.64779e-05 0.999999 -0.00158939 -5.61316e-05 1 3.4698e-05 -0.00649661 0.999978 0.00159431 0.00188786 0.999998 0.000274164 5.84876e-05 1 1.69138e-05 3.31556e-05 1 2.17003e-05 3.97659e-05 1 5.11122e-05 3.8619e-05 1 3.46319e-05 -1.90172e-05 1 -6.11569e-05 -1.16743e-05 1 -1.34531e-05 4.2893e-06 1 -3.37374e-05 3.495e-05 1 4.66163e-05 -3.07766e-05 1 -5.22901e-05 -1.94218e-05 1 -6.12918e-05 -4.83003e-05 1 3.66035e-05 1.62019e-06 1 -1.09132e-05 -2.73232e-06 1 -2.97883e-05 2.00833e-05 1 3.8846e-06 3.30173e-05 1 -1.64437e-05 9.01407e-06 1 4.73892e-06 -0.000601574 1 0.00052258 -0.927347 0.186243 -0.324562 -0.728036 -0.591608 -0.346357 -0.676981 0.439566 -0.590321 -0.886238 0.158296 0.435345 -0.882154 -0.254753 0.396112 -0.961574 0.262632 0.0800019 -0.296609 0.130294 0.946069 -0.324243 -0.133455 0.936513 -0.560135 0.163653 0.812076 -0.568974 -0.321806 0.756776 0.342305 0.321808 0.882761 0.318794 -0.163653 0.933589 0.0549539 0.136732 0.989083 0.639833 0.664683 0.385759 0.796397 -0.219376 0.563584 0.725565 -0.606144 -0.325799 0.567515 0.810973 -0.142302 0.976739 -0.206408 -0.0581054 0.193592 -0.0291362 0.980649 0.000101592 -1 -4.56178e-05 -0.000128559 -1 0.000157837 -0.218056 -0.97413 -0.0593563 -0.000179156 -1 -0.000120823 0 -1 0 0.213863 0.976728 -0.0163115 -9.93679e-08 1 2.96514e-06 0.000212373 0.99998 -0.0063372 0.0437539 0.893402 -0.447122 -0.725749 0.620059 0.298018 -0.927347 0.186243 -0.324562 -0.728037 -0.591606 -0.346358 -0.676981 0.439567 -0.590321 -0.887022 -0.141874 0.439391 -0.970212 0.176596 0.165838 -0.977547 -0.158823 0.13848 -0.382165 0.321782 0.86626 -0.434725 -0.16365 0.885569 -0.663601 0.141924 0.7345 0.334409 0.438196 0.834359 0.0579955 -0.0879923 0.994431 0.937915 -0.141872 0.316524 0.801175 0.179684 0.570818 0.792692 -0.128278 0.595973 0.811506 -0.440003 -0.38452 0.794701 0.591607 -0.135838 0.97674 -0.206406 -0.0581055 0.698335 0.142687 -0.701405 -0.0514129 -0.995854 0.0750405 1.22852e-06 -1 -1.79311e-06 -7.50484e-06 -1 2.05914e-06 0 1 0 -0.0372136 0.996459 0.0754029 0 1 0 -0.0241388 0.96324 -0.267555 -0.927347 0.186244 -0.324562 -0.728037 -0.591607 -0.346357 -0.676981 0.439567 -0.59032 -0.887022 -0.141871 0.439391 -0.970211 0.176601 0.165838 -0.977547 -0.158825 0.13848 -0.382165 0.321782 0.86626 -0.434725 -0.16365 0.885569 -0.663601 0.141924 0.7345 0.439391 -0.141871 0.887022 0.17815 0.163653 0.970299 0.1328 -0.321782 0.937454 0.90613 0.302503 0.29567 0.785583 -0.263791 0.559709 0.796397 -0.219374 0.563584 0.849801 0.302504 -0.43166 0.952157 -0.258668 -0.162752 0.953005 -0.255275 -0.163143 0.684455 0.143199 -0.714853 -0.0514134 -0.995854 0.0750403 3.92801e-07 -1 -1.67472e-06 -5.5622e-06 -1 4.1501e-07 -9.73106e-06 -1 2.79088e-06 0 1 0 -0.0372134 0.996459 0.0754029 0 1 0 -0.0241377 0.96324 -0.267554 -0.012405 0.99988 0.00924409 -0.0863893 0.986233 0.141004 0 1 0 0 1 0 0.00728632 0.999969 -0.00310507 -0.943139 0.0352141 -0.330527 -0.863152 -0.381138 -0.331215 -0.835938 -0.0179362 -0.54853 -0.895585 -0.101744 -0.4331 -0.753013 0.0106824 -0.657919 -0.74861 -0.0476448 -0.661297 -0.721853 0.30633 -0.620557 -0.706595 -0.113849 -0.698399 -0.974634 0.0471905 -0.218772 -0.939066 -0.0625063 -0.338005 -0.975569 0.141282 0.168241 -0.960336 -0.240996 0.140268 -0.875036 0.406389 0.262982 -0.882391 -0.45056 0.135579 -0.965092 0.251807 0.0720511 -0.927498 0.0425327 0.371401 -0.941354 -0.0128536 0.337177 -0.913562 0.028646 0.40569 0.0489362 -0.715567 0.696828 -0.162513 0.000903835 0.986706 -0.287211 -0.117114 0.950681 -0.491738 0.367192 0.789534 -0.67589 -0.59801 0.430762 -0.701292 0.00663433 0.712843 -0.697456 -0.00609747 0.716602 0.13229 0.515387 0.846685 -0.00314692 -0.60723 0.79452 0.0761231 -0.173263 0.981929 0.0684503 0.0343049 0.997065 0.084928 0.00890926 0.996347 0.274414 -0.62312 0.732405 0.323364 0.404561 0.855433 0.386093 -0.261919 0.884495 0.875154 0.348958 -0.335161 0.897335 -0.0474872 0.438789 0.745567 0.332511 0.577553 0.738569 -0.157945 0.655415 0.56784 -0.223441 0.792232 0.965274 -0.218067 0.143848 0.739412 0.187918 0.646496 0.838678 0.410596 0.357812 0.808596 -0.0436233 0.586745 0.679939 0.716885 -0.154142 0.959592 -0.24304 -0.141828 0.980846 0.0990257 -0.167738 0.913085 -0.0405007 -0.405753 0.506038 -0.736959 -0.448126 0.96703 -0.214453 -0.137342 0.861773 -0.291788 -0.414978 0.903109 0.140689 -0.405709 0.60999 0.222131 -0.760638 -0.864416 0.208957 0.457299 0.69675 -0.0199336 -0.717037 0.699362 -0.0283189 -0.714207 -0.131387 0.755713 -0.641589 -0.0583855 -0.396849 -0.916025 -0.342306 0.321807 -0.882761 -0.318795 -0.163651 -0.933589 -0.0573508 0.134146 -0.989301 -0.0423577 -0.0183958 -0.998933 -0.279214 -0.607693 -0.743471 -0.138554 0.547912 -0.824982 -0.0392404 -0.376885 -0.925429 -0.319901 0.419069 -0.849732 -0.386093 -0.26192 -0.884494 -0.186661 0.311397 -0.931767 0.0557215 -0.805959 -0.589343 -0.0315355 -0.334659 -0.941812 0.0125706 0.0380501 -0.999197 -0.0755665 -0.0540346 -0.995676 -0.27058 -0.632288 -0.725946 0.862767 -0.00042884 0.505602 0.862911 0 0.505356 0.863255 0.00171987 0.504766 0.895569 -0.0102869 0.444804 0.873208 0.0786869 0.480954 0.891327 -0.256833 0.373596 0.862162 5.48457e-05 0.506633 0.863242 5.48221e-05 0.50479 0.91386 -0.229554 0.334911 0.872882 -0.0023348 0.487926 0.863608 -0.00175415 0.50416 0.859964 0.00773716 0.510296 0.862207 -0.00359054 0.506543 0.86527 -0.00397273 0.501291 0.858567 0.00733381 0.51265 0.802035 0.0809704 0.591763 0.837838 0.0795816 0.540087 -0.862692 0 -0.505729 -0.856797 -0.00623575 -0.515617 -0.862857 0 -0.505448 -0.862845 4.46932e-05 -0.505468 -0.861907 6.22197e-05 -0.507067 -0.862767 0 -0.505602 -0.862782 -5.65025e-05 -0.505576 -0.862767 0 -0.505602 -0.862845 -0.000290295 -0.505468 -0.862433 -0.000320018 -0.506172 -0.862806 0.000127778 -0.505535 -0.86107 -0.00174943 -0.508483 -0.861839 -0.00012447 -0.507182 -0.862368 0.000757466 -0.506281 -0.862767 0 -0.505602 -0.862767 0 -0.505602 -0.862767 0 -0.505602 -0.862767 -3.43676e-07 -0.505602 -0.862684 -4.75173e-05 -0.505743 -0.8627 0 -0.505717 -0.8627 0 -0.505717 -0.863071 0.000639334 -0.505082 -0.811751 -0.439565 0.384502 -0.793653 0.593179 0.135105 -0.884653 -0.463789 0.0478443 -0.306226 0.37506 0.874961 -0.364526 -0.561886 0.742567 -0.590272 0.44 0.676741 0.334409 0.438196 0.834359 0.0582893 -0.0874738 0.99446 0.0534719 -0.140257 0.98867 0.949486 0.0498844 0.309818 0.868304 -0.370192 0.33016 0.656732 0.593178 0.465664 0.659375 -0.46379 0.591713 0.890463 0.0498879 -0.452314 0.847442 -0.370191 -0.380526 0.79445 0.591984 -0.135662 0.910116 -0.410802 -0.0541411 -0.0692776 -0.995197 0.0691629 -0.00126279 -0.999999 6.3862e-05 -0.000462377 -1 0.000461611 0.000141121 1 -2.41867e-05 -0.0452858 0.995811 0.0794381 -0.000221335 1 0.000146919 0.445084 0.845349 -0.295441 -0.924338 0.206405 -0.320931 -0.728037 -0.591607 -0.346358 -0.676981 0.439565 -0.590321 -0.342305 0.321808 -0.882761 -0.318795 -0.163651 -0.933589 -0.0573508 0.134146 -0.989301 -0.0423577 -0.0183958 -0.998933 -0.690978 -0.256576 0.675809 -0.927476 0.110267 0.357253 -0.990656 -0.135933 0.0111132 -0.857847 0.359848 -0.36689 0.87196 0.00183376 -0.489573 0.923184 0.261196 -0.28197 0.962558 0.123973 0.241064 0.662408 -0.0817793 0.744667 0.56183 0.102672 0.820856 0.00251689 -0.0137623 0.999902 -0.24359 0.708659 -0.662168 0.00289993 -0.999967 -0.00765183 -0.712279 0.678309 -0.180434 0.0035258 -0.999994 2.28501e-05 0.00134753 -0.999985 0.0053283 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0100184 -0.998603 0.0518887 -0.0897467 -0.994149 -0.060108 -3.82872e-05 -1 -7.49109e-05 -0.000167661 -1 0.000200681 5.04076e-05 -1 0.000210724 7.74426e-05 -1 8.08247e-05 0 -1 0 0 -1 0 0 -1 0 0.000324573 -1 7.91358e-07 -0.0025541 -0.999994 -0.00245751 -0.00381581 -0.999992 0.000773884 -0.00208104 -0.999936 0.0111654 -0.00299414 -0.99999 -0.0033783 -0.00349366 -0.99999 -0.00296166 -0.00344292 -0.999988 -0.00358736 -0.00141608 -0.999992 -0.00378073 -0.00215056 -0.999995 -0.00222627 0.000477972 -0.999998 -0.00170194 5.73408e-05 -1 -1.33465e-05 -0.00386291 -0.999992 0.000805583 -1.75218e-05 -1 3.16888e-05 4.1513e-06 -1 6.06595e-06 -6.01013e-06 -1 -3.14286e-05 -0.00460727 -0.999989 0.000406842 -0.00477605 -0.999956 0.00811111 0.00392784 -0.999955 -0.00863536 0.00371341 -0.99996 0.00812813 0.00738024 -0.999892 0.012671 -0.010588 -0.999861 0.0128623 0.00383757 -0.999993 -0.000130233 0.00201547 -0.999998 0.000836238 0.00179523 -0.999998 0.000166277 0.000289476 -0.999999 -0.00153099 0.000101714 -0.999999 -0.00162326 0.00312529 -0.999993 -0.00196548 0.00286332 -0.999992 -0.00285146 0.0037278 -0.999991 -0.00215649 0.00191033 -0.999995 -0.00257131 0.00191342 -0.999998 -0.000126696 0.0019442 -0.999998 -0.000100988 0.000164882 -1 9.08151e-05 0.00012506 -1 9.48009e-05 -5.3349e-05 -1 9.57796e-05 0.000197112 -1 0.00023582 -2.35038e-05 -1 3.82577e-05 -1.45028e-05 -1 -0.000161109 0.000253359 -1 3.45634e-05 -4.6199e-05 -1 -6.30248e-06 -3.35975e-05 -1 -9.04196e-05 -0.000482489 -0.999995 -0.00326778 -0.348658 -0.24928 0.903492 0.155288 -0.186065 0.970188 -0.00220137 -0.999989 0.004101 4.16984e-05 -1 -7.76812e-05 0.00141926 -0.999994 -0.00305775 0.000487147 -0.999995 0.00309683 0.0150413 -0.999881 0.00330502 6.17804e-06 -1 3.92743e-05 -0.0145758 -0.999479 0.0287983 0.021238 -0.994906 -0.0985435 -0.0389394 -0.998942 0.024471 -0.000111424 -1 -2.22891e-05 -0.000158365 -1 3.69714e-05 -0.000100094 -1 -1.77615e-05 -7.37412e-06 -1 -2.81269e-05 1.9493e-05 -1 7.43517e-05 -9.82589e-05 -1 -5.79942e-05 -0.00169425 -0.999999 -0.000183355 -0.000150507 -1 1.30779e-05 0 -1 0 0 -1 0 -0.000144568 -0.999997 -0.00226913 -0.0022025 -0.999995 -0.00210562 -0.538401 0.139628 -0.831041 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 2.50239e-05 -1 -1.90173e-05 0.000403238 -1 -9.76158e-07 -0.00816984 -0.999966 0.000681212 0 -1 0 0.845726 -0.0631479 0.529867 0.927546 -0.305707 -0.214948 0.0205849 -0.999779 0.00419446 0.000664621 -0.999998 -0.00165377 0.000110762 -1 -0.000213629 0.147555 -0.894068 -0.42293 0.507006 -0.861544 -0.0262042 0.000985401 0.999999 0.000978516 0.115676 0.880621 -0.459485 -0.981952 0.187778 0.0225929 0.245246 0.821082 0.515441 -0.152872 0.819627 -0.552125 3.06589e-05 1 -6.66455e-05 -2.42962e-05 1 5.90704e-05 -0.00477471 0.999988 -0.000918299 0.152872 -0.819627 0.552125 -6.90626e-05 -1 -0.000157132 -0.000705016 0.999999 -0.00160406 -0.000133909 1 4.31395e-05 7.83565e-05 1 -3.35803e-05 0.00192167 0.999998 0.000112487 -0.000706043 1 -0.000159073 0.402076 0.829057 0.388587 -0.000640627 1 0.000664742 0.0476275 0.722911 0.689298 -0.259425 -0.517771 -0.815237 -0.000671315 0.999999 0.00119143 0.128194 -0.254402 -0.958565 -9.36355e-05 1 -5.45117e-05 0.000184076 1 7.31437e-05 -0.47713 -0.11246 -0.871608 0 1 0 0 1 0 0.000145816 -1 -7.17658e-05 9.79235e-05 1 -0.000139529 9.1252e-05 1 -0.000115978 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.208564 0.929147 0.305264 0.868703 0.112118 0.482478 0.955549 0.128265 0.26547 0.0422621 0.999007 0.0141075 0.0445575 0.998999 0.00383205 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.274477 0.934328 0.227361 0.560276 0.116694 -0.820045 0.352966 0.108754 -0.929294 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.198069 0.970702 -0.136035 -0.628318 0.188475 -0.75478 -0.788377 0.183416 -0.587214 0 1 0 0.208565 0.929147 -0.305264 -0.868703 0.112118 -0.482477 -0.955542 0.128263 -0.265496 -0.0443241 0.998908 -0.0147958 -0.0467573 0.998898 -0.00402124 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.0141233 0.999756 -0.0169659 0.0726946 0.997304 0.0100502 0 1 0 0 1 0 4.046e-06 -1 1.65613e-05 0 1 0 0.000140665 1 -0.000436273 0.00029619 1 -0.000524127 0.000137691 1 -0.000493988 0.00417921 0.999981 -0.00442614 0 1 0 0.00103757 0.999999 3.72683e-05 0.00319564 0.999995 -0.00078284 0.00265326 0.999996 -0.000826746 0.00135238 0.999999 1.98858e-06 0.00104299 0.999999 0.000704478 0.00153229 0.999999 0.000649316 0.000836138 0.999999 0.001159 0.00127675 0.999999 0.0011961 0.000178478 0.999998 0.00201236 0.00101189 0.999996 0.0026459 0.0003829 0.999996 0.00275015 -0.000254888 0.999998 0.00185529 -0.000740627 0.999999 -0.000723331 -0.00152643 0.999998 -0.00088657 -0.00159943 0.999999 -0.000541605 -0.000450864 1 -0.000843376 -0.000154129 0.999999 -0.00132891 0.00167952 0.999939 -0.0108774 -0.00679795 0.999969 -0.00397402 -0.00193599 0.999998 -0.000410326 -0.00160279 0.999999 0.000287947 -0.00194196 0.999998 0.000747954 -0.000897661 0.999999 0.000648039 -0.000542916 1 0.000816907 -0.000259557 0.999998 0.00185594 0.00576584 0.999939 0.00938891 0.00466182 0.999914 0.0122298 0.000674308 1 0.000370089 0.000937232 1 -5.19525e-05 0.00115682 0.999999 0.000491751 -0.00217647 0.999992 -0.00325372 0.000249741 1 -0.000330719 -0.00111069 0.999987 0.00493693 -0.000653887 0.999997 0.00237139 0.000254374 0.999987 -0.00501106 0.000457955 1 -5.9801e-05 0.000365955 0.999999 -0.00123878 0.000948362 1 -9.55637e-05 0.000302797 1 -0.000188414 -0.00174237 0.999998 -0.000954318 0.00274656 0.999996 -0.000912622 -0.000312971 1 -0.000554142 -0.00179155 0.999998 0.000474676 -0.00187445 0.999997 -0.00122576 -0.00172865 0.999998 -0.000990662 -0.000675589 1 -1.23038e-06 -0.000662013 1 0.0001564 -0.380611 0.921946 -0.0717683 0.0157213 0.999333 -0.0329583 -0.00394137 0.81809 0.575077 0.644611 0.762227 0.0590405 -0.00586968 0.999952 0.00778903 -0.0157776 0.999759 0.0152935 -0.482894 0.859398 -0.168071 -0.245681 0.734506 -0.632567 0.487357 0.457162 -0.743967 0.324785 0 -0.945788 0.988238 -0.141047 -0.0590869 0.515612 0.819761 -0.249271 0.312702 0.0830069 -0.946218 0.312702 0.0829951 -0.946218 0.312702 0.0830071 -0.946218 0.298259 -0.00233718 -0.954482 0.294543 -0.00840587 -0.955601 0.438724 0.0431309 0.897586 0.399247 0.0311595 -0.916314 0.0850908 0.994872 0.0546782 0.0213102 0.0692223 -0.997374 -0.910688 -0.191427 -0.366063 -0.886438 -0.114527 -0.448455 0.657012 0.715595 -0.23719 0.515612 0.819761 -0.249272 0.988238 -0.141047 -0.0590908 0.515614 0.819759 -0.249273 0.657017 0.715591 -0.237189 0.51561 0.819763 -0.249271 -0.164335 0.769071 -0.617677 -0.658298 0.450678 -0.602937 -0.953955 0.162768 -0.251945 -0.960009 0.173366 0.219834 -0.562347 0.526649 0.637501 -0.0114046 0.996457 -0.0833214 -0.00655813 0.987943 -0.154681 -0.879954 0.387178 -0.27527 -0.83233 0.395399 0.388441 0.0086996 0.99988 0.0127844 -0.66135 0.318769 -0.678972 -0.803836 0.241196 -0.543757 -0.199126 -0.425916 -0.882578 -0.961175 -0.00272784 -0.275927 0.985652 -0.145272 0.0859455 0.930605 0.109333 0.349313 -0.928449 -0.308815 -0.206436 0.658122 -0.277293 0.699988 0.612658 0.0987817 0.784151 -0.00878517 -0.434398 -0.900678 -0.192627 -0.970023 -0.148155 -0.982408 0.0242284 -0.18517 0.882595 -0.0984089 -0.459718 0.278566 -0.953672 -0.113629 -0.0756741 0.0033934 -0.997127 0.998815 0.0199944 -0.0443601 0.998798 0.0173287 -0.0458449 -0.968157 -0.0231958 0.249266 0.35106 0.145973 0.924905 0.504463 -0.858677 0.0905057 0.533757 0.453625 -0.713672 0.148867 -0.125934 -0.980805 0.449132 -0.636746 -0.626766 0.00258127 -0.999996 -0.000827129 -4.56846e-05 -1 -0.000172106 0 -1 0 -0.000548898 -1 -0.000106141 -0.00023344 -1 0.000160731 0.000644345 -1 0.000457129 0.000489233 -1 0.000260073 0 -1 0 0 -1 0 0 -1 0 0.0184578 -0.98215 0.187191 0.0429373 -0.985866 0.161943 -0.0413297 -0.938203 0.343608 -0.12465 -0.984998 0.11934 -0.2317 -0.971337 0.053096 -0.324353 -0.940932 0.0971692 -0.157172 -0.974486 0.160232 0.000577235 -1 -0.000370954 0.000765124 -1 -0.000396366 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1.84069e-06 -1 3.00865e-06 7.8062e-07 -1 1.88565e-06 -0.000561643 -0.99999 -0.00442379 0.000211245 -0.999998 -0.00202111 0.000430905 -0.999997 -0.0025751 0 -1 0 0.00102133 -0.999999 -0.000876675 0.00093976 -0.999999 -0.00076578 0.953149 -0.171514 -0.24918 0.18373 -0.982967 -0.00427815 0.71325 0.121686 0.690265 0.885396 -0.405584 -0.227101 0.657228 -0.467744 -0.590988 0.547761 -0.0083483 0.836593 0.590828 0.0967155 0.80098 -0.851645 0.220073 -0.475677 -0.999976 0.00584992 0.00370276 -0.991996 -0.101611 -0.0749568 0.74111 -0.361593 0.565691 0.292969 -0.703386 0.647624 -0.731397 -0.655968 -0.186452 -0.619954 -0.746303 -0.24226 -0.740455 -0.00682355 0.672071 -0.71539 0.0586648 0.696259 0.00222252 -0.146704 -0.989178 0.77723 0.0123278 0.629096 -0.27431 -0.948504 -0.158411 0.484538 -0.0929462 -0.869819 -0.499077 0.00218296 0.866555 -0.290682 0.35958 0.886683 0.571688 -0.751789 -0.328612 0.942356 0.30578 -0.135879 -0.163277 0.25508 -0.953035 -0.137913 -0.824633 -0.548599 -0.473791 -0.817011 0.328658 -0.000609206 -0.003414 0.999994 -0.155983 -0.189861 0.969341 -0.637144 -0.058121 -0.768551 -0.0640328 -0.994018 -0.0884721 -0.409612 -0.190187 -0.892215 0.423823 0.00767362 0.905713 0.485441 0.141228 0.862787 0.896737 -0.0973129 -0.431733 0.249168 -0.775292 -0.580377 -0.0662409 -0.955747 -0.286636 0.289543 -0.906478 0.307346 0.316406 -0.896616 0.309785 -0.442247 -0.8484 -0.290922 0.354852 -0.320867 0.878137 0.684002 0.0367545 0.728554 -0.663244 0.00053842 -0.748403 0.128732 -0.988793 -0.0756016 0.894956 -0.446141 0.00328692 -0.664408 -0.000214262 -0.74737 -0.661606 0.00116428 -0.74985 -0.647312 0.00782882 -0.762185 0.894957 -0.446141 0.00328589 0.894955 -0.446144 0.00328738 -0.664227 -0.000374523 -0.74753 -0.663739 0.000346661 -0.747964 -0.664342 -0.00027216 -0.747429 0.171749 -0.985107 -0.00818015 0.852975 0.510746 0.107576 0.702864 0.698874 0.132505 -0.696751 -0.015659 -0.717142 -0.589303 0.046052 -0.806599 -0.626244 0.325746 0.708314 -0.613512 0.464302 0.63877 -0.598617 -0.00922358 -0.800982 -0.588904 0.0592 -0.806032 -0.305011 -0.927436 0.216406 -0.231969 -0.950995 0.204449 -0.5695 -0.0283716 -0.821502 0.392058 0.238104 0.888593 -0.566476 -0.016412 -0.823915 -0.306228 -0.94739 0.0931475 -0.317849 -0.948066 0.0119636 -0.563102 0.012718 -0.82629 -0.580281 -0.00728316 -0.814384 0.582961 0.00490484 0.812485 0.821825 -0.0118074 -0.569618 0.83954 -0.00500787 -0.543274 0.731842 0.018389 -0.681226 -0.0671832 0.962346 0.263394 0.688662 0.33901 -0.64095 0.0986295 -0.989402 0.106561 -0.705472 -0.0900123 0.702999 -0.0680502 0.965339 0.25197 0.0982685 -0.989479 0.106184 0.704227 0.00926212 -0.709914 0.744361 0.0176832 -0.667543 0.729707 0.0228485 -0.683378 0.764225 -0.111272 0.635279 0.714634 -0.162824 0.680284 0.940918 0.059987 -0.333279 -0.847278 0.0326781 0.530144 0.823772 -0.0191498 -0.566598 0.264029 -0.775889 -0.572962 -0.770837 0.624892 -0.123774 -0.918857 0.167161 0.357435 0.847883 -0.0212025 -0.529759 -0.846204 0.0203925 0.532469 -0.262323 0.95455 -0.141496 -0.0394055 -0.980686 -0.191581 0.832252 0.00306388 -0.55439 0.808842 -0.00400831 -0.588013 0.832837 -0.00717063 -0.553472 0.00200453 0.999991 0.00373843 0.500367 -0.0361575 -0.865058 0.54415 -0.4859 -0.68396 0.213828 -0.0324945 -0.976331 0.437104 -0.500056 -0.747585 0.437702 -0.499886 -0.747349 0.683984 -0.475196 -0.553493 -0.681548 -0.230083 0.694661 0.896645 -0.255127 0.361853 0.912578 -0.228501 0.3391 -0.912578 0.2285 -0.3391 -0.896645 0.255127 -0.361853 0.0366771 0.998088 0.049751 0.102542 -0.994305 -0.0290419 0.158847 -0.986658 -0.0356947 -0.0150575 -0.96336 -0.267789 -0.0154463 -0.967134 -0.253796 0.486753 0.873538 -0.00133777 0.720356 -0.692729 0.0348496 0.0529198 -0.995243 0.0817941 -0.20216 -0.977881 0.0536683 -0.0746408 -0.994785 -0.069509 0.0667214 0.972775 -0.221938 -0.274419 0.787728 0.551525 -0.110673 0.841996 0.52801 0.239306 0.368037 0.898488 0.840113 0.492212 0.227897 0.705423 0.645018 -0.293819 0.632157 -0.459324 -0.624018 0.589026 0.154129 -0.79328 0.242952 0.586469 -0.772676 -0.228234 -0.651437 -0.72356 -0.563966 0.54346 -0.621766 -0.823265 -0.511793 -0.245566 -0.843083 0.535105 0.0535978 -0.588565 -0.646196 0.485821 0.751651 -0.551394 -0.361919 0.850639 -0.421291 -0.314527 0.495017 -0.868793 -0.0125015 0.68623 -0.532867 0.495117 0.498079 0.654048 0.569332 -0.0582764 -0.646485 0.760698 -0.371548 0.774405 0.512103 -0.55503 -0.787733 0.267244 -0.542445 -0.821711 0.17477 -0.869073 0.458003 -0.186937 -0.676121 -0.382983 -0.629432 -0.474647 0.496493 -0.726777 0.0582654 -0.646496 -0.760689 0.375649 0.458038 -0.80566 0.921523 -0.0589133 -0.383828 0.968108 0.242577 -0.0626413 0.896996 -0.0864413 0.433504 0.785006 0.135474 0.604494 0.495056 -0.121342 0.860346 -0.188311 0.396725 0.898414 0.0642602 -0.0979245 0.993117 -0.596561 0.209598 0.774715 -0.820453 -0.25885 0.509757 -0.983548 0.169067 0.0636397 -0.872269 -0.182395 -0.453739 -0.789519 0.0838596 -0.60797 -0.114004 -0.0848444 -0.989851 -0.0645659 0.00503111 -0.997901 0.586744 0.176931 -0.790207 0.598055 0.197813 -0.77666 0.782383 -0.209594 -0.58647 0.992201 0.0979246 0.0771224 0.994317 -0.103459 -0.0251112 0.598015 -0.0770349 0.797774 0.460879 0.195981 0.865553 -0.0763747 -0.169065 0.982641 -0.520349 0.258849 0.813778 -0.782383 -0.209595 0.58647 -0.992201 0.0979241 -0.0771217 -0.992609 0.0949235 -0.0756088 -0.597686 -0.0838588 -0.797332 -0.442396 0.182395 -0.878076 0.0763821 -0.169063 -0.982641 0.520348 0.258849 -0.813778 0.831197 -0.385205 -0.400909 -0.514864 -0.743467 0.426816 -0.868321 0.404526 -0.287015 0.506747 0.739833 0.442555 0.754493 -0.63948 -0.147665 -0.082585 -0.900309 0.427345 -0.919055 -0.329192 -0.216727 0.0834082 0.960216 0.266512 0.174583 0.965602 0.192699 -0.430232 -0.708455 -0.559457 0.835424 -0.289984 0.46688 0.904937 -0.207274 0.371653 -0.154992 0.915941 -0.370175 -0.759277 0.260993 0.596138 -0.626296 0.4781 -0.615771 -0.193019 -0.920324 0.340217 0.116455 -0.992207 0.0443148 0.955651 0.282111 -0.084522 0.817215 0.523712 0.240592 -0.809515 0.372446 -0.45384 -0.803829 0.0401798 0.593502 0.103451 -0.925427 -0.364531 0.872488 0.123064 0.472884 -0.905 -0.331139 0.267064 -0.81576 -0.559727 -0.145744 0.737822 -0.630064 -0.242153 0.811844 -0.116823 -0.572068 0.510345 0.831615 0.219009 -0.0163524 0.978761 -0.204353 -0.00799629 0.990592 0.136616 0.00583839 0.98983 0.142138 -7.20579e-05 1 0.000178691 -0.00139711 0.999999 0.00056365 -1.26655e-08 1 3.14082e-08 0 1 0 0.000471666 1 0.000106341 0.00054726 0.999999 0.00102897 0.00026974 0.999991 0.0042074 -0.00152124 0.999965 0.0082877 0.00174044 0.999871 0.0159737 -0.00400755 0.999306 0.0370332 1.14569e-05 0.998889 0.0471321 0.0036794 0.995416 0.0955684 -0.00262327 0.99134 0.131292 1.90547e-05 -1 -0.000264625 -7.17133e-06 -1 -1.96864e-05 0.000344187 -0.999922 0.0124616 -0.000434715 -0.999994 0.00352368 0.00141115 -0.999998 0.00167034 -8.55725e-05 -1 0.000163114 -2.52261e-08 -1 -3.16525e-08 -1.02222e-05 -1 -1.28264e-05 1.41448e-05 -1 -4.45905e-06 0.999979 0 0.00647929 0.999979 0 0.00647929 6.96906e-05 1 -0.000102084 4.47745e-05 1 0.000182746 -0.000321468 1 -0.000574583 -5.3805e-08 1 8.30185e-06 -4.93287e-06 1 1.16515e-06 0.0126996 -0.974624 0.223489 -0.031388 -0.999471 0.00850287 -9.24452e-05 -1 -0.000190559 0 -1 0 0 -1 0 -5.98967e-08 -1 1.03269e-07 -0.99998 -0.000303485 -0.00633286 -0.999973 -0.00045276 -0.0073381 1.14171e-05 -1 -9.39474e-06 0.999966 4.30475e-06 0.00819794 0.999966 4.2713e-06 0.00819816 0.754473 -0.64165 0.138044 0.243601 -0.969192 0.036401 0.0976098 -0.992057 -0.0793375 -0.735194 -0.677247 -0.0287479 -0.812028 0.57951 0.0691287 -0.129392 0.984521 -0.118221 0.10877 0.990419 -0.0850898 0.871544 0.489854 0.0212979 0.770063 0.637948 0.0049905 0.965865 0.25897 0.00625826 0.998513 0.0437464 0.0325431 0.79153 0.611109 0.00500354 0.97274 0.231809 0.00644773 0.685493 -0.728065 0.00448176 0.659784 -0.751455 -0.000302458 0.703368 -0.710812 0.00442872 0.980571 -0.19606 0.00642933 0.976932 -0.213456 0.00632995 -0.87421 0.484679 -0.0290315 -0.999167 -0.000107126 0.0408117 0.941132 -0.00599732 0.337985 -0.703905 2.71888e-05 -0.710295 -0.987043 -0.0659867 0.146259 -0.591471 -0.794926 -0.135111 -0.833292 0.552588 -0.0164769 0.719845 -0.0155134 -0.693961 0.724107 0.00285401 -0.689682 0.719319 -0.00224056 -0.694676 0.706264 -5.53724e-06 -0.707948 0.758519 0.650727 0.0346763 0.518109 0.844125 -0.137902 0.859653 -0.510301 0.0242881 0.677705 -0.403504 -0.614736 0.56069 -0.5938 -0.577086 0.465026 -0.744261 -0.479402 0.171964 -0.969766 -0.173153 -0.168276 0.979479 -0.110925 -0.925614 -0.00885829 -0.378365 -0.565842 -0.539969 -0.623102 -0.393813 -0.824636 -0.406061 -0.16409 -0.984566 -0.0608623 -0.290687 -0.913376 -0.285035 -0.532888 0.598439 -0.598248 -0.667166 0.196741 -0.718458 -0.820211 0.569109 0.0580514 -0.687124 0.350617 -0.636339 -0.57635 0.574473 -0.581208 -0.361645 0.848554 -0.386223 -0.129513 0.984485 -0.118389 0.560196 0.592264 -0.579141 0.68324 0.381228 -0.622774 0.369306 0.82809 -0.421759 0.757236 -0.647692 -0.0841975 0.848185 -0.529699 -0.00069994 -0.244151 -0.968058 0.0570512 -0.785094 -0.590288 0.187585 -0.737634 -0.651304 0.178041 0.970786 -0.0765597 -0.227404 -0.945327 0.238245 0.222703 -0.693896 0.701339 0.163195 -0.681633 0.71396 0.160119 -0.280378 0.957659 0.0653996 0.0200941 0.999661 -0.0165861 0.0257112 -0.999618 0.0101122 0 1 0 -0.00226701 0.999997 0.000163603 0 1 0 -0.00919683 0.998442 -0.0550433 0.0728603 0.996171 0.0483148 -0.0477027 0.998715 -0.0171184 -0.00496386 0.998359 -0.0570441 0.709562 -0.198353 0.676149 0.969451 0.0283362 0.243642 0.97921 -0.181666 0.090254 0.935655 0.0486686 -0.349545 0.790087 -0.267065 -0.551759 0.567189 0.127247 -0.813698 0.0444125 -0.230194 -0.972131 -0.536329 0.106316 -0.837286 0.148206 0.986463 0.0701821 0.741974 0.0857196 0.664926 -0.999979 -7.49807e-06 -0.00647196 -0.999979 -4.00034e-06 -0.00646766 -0.999979 -1.05781e-05 -0.00644298 -0.999979 -1.28791e-05 -0.00646614 -0.998889 0.0467507 -0.0059651 -0.979635 0.00926379 -0.200575 -0.81 0.00440466 -0.586414 -0.7936 0.0878801 -0.602059 -0.930975 -0.156456 -0.329859 -0.931407 -0.218692 -0.290955 -0.800644 -0.0781794 -0.594018 -0.849517 0.135992 -0.509732 -0.818847 0.573972 -0.00675197 -0.97995 0.199173 -0.00537744 -0.187913 0.982185 -0.00120986 -0.999953 -0.00866645 -0.00442205 -0.156425 -0.987689 -0.0010074 -0.189038 -0.98197 -0.000517046 -0.553432 -0.832881 -0.0046253 0 -1 0 0 -1 0 0 -1 0 1.37343e-10 -1 -2.11979e-08 0.0341539 -0.998089 -0.0514977 -0.0600738 -0.996955 -0.0497273 3.60883e-09 -1 -4.04012e-08 -2.58106e-08 -1 -3.07613e-08 -0.0586508 -0.994605 0.0855642 0.0108806 -0.999672 -0.0231765 0.0558415 -0.993625 0.0979346 -0.00720075 -0.995035 0.099262 -0.0125575 -0.997899 0.0635617 -5.75948e-07 -1 -2.52861e-06 0 -1 0 0 -1 0 0.000262573 -1 -5.91044e-06 6.94417e-07 1 0.000118277 2.61073e-06 1 4.297e-06 -1.37343e-10 1 2.11979e-08 -8.1257e-06 1 -2.5691e-06 0.00021557 1 6.81569e-05 0.0270453 0.999559 0.0122994 -0.000105731 1 -1.28655e-05 1.8927e-08 1 3.11519e-08 -0.0413372 0.998645 0.0316096 -0.069144 0.992661 0.0992088 -0.0252357 0.96729 0.252415 2.58106e-08 1 3.07613e-08 1.47485e-08 1 3.4386e-08 -0.0816327 0.996354 -0.0248049 -0.097456 0.994934 -0.0246751 -0.0990585 0.994381 0.037339 0.000103722 1 0.000322633 0.000433346 1 -0.000167474 0.14102 -0.990006 0.000913785 0.135887 -0.990724 0.000868515 0.407091 0.913384 0.00263823 0.135959 0.990714 0.000881048 -0.754914 0.0113982 -0.655724 -0.755383 0.00330052 -0.655275 0 -1 0 0 -1 0 0.0270053 -0.998942 -0.0372214 0.022502 -0.998598 -0.0479223 -0.000869273 -0.999999 -0.000880606 -0.000718518 -0.999999 -0.000821472 0 -1 0 0.0482639 -0.998781 0.0103815 0.0396445 -0.997368 0.0607035 0.0215799 -0.999766 -0.00170095 0.0654762 -0.996897 -0.0437059 0.0720192 -0.997403 -0.0012193 -0.431531 0.131389 -0.892479 -0.497089 -0.0215615 -0.867432 0.073832 -0.0389368 -0.99651 0.209651 0.221164 -0.952435 0.73325 0.0717134 -0.676167 0.992204 -0.124294 -0.00908858 0.915246 0.155595 0.371637 0.749731 -0.0942442 0.654997 0.76974 0.0118871 0.638247 0.94899 0 -0.315307 0.949197 0.000506489 -0.314681 0.97362 0 -0.228174 0.97362 5.66676e-08 -0.228174 -0.755424 -0.00324315 -0.655228 -0.755307 -0.00130847 -0.655369 -0.97322 0 0.229877 -0.97322 0 0.229877 -0.97322 0 0.229877 -0.968401 0.0977641 0.229436 -0.97322 0 0.229876 -0.97322 -2.03433e-06 0.229875 -0.00587096 0.0034776 -0.999977 -0.00571266 -0.00463348 -0.999973 -0.00564321 -3.13407e-05 -0.999984 -0.00577642 -0.000177956 -0.999983 -0.00585591 0.00011542 -0.999983 -0.00580942 -0.000519519 -0.999983 -0.00561618 4.79324e-05 -0.999984 -0.00566302 -1.90377e-05 -0.999984 -0.00590099 0 -0.999983 0.961103 -0.00513555 -0.276142 0.96229 0 -0.272025 0.96229 6.75581e-08 -0.272025 0.988823 0.000812849 -0.149093 0.988276 0 -0.152676 0.979618 0 -0.200868 0.979618 0 -0.200868 0.931063 0.179192 -0.317822 0.514237 0.843403 -0.155669 0.533264 0.830815 -0.159298 0.896575 0.363203 -0.253449 0.934862 0.279347 -0.219086 0.448599 0.88874 -0.0943376 -0.990422 0.137908 -0.00680496 -0.147155 0.989113 -0.000145569 -0.164636 0.986354 -0.000497306 -0.983184 0.182512 -0.00617594 -0.983161 0.182741 -0.000514927 -0.185425 0.978556 0.0896946 -0.39443 0.908615 0.137276 -0.19077 0.973464 0.126388 -0.188985 0.981976 0.00291025 -0.189045 0.981888 0.0125558 -0.213424 0.976856 0.0142174 -0.324492 0.944934 0.042478 -0.309009 0.946895 0.0888959 -0.840406 0.541945 -0.00378562 -0.840434 0.541915 0.000429779 -0.864665 0.502331 -0.00413262 -0.888021 0.45584 0.0602389 -0.86582 0.496457 0.0623444 -0.854536 0.51937 -0.00467902 -0.553346 0.832746 0.0185095 -0.553268 0.832997 -0.00324706 -0.501218 0.865318 -0.00216789 -0.0703918 0.995665 -0.0608034 -0.00372213 0.999987 0.00350656 -0.11492 0.990919 -0.0698137 -0.834831 0.208146 -0.509639 -0.503694 0.83419 -0.224544 -0.235379 0.950417 -0.203234 -0.71537 0.334118 -0.613686 -0.610929 0.578335 -0.540642 0.157001 0.986931 0.0363129 0.135048 0.990833 -0.00355303 -0.100503 0.98861 -0.112021 0.759389 0.556278 -0.337466 -0.435426 0.648471 -0.624412 -0.373674 -0.926058 0.0527736 -0.255324 -0.966619 0.021385 -0.985866 -0.167516 -0.00249255 -0.938133 -0.346268 -0.00237925 -0.996683 -0.0777374 0.0240965 -0.981969 -0.188947 -0.00606114 -0.214376 -0.97639 0.0265747 -0.397808 -0.911865 0.101249 -0.330243 -0.932681 0.145072 -0.999768 0.0183601 -0.0112887 -0.446586 -0.889215 0.0992866 -0.27431 -0.961581 0.0107977 -0.229505 -0.973308 0.000136829 -0.156423 -0.987689 -0.00132623 -0.592096 -0.805868 -0.000172723 -0.464686 -0.879483 0.102841 -0.509458 -0.860492 -0.00252839 -0.682382 -0.730277 0.0323969 -0.843291 -0.533948 -0.0613169 -0.845156 -0.534493 -0.00535842 -0.859225 -0.511572 -0.0051258 -0.643528 -0.715751 -0.271241 -0.337663 -0.937603 -0.0829754 -0.575769 -0.624215 -0.528059 -0.625407 -0.568332 -0.534664 -0.652273 -0.504216 -0.565956 -0.255281 -0.940627 -0.223726 -0.125669 -0.986692 -0.103181 -0.475113 -0.614394 -0.629911 -0.367304 -0.324504 -0.871656 -0.0503611 -0.431761 -0.900581 0.580059 -0.581311 0.570622 0.734769 -0.131139 0.66552 0.215899 -0.974041 -0.0680607 0.441628 -0.883704 -0.155022 0.649673 -0.731361 -0.207451 0.93143 -0.191481 -0.309473 0.940165 -0.122876 -0.317791 0.337517 -0.939157 -0.0637736 0.942446 -0.250632 -0.221311 0.905689 -0.337903 -0.256025 0.476511 -0.872899 -0.10481 0.944203 -0.243962 -0.221276 0.774422 -0.632627 0.00733633 -0.0075722 0 0.999971 -0.184587 0.982816 -0.000489978 -0.00655059 0.000169391 0.999979 0.446353 0.893654 0.0463953 -0.00647894 0.000746539 0.999979 -0.00648094 0.00116144 0.999978 -0.00667553 -4.03221e-05 0.999978 -0.00676748 -9.6728e-05 0.999977 0.140922 -0.989915 0.0144311 0.446988 -0.894429 0.0140859 -0.00647894 -0.000746494 0.999979 -0.00648094 -0.00116136 0.999978 -0.00660602 -0.000388904 0.999978 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0.233589 0.88354 0.405949 0.430359 0.87837 0.207986 0 1 0 0 1 0 0.96078 -0.197442 -0.194729 0.937444 7.04163e-05 0.348136 0.937459 0.000144851 0.348095 -0.937469 -3.11505e-05 -0.348068 0.939063 -0.00634241 0.343687 0.999979 5.72899e-06 0.00647338 0.99998 0.000182304 0.00637355 -0.00248788 -0.991629 0.129093 0.000331037 -0.993828 0.110934 -0.00151523 -0.997551 0.0699215 -0.000205493 -0.999496 0.0317397 -0.00146187 -0.999601 0.0282016 0.00092852 -0.998276 0.0586855 -8.739e-05 -0.999909 0.0134979 0.00124873 -0.999909 0.0134236 -0.000170865 -0.997314 0.0732492 -0.000841686 -0.999563 -0.0295562 -0.0174059 0.995616 0.091898 -0.000278243 -0.987726 0.156199 0.0023843 -0.990803 0.135293 -0.00097369 -0.997832 0.0657994 -0.000467126 -0.995273 0.0971116 -0.00256007 -0.988959 0.14817 0.00198062 0.988456 0.151496 0.0003961 0.988708 0.149857 0.000386274 0.988704 0.149884 0.000118255 0.997008 0.0772994 -0.00192765 0.995665 0.0929917 -0.000879477 0.999752 0.0222365 0.0185233 0.999744 -0.0130273 0.00262642 0.999844 0.0174746 0.903261 -0.38934 -0.180373 0.811135 -0.582093 -0.0568136 0.297123 -0.954831 -0.00401686 0.936713 -0.349992 0.00866323 0.659552 -0.750631 0.0393117 0.659989 -0.751273 0.00155405 0.827092 -0.561978 0.00996248 0.919471 -0.393144 0.00314534 0.107396 -0.994104 0.0149696 0.12565 -0.991705 0.0270793 0.243172 -0.96996 0.00675165 0.33986 -0.93993 0.032056 0.199543 -0.96021 0.195394 0.924019 -0.162721 0.345991 0.160866 -0.968839 0.188344 0.32798 -0.925405 0.189879 0.857635 -0.359396 0.367827 0.250782 -0.955832 0.153274 0.310154 -0.916747 0.251753 0.932515 -0.0922724 0.349144 0.301161 -0.945695 0.12232 0.25862 -0.948059 0.185205 0.915323 -0.169144 0.365478 0.418534 -0.897734 0.137491 0.948622 -0.247138 -0.197582 0.560381 0.81855 -0.126293 0.933944 0.357293 0.00952097 0.673982 0.73872 0.00635745 0.998919 -0.0433604 -0.0167566 0.639225 0.769009 0.00415778 0.0260649 0.999554 0.0145603 0.378348 0.88848 0.259724 0.429765 0.863472 0.26404 0.872199 0.345473 0.346292 0.453032 0.875774 0.166679 0.477454 0.863096 0.16463 0.29054 0.948484 0.126353 0.576759 0.745985 0.332951 0.969275 -0.0387619 -0.242907 0.78966 -0.034209 0.61259 0.995214 9.14111e-06 0.0977202 0.99558 -0.0736469 0.0582821 0.45215 0.891203 0.0362977 0.999112 -0.00211003 -0.0420834 0 -1 0 0 -1 0 0 -1 0 -0.0112479 -0.999699 -0.0217936 -0.00155038 -0.999712 -0.0239619 -0.00229352 -0.999734 -0.0229721 -0.00851855 -0.999903 0.0110625 -0.0113871 -0.999887 0.00984149 0 -1 0 0 -1 0 0 -1 0 5.83119e-06 -0.999773 0.0212888 0.00136998 -0.999775 0.0211724 -0.00409542 -0.999612 0.0275385 0.348097 7.82358e-05 -0.937459 0.349389 -0.000106886 -0.936978 0.348123 -2.85614e-06 -0.937449 -0.937462 -5.85883e-06 -0.348088 -0.93746 0 -0.348093 -0.964241 0 -0.265027 -0.964241 0 -0.265027 -0.995609 0 -0.0936052 -0.995609 0 -0.0936052 -0.999979 0 -0.00648323 -0.999979 0 -0.00648323 -0.999978 -0.00625044 0.00218363 -0.998109 0 0.0614722 -0.98266 5.55863e-05 0.185419 0.00659793 -9.42003e-06 -0.999978 -0.0133311 -0.00173413 -0.99991 -0.0813596 0.0172483 -0.996536 0.00675177 0.000174269 -0.999977 0.00634548 2.00207e-06 -0.99998 0.00636136 5.32133e-06 -0.99998 0.00645562 -2.74485e-06 -0.999979 0.00652841 -3.768e-05 -0.999979 0.00645202 -7.97714e-06 -0.999979 0.00652189 1.29485e-05 -0.999979 0.00624658 0.000348923 -0.99998 0.00648166 -3.64068e-06 -0.999979 0.169257 -0.135472 -0.976217 0.00647587 -4.15098e-06 -0.999979 0.00645118 1.23893e-06 -0.999979 0.00646999 5.85125e-06 -0.999979 0.00646763 -6.06299e-06 -0.999979 0.00646863 -6.50096e-06 -0.999979 -0.203981 -0.156467 -0.96639 0.00646875 6.50801e-06 -0.999979 0.00644645 3.88403e-06 -0.999979 0.00596797 0.000251586 -0.999982 -0.0253116 0.9995 0.0189734 -0.0231124 0.999613 0.0155039 0 1 0 -0.00242053 0.999973 -0.00699808 -0.00334982 0.999984 -0.00446876 -0.0151164 0.999885 -0.00117497 -0.0219408 0.999759 -0.0004111 0 1 0 -0.000705508 0.999959 0.00907711 0.0118819 0.999804 0.0158509 0.00152461 0.999972 0.00727287 0 1 0 0 1 0 -0.0343056 -0.00121019 0.999411 -0.0224224 0 0.999749 -0.999062 0.0010371 0.0433004 -0.378861 -0.916152 -0.130884 -0.87835 -0.336539 -0.339473 -0.0356999 0.999351 -0.00487205 -0.827567 -0.513219 -0.227461 -0.847733 -0.524402 -0.0797021 -0.924588 -0.380968 -0.000498638 -0.999844 0.0164046 -0.00648235 -0.512028 -0.858899 -0.0109397 -0.701876 -0.702499 0.117755 -0.604806 -0.787002 0.121812 -0.267085 0.961761 0.0606756 -0.983108 -0.00128388 0.183024 -0.840372 0.518296 0.158571 -0.943651 0.252121 0.214376 -0.91832 0.391778 0.056558 -0.987894 0.155 -0.00640487 -0.947173 0.320714 -0.0025457 -0.594264 0.804249 -0.00578599 -0.21863 0.975808 -0.000397782 -0.160704 0.987002 -0.00104087 -0.729655 -0.618535 -0.291578 -0.864794 0.495501 -0.0813061 -0.828918 0.510869 -0.227833 -0.87732 0.335716 -0.342935 -0.193926 -0.976896 -0.0898111 0.0120673 -0.999718 0.0204536 0.0682422 0.996547 -0.0472911 -0.0976134 -0.995221 -0.00251887 0.999983 5.17376e-05 0.00584607 0.999982 -1.4646e-05 0.00598864 -0.99998 -0.000436159 -0.0062796 -0.00649383 -3.44627e-06 0.999979 -0.00635452 -4.46339e-05 0.99998 0.00360969 -0.00378806 0.999986 -0.155181 0.0484949 0.986695 0.00372887 0.00124944 0.999992 -0.00136897 -0.00236325 0.999996 -0.00648508 1.60645e-05 0.999979 -0.00649238 1.20502e-05 0.999979 -0.0102633 -0.00113096 0.999947 -0.00647361 2.14186e-05 0.999979 -0.00646667 4.46174e-06 0.999979 -0.0064958 6.97637e-06 0.999979 0.435491 0.602601 -0.668745 0.00081746 0.00121644 0.999999 0.021193 -0.00121067 0.999775 -0.513159 -0.220659 0.829444 -0.001702 0.010958 0.999939 -0.00653359 -1.68336e-05 0.999979 -0.00647645 -1.19561e-05 0.999979 -0.00616536 0.0380004 0.999259 -0.00457044 0.0581274 0.998299 -0.00674751 0.0108195 0.999919 -0.0166803 0.0136799 0.999767 -0.00364489 -0.0121683 0.999919 -0.0146595 0.0706506 0.997393 -0.00598108 0.000809751 0.999982 0.0195764 -0.0563139 -0.998221 -0.000234243 0.00425288 0.999991 0.0166416 0.0178922 0.999701 0.0668749 -0.025912 0.997425 -0.00150114 0.00176579 0.999997 -0.0118128 -0.00412449 0.999922 -0.00661857 -6.97872e-05 0.999978 -0.0149887 -0.00142752 0.999887 0.000108595 0.032355 0.999476 -0.00274306 -0.00122658 0.999996 0.0359911 0.00529605 0.999338 0.00327226 -0.00384285 0.999987 -0.0267924 0.00402436 0.999633 0.00816592 -0.296043 0.95514 -0.00928221 0.901687 0.43229 0.869398 0.207801 0.448292 -0.714902 -5.32575e-06 0.699224 -0.389093 0.0204635 -0.920971 0.87878 0 -0.477226 0.160243 -0.0128887 -0.986993 0.190349 -0.0369755 -0.98102 -0.00399884 -0.709274 0.704922 -0.0126663 -0.976468 0.21529 -0.125353 0.0478933 0.990956 -0.226622 0.0141285 0.97388 0.559525 0.781628 0.275662 -0.0104544 -0.28326 0.958986 -0.00461121 -0.705678 0.708518 -0.0185763 -0.00497225 0.999815 0.0329574 0.384967 -0.922342 0.00327779 -0.978646 0.205525 + + + + + + + + + + + + + + +

411 0 412 0 409 0 393 1 288 1 392 1 392 2 288 2 284 2 306 3 91 3 276 3 1 4 300 4 110 4 11 5 319 5 325 5 11 6 325 6 366 6 331 7 276 7 91 7 299 8 133 8 356 8 356 9 133 9 357 9 109 10 54 10 2 10 2 11 54 11 55 11 2 12 55 12 3 12 3 13 55 13 67 13 3 14 67 14 114 14 114 15 67 15 65 15 114 16 65 16 4 16 4 17 65 17 5 17 5 18 65 18 64 18 5 19 64 19 6 19 6 20 64 20 102 20 102 21 64 21 7 21 102 22 7 22 105 22 105 23 7 23 8 23 105 24 8 24 334 24 334 25 8 25 9 25 9 26 8 26 53 26 9 27 53 27 119 27 119 28 53 28 10 28 119 29 10 29 117 29 117 30 10 30 51 30 117 31 51 31 11 31 11 32 51 32 48 32 11 33 48 33 12 33 12 34 48 34 49 34 12 35 49 35 13 35 13 36 49 36 14 36 13 37 14 37 376 37 376 38 14 38 15 38 426 39 16 39 17 39 426 40 17 40 424 40 18 41 16 41 426 41 18 42 423 42 16 42 16 43 423 43 19 43 16 44 19 44 17 44 17 45 19 45 424 45 424 46 19 46 425 46 425 47 311 47 424 47 424 48 311 48 426 48 21 49 22 49 20 49 428 50 22 50 21 50 20 51 430 51 21 51 428 52 429 52 22 52 22 53 429 53 23 53 22 54 23 54 20 54 20 55 23 55 283 55 20 56 283 56 430 56 430 57 283 57 431 57 26 58 24 58 25 58 26 59 25 59 405 59 405 60 270 60 26 60 26 61 270 61 24 61 24 62 270 62 267 62 28 63 29 63 27 63 28 64 27 64 407 64 29 65 30 65 27 65 29 66 271 66 30 66 30 67 271 67 291 67 30 68 291 68 27 68 27 69 291 69 407 69 407 70 291 70 273 70 32 71 420 71 31 71 419 72 420 72 32 72 420 73 421 73 31 73 31 74 421 74 422 74 432 75 400 75 33 75 33 76 400 76 281 76 33 77 281 77 34 77 34 78 281 78 0 78 33 79 417 79 432 79 417 80 33 80 34 80 417 81 34 81 0 81 415 82 278 82 41 82 41 83 278 83 36 83 41 84 36 84 37 84 37 85 36 85 42 85 42 86 36 86 416 86 399 87 410 87 38 87 38 88 410 88 40 88 38 89 40 89 39 89 39 90 40 90 411 90 411 91 40 91 412 91 41 92 413 92 415 92 413 93 41 93 37 93 413 94 37 94 42 94 287 95 285 95 44 95 367 96 333 96 315 96 315 97 333 97 43 97 315 98 43 98 44 98 44 99 43 99 92 99 44 100 92 100 287 100 307 101 45 101 306 101 306 102 45 102 91 102 46 103 193 103 47 103 48 104 193 104 49 104 49 105 193 105 46 105 49 106 46 106 14 106 14 107 46 107 15 107 46 108 47 108 50 108 48 109 51 109 193 109 193 110 51 110 10 110 193 111 10 111 53 111 64 112 52 112 7 112 7 113 52 113 8 113 8 114 52 114 192 114 8 115 192 115 53 115 192 116 193 116 53 116 60 117 100 117 82 117 75 118 56 118 123 118 97 119 83 119 81 119 97 120 81 120 100 120 100 121 81 121 82 121 77 122 75 122 123 122 78 123 76 123 60 123 192 124 52 124 189 124 189 125 52 125 61 125 61 126 52 126 174 126 174 127 52 127 62 127 52 128 64 128 62 128 62 129 64 129 63 129 63 130 64 130 171 130 171 131 64 131 65 131 171 132 65 132 170 132 170 133 65 133 66 133 66 134 65 134 67 134 66 135 67 135 168 135 168 136 67 136 167 136 167 137 67 137 165 137 165 138 67 138 55 138 165 139 55 139 68 139 68 140 55 140 69 140 69 141 55 141 54 141 69 142 54 142 57 142 69 143 57 143 161 143 161 144 57 144 70 144 70 145 57 145 160 145 160 146 57 146 59 146 160 147 59 147 71 147 71 148 59 148 158 148 74 149 72 149 58 149 58 150 72 150 158 150 58 151 158 151 59 151 74 152 157 152 72 152 75 153 73 153 56 153 56 154 73 154 74 154 74 155 73 155 157 155 75 156 156 156 73 156 76 157 78 157 77 157 77 158 78 158 154 158 77 159 154 159 75 159 75 160 154 160 79 160 75 161 79 161 156 161 82 162 80 162 60 162 60 163 80 163 78 163 81 164 83 164 151 164 151 165 83 165 149 165 149 166 83 166 84 166 149 167 84 167 147 167 147 168 84 168 85 168 147 169 85 169 145 169 145 170 85 170 87 170 145 171 87 171 144 171 144 172 87 172 86 172 86 173 87 173 143 173 143 174 87 174 176 174 87 175 394 175 176 175 176 176 394 176 178 176 179 177 178 177 394 177 179 178 394 178 88 178 179 179 88 179 181 179 181 180 88 180 182 180 88 181 89 181 182 181 194 182 182 182 195 182 195 183 182 183 89 183 195 184 89 184 46 184 91 185 45 185 90 185 98 186 328 186 329 186 98 187 329 187 121 187 329 188 331 188 121 188 121 189 331 189 90 189 91 190 90 190 331 190 376 191 92 191 13 191 13 192 92 192 43 192 13 193 43 193 12 193 12 194 43 194 333 194 2 195 340 195 341 195 126 196 110 196 93 196 126 197 93 197 125 197 125 198 93 198 346 198 125 199 346 199 124 199 364 200 140 200 105 200 5 201 94 201 107 201 132 202 95 202 127 202 333 203 11 203 12 203 365 204 334 204 9 204 105 205 334 205 364 205 99 206 122 206 352 206 352 207 122 207 350 207 352 208 353 208 99 208 99 209 353 209 368 209 100 210 96 210 97 210 97 211 96 211 130 211 97 212 130 212 98 212 127 213 95 213 126 213 99 214 368 214 100 214 100 215 368 215 101 215 100 216 101 216 96 216 105 217 140 217 102 217 102 218 140 218 6 218 103 219 113 219 111 219 274 220 328 220 104 220 104 221 328 221 98 221 104 222 98 222 130 222 140 223 106 223 6 223 6 224 106 224 361 224 5 225 107 225 4 225 4 226 107 226 108 226 4 227 108 227 359 227 2 228 341 228 109 228 109 229 341 229 342 229 109 230 342 230 357 230 132 231 127 231 133 231 133 232 127 232 109 232 133 233 109 233 357 233 1 234 110 234 126 234 1 235 126 235 95 235 346 236 347 236 124 236 124 237 347 237 355 237 350 238 122 238 112 238 112 239 122 239 111 239 112 240 111 240 113 240 365 241 9 241 142 241 94 242 5 242 362 242 362 243 5 243 6 243 362 244 6 244 361 244 3 245 114 245 136 245 136 246 134 246 3 246 3 247 134 247 358 247 103 248 111 248 115 248 115 249 111 249 123 249 115 250 123 250 116 250 116 251 123 251 124 251 116 252 124 252 355 252 117 253 11 253 366 253 3 254 358 254 118 254 3 255 118 255 2 255 2 256 118 256 340 256 142 257 9 257 119 257 142 258 119 258 120 258 120 259 119 259 117 259 120 260 117 260 366 260 4 261 359 261 114 261 114 262 359 262 138 262 114 263 138 263 136 263 121 264 90 264 85 264 121 265 85 265 84 265 121 266 84 266 98 266 98 267 84 267 83 267 98 268 83 268 97 268 99 269 100 269 60 269 99 270 60 270 122 270 122 271 60 271 76 271 122 272 76 272 111 272 111 273 76 273 77 273 111 274 77 274 123 274 124 275 123 275 56 275 124 276 56 276 125 276 125 277 56 277 74 277 125 278 74 278 126 278 126 279 74 279 58 279 126 280 58 280 127 280 127 281 58 281 59 281 127 282 59 282 57 282 127 283 57 283 109 283 109 284 57 284 54 284 370 285 113 285 304 285 304 286 113 286 103 286 304 287 103 287 279 287 279 288 103 288 115 288 279 289 115 289 128 289 128 290 115 290 116 290 128 291 116 291 301 291 301 292 116 292 355 292 274 293 104 293 129 293 129 294 104 294 130 294 129 295 130 295 277 295 277 296 130 296 96 296 277 297 96 297 131 297 131 298 96 298 101 298 131 299 101 299 369 299 369 300 101 300 368 300 300 301 1 301 280 301 280 302 1 302 95 302 280 303 95 303 298 303 298 304 95 304 132 304 298 305 132 305 299 305 299 306 132 306 133 306 296 307 358 307 294 307 294 308 358 308 134 308 294 309 134 309 135 309 135 310 134 310 136 310 135 311 136 311 137 311 137 312 136 312 138 312 137 313 138 313 293 313 293 314 138 314 359 314 371 315 312 315 141 315 364 316 363 316 140 316 140 317 363 317 139 317 140 318 139 318 371 318 140 319 371 319 106 319 360 320 361 320 141 320 141 321 361 321 106 321 141 322 106 322 371 322 323 323 365 323 317 323 317 324 365 324 142 324 317 325 142 325 324 325 324 326 142 326 120 326 324 327 120 327 325 327 325 328 120 328 366 328 289 329 241 329 269 329 269 330 241 330 242 330 212 331 86 331 143 331 212 332 143 332 210 332 210 333 143 333 176 333 86 334 212 334 213 334 86 335 213 335 144 335 144 336 213 336 145 336 145 337 213 337 214 337 145 338 214 338 146 338 145 339 146 339 147 339 147 340 146 340 149 340 149 341 146 341 148 341 216 342 151 342 148 342 148 343 151 343 149 343 150 344 81 344 216 344 216 345 81 345 151 345 152 346 81 346 150 346 218 347 82 347 81 347 218 348 81 348 152 348 82 349 218 349 80 349 80 350 218 350 219 350 80 351 219 351 220 351 80 352 220 352 78 352 78 353 220 353 153 353 78 354 153 354 154 354 154 355 153 355 221 355 154 356 221 356 79 356 79 357 221 357 155 357 79 358 155 358 156 358 156 359 155 359 225 359 156 360 225 360 73 360 73 361 225 361 227 361 73 362 227 362 157 362 157 363 227 363 226 363 157 364 226 364 72 364 226 365 158 365 72 365 158 366 226 366 159 366 158 367 159 367 71 367 71 368 159 368 160 368 159 369 162 369 160 369 160 370 162 370 70 370 70 371 162 371 161 371 161 372 162 372 163 372 161 373 163 373 69 373 163 374 164 374 69 374 69 375 164 375 68 375 164 376 229 376 68 376 68 377 229 377 165 377 165 378 229 378 166 378 165 379 166 379 167 379 167 380 166 380 168 380 168 381 166 381 169 381 168 382 169 382 66 382 66 383 169 383 230 383 66 384 230 384 170 384 170 385 230 385 231 385 170 386 231 386 172 386 170 387 172 387 171 387 173 388 62 388 233 388 233 389 62 389 63 389 171 390 172 390 63 390 63 391 172 391 233 391 62 392 173 392 174 392 174 393 173 393 175 393 174 394 175 394 61 394 239 395 189 395 237 395 237 396 189 396 235 396 235 397 189 397 61 397 235 398 61 398 175 398 210 399 176 399 177 399 177 400 176 400 178 400 177 401 178 401 209 401 209 402 178 402 179 402 209 403 179 403 208 403 208 404 179 404 180 404 180 405 179 405 181 405 180 406 181 406 183 406 181 407 182 407 183 407 183 408 182 408 194 408 183 409 194 409 205 409 289 410 326 410 184 410 241 411 289 411 184 411 241 412 184 412 185 412 241 413 185 413 186 413 186 414 185 414 240 414 240 415 185 415 190 415 240 416 190 416 187 416 191 417 187 417 190 417 188 418 238 418 191 418 191 419 238 419 187 419 189 420 239 420 188 420 188 421 239 421 238 421 192 422 185 422 193 422 193 423 185 423 184 423 190 424 185 424 192 424 190 425 192 425 191 425 191 426 192 426 188 426 188 427 192 427 189 427 47 428 193 428 196 428 196 429 193 429 184 429 46 430 50 430 195 430 47 431 196 431 197 431 47 432 197 432 50 432 50 433 197 433 198 433 50 434 198 434 199 434 50 435 199 435 194 435 50 436 194 436 195 436 320 437 197 437 196 437 320 438 196 438 266 438 205 439 194 439 204 439 204 440 194 440 199 440 197 441 200 441 198 441 198 442 200 442 203 442 198 443 203 443 199 443 199 444 203 444 204 444 197 445 320 445 200 445 200 446 320 446 201 446 200 447 201 447 242 447 242 448 201 448 269 448 242 449 247 449 202 449 242 450 202 450 200 450 200 451 202 451 206 451 200 452 206 452 203 452 203 453 206 453 204 453 204 454 206 454 205 454 205 455 206 455 250 455 205 456 250 456 183 456 183 457 250 457 180 457 180 458 250 458 207 458 180 459 207 459 208 459 208 460 207 460 209 460 209 461 207 461 211 461 209 462 211 462 177 462 177 463 211 463 210 463 210 464 211 464 258 464 210 465 258 465 212 465 212 466 258 466 213 466 213 467 258 467 214 467 214 468 258 468 215 468 214 469 215 469 146 469 146 470 215 470 256 470 146 471 256 471 148 471 148 472 256 472 216 472 216 473 256 473 253 473 216 474 253 474 150 474 150 475 253 475 152 475 152 476 253 476 255 476 152 477 255 477 218 477 218 478 255 478 217 478 218 479 217 479 254 479 218 480 254 480 219 480 219 481 254 481 220 481 220 482 254 482 259 482 220 483 259 483 153 483 153 484 259 484 243 484 153 485 243 485 221 485 221 486 243 486 222 486 221 487 222 487 155 487 155 488 222 488 223 488 155 489 223 489 225 489 225 490 223 490 224 490 224 491 227 491 225 491 249 492 226 492 224 492 224 493 226 493 227 493 228 494 159 494 249 494 249 495 159 495 226 495 228 496 162 496 159 496 245 497 163 497 228 497 228 498 163 498 162 498 244 499 164 499 245 499 245 500 164 500 163 500 244 501 229 501 164 501 252 502 169 502 166 502 252 503 166 503 244 503 244 504 166 504 229 504 169 505 252 505 230 505 230 506 252 506 251 506 230 507 251 507 231 507 231 508 251 508 172 508 172 509 251 509 232 509 172 510 232 510 233 510 233 511 232 511 173 511 173 512 232 512 234 512 173 513 234 513 175 513 175 514 234 514 235 514 235 515 234 515 236 515 235 516 236 516 237 516 237 517 236 517 246 517 237 518 246 518 239 518 246 519 238 519 239 519 238 520 246 520 187 520 187 521 246 521 240 521 240 522 246 522 186 522 186 523 246 523 247 523 186 524 247 524 241 524 241 525 247 525 242 525 246 526 264 526 247 526 222 527 243 527 248 527 207 528 250 528 257 528 261 529 247 529 264 529 257 530 250 530 261 530 252 531 244 531 248 531 232 532 251 532 248 532 222 533 248 533 223 533 228 534 248 534 245 534 245 535 248 535 244 535 262 536 234 536 248 536 248 537 234 537 232 537 264 538 246 538 262 538 262 539 246 539 236 539 262 540 236 540 234 540 247 541 261 541 202 541 248 542 228 542 249 542 261 543 250 543 206 543 261 544 206 544 202 544 257 545 258 545 211 545 257 546 211 546 207 546 223 547 248 547 224 547 248 548 251 548 252 548 253 549 256 549 248 549 248 550 256 550 257 550 248 551 254 551 217 551 248 552 217 552 255 552 248 553 255 553 253 553 248 554 249 554 224 554 256 555 215 555 257 555 257 556 215 556 258 556 243 557 259 557 248 557 248 558 259 558 254 558 264 559 260 559 261 559 261 560 260 560 265 560 261 561 265 561 257 561 257 562 265 562 248 562 248 563 265 563 263 563 262 564 248 564 263 564 262 565 263 565 264 565 264 566 263 566 260 566 265 567 260 567 263 567 196 568 184 568 266 568 266 569 184 569 326 569 267 570 429 570 404 570 404 571 429 571 427 571 404 572 427 572 310 572 269 573 267 573 270 573 269 574 270 574 327 574 327 575 270 575 314 575 314 576 270 576 268 576 272 577 406 577 271 577 271 578 406 578 398 578 273 579 313 579 314 579 268 580 310 580 403 580 268 581 403 581 314 581 314 582 403 582 273 582 310 583 406 583 403 583 408 584 311 584 410 584 410 585 311 585 425 585 410 586 425 586 306 586 410 587 274 587 40 587 276 588 275 588 332 588 332 589 330 589 276 589 276 590 330 590 274 590 276 591 274 591 306 591 306 592 274 592 410 592 274 593 129 593 40 593 40 594 129 594 277 594 412 595 40 595 277 595 408 596 412 596 278 596 401 597 416 597 400 597 418 598 408 598 414 598 414 599 401 599 418 599 418 600 401 600 400 600 408 601 278 601 414 601 36 602 304 602 279 602 279 603 128 603 36 603 36 604 128 604 301 604 36 605 301 605 416 605 356 606 35 606 281 606 298 607 281 607 280 607 280 608 281 608 300 608 293 609 398 609 295 609 35 610 282 610 402 610 356 611 282 611 35 611 418 612 35 612 402 612 379 613 19 613 381 613 381 614 19 614 423 614 381 615 423 615 382 615 382 616 423 616 288 616 311 617 427 617 423 617 429 618 267 618 269 618 431 619 283 619 284 619 284 620 283 620 287 620 23 621 285 621 283 621 283 622 285 622 287 622 386 623 384 623 286 623 286 624 384 624 284 624 286 625 284 625 377 625 377 626 284 626 287 626 285 627 23 627 429 627 285 628 429 628 375 628 431 629 284 629 288 629 427 630 431 630 423 630 423 631 431 631 288 631 289 632 269 632 327 632 269 633 201 633 290 633 269 634 290 634 429 634 429 635 290 635 375 635 271 636 360 636 141 636 271 637 141 637 291 637 291 638 141 638 312 638 291 639 312 639 273 639 273 640 312 640 313 640 338 641 337 641 336 641 336 642 292 642 338 642 338 643 292 643 360 643 338 644 360 644 271 644 338 645 271 645 293 645 293 646 271 646 398 646 282 647 296 647 294 647 282 648 294 648 295 648 295 649 294 649 135 649 295 650 135 650 137 650 295 651 137 651 293 651 282 652 339 652 296 652 297 653 339 653 343 653 343 654 339 654 282 654 343 655 282 655 344 655 344 656 282 656 356 656 298 657 299 657 281 657 281 658 299 658 356 658 281 659 400 659 300 659 400 660 416 660 301 660 400 661 301 661 300 661 300 662 301 662 348 662 300 663 348 663 345 663 348 664 302 664 303 664 348 665 303 665 345 665 36 666 278 666 304 666 304 667 278 667 370 667 349 668 370 668 351 668 351 669 370 669 278 669 351 670 278 670 305 670 305 671 278 671 354 671 278 672 369 672 354 672 277 673 131 673 412 673 412 674 131 674 369 674 412 675 369 675 278 675 306 676 425 676 19 676 306 677 19 677 307 677 307 678 19 678 379 678 307 679 379 679 309 679 389 680 388 680 308 680 308 681 388 681 309 681 308 682 309 682 378 682 378 683 309 683 379 683 310 684 427 684 406 684 427 685 311 685 406 685 406 686 311 686 408 686 406 687 408 687 402 687 402 688 408 688 418 688 321 689 316 689 375 689 375 690 316 690 285 690 371 691 322 691 312 691 312 692 322 692 313 692 313 693 322 693 314 693 314 694 322 694 372 694 315 695 44 695 316 695 363 696 322 696 139 696 139 697 322 697 371 697 373 698 372 698 318 698 318 699 372 699 335 699 323 700 317 700 326 700 323 701 326 701 318 701 318 702 326 702 373 702 326 703 325 703 266 703 266 704 325 704 320 704 320 705 325 705 319 705 367 706 321 706 319 706 319 707 321 707 374 707 319 708 374 708 320 708 316 709 321 709 315 709 315 710 321 710 367 710 322 711 363 711 335 711 322 712 335 712 372 712 317 713 324 713 326 713 326 714 324 714 325 714 372 715 373 715 314 715 314 716 373 716 327 716 374 717 321 717 290 717 290 718 321 718 375 718 373 719 326 719 327 719 327 720 326 720 289 720 290 721 201 721 374 721 374 722 201 722 320 722 328 723 274 723 330 723 328 724 330 724 329 724 329 725 330 725 332 725 329 726 332 726 331 726 331 727 332 727 275 727 331 728 275 728 276 728 333 729 367 729 11 729 11 730 367 730 319 730 365 731 323 731 334 731 334 732 323 732 318 732 334 733 318 733 335 733 334 734 335 734 364 734 364 735 335 735 363 735 362 736 360 736 292 736 362 737 292 737 94 737 94 738 292 738 336 738 94 739 336 739 107 739 107 740 336 740 337 740 107 741 337 741 108 741 108 742 337 742 338 742 108 743 338 743 359 743 118 744 339 744 340 744 340 745 339 745 297 745 340 746 297 746 341 746 341 747 297 747 343 747 341 748 343 748 342 748 342 749 343 749 344 749 342 750 344 750 357 750 357 751 344 751 356 751 110 752 300 752 345 752 110 753 345 753 93 753 93 754 345 754 303 754 93 755 303 755 346 755 346 756 303 756 302 756 346 757 302 757 347 757 347 758 302 758 348 758 347 759 348 759 355 759 112 760 370 760 349 760 112 761 349 761 350 761 350 762 349 762 351 762 350 763 351 763 352 763 352 764 351 764 305 764 352 765 305 765 353 765 353 766 305 766 354 766 353 767 354 767 368 767 301 768 355 768 348 768 358 769 296 769 339 769 358 770 339 770 118 770 293 771 359 771 338 771 361 772 360 772 362 772 369 773 368 773 354 773 113 774 370 774 112 774 285 775 316 775 44 775 287 776 92 776 377 776 377 777 92 777 376 777 377 778 376 778 15 778 397 779 378 779 395 779 395 780 378 780 379 780 395 781 379 781 380 781 380 782 379 782 381 782 288 783 393 783 383 783 288 784 383 784 382 784 382 785 383 785 381 785 381 786 383 786 380 786 45 787 307 787 90 787 90 788 307 788 309 788 85 789 90 789 396 789 396 790 90 790 309 790 392 791 284 791 385 791 385 792 284 792 384 792 386 793 387 793 384 793 384 794 387 794 385 794 286 795 387 795 386 795 15 796 391 796 377 796 377 797 391 797 286 797 286 798 391 798 387 798 388 799 389 799 390 799 388 800 390 800 396 800 388 801 396 801 309 801 308 802 378 802 397 802 308 803 397 803 390 803 308 804 390 804 389 804 46 805 391 805 15 805 89 806 387 806 46 806 46 807 387 807 391 807 89 808 392 808 385 808 89 809 385 809 387 809 392 810 89 810 88 810 392 811 88 811 393 811 393 812 88 812 383 812 383 813 88 813 394 813 383 814 394 814 380 814 380 815 394 815 395 815 87 816 397 816 395 816 87 817 395 817 394 817 87 818 396 818 390 818 87 819 390 819 397 819 87 820 85 820 396 820 422 821 282 821 31 821 31 822 282 822 295 822 31 823 295 823 32 823 32 824 295 824 419 824 419 825 295 825 398 825 409 826 38 826 39 826 411 827 409 827 39 827 399 828 38 828 409 828 408 829 410 829 409 829 409 830 410 830 399 830 408 831 409 831 412 831 414 832 278 832 413 832 413 833 278 833 415 833 418 834 400 834 417 834 417 835 400 835 432 835 413 836 42 836 401 836 401 837 42 837 416 837 402 838 282 838 421 838 421 839 282 839 422 839 417 840 0 840 418 840 418 841 0 841 35 841 272 842 271 842 28 842 28 843 271 843 29 843 398 844 406 844 419 844 419 845 406 845 420 845 28 846 407 846 403 846 403 847 407 847 273 847 310 848 268 848 25 848 25 849 268 849 405 849 25 850 24 850 404 850 404 851 24 851 267 851 427 852 429 852 21 852 21 853 429 853 428 853 21 854 430 854 427 854 427 855 430 855 431 855 18 856 426 856 423 856 423 857 426 857 311 857 25 858 404 858 310 858 405 859 268 859 270 859 28 860 403 860 406 860 28 861 406 861 272 861 413 862 401 862 414 862 0 863 281 863 35 863 420 864 406 864 402 864 420 865 402 865 421 865 815 866 438 866 814 866 761 867 887 867 439 867 761 868 439 868 759 868 759 869 439 869 774 869 1094 870 741 870 1063 870 1063 871 741 871 1062 871 444 872 606 872 443 872 444 873 443 873 445 873 445 874 443 874 446 874 445 875 446 875 623 875 623 876 446 876 447 876 623 877 447 877 622 877 622 878 447 878 448 878 622 879 448 879 610 879 622 880 610 880 449 880 449 881 610 881 609 881 449 882 609 882 1047 882 449 883 1047 883 631 883 450 884 638 884 1031 884 638 885 450 885 1031 885 818 886 1030 886 516 886 516 887 1030 887 452 887 516 888 452 888 519 888 519 889 452 889 451 889 451 890 452 890 1029 890 1006 891 1005 891 453 891 453 892 1005 892 909 892 453 893 909 893 1003 893 1003 894 909 894 1004 894 1006 895 453 895 1003 895 1000 896 1002 896 999 896 999 897 1002 897 912 897 999 898 912 898 911 898 999 899 911 899 1001 899 998 900 916 900 543 900 544 901 543 901 915 901 915 902 543 902 916 902 913 903 918 903 995 903 455 904 995 904 454 904 913 905 995 905 455 905 582 906 953 906 890 906 458 907 947 907 718 907 716 908 559 908 460 908 716 909 460 909 715 909 715 910 460 910 557 910 925 911 559 911 717 911 559 912 724 912 717 912 928 913 463 913 712 913 927 914 923 914 696 914 518 915 709 915 464 915 465 916 926 916 704 916 732 917 701 917 472 917 466 918 862 918 861 918 1085 919 765 919 902 919 488 920 877 920 901 920 469 921 864 921 763 921 469 922 763 922 864 922 900 923 868 923 865 923 893 924 590 924 592 924 741 925 1094 925 1062 925 591 926 590 926 893 926 473 927 474 927 597 927 860 928 883 928 884 928 475 929 898 929 476 929 857 930 594 930 1067 930 856 931 788 931 478 931 856 932 478 932 829 932 829 933 478 933 787 933 829 934 787 934 828 934 828 935 787 935 785 935 828 936 785 936 479 936 479 937 785 937 783 937 479 938 783 938 846 938 846 939 783 939 480 939 846 940 480 940 844 940 844 941 480 941 481 941 482 942 481 942 483 942 482 943 483 943 849 943 440 944 873 944 773 944 879 945 768 945 442 945 879 946 442 946 468 946 468 947 442 947 1084 947 487 948 892 948 488 948 488 949 892 949 489 949 773 950 490 950 440 950 440 951 887 951 491 951 873 952 491 952 492 952 873 953 492 953 875 953 875 954 492 954 772 954 772 955 493 955 766 955 766 956 493 956 1087 956 494 957 501 957 495 957 494 958 495 958 771 958 771 959 495 959 827 959 771 960 827 960 496 960 496 961 827 961 503 961 869 962 504 962 870 962 870 963 504 963 847 963 870 964 847 964 497 964 497 965 847 965 498 965 497 966 498 966 1075 966 770 967 508 967 865 967 865 968 508 968 499 968 865 969 499 969 867 969 867 970 499 970 843 970 1087 971 493 971 500 971 1087 972 500 972 502 972 502 973 500 973 501 973 502 974 501 974 494 974 502 975 494 975 872 975 503 976 827 976 848 976 503 977 848 977 505 977 505 978 848 978 504 978 505 979 504 979 869 979 1075 980 498 980 506 980 506 981 498 981 845 981 506 982 845 982 1076 982 1076 983 845 983 508 983 1076 984 508 984 507 984 507 985 508 985 770 985 1064 986 867 986 843 986 1064 987 843 987 842 987 1064 988 842 988 1065 988 1065 989 842 989 841 989 890 990 1095 990 814 990 890 991 814 991 882 991 882 992 814 992 438 992 882 993 438 993 583 993 583 994 438 994 815 994 583 995 815 995 509 995 509 996 815 996 437 996 509 997 437 997 584 997 584 998 437 998 586 998 586 999 437 999 816 999 586 1000 816 1000 587 1000 587 1001 816 1001 436 1001 587 1002 436 1002 510 1002 587 1003 510 1003 511 1003 511 1004 510 1004 512 1004 511 1005 512 1005 588 1005 588 1006 512 1006 817 1006 588 1007 817 1007 513 1007 513 1008 817 1008 435 1008 513 1009 435 1009 589 1009 589 1010 435 1010 825 1010 589 1011 825 1011 592 1011 592 1012 825 1012 824 1012 592 1013 824 1013 1141 1013 1141 1014 824 1014 434 1014 1141 1015 434 1015 891 1015 891 1016 434 1016 595 1016 595 1017 434 1017 514 1017 595 1018 514 1018 823 1018 595 1019 823 1019 470 1019 470 1020 823 1020 821 1020 470 1021 821 1021 515 1021 515 1022 821 1022 433 1022 515 1023 433 1023 894 1023 894 1024 433 1024 803 1024 894 1025 803 1025 897 1025 826 1026 818 1026 516 1026 707 1027 709 1027 518 1027 451 1028 517 1028 530 1028 530 1029 517 1029 818 1029 519 1030 451 1030 518 1030 708 1031 516 1031 520 1031 520 1032 516 1032 519 1032 520 1033 519 1033 518 1033 802 1034 904 1034 732 1034 523 1035 465 1035 822 1035 822 1036 465 1036 943 1036 521 1037 522 1037 523 1037 523 1038 522 1038 465 1038 524 1039 927 1039 525 1039 927 1040 533 1040 525 1040 712 1041 813 1041 928 1041 928 1042 813 1042 812 1042 927 1043 524 1043 526 1043 927 1044 526 1044 527 1044 527 1045 526 1045 528 1045 527 1046 528 1046 711 1046 711 1047 528 1047 813 1047 711 1048 813 1048 529 1048 529 1049 813 1049 712 1049 518 1050 451 1050 530 1050 518 1051 530 1051 707 1051 707 1052 530 1052 531 1052 707 1053 531 1053 532 1053 707 1054 532 1054 710 1054 710 1055 532 1055 525 1055 710 1056 525 1056 533 1056 706 1057 522 1057 521 1057 706 1058 521 1058 534 1058 706 1059 534 1059 700 1059 700 1060 534 1060 826 1060 700 1061 826 1061 708 1061 708 1062 826 1062 516 1062 904 1063 802 1063 819 1063 904 1064 819 1064 535 1064 535 1065 819 1065 820 1065 535 1066 820 1066 536 1066 536 1067 820 1067 822 1067 536 1068 822 1068 537 1068 537 1069 822 1069 943 1069 542 1070 601 1070 576 1070 538 1071 574 1071 602 1071 602 1072 574 1072 573 1072 572 1073 540 1073 611 1073 572 1074 611 1074 573 1074 543 1075 544 1075 561 1075 714 1076 543 1076 561 1076 995 1077 544 1077 998 1077 995 1078 998 1078 454 1078 544 1079 995 1079 545 1079 545 1080 995 1080 996 1080 545 1081 996 1081 625 1081 625 1082 996 1082 454 1082 625 1083 454 1083 1037 1083 454 1084 998 1084 1037 1084 1037 1085 998 1085 714 1085 714 1086 998 1086 543 1086 714 1087 462 1087 945 1087 714 1088 945 1088 1037 1088 462 1089 714 1089 718 1089 462 1090 718 1090 947 1090 947 1091 458 1091 548 1091 720 1092 964 1092 546 1092 720 1093 547 1093 548 1093 720 1094 548 1094 458 1094 546 1095 547 1095 720 1095 964 1096 720 1096 549 1096 720 1097 461 1097 549 1097 549 1098 461 1098 550 1098 461 1099 457 1099 550 1099 550 1100 457 1100 551 1100 456 1101 551 1101 702 1101 702 1102 551 1102 457 1102 745 1103 562 1103 552 1103 745 1104 552 1104 744 1104 744 1105 552 1105 553 1105 744 1106 553 1106 554 1106 553 1107 688 1107 554 1107 554 1108 688 1108 680 1108 554 1109 680 1109 961 1109 680 1110 556 1110 967 1110 680 1111 967 1111 961 1111 961 1112 967 1112 960 1112 681 1113 950 1113 555 1113 555 1114 950 1114 556 1114 555 1115 556 1115 680 1115 456 1116 701 1116 687 1116 713 1117 557 1117 619 1117 619 1118 557 1118 620 1118 620 1119 557 1119 460 1119 620 1120 460 1120 621 1120 621 1121 460 1121 558 1121 460 1122 559 1122 558 1122 558 1123 559 1123 560 1123 560 1124 559 1124 459 1124 560 1125 459 1125 624 1125 624 1126 459 1126 561 1126 624 1127 561 1127 545 1127 545 1128 561 1128 544 1128 456 1129 687 1129 562 1129 456 1130 562 1130 745 1130 456 1131 745 1131 551 1131 651 1132 676 1132 563 1132 651 1133 563 1133 654 1133 654 1134 563 1134 674 1134 654 1135 674 1135 564 1135 564 1136 674 1136 673 1136 564 1137 673 1137 565 1137 565 1138 673 1138 656 1138 656 1139 672 1139 657 1139 657 1140 672 1140 574 1140 657 1141 574 1141 658 1141 658 1142 574 1142 575 1142 658 1143 575 1143 659 1143 659 1144 575 1144 671 1144 659 1145 671 1145 662 1145 661 1146 648 1146 660 1146 660 1147 648 1147 640 1147 660 1148 640 1148 486 1148 486 1149 640 1149 641 1149 486 1150 641 1150 485 1150 485 1151 641 1151 642 1151 485 1152 642 1152 655 1152 655 1153 642 1153 569 1153 655 1154 569 1154 484 1154 484 1155 569 1155 568 1155 484 1156 568 1156 653 1156 653 1157 568 1157 644 1157 653 1158 644 1158 652 1158 652 1159 644 1159 645 1159 652 1160 645 1160 646 1160 566 1161 646 1161 645 1161 566 1162 645 1162 786 1162 786 1163 645 1163 644 1163 786 1164 644 1164 643 1164 786 1165 643 1165 784 1165 784 1166 643 1166 568 1166 784 1167 568 1167 567 1167 567 1168 568 1168 569 1168 567 1169 569 1169 642 1169 567 1170 642 1170 782 1170 782 1171 642 1171 570 1171 570 1172 642 1172 641 1172 570 1173 641 1173 781 1173 781 1174 641 1174 640 1174 781 1175 640 1175 571 1175 781 1176 571 1176 780 1176 780 1177 571 1177 648 1177 675 1178 608 1178 539 1178 675 1179 539 1179 572 1179 572 1180 539 1180 540 1180 574 1181 538 1181 575 1181 575 1182 538 1182 576 1182 575 1183 576 1183 601 1183 1091 1184 577 1184 917 1184 917 1185 577 1185 959 1185 1090 1186 969 1186 1092 1186 1092 1187 969 1187 970 1187 946 1188 577 1188 1091 1188 946 1189 1091 1189 1010 1189 1012 1190 577 1190 946 1190 905 1191 1019 1191 578 1191 905 1192 578 1192 1017 1192 1017 1193 578 1193 1015 1193 577 1194 1012 1194 1014 1194 577 1195 1014 1195 578 1195 578 1196 1014 1196 1015 1196 1011 1197 966 1197 971 1197 971 1198 1016 1198 1013 1198 971 1199 1013 1199 1011 1199 966 1200 1009 1200 971 1200 971 1201 1009 1201 970 1201 970 1202 1009 1202 948 1202 962 1203 1011 1203 1013 1203 1092 1204 970 1204 948 1204 614 1205 914 1205 615 1205 1062 1206 741 1206 579 1206 885 1207 580 1207 581 1207 883 1208 742 1208 884 1208 884 1209 742 1209 958 1209 582 1210 958 1210 956 1210 956 1211 958 1211 734 1211 956 1212 734 1212 736 1212 955 1213 951 1213 582 1213 582 1214 956 1214 955 1214 476 1215 882 1215 898 1215 898 1216 890 1216 476 1216 476 1217 890 1217 882 1217 583 1218 509 1218 584 1218 585 1219 586 1219 477 1219 477 1220 586 1220 587 1220 896 1221 587 1221 511 1221 896 1222 511 1222 588 1222 590 1223 589 1223 592 1223 1093 1224 513 1224 589 1224 1093 1225 589 1225 590 1225 591 1226 513 1226 1093 1226 592 1227 1141 1227 891 1227 471 1228 595 1228 859 1228 470 1229 471 1229 858 1229 858 1230 859 1230 470 1230 470 1231 859 1231 595 1231 897 1232 593 1232 594 1232 1067 1233 594 1233 593 1233 593 1234 738 1234 739 1234 474 1235 598 1235 597 1235 474 1236 880 1236 598 1236 597 1237 880 1237 474 1237 608 1238 675 1238 599 1238 699 1239 599 1239 679 1239 699 1240 679 1240 600 1240 1025 1241 600 1241 668 1241 1025 1242 668 1242 1059 1242 541 1243 668 1243 601 1243 541 1244 601 1244 542 1244 602 1245 1032 1245 538 1245 538 1246 1032 1246 1049 1246 538 1247 1049 1247 603 1247 538 1248 603 1248 576 1248 576 1249 603 1249 604 1249 576 1250 604 1250 605 1250 576 1251 605 1251 542 1251 1039 1252 668 1252 541 1252 605 1253 1054 1253 542 1253 542 1254 1054 1254 1053 1254 542 1255 1053 1255 1052 1255 542 1256 1052 1256 541 1256 541 1257 1052 1257 1050 1257 541 1258 1050 1258 1039 1258 606 1259 611 1259 443 1259 443 1260 611 1260 446 1260 600 1261 1038 1261 699 1261 1038 1262 607 1262 699 1262 699 1263 607 1263 1043 1263 699 1264 1043 1264 608 1264 608 1265 1043 1265 1046 1265 608 1266 1046 1266 1047 1266 608 1267 1047 1267 609 1267 608 1268 609 1268 539 1268 539 1269 609 1269 610 1269 539 1270 610 1270 448 1270 539 1271 448 1271 540 1271 540 1272 448 1272 447 1272 540 1273 447 1273 446 1273 540 1274 446 1274 611 1274 612 1275 613 1275 945 1275 612 1276 615 1276 617 1276 612 1277 614 1277 615 1277 612 1278 617 1278 616 1278 612 1279 616 1279 613 1279 613 1280 616 1280 950 1280 613 1281 950 1281 618 1281 945 1282 613 1282 1034 1282 1034 1283 613 1283 618 1283 1034 1284 1027 1284 945 1284 1027 1285 1028 1285 945 1285 945 1286 1028 1286 1033 1286 945 1287 1033 1287 1037 1287 1036 1288 444 1288 445 1288 631 1289 619 1289 449 1289 449 1290 619 1290 620 1290 449 1291 620 1291 621 1291 449 1292 621 1292 622 1292 621 1293 558 1293 622 1293 622 1294 558 1294 560 1294 622 1295 560 1295 624 1295 622 1296 624 1296 623 1296 623 1297 624 1297 545 1297 623 1298 545 1298 445 1298 445 1299 545 1299 625 1299 1042 1300 632 1300 694 1300 1042 1301 694 1301 1044 1301 1044 1302 694 1302 626 1302 1044 1303 626 1303 627 1303 1044 1304 627 1304 1045 1304 1045 1305 627 1305 628 1305 1045 1306 628 1306 629 1306 1045 1307 629 1307 631 1307 631 1308 629 1308 630 1308 631 1309 630 1309 619 1309 445 1310 625 1310 1036 1310 1042 1311 1041 1311 632 1311 632 1312 1041 1312 1060 1312 632 1313 1060 1313 633 1313 1031 1314 777 1314 638 1314 777 1315 1031 1315 634 1315 779 1316 780 1316 648 1316 779 1317 648 1317 647 1317 779 1318 647 1318 635 1318 779 1319 635 1319 930 1319 930 1320 635 1320 931 1320 930 1321 931 1321 777 1321 931 1322 638 1322 777 1322 790 1323 634 1323 639 1323 639 1324 634 1324 1031 1324 636 1325 637 1325 933 1325 933 1326 790 1326 636 1326 636 1327 790 1327 639 1327 637 1328 932 1328 933 1328 637 1329 646 1329 932 1329 932 1330 646 1330 566 1330 640 1331 648 1331 571 1331 568 1332 643 1332 644 1332 652 1333 646 1333 797 1333 797 1334 646 1334 637 1334 797 1335 637 1335 796 1335 796 1336 637 1336 636 1336 796 1337 636 1337 795 1337 795 1338 636 1338 639 1338 795 1339 639 1339 794 1339 794 1340 639 1340 1031 1340 794 1341 1031 1341 638 1341 794 1342 638 1342 793 1342 793 1343 638 1343 931 1343 793 1344 931 1344 792 1344 792 1345 931 1345 635 1345 792 1346 635 1346 661 1346 661 1347 635 1347 647 1347 661 1348 647 1348 648 1348 794 1349 667 1349 795 1349 795 1350 667 1350 649 1350 795 1351 649 1351 796 1351 796 1352 649 1352 666 1352 796 1353 666 1353 797 1353 797 1354 666 1354 650 1354 797 1355 650 1355 652 1355 652 1356 650 1356 651 1356 652 1357 651 1357 653 1357 653 1358 651 1358 654 1358 653 1359 654 1359 484 1359 484 1360 654 1360 564 1360 484 1361 564 1361 655 1361 655 1362 564 1362 565 1362 655 1363 565 1363 656 1363 655 1364 656 1364 485 1364 485 1365 656 1365 657 1365 485 1366 657 1366 486 1366 486 1367 657 1367 658 1367 486 1368 658 1368 660 1368 660 1369 658 1369 659 1369 660 1370 659 1370 661 1370 661 1371 659 1371 662 1371 661 1372 662 1372 792 1372 792 1373 662 1373 663 1373 792 1374 663 1374 793 1374 793 1375 663 1375 664 1375 793 1376 664 1376 794 1376 794 1377 664 1377 667 1377 662 1378 671 1378 670 1378 662 1379 670 1379 663 1379 663 1380 670 1380 669 1380 663 1381 669 1381 664 1381 664 1382 669 1382 665 1382 664 1383 665 1383 667 1383 667 1384 679 1384 649 1384 649 1385 679 1385 678 1385 649 1386 678 1386 666 1386 666 1387 678 1387 677 1387 666 1388 677 1388 650 1388 650 1389 677 1389 676 1389 650 1390 676 1390 651 1390 600 1391 667 1391 668 1391 668 1392 667 1392 665 1392 668 1393 665 1393 669 1393 668 1394 669 1394 601 1394 601 1395 669 1395 670 1395 601 1396 670 1396 671 1396 601 1397 671 1397 575 1397 573 1398 574 1398 672 1398 573 1399 672 1399 656 1399 573 1400 656 1400 572 1400 572 1401 656 1401 673 1401 572 1402 673 1402 674 1402 572 1403 674 1403 675 1403 675 1404 674 1404 563 1404 675 1405 563 1405 676 1405 675 1406 676 1406 599 1406 599 1407 676 1407 677 1407 599 1408 677 1408 679 1408 679 1409 677 1409 678 1409 600 1410 679 1410 667 1410 680 1411 1035 1411 555 1411 1040 1412 1048 1412 1051 1412 555 1413 1035 1413 681 1413 562 1414 1055 1414 689 1414 1058 1415 1057 1415 1035 1415 690 1416 1040 1416 691 1416 691 1417 1040 1417 1051 1417 691 1418 1051 1418 693 1418 693 1419 1051 1419 682 1419 682 1420 1051 1420 683 1420 682 1421 683 1421 692 1421 692 1422 683 1422 685 1422 692 1423 685 1423 684 1423 684 1424 685 1424 686 1424 686 1425 685 1425 1055 1425 686 1426 1055 1426 687 1426 687 1427 1055 1427 562 1427 1058 1428 1035 1428 680 1428 1058 1429 680 1429 1056 1429 1056 1430 680 1430 688 1430 1056 1431 688 1431 553 1431 1056 1432 553 1432 689 1432 689 1433 553 1433 552 1433 689 1434 552 1434 562 1434 936 1435 1022 1435 937 1435 937 1436 1022 1436 1023 1436 937 1437 1023 1437 464 1437 464 1438 1023 1438 1024 1438 464 1439 1024 1439 938 1439 938 1440 1024 1440 1026 1440 938 1441 1026 1441 705 1441 687 1442 701 1442 686 1442 686 1443 701 1443 703 1443 686 1444 703 1444 684 1444 684 1445 703 1445 941 1445 684 1446 941 1446 692 1446 692 1447 941 1447 940 1447 692 1448 940 1448 682 1448 682 1449 940 1449 926 1449 682 1450 926 1450 693 1450 693 1451 926 1451 939 1451 693 1452 939 1452 691 1452 691 1453 939 1453 705 1453 691 1454 705 1454 690 1454 690 1455 705 1455 1026 1455 633 1456 1022 1456 632 1456 632 1457 1022 1457 936 1457 632 1458 936 1458 694 1458 694 1459 936 1459 695 1459 694 1460 695 1460 626 1460 626 1461 695 1461 935 1461 626 1462 935 1462 627 1462 627 1463 935 1463 696 1463 627 1464 696 1464 628 1464 628 1465 696 1465 697 1465 628 1466 697 1466 629 1466 629 1467 697 1467 698 1467 629 1468 698 1468 630 1468 630 1469 698 1469 934 1469 630 1470 934 1470 619 1470 619 1471 934 1471 713 1471 608 1472 599 1472 699 1472 722 1473 908 1473 721 1473 708 1474 705 1474 700 1474 700 1475 705 1475 706 1475 976 1476 731 1476 701 1476 701 1477 731 1477 942 1477 701 1478 942 1478 472 1478 701 1479 456 1479 976 1479 976 1480 456 1480 702 1480 701 1481 904 1481 703 1481 926 1482 943 1482 704 1482 926 1483 704 1483 522 1483 703 1484 904 1484 535 1484 703 1485 535 1485 941 1485 941 1486 535 1486 536 1486 941 1487 536 1487 537 1487 941 1488 537 1488 940 1488 940 1489 537 1489 943 1489 940 1490 943 1490 926 1490 939 1491 926 1491 522 1491 939 1492 522 1492 705 1492 705 1493 522 1493 706 1493 520 1494 464 1494 708 1494 708 1495 464 1495 938 1495 708 1496 938 1496 705 1496 937 1497 464 1497 709 1497 464 1498 520 1498 709 1498 923 1499 927 1499 696 1499 697 1500 696 1500 927 1500 696 1501 935 1501 533 1501 696 1502 533 1502 923 1502 937 1503 709 1503 707 1503 937 1504 707 1504 936 1504 936 1505 707 1505 710 1505 936 1506 710 1506 935 1506 935 1507 710 1507 533 1507 927 1508 527 1508 697 1508 697 1509 527 1509 711 1509 697 1510 711 1510 698 1510 711 1511 529 1511 712 1511 463 1512 557 1512 712 1512 712 1513 557 1513 713 1513 712 1514 713 1514 934 1514 712 1515 934 1515 711 1515 711 1516 934 1516 698 1516 717 1517 561 1517 459 1517 459 1518 559 1518 717 1518 559 1519 725 1519 925 1519 559 1520 925 1520 717 1520 557 1521 463 1521 733 1521 557 1522 733 1522 715 1522 716 1523 725 1523 559 1523 994 1524 714 1524 561 1524 994 1525 561 1525 992 1525 561 1526 717 1526 992 1526 718 1527 714 1527 458 1527 719 1528 722 1528 457 1528 461 1529 719 1529 457 1529 722 1530 719 1530 458 1530 458 1531 719 1531 720 1531 720 1532 719 1532 461 1532 457 1533 976 1533 702 1533 1021 1534 929 1534 994 1534 994 1535 929 1535 714 1535 1007 1536 1021 1536 1020 1536 1021 1537 1007 1537 929 1537 929 1538 1007 1538 458 1538 714 1539 929 1539 458 1539 976 1540 457 1540 721 1540 721 1541 457 1541 722 1541 1020 1542 722 1542 458 1542 1020 1543 458 1543 1007 1543 812 1544 463 1544 928 1544 807 1545 724 1545 723 1545 723 1546 724 1546 725 1546 809 1547 717 1547 807 1547 807 1548 717 1548 724 1548 990 1549 727 1549 726 1549 990 1550 993 1550 727 1550 726 1551 728 1551 986 1551 728 1552 985 1552 986 1552 800 1553 985 1553 728 1553 985 1554 800 1554 987 1554 729 1555 987 1555 800 1555 976 1556 921 1556 731 1556 731 1557 921 1557 983 1557 942 1558 731 1558 983 1558 942 1559 983 1559 732 1559 732 1560 983 1560 802 1560 717 1561 809 1561 727 1561 717 1562 727 1562 992 1562 992 1563 727 1563 993 1563 463 1564 812 1564 804 1564 463 1565 804 1565 733 1565 733 1566 804 1566 806 1566 733 1567 806 1567 715 1567 715 1568 806 1568 723 1568 715 1569 723 1569 716 1569 716 1570 723 1570 725 1570 735 1571 736 1571 734 1571 897 1572 803 1572 1104 1572 805 1573 957 1573 1096 1573 1096 1574 957 1574 954 1574 1096 1575 954 1575 1097 1575 1097 1576 954 1576 808 1576 1095 1577 890 1577 953 1577 1095 1578 953 1578 805 1578 805 1579 953 1579 957 1579 897 1580 1104 1580 593 1580 593 1581 1104 1581 737 1581 593 1582 737 1582 738 1582 738 1583 737 1583 801 1583 738 1584 801 1584 739 1584 739 1585 801 1585 1103 1585 739 1586 1103 1586 596 1586 596 1587 1103 1587 880 1587 880 1588 1103 1588 1102 1588 880 1589 1102 1589 598 1589 598 1590 1102 1590 1101 1590 598 1591 1101 1591 799 1591 598 1592 799 1592 740 1592 740 1593 799 1593 798 1593 740 1594 798 1594 895 1594 895 1595 798 1595 811 1595 895 1596 811 1596 741 1596 741 1597 811 1597 1100 1597 741 1598 1100 1598 579 1598 579 1599 1100 1599 810 1599 579 1600 810 1600 885 1600 885 1601 810 1601 1099 1601 885 1602 1099 1602 580 1602 580 1603 1099 1603 1098 1603 580 1604 1098 1604 581 1604 581 1605 1098 1605 742 1605 742 1606 1098 1606 808 1606 742 1607 808 1607 954 1607 742 1608 954 1608 958 1608 962 1609 1013 1609 961 1609 961 1610 1013 1610 554 1610 554 1611 1013 1611 743 1611 554 1612 743 1612 744 1612 744 1613 743 1613 745 1613 551 1614 910 1614 550 1614 905 1615 963 1615 964 1615 905 1616 964 1616 910 1616 910 1617 964 1617 549 1617 910 1618 549 1618 550 1618 1019 1619 965 1619 578 1619 578 1620 965 1620 722 1620 746 1621 1066 1621 841 1621 746 1622 841 1622 747 1622 746 1623 747 1623 748 1623 748 1624 747 1624 749 1624 748 1625 749 1625 839 1625 748 1626 839 1626 1072 1626 1072 1627 839 1627 1074 1627 861 1628 753 1628 750 1628 861 1629 750 1629 863 1629 863 1630 750 1630 838 1630 863 1631 838 1631 769 1631 769 1632 838 1632 1081 1632 755 1633 835 1633 467 1633 467 1634 835 1634 834 1634 467 1635 834 1635 878 1635 878 1636 834 1636 833 1636 878 1637 833 1637 441 1637 775 1638 832 1638 877 1638 877 1639 832 1639 751 1639 877 1640 751 1640 774 1640 774 1641 751 1641 758 1641 1074 1642 839 1642 752 1642 1074 1643 752 1643 754 1643 754 1644 752 1644 753 1644 754 1645 753 1645 861 1645 754 1646 861 1646 776 1646 1081 1647 838 1647 836 1647 1081 1648 836 1648 1082 1648 1082 1649 836 1649 835 1649 1082 1650 835 1650 755 1650 441 1651 833 1651 1086 1651 1086 1652 833 1652 756 1652 1086 1653 756 1653 832 1653 1086 1654 832 1654 757 1654 757 1655 832 1655 775 1655 774 1656 758 1656 759 1656 759 1657 758 1657 760 1657 759 1658 760 1658 761 1658 761 1659 760 1659 491 1659 761 1660 491 1660 887 1660 862 1661 903 1661 762 1661 862 1662 762 1662 1077 1662 889 1663 903 1663 863 1663 1066 1664 763 1664 1070 1664 864 1665 1069 1665 763 1665 763 1666 1069 1666 1070 1666 867 1667 1068 1667 868 1667 868 1668 1068 1668 1071 1668 868 1669 1071 1669 866 1669 866 1670 1071 1670 1073 1670 1083 1671 764 1671 1080 1671 871 1672 1078 1672 1079 1672 871 1673 1079 1673 764 1673 764 1674 1079 1674 1080 1674 1085 1675 886 1675 765 1675 765 1676 886 1676 872 1676 875 1677 1089 1677 876 1677 876 1678 1089 1678 773 1678 773 1679 1089 1679 490 1679 767 1680 1088 1680 487 1680 1088 1681 767 1681 774 1681 441 1682 768 1682 878 1682 878 1683 768 1683 879 1683 1084 1684 755 1684 468 1684 889 1685 863 1685 769 1685 1077 1686 776 1686 862 1686 862 1687 776 1687 861 1687 1072 1688 1069 1688 864 1688 1068 1689 867 1689 1064 1689 507 1690 770 1690 1073 1690 1073 1691 770 1691 866 1691 1078 1692 497 1692 1075 1692 497 1693 1078 1693 871 1693 1083 1694 869 1694 764 1694 496 1695 1085 1695 771 1695 766 1696 875 1696 772 1696 766 1697 1089 1697 875 1697 491 1698 873 1698 440 1698 757 1699 775 1699 489 1699 489 1700 775 1700 488 1700 1066 1701 746 1701 763 1701 1072 1702 864 1702 748 1702 777 1703 791 1703 778 1703 777 1704 778 1704 930 1704 930 1705 778 1705 779 1705 779 1706 778 1706 850 1706 779 1707 850 1707 780 1707 780 1708 850 1708 849 1708 780 1709 849 1709 483 1709 780 1710 483 1710 781 1710 781 1711 483 1711 481 1711 781 1712 481 1712 570 1712 570 1713 481 1713 480 1713 570 1714 480 1714 782 1714 782 1715 480 1715 567 1715 480 1716 783 1716 567 1716 567 1717 783 1717 785 1717 567 1718 785 1718 784 1718 784 1719 785 1719 787 1719 784 1720 787 1720 786 1720 786 1721 787 1721 478 1721 786 1722 478 1722 566 1722 566 1723 478 1723 788 1723 566 1724 788 1724 932 1724 932 1725 788 1725 789 1725 932 1726 789 1726 933 1726 933 1727 789 1727 790 1727 790 1728 789 1728 855 1728 790 1729 855 1729 634 1729 634 1730 855 1730 853 1730 634 1731 853 1731 777 1731 777 1732 853 1732 791 1732 728 1733 798 1733 799 1733 728 1734 799 1734 800 1734 800 1735 799 1735 1101 1735 800 1736 1101 1736 1102 1736 800 1737 1102 1737 729 1737 729 1738 1102 1738 1103 1738 729 1739 1103 1739 801 1739 729 1740 801 1740 730 1740 730 1741 801 1741 1104 1741 730 1742 1104 1742 983 1742 983 1743 1104 1743 802 1743 802 1744 1104 1744 803 1744 812 1745 1095 1745 804 1745 804 1746 1095 1746 805 1746 804 1747 805 1747 806 1747 806 1748 805 1748 1096 1748 806 1749 1096 1749 723 1749 723 1750 1096 1750 1097 1750 723 1751 1097 1751 807 1751 807 1752 1097 1752 808 1752 807 1753 808 1753 809 1753 809 1754 808 1754 1098 1754 809 1755 1098 1755 727 1755 727 1756 1098 1756 1099 1756 727 1757 1099 1757 726 1757 726 1758 1099 1758 810 1758 726 1759 810 1759 1100 1759 726 1760 1100 1760 728 1760 728 1761 1100 1761 811 1761 728 1762 811 1762 798 1762 1095 1763 812 1763 814 1763 814 1764 812 1764 813 1764 814 1765 813 1765 528 1765 814 1766 528 1766 815 1766 815 1767 528 1767 526 1767 815 1768 526 1768 437 1768 437 1769 526 1769 524 1769 437 1770 524 1770 816 1770 816 1771 524 1771 525 1771 816 1772 525 1772 436 1772 436 1773 525 1773 532 1773 436 1774 532 1774 510 1774 510 1775 532 1775 531 1775 510 1776 531 1776 512 1776 512 1777 531 1777 530 1777 512 1778 530 1778 817 1778 817 1779 530 1779 818 1779 802 1780 803 1780 819 1780 819 1781 803 1781 433 1781 819 1782 433 1782 820 1782 820 1783 433 1783 821 1783 820 1784 821 1784 822 1784 822 1785 821 1785 823 1785 822 1786 823 1786 523 1786 523 1787 823 1787 514 1787 523 1788 514 1788 521 1788 521 1789 514 1789 434 1789 521 1790 434 1790 534 1790 534 1791 434 1791 824 1791 534 1792 824 1792 826 1792 826 1793 824 1793 825 1793 826 1794 825 1794 818 1794 818 1795 825 1795 435 1795 818 1796 435 1796 817 1796 479 1797 848 1797 827 1797 479 1798 827 1798 828 1798 828 1799 827 1799 495 1799 828 1800 495 1800 501 1800 828 1801 501 1801 829 1801 829 1802 501 1802 500 1802 829 1803 500 1803 493 1803 829 1804 493 1804 856 1804 856 1805 493 1805 772 1805 856 1806 772 1806 492 1806 856 1807 492 1807 491 1807 856 1808 491 1808 830 1808 830 1809 491 1809 760 1809 830 1810 760 1810 758 1810 830 1811 758 1811 831 1811 831 1812 758 1812 751 1812 831 1813 751 1813 832 1813 831 1814 832 1814 756 1814 831 1815 756 1815 854 1815 854 1816 756 1816 833 1816 854 1817 833 1817 834 1817 854 1818 834 1818 837 1818 834 1819 835 1819 837 1819 837 1820 835 1820 836 1820 837 1821 836 1821 838 1821 837 1822 838 1822 852 1822 852 1823 838 1823 750 1823 852 1824 750 1824 753 1824 852 1825 753 1825 851 1825 851 1826 753 1826 752 1826 851 1827 752 1827 839 1827 851 1828 839 1828 840 1828 840 1829 839 1829 749 1829 840 1830 749 1830 747 1830 840 1831 747 1831 849 1831 849 1832 747 1832 841 1832 849 1833 841 1833 482 1833 482 1834 841 1834 842 1834 482 1835 842 1835 843 1835 482 1836 843 1836 481 1836 481 1837 843 1837 499 1837 481 1838 499 1838 844 1838 844 1839 499 1839 508 1839 844 1840 508 1840 845 1840 844 1841 845 1841 846 1841 846 1842 845 1842 498 1842 846 1843 498 1843 847 1843 846 1844 847 1844 479 1844 479 1845 847 1845 504 1845 479 1846 504 1846 848 1846 840 1847 849 1847 850 1847 840 1848 850 1848 851 1848 851 1849 850 1849 778 1849 851 1850 778 1850 852 1850 852 1851 778 1851 791 1851 852 1852 791 1852 837 1852 837 1853 791 1853 854 1853 854 1854 791 1854 853 1854 854 1855 853 1855 831 1855 831 1856 853 1856 855 1856 831 1857 855 1857 789 1857 831 1858 789 1858 830 1858 830 1859 789 1859 788 1859 830 1860 788 1860 856 1860 857 1861 1067 1861 594 1861 858 1862 471 1862 859 1862 476 1863 898 1863 475 1863 860 1864 884 1864 883 1864 473 1865 597 1865 474 1865 732 1866 472 1866 942 1866 861 1867 863 1867 903 1867 746 1868 748 1868 864 1868 763 1869 746 1869 864 1869 868 1870 866 1870 865 1870 865 1871 867 1871 868 1871 865 1872 866 1872 770 1872 870 1873 764 1873 869 1873 870 1874 497 1874 871 1874 870 1875 871 1875 899 1875 899 1876 871 1876 764 1876 899 1877 764 1877 870 1877 765 1878 872 1878 494 1878 494 1879 771 1879 1085 1879 875 1880 874 1880 873 1880 874 1881 773 1881 873 1881 874 1882 875 1882 876 1882 874 1883 876 1883 773 1883 487 1884 488 1884 767 1884 767 1885 488 1885 901 1885 877 1886 488 1886 775 1886 877 1887 774 1887 901 1887 901 1888 774 1888 767 1888 468 1889 755 1889 467 1889 467 1890 878 1890 879 1890 467 1891 879 1891 468 1891 739 1892 596 1892 880 1892 897 1893 594 1893 1067 1893 893 1894 592 1894 891 1894 881 1895 896 1895 588 1895 881 1896 588 1896 513 1896 586 1897 585 1897 477 1897 896 1898 477 1898 587 1898 882 1899 583 1899 892 1899 892 1900 583 1900 584 1900 892 1901 584 1901 586 1901 582 1902 890 1902 888 1902 582 1903 888 1903 958 1903 958 1904 888 1904 884 1904 579 1905 885 1905 886 1905 886 1906 885 1906 581 1906 886 1907 581 1907 742 1907 1087 1908 502 1908 883 1908 898 1909 439 1909 887 1909 890 1910 490 1910 888 1910 888 1911 490 1911 1089 1911 762 1912 889 1912 591 1912 1074 1913 754 1913 471 1913 872 1914 742 1914 502 1914 502 1915 742 1915 883 1915 1087 1916 883 1916 884 1916 1087 1917 884 1917 766 1917 490 1918 890 1918 440 1918 440 1919 890 1919 898 1919 898 1920 892 1920 439 1920 439 1921 892 1921 1088 1921 896 1922 768 1922 441 1922 881 1923 442 1923 768 1923 762 1924 591 1924 893 1924 505 1925 1062 1925 503 1925 503 1926 1062 1926 496 1926 496 1927 1062 1927 579 1927 887 1928 440 1928 898 1928 892 1929 586 1929 489 1929 442 1930 881 1930 513 1930 1074 1931 471 1931 470 1931 1074 1932 470 1932 1072 1932 1083 1933 1080 1933 741 1933 579 1934 886 1934 496 1934 882 1935 892 1935 898 1935 896 1936 881 1936 768 1936 515 1937 894 1937 1070 1937 888 1938 1089 1938 884 1938 884 1939 1089 1939 766 1939 591 1940 1084 1940 513 1940 513 1941 1084 1941 442 1941 1070 1942 1069 1942 515 1942 515 1943 1069 1943 470 1943 470 1944 1069 1944 1072 1944 1066 1945 897 1945 1067 1945 1073 1946 1071 1946 739 1946 739 1947 1071 1947 1068 1947 1086 1948 477 1948 896 1948 1086 1949 896 1949 441 1949 1084 1950 591 1950 1082 1950 1082 1951 591 1951 1081 1951 1081 1952 591 1952 769 1952 769 1953 591 1953 889 1953 891 1954 1077 1954 762 1954 891 1955 762 1955 893 1955 897 1956 1066 1956 1070 1956 897 1957 1070 1957 894 1957 1080 1958 1079 1958 895 1958 895 1959 1079 1959 740 1959 740 1960 1079 1960 1078 1960 872 1961 886 1961 742 1961 757 1962 586 1962 1086 1962 1086 1963 586 1963 477 1963 757 1964 489 1964 586 1964 895 1965 741 1965 1080 1965 891 1966 595 1966 1077 1966 1083 1967 741 1967 505 1967 505 1968 741 1968 1062 1968 506 1969 1076 1969 597 1969 471 1970 776 1970 595 1970 595 1971 776 1971 1077 1971 597 1972 1075 1972 506 1972 776 1973 471 1973 754 1973 507 1974 880 1974 1076 1974 1076 1975 880 1975 597 1975 507 1976 1073 1976 880 1976 880 1977 1073 1977 739 1977 1078 1978 598 1978 740 1978 1068 1979 593 1979 739 1979 1067 1980 593 1980 1064 1980 1064 1981 593 1981 1068 1981 597 1982 598 1982 1075 1982 1075 1983 598 1983 1078 1983 900 1984 865 1984 868 1984 902 1985 765 1985 494 1985 902 1986 494 1986 1085 1986 466 1987 861 1987 903 1987 466 1988 903 1988 862 1988 732 1989 904 1989 701 1989 991 1990 913 1990 992 1990 992 1991 913 1991 982 1991 905 1992 910 1992 965 1992 906 1993 743 1993 1013 1993 1090 1994 914 1994 944 1994 1005 1995 912 1995 975 1995 973 1996 907 1996 911 1996 973 1997 911 1997 906 1997 908 1998 909 1998 975 1998 975 1999 909 1999 1005 1999 912 2000 1005 2000 1004 2000 912 2001 1004 2001 911 2001 911 2002 1004 2002 910 2002 911 2003 910 2003 743 2003 911 2004 743 2004 906 2004 910 2005 1004 2005 965 2005 965 2006 1004 2006 722 2006 722 2007 1004 2007 909 2007 722 2008 909 2008 908 2008 912 2009 1002 2009 975 2009 975 2010 1002 2010 919 2010 919 2011 1002 2011 978 2011 978 2012 1002 2012 907 2012 978 2013 907 2013 973 2013 978 2014 973 2014 972 2014 915 2015 982 2015 913 2015 915 2016 913 2016 997 2016 978 2017 972 2017 968 2017 978 2018 968 2018 974 2018 974 2019 968 2019 969 2019 916 2020 994 2020 915 2020 982 2021 915 2021 994 2021 916 2022 959 2022 994 2022 917 2023 913 2023 455 2023 917 2024 455 2024 944 2024 944 2025 455 2025 1090 2025 944 2026 914 2026 614 2026 917 2027 959 2027 916 2027 917 2028 916 2028 997 2028 917 2029 997 2029 913 2029 1090 2030 455 2030 969 2030 969 2031 455 2031 918 2031 969 2032 918 2032 974 2032 974 2033 918 2033 913 2033 1016 2034 973 2034 1013 2034 1013 2035 973 2035 906 2035 979 2036 920 2036 919 2036 919 2037 920 2037 975 2037 921 2038 977 2038 980 2038 980 2039 977 2039 979 2039 922 2040 972 2040 971 2040 1018 2041 922 2041 971 2041 972 2042 922 2042 968 2042 968 2043 922 2043 1018 2043 704 2044 943 2044 465 2044 518 2045 709 2045 520 2045 927 2046 923 2046 533 2046 928 2047 924 2047 712 2047 925 2048 725 2048 724 2048 926 2049 465 2049 522 2049 704 2050 926 2050 522 2050 518 2051 464 2051 709 2051 923 2052 927 2052 696 2052 928 2053 712 2053 924 2053 925 2054 724 2054 559 2054 935 2055 695 2055 936 2055 948 2056 914 2056 1092 2056 1091 2057 944 2057 614 2057 910 2058 551 2058 743 2058 743 2059 551 2059 745 2059 1015 2060 547 2060 1017 2060 1017 2061 547 2061 546 2061 945 2062 946 2062 1010 2062 462 2063 1012 2063 946 2063 945 2064 929 2064 462 2064 462 2065 929 2065 945 2065 462 2066 946 2066 945 2066 1014 2067 1008 2067 548 2067 1012 2068 1008 2068 1014 2068 1012 2069 462 2069 1008 2069 1008 2070 462 2070 947 2070 1008 2071 947 2071 548 2071 1011 2072 960 2072 967 2072 617 2073 948 2073 1009 2073 949 2074 966 2074 556 2074 966 2075 949 2075 1009 2075 949 2076 950 2076 1009 2076 1009 2077 950 2077 616 2077 949 2078 556 2078 950 2078 954 2079 735 2079 958 2079 958 2080 735 2080 734 2080 582 2081 951 2081 953 2081 953 2082 951 2082 952 2082 955 2083 952 2083 951 2083 957 2084 736 2084 735 2084 953 2085 952 2085 957 2085 735 2086 954 2086 957 2086 955 2087 956 2087 957 2087 957 2088 956 2088 736 2088 952 2089 955 2089 957 2089 1021 2090 994 2090 959 2090 959 2091 577 2091 1021 2091 615 2092 914 2092 617 2092 617 2093 914 2093 948 2093 612 2094 945 2094 1010 2094 612 2095 1010 2095 614 2095 547 2096 1015 2096 1014 2096 547 2097 1014 2097 548 2097 962 2098 960 2098 1011 2098 962 2099 961 2099 960 2099 964 2100 963 2100 1017 2100 964 2101 1017 2101 546 2101 965 2102 1019 2102 905 2102 556 2103 966 2103 1011 2103 556 2104 1011 2104 967 2104 617 2105 1009 2105 616 2105 968 2106 1018 2106 970 2106 968 2107 970 2107 969 2107 971 2108 972 2108 973 2108 971 2109 973 2109 1016 2109 578 2110 722 2110 1020 2110 974 2111 990 2111 988 2111 974 2112 988 2112 978 2112 978 2113 988 2113 989 2113 978 2114 984 2114 981 2114 978 2115 989 2115 984 2115 920 2116 977 2116 975 2116 977 2117 721 2117 975 2117 975 2118 721 2118 908 2118 921 2119 721 2119 977 2119 978 2120 981 2120 919 2120 979 2121 919 2121 981 2121 920 2122 979 2122 977 2122 979 2123 981 2123 980 2123 990 2124 974 2124 913 2124 990 2125 913 2125 991 2125 992 2126 982 2126 994 2126 921 2127 976 2127 721 2127 983 2128 921 2128 730 2128 921 2129 980 2129 730 2129 730 2130 980 2130 729 2130 980 2131 981 2131 729 2131 729 2132 981 2132 984 2132 988 2133 990 2133 726 2133 988 2134 726 2134 986 2134 989 2135 985 2135 987 2135 987 2136 729 2136 984 2136 988 2137 986 2137 985 2137 988 2138 985 2138 989 2138 984 2139 989 2139 987 2139 993 2140 990 2140 991 2140 991 2141 992 2141 993 2141 996 2142 995 2142 918 2142 996 2143 918 2143 455 2143 996 2144 455 2144 454 2144 544 2145 915 2145 997 2145 997 2146 998 2146 544 2146 998 2147 997 2147 916 2147 1001 2148 1000 2148 999 2148 1001 2149 911 2149 907 2149 1001 2150 907 2150 1000 2150 1000 2151 907 2151 1002 2151 1003 2152 1004 2152 1006 2152 1006 2153 1004 2153 1005 2153 1010 2154 1091 2154 614 2154 963 2155 905 2155 1017 2155 970 2156 1018 2156 971 2156 578 2157 1020 2157 577 2157 577 2158 1020 2158 1021 2158 1061 2159 690 2159 1026 2159 1024 2160 1023 2160 1025 2160 1022 2161 1025 2161 1023 2161 1024 2162 1025 2162 1059 2162 1024 2163 1059 2163 1026 2163 1026 2164 1059 2164 1061 2164 1027 2165 602 2165 573 2165 1027 2166 573 2166 1028 2166 1028 2167 573 2167 611 2167 1028 2168 611 2168 1033 2168 451 2169 1029 2169 517 2169 1030 2170 818 2170 1029 2170 1029 2171 818 2171 517 2171 450 2172 1029 2172 452 2172 450 2173 452 2173 1030 2173 450 2174 1030 2174 1029 2174 681 2175 1035 2175 950 2175 950 2176 1035 2176 1034 2176 950 2177 1034 2177 618 2177 602 2178 1027 2178 1032 2178 1032 2179 1027 2179 1034 2179 1032 2180 1034 2180 1035 2180 1032 2181 1035 2181 1057 2181 1033 2182 611 2182 1037 2182 1037 2183 611 2183 606 2183 1037 2184 606 2184 1036 2184 1036 2185 606 2185 444 2185 625 2186 1037 2186 1036 2186 600 2187 1025 2187 1038 2187 1038 2188 1025 2188 1022 2188 1038 2189 1022 2189 1041 2189 1041 2190 1022 2190 1060 2190 1059 2191 1039 2191 1061 2191 1061 2192 1039 2192 1040 2192 1040 2193 1039 2193 1048 2193 607 2194 1038 2194 1041 2194 1041 2195 1042 2195 607 2195 607 2196 1042 2196 1044 2196 607 2197 1044 2197 1043 2197 1043 2198 1044 2198 1045 2198 1043 2199 1045 2199 1046 2199 1046 2200 1045 2200 631 2200 1046 2201 631 2201 1047 2201 1048 2202 1039 2202 1050 2202 1049 2203 1032 2203 1057 2203 1048 2204 1050 2204 1051 2204 1051 2205 1050 2205 1052 2205 1051 2206 1052 2206 683 2206 683 2207 1052 2207 1053 2207 683 2208 1053 2208 685 2208 685 2209 1053 2209 1054 2209 685 2210 1054 2210 1055 2210 1055 2211 1054 2211 605 2211 1055 2212 605 2212 689 2212 689 2213 605 2213 604 2213 689 2214 604 2214 1056 2214 1056 2215 604 2215 603 2215 1056 2216 603 2216 1049 2216 1056 2217 1049 2217 1058 2217 1058 2218 1049 2218 1057 2218 1039 2219 1059 2219 668 2219 1060 2220 1022 2220 633 2220 690 2221 1061 2221 1040 2221 1063 2222 1062 2222 1094 2222 1064 2223 1065 2223 1067 2223 1066 2224 1067 2224 841 2224 841 2225 1067 2225 1065 2225 903 2226 889 2226 762 2226 755 2227 1084 2227 1082 2227 869 2228 1083 2228 505 2228 1085 2229 496 2229 886 2229 487 2230 1088 2230 892 2230 439 2231 1088 2231 774 2231 1092 2232 914 2232 1090 2232 944 2233 1091 2233 917 2233 591 2234 1093 2234 590 2234 801 2235 737 2235 1104 2235 2120 2236 1135 2236 1114 2236 1107 2237 1401 2237 1400 2237 1109 2238 1396 2238 1108 2238 1111 2239 1110 2239 1112 2239 1375 2240 1113 2240 1388 2240 1418 2241 1420 2241 1117 2241 1116 2242 1580 2242 1117 2242 1116 2243 1954 2243 1627 2243 1557 2244 1547 2244 1117 2244 1117 2245 1547 2245 1840 2245 1527 2246 1557 2246 1530 2246 1530 2247 1557 2247 1117 2247 1530 2248 1117 2248 1474 2248 1474 2249 1117 2249 1580 2249 1474 2250 1580 2250 1789 2250 1608 2251 1116 2251 1627 2251 1608 2252 1627 2252 1115 2252 1117 2253 1684 2253 1415 2253 1117 2254 1543 2254 1509 2254 1117 2255 1487 2255 1442 2255 1116 2256 1117 2256 1606 2256 1116 2257 1606 2257 1640 2257 1607 2258 1881 2258 1606 2258 1443 2259 1457 2259 1442 2259 1442 2260 1457 2260 1117 2260 1117 2261 1457 2261 1606 2261 1473 2262 1487 2262 1471 2262 1509 2263 1507 2263 1570 2263 1509 2264 1570 2264 1117 2264 1117 2265 1570 2265 1471 2265 1117 2266 1471 2266 1487 2266 1413 2267 1412 2267 1841 2267 1413 2268 1841 2268 1543 2268 1842 2269 1843 2269 1415 2269 1117 2270 1415 2270 1543 2270 1439 2271 1686 2271 1118 2271 1611 2272 1930 2272 1119 2272 1546 2273 1513 2273 1119 2273 1491 2274 1579 2274 1119 2274 1559 2275 1548 2275 1118 2275 1438 2276 1836 2276 1730 2276 1438 2277 1730 2277 1439 2277 1439 2278 1118 2278 1728 2278 1728 2279 1118 2279 1548 2279 1728 2280 1548 2280 1834 2280 1572 2281 1806 2281 1559 2281 1572 2282 1559 2282 1118 2282 1572 2283 1118 2283 1480 2283 1480 2284 1118 2284 1581 2284 1480 2285 1581 2285 1478 2285 1460 2286 1461 2286 1766 2286 1644 2287 1652 2287 1594 2287 1644 2288 1594 2288 1119 2288 1119 2289 1594 2289 1460 2289 1119 2290 1460 2290 1118 2290 1118 2291 1460 2291 1581 2291 1613 2292 1626 2292 1611 2292 1579 2293 1445 2293 1459 2293 1579 2294 1459 2294 1119 2294 1119 2295 1459 2295 1611 2295 1476 2296 1475 2296 1491 2296 1513 2297 1512 2297 1528 2297 1513 2298 1528 2298 1119 2298 1119 2299 1528 2299 1476 2299 1119 2300 1476 2300 1491 2300 1437 2301 1432 2301 1546 2301 1118 2302 1655 2302 1435 2302 1118 2303 1435 2303 1119 2303 1119 2304 1435 2304 1437 2304 1119 2305 1437 2305 1546 2305 1122 2306 1936 2306 1617 2306 1122 2307 1449 2307 1495 2307 1122 2308 1560 2308 1120 2308 1429 2309 1122 2309 1121 2309 1121 2310 1122 2310 1120 2310 1121 2311 1120 2311 1830 2311 1574 2312 1533 2312 1560 2312 1574 2313 1560 2313 1122 2313 1574 2314 1122 2314 1573 2314 1573 2315 1122 2315 1495 2315 1573 2316 1495 2316 1786 2316 1462 2317 1450 2317 1449 2317 1449 2318 1122 2318 1617 2318 1429 2319 1549 2319 1514 2319 1429 2320 1493 2320 1582 2320 1653 2321 1628 2321 1595 2321 1122 2322 1595 2322 1935 2322 1582 2323 1770 2323 1122 2323 1582 2324 1122 2324 1429 2324 1477 2325 1494 2325 1493 2325 1514 2326 1515 2326 1531 2326 1514 2327 1531 2327 1429 2327 1429 2328 1531 2328 1477 2328 1429 2329 1477 2329 1493 2329 1426 2330 2057 2330 1549 2330 1705 2331 1708 2331 1123 2331 1797 2332 1575 2332 1123 2332 1151 2333 1123 2333 1708 2333 1124 2334 1818 2334 1705 2334 1124 2335 1705 2335 1123 2335 1124 2336 1123 2336 1562 2336 1562 2337 1123 2337 1575 2337 1562 2338 1575 2338 1814 2338 1585 2339 1794 2339 1797 2339 1585 2340 1797 2340 1123 2340 1585 2341 1123 2341 1125 2341 1647 2342 1883 2342 1600 2342 1647 2343 1600 2343 1940 2343 1123 2344 1158 2344 2096 2344 1123 2345 1561 2345 1516 2345 1127 2346 1599 2346 1940 2346 1123 2347 1584 2347 1127 2347 1599 2348 1630 2348 1126 2348 1599 2349 1126 2349 1940 2349 1940 2350 1126 2350 1646 2350 1127 2351 1765 2351 1597 2351 1123 2352 1127 2352 1940 2352 1123 2353 1940 2353 1125 2353 1125 2354 1940 2354 1600 2354 1481 2355 1496 2355 1584 2355 1516 2356 1659 2356 1534 2356 1516 2357 1534 2357 1123 2357 1123 2358 1534 2358 1481 2358 1123 2359 1481 2359 1584 2359 1123 2360 2096 2360 1561 2360 1676 2361 1410 2361 1130 2361 1676 2362 1820 2362 1565 2362 1676 2363 1586 2363 1128 2363 1128 2364 1601 2364 1129 2364 1129 2365 1944 2365 1603 2365 1129 2366 1451 2366 1498 2366 1129 2367 1518 2367 1566 2367 1676 2368 1408 2368 1656 2368 1660 2369 1518 2369 1576 2369 1576 2370 1518 2370 1129 2370 1576 2371 1129 2371 1483 2371 1483 2372 1129 2372 1498 2372 1483 2373 1498 2373 1661 2373 1465 2374 1451 2374 1602 2374 1602 2375 1451 2375 1129 2375 1602 2376 1129 2376 1603 2376 1885 2377 1875 2377 1601 2377 1129 2378 1601 2378 1941 2378 1676 2379 1128 2379 1129 2379 1676 2380 1129 2380 1409 2380 1409 2381 1129 2381 1566 2381 1409 2382 1566 2382 1822 2382 1822 2383 1566 2383 1657 2383 1798 2384 1796 2384 1586 2384 1565 2385 1815 2385 1817 2385 1565 2386 1817 2386 1676 2386 1676 2387 1817 2387 1798 2387 1676 2388 1798 2388 1586 2388 1691 2389 1689 2389 1821 2389 1691 2390 1821 2390 1820 2390 1828 2391 1694 2391 1130 2391 1676 2392 1130 2392 1820 2392 1965 2393 1943 2393 1390 2393 1390 2394 1943 2394 1946 2394 1390 2395 1946 2395 1943 2395 1390 2396 1943 2396 1965 2396 1969 2397 1939 2397 1938 2397 1969 2398 1938 2398 1939 2398 2119 2399 1931 2399 1971 2399 1971 2400 1931 2400 1145 2400 1971 2401 1145 2401 1931 2401 1131 2402 1954 2402 1132 2402 1131 2403 1132 2403 1143 2403 1131 2404 1143 2404 1954 2404 1974 2405 1957 2405 1133 2405 2120 2406 1949 2406 1964 2406 1964 2407 1949 2407 1950 2407 1964 2408 1950 2408 2120 2408 2120 2409 1950 2409 1949 2409 1147 2410 1933 2410 1134 2410 1147 2411 1134 2411 1933 2411 1389 2412 1948 2412 1947 2412 1389 2413 1947 2413 1959 2413 1959 2414 1947 2414 1948 2414 1959 2415 1948 2415 1389 2415 1952 2416 1963 2416 1953 2416 1953 2417 1963 2417 1135 2417 1953 2418 1135 2418 1964 2418 1953 2419 1964 2419 1950 2419 1950 2420 1964 2420 1136 2420 1950 2421 1136 2421 1962 2421 1950 2422 1962 2422 1873 2422 1938 2423 1968 2423 1137 2423 1938 2424 1137 2424 1942 2424 1942 2425 1137 2425 1966 2425 1942 2426 1966 2426 1946 2426 1946 2427 1966 2427 1390 2427 1946 2428 1390 2428 1138 2428 1946 2429 1138 2429 1945 2429 1945 2430 1138 2430 1967 2430 1945 2431 1967 2431 1139 2431 1139 2432 1967 2432 1960 2432 1139 2433 1960 2433 1947 2433 1947 2434 1960 2434 1959 2434 1947 2435 1959 2435 1963 2435 1947 2436 1963 2436 1952 2436 1140 2437 1968 2437 1938 2437 1938 2438 1937 2438 1140 2438 1140 2439 1937 2439 1141 2439 1141 2440 1937 2440 1142 2440 1142 2441 1937 2441 1933 2441 1142 2442 1933 2442 1147 2442 1143 2443 1961 2443 1972 2443 1143 2444 1972 2444 1144 2444 1144 2445 1972 2445 1971 2445 1144 2446 1971 2446 1145 2446 1145 2447 1971 2447 1970 2447 1145 2448 1970 2448 1932 2448 1932 2449 1970 2449 1146 2449 1932 2450 1146 2450 1934 2450 1934 2451 1146 2451 1147 2451 1934 2452 1147 2452 1933 2452 1143 2453 1149 2453 1961 2453 1957 2454 1973 2454 1148 2454 1148 2455 1973 2455 1149 2455 1148 2456 1149 2456 1143 2456 1957 2457 1133 2457 1973 2457 1863 2458 1150 2458 1957 2458 1957 2459 1150 2459 1133 2459 1151 2460 1708 2460 2108 2460 1155 2461 2099 2461 1433 2461 1154 2462 1677 2462 1406 2462 1154 2463 1406 2463 1677 2463 1158 2464 1159 2464 1156 2464 1156 2465 1159 2465 1707 2465 1429 2466 1121 2466 1702 2466 2056 2467 1166 2467 1755 2467 1755 2468 1265 2468 1171 2468 1755 2469 1171 2469 1751 2469 1751 2470 1266 2470 1163 2470 1163 2471 1170 2471 1272 2471 1272 2472 1170 2472 1169 2472 1272 2473 1273 2473 1276 2473 1276 2474 1273 2474 1165 2474 1168 2475 1278 2475 1749 2475 1749 2476 1282 2476 1167 2476 1749 2477 1167 2477 1750 2477 1750 2478 1164 2478 1336 2478 1167 2479 1282 2479 1281 2479 1163 2480 1266 2480 1267 2480 1997 2481 1749 2481 1278 2481 1668 2482 1669 2482 2087 2482 1188 2483 1719 2483 1718 2483 1188 2484 1718 2484 2074 2484 2074 2485 1718 2485 2072 2485 2072 2486 1718 2486 1717 2486 2072 2487 1717 2487 2071 2487 2071 2488 1717 2488 1715 2488 2071 2489 1715 2489 1174 2489 2071 2490 1174 2490 1173 2490 1173 2491 1174 2491 1725 2491 1173 2492 1725 2492 2067 2492 2067 2493 1725 2493 1724 2493 2067 2494 1724 2494 2084 2494 2084 2495 1724 2495 1721 2495 2084 2496 1721 2496 2083 2496 2083 2497 1721 2497 1720 2497 2083 2498 1720 2498 2082 2498 2082 2499 1720 2499 1175 2499 2082 2500 1175 2500 1176 2500 1176 2501 1175 2501 1710 2501 1176 2502 1710 2502 1177 2502 1177 2503 1710 2503 1178 2503 1177 2504 1178 2504 2079 2504 2079 2505 1178 2505 1711 2505 2079 2506 1711 2506 1179 2506 1179 2507 1711 2507 1712 2507 1179 2508 1712 2508 2077 2508 2077 2509 1712 2509 1180 2509 2077 2510 1180 2510 2075 2510 1188 2511 1338 2511 1719 2511 2076 2512 1667 2512 1670 2512 2076 2513 1670 2513 2078 2513 2078 2514 1670 2514 1671 2514 2078 2515 1671 2515 2080 2515 2080 2516 1671 2516 1672 2516 2080 2517 1672 2517 1181 2517 1181 2518 1672 2518 1673 2518 1181 2519 1673 2519 2081 2519 2081 2520 1673 2520 1182 2520 1182 2521 1673 2521 1183 2521 1182 2522 1183 2522 1185 2522 1185 2523 1183 2523 1184 2523 1185 2524 1184 2524 1186 2524 1184 2525 1674 2525 1186 2525 1186 2526 1674 2526 2066 2526 2066 2527 1674 2527 1675 2527 2066 2528 1675 2528 2068 2528 2068 2529 1675 2529 1678 2529 2068 2530 1678 2530 2069 2530 2069 2531 1678 2531 2070 2531 2070 2532 1678 2532 1680 2532 2070 2533 1680 2533 2073 2533 2073 2534 1680 2534 1187 2534 2073 2535 1187 2535 2074 2535 2074 2536 1187 2536 1188 2536 1188 2537 1683 2537 1160 2537 1252 2538 2049 2538 2053 2538 2053 2539 2049 2539 1376 2539 2053 2540 1376 2540 1254 2540 1254 2541 1376 2541 2050 2541 1254 2542 2050 2542 2051 2542 2051 2543 2050 2543 2047 2543 2051 2544 2047 2544 1384 2544 2051 2545 1384 2545 2052 2545 2052 2546 1384 2546 2048 2546 1252 2547 2048 2547 2049 2547 1455 2548 1467 2548 1456 2548 1354 2549 1501 2549 2039 2549 1520 2550 1539 2550 1524 2550 1859 2551 1860 2551 2062 2551 2044 2552 1727 2552 1726 2552 1623 2553 1636 2553 2035 2553 2028 2554 2032 2554 1904 2554 2028 2555 1904 2555 2032 2555 2025 2556 1896 2556 1897 2556 1913 2557 1897 2557 2025 2557 1913 2558 2025 2558 1897 2558 2030 2559 2033 2559 2026 2559 1198 2560 2026 2560 1915 2560 1198 2561 1915 2561 2026 2561 1219 2562 1921 2562 2011 2562 2011 2563 1921 2563 1219 2563 1197 2564 1191 2564 1192 2564 1192 2565 1191 2565 2032 2565 1192 2566 2032 2566 1250 2566 1250 2567 2032 2567 1193 2567 1250 2568 1193 2568 1194 2568 1194 2569 1193 2569 2031 2569 1195 2570 1896 2570 1196 2570 1196 2571 1896 2571 1251 2571 1896 2572 2033 2572 1251 2572 1251 2573 2033 2573 1901 2573 2033 2574 2030 2574 1901 2574 1901 2575 2030 2575 1197 2575 1197 2576 2030 2576 1191 2576 2028 2577 2032 2577 1191 2577 2028 2578 1191 2578 1198 2578 1198 2579 1191 2579 2034 2579 1198 2580 2034 2580 2026 2580 1203 2581 1211 2581 1210 2581 1205 2582 1200 2582 1218 2582 2029 2583 1212 2583 1203 2583 2010 2584 1219 2584 1205 2584 2010 2585 1205 2585 1204 2585 1205 2586 1207 2586 1204 2586 1204 2587 1207 2587 1206 2587 1206 2588 1207 2588 2012 2588 1207 2589 1208 2589 2012 2589 2012 2590 1208 2590 2014 2590 1208 2591 1199 2591 2014 2591 2014 2592 1199 2592 2015 2592 1199 2593 1209 2593 2015 2593 2015 2594 1209 2594 2017 2594 2017 2595 1209 2595 2018 2595 1209 2596 1210 2596 2018 2596 2018 2597 1210 2597 2019 2597 1210 2598 1211 2598 2019 2598 1211 2599 1203 2599 2019 2599 2019 2600 1203 2600 1213 2600 1203 2601 1212 2601 1213 2601 1213 2602 1212 2602 1214 2602 1212 2603 2029 2603 1214 2603 1214 2604 2029 2604 2022 2604 2029 2605 1202 2605 2022 2605 2022 2606 1202 2606 2021 2606 1202 2607 1215 2607 2021 2607 2021 2608 1215 2608 1216 2608 1215 2609 1201 2609 1216 2609 1216 2610 1201 2610 1217 2610 1201 2611 1218 2611 1217 2611 1217 2612 1218 2612 2009 2612 2009 2613 1218 2613 2008 2613 1218 2614 1200 2614 2008 2614 2008 2615 1200 2615 1219 2615 1219 2616 1200 2616 1205 2616 1221 2617 1255 2617 1222 2617 1222 2618 1223 2618 2011 2618 1225 2619 1260 2619 2023 2619 1228 2620 1925 2620 1229 2620 1230 2621 1229 2621 1231 2621 1231 2622 1229 2622 1244 2622 1232 2623 1244 2623 1242 2623 1241 2624 1242 2624 1233 2624 1234 2625 1233 2625 1235 2625 1238 2626 1239 2626 1237 2626 1249 2627 1237 2627 1236 2627 1237 2628 1190 2628 1238 2628 1238 2629 1190 2629 1239 2629 1239 2630 1190 2630 1911 2630 1239 2631 1911 2631 1919 2631 1919 2632 1911 2632 1910 2632 1919 2633 1910 2633 1235 2633 1235 2634 1910 2634 1240 2634 1235 2635 1240 2635 1234 2635 1234 2636 1240 2636 1233 2636 1240 2637 1914 2637 1233 2637 1233 2638 1914 2638 1241 2638 1241 2639 1914 2639 1242 2639 1242 2640 1914 2640 1912 2640 1242 2641 1912 2641 1232 2641 1232 2642 1912 2642 1243 2642 1232 2643 1243 2643 1244 2643 1244 2644 1243 2644 1916 2644 1244 2645 1916 2645 1231 2645 1231 2646 1916 2646 1245 2646 1231 2647 1245 2647 1230 2647 1230 2648 1245 2648 1903 2648 1230 2649 1903 2649 1229 2649 1229 2650 1903 2650 1905 2650 1229 2651 1905 2651 1228 2651 1228 2652 1905 2652 1246 2652 1228 2653 1246 2653 1925 2653 1925 2654 1246 2654 1902 2654 1925 2655 1902 2655 1929 2655 1929 2656 1902 2656 1247 2656 1929 2657 1247 2657 1908 2657 1929 2658 1908 2658 1227 2658 1227 2659 1908 2659 1906 2659 1227 2660 1906 2660 1928 2660 1928 2661 1906 2661 1226 2661 1226 2662 1906 2662 1248 2662 1226 2663 1248 2663 1236 2663 1236 2664 1248 2664 1917 2664 1236 2665 1917 2665 1249 2665 1249 2666 1917 2666 1909 2666 1249 2667 1909 2667 1237 2667 1237 2668 1909 2668 1190 2668 1915 2669 1901 2669 1904 2669 1904 2670 1901 2670 1197 2670 1904 2671 1197 2671 1192 2671 1904 2672 1192 2672 1250 2672 1907 2673 1250 2673 1194 2673 1907 2674 1194 2674 1913 2674 1913 2675 1194 2675 2031 2675 1913 2676 2031 2676 1196 2676 1915 2677 1251 2677 1901 2677 1897 2678 1195 2678 1898 2678 1254 2679 1253 2679 1252 2679 1254 2680 1339 2680 1253 2680 2051 2681 1339 2681 1254 2681 2051 2682 2089 2682 1339 2682 2051 2683 1340 2683 2089 2683 2051 2684 1341 2684 1340 2684 1341 2685 1343 2685 1342 2685 1252 2686 1343 2686 1341 2686 1253 2687 1344 2687 1252 2687 1252 2688 1344 2688 1343 2688 1923 2689 2055 2689 2011 2689 2011 2690 2055 2690 1756 2690 1923 2691 2011 2691 1223 2691 1748 2692 2085 2692 1223 2692 1223 2693 1222 2693 1748 2693 1748 2694 1222 2694 1255 2694 1747 2695 1255 2695 1221 2695 1747 2696 1221 2696 1753 2696 1753 2697 1221 2697 2016 2697 1753 2698 2016 2698 1256 2698 2016 2699 1220 2699 1256 2699 1256 2700 1220 2700 1257 2700 1256 2701 1257 2701 1258 2701 1258 2702 1257 2702 1757 2702 1257 2703 1259 2703 1757 2703 1757 2704 1259 2704 2023 2704 1757 2705 2023 2705 1758 2705 1758 2706 2023 2706 1261 2706 2023 2707 1260 2707 1261 2707 1261 2708 1260 2708 1225 2708 1261 2709 1225 2709 1759 2709 1759 2710 1225 2710 1224 2710 1759 2711 1224 2711 1752 2711 1752 2712 1224 2712 1754 2712 1754 2713 1224 2713 2020 2713 1754 2714 2020 2714 1756 2714 1756 2715 2020 2715 1262 2715 1756 2716 1262 2716 2011 2716 2088 2717 1374 2717 2004 2717 1336 2718 1374 2718 2088 2718 2005 2719 2056 2719 2004 2719 2004 2720 2056 2720 2088 2720 1263 2721 2006 2721 1755 2721 1264 2722 1755 2722 2006 2722 1977 2723 1265 2723 1264 2723 1264 2724 1265 2724 1755 2724 1265 2725 1977 2725 1171 2725 1171 2726 1977 2726 1979 2726 1171 2727 1979 2727 1980 2727 1982 2728 1751 2728 1980 2728 1980 2729 1751 2729 1171 2729 1266 2730 1751 2730 1982 2730 1163 2731 1267 2731 1984 2731 1163 2732 1984 2732 1269 2732 1163 2733 1269 2733 1170 2733 1268 2734 1170 2734 1269 2734 1270 2735 1170 2735 1268 2735 1988 2736 1169 2736 1270 2736 1270 2737 1169 2737 1170 2737 1169 2738 1988 2738 1272 2738 1272 2739 1988 2739 1271 2739 1272 2740 1271 2740 1273 2740 1274 2741 1165 2741 1273 2741 1275 2742 1165 2742 1274 2742 1277 2743 1276 2743 1275 2743 1275 2744 1276 2744 1165 2744 1991 2745 1168 2745 1277 2745 1277 2746 1168 2746 1276 2746 1993 2747 1168 2747 1991 2747 1168 2748 1993 2748 1278 2748 1278 2749 1993 2749 1279 2749 1278 2750 1279 2750 1997 2750 1280 2751 1749 2751 1997 2751 1282 2752 1749 2752 1280 2752 1167 2753 1281 2753 1283 2753 1167 2754 1283 2754 1285 2754 1284 2755 1750 2755 1285 2755 1285 2756 1750 2756 1167 2756 2002 2757 1750 2757 1284 2757 1286 2758 1164 2758 2002 2758 2002 2759 1164 2759 1750 2759 1374 2760 1336 2760 1286 2760 1286 2761 1336 2761 1164 2761 1755 2762 1166 2762 1263 2762 1263 2763 1166 2763 2005 2763 2005 2764 1166 2764 2056 2764 1305 2765 1293 2765 1287 2765 1287 2766 1293 2766 1716 2766 1716 2767 1293 2767 1740 2767 1716 2768 1740 2768 1288 2768 1288 2769 1740 2769 1746 2769 1288 2770 1746 2770 1289 2770 1289 2771 1746 2771 1308 2771 1289 2772 1308 2772 1294 2772 1289 2773 1294 2773 1723 2773 1723 2774 1294 2774 1744 2774 1723 2775 1744 2775 1722 2775 1722 2776 1744 2776 1295 2776 1722 2777 1295 2777 1290 2777 1290 2778 1295 2778 1296 2778 1290 2779 1296 2779 1291 2779 1291 2780 1296 2780 1742 2780 1291 2781 1742 2781 1297 2781 1291 2782 1297 2782 1709 2782 1709 2783 1297 2783 1298 2783 1709 2784 1298 2784 1713 2784 1713 2785 1298 2785 1299 2785 1713 2786 1299 2786 1714 2786 1714 2787 1299 2787 1741 2787 1714 2788 1741 2788 1292 2788 1292 2789 1741 2789 1303 2789 1737 2790 1741 2790 1302 2790 1741 2791 1737 2791 1303 2791 1745 2792 1732 2792 1744 2792 1305 2793 1287 2793 1736 2793 1305 2794 1736 2794 1304 2794 1306 2795 1304 2795 1735 2795 1735 2796 1304 2796 1736 2796 1307 2797 1306 2797 1734 2797 1734 2798 1306 2798 1735 2798 1308 2799 1307 2799 1309 2799 1309 2800 1307 2800 1734 2800 1745 2801 1308 2801 1733 2801 1733 2802 1308 2802 1309 2802 1745 2803 1733 2803 1732 2803 1744 2804 1732 2804 1310 2804 1744 2805 1310 2805 1743 2805 1310 2806 1739 2806 1743 2806 1739 2807 1300 2807 1743 2807 1301 2808 1300 2808 1311 2808 1311 2809 1300 2809 1739 2809 1738 2810 1301 2810 1311 2810 1738 2811 1302 2811 1301 2811 1328 2812 1330 2812 1331 2812 1331 2813 1332 2813 1313 2813 1736 2814 1319 2814 1735 2814 1319 2815 1322 2815 1735 2815 1735 2816 1322 2816 1323 2816 1326 2817 1327 2817 1317 2817 1317 2818 1318 2818 1312 2818 2054 2819 1923 2819 1736 2819 1736 2820 1923 2820 1921 2820 1736 2821 1921 2821 1319 2821 1319 2822 1921 2822 1320 2822 1319 2823 1320 2823 1322 2823 1322 2824 1320 2824 1321 2824 1322 2825 1321 2825 1924 2825 1322 2826 1924 2826 1323 2826 1323 2827 1924 2827 1324 2827 1324 2828 1924 2828 1926 2828 1324 2829 1926 2829 1316 2829 1316 2830 1926 2830 1325 2830 1316 2831 1325 2831 1326 2831 1326 2832 1325 2832 1327 2832 1317 2833 1327 2833 1927 2833 1317 2834 1927 2834 1318 2834 1318 2835 1927 2835 1329 2835 1318 2836 1329 2836 1312 2836 1312 2837 1329 2837 1328 2837 1328 2838 1329 2838 1330 2838 1331 2839 1330 2839 1332 2839 1313 2840 1332 2840 1920 2840 1313 2841 1920 2841 1333 2841 1333 2842 1920 2842 1918 2842 1333 2843 1918 2843 1314 2843 1314 2844 1918 2844 1334 2844 1314 2845 1334 2845 1315 2845 1315 2846 1334 2846 1922 2846 1341 2847 1336 2847 1340 2847 1336 2848 1341 2848 1337 2848 1336 2849 1337 2849 1292 2849 1338 2850 1253 2850 1719 2850 1719 2851 1253 2851 1339 2851 1340 2852 2088 2852 2089 2852 1341 2853 1342 2853 1337 2853 1337 2854 1342 2854 2064 2854 1342 2855 1343 2855 2064 2855 2064 2856 1343 2856 1344 2856 2064 2857 1344 2857 1335 2857 1335 2858 1344 2858 1253 2858 1335 2859 1253 2859 1338 2859 2113 2860 1951 2860 1638 2860 1638 2861 1951 2861 1346 2861 1346 2862 1951 2862 1345 2862 1346 2863 1345 2863 1636 2863 1636 2864 1345 2864 1949 2864 1636 2865 1949 2865 1347 2865 1636 2866 1347 2866 1635 2866 1506 2867 1620 2867 1624 2867 1506 2868 1624 2868 1348 2868 1348 2869 1624 2869 1621 2869 1348 2870 1621 2870 1467 2870 1467 2871 1621 2871 1623 2871 1467 2872 1623 2872 1349 2872 1467 2873 1349 2873 1872 2873 1506 2874 1350 2874 1505 2874 1505 2875 1350 2875 1351 2875 1505 2876 1351 2876 1501 2876 1501 2877 1351 2877 1455 2877 1501 2878 1455 2878 1871 2878 1501 2879 1871 2879 1500 2879 1352 2880 1486 2880 1541 2880 1541 2881 1486 2881 1353 2881 1541 2882 1353 2882 1539 2882 1539 2883 1353 2883 1354 2883 1539 2884 1354 2884 1355 2884 1539 2885 1355 2885 1870 2885 1556 2886 1525 2886 1555 2886 1555 2887 1525 2887 1522 2887 1555 2888 1522 2888 1554 2888 1554 2889 1522 2889 1520 2889 1554 2890 1520 2890 2062 2890 2062 2891 1520 2891 1523 2891 2062 2892 1523 2892 1553 2892 2007 2893 1114 2893 1356 2893 1356 2894 1114 2894 1399 2894 1356 2895 1399 2895 1978 2895 1978 2896 1399 2896 1398 2896 1978 2897 1398 2897 1357 2897 1357 2898 1398 2898 1105 2898 1357 2899 1105 2899 1358 2899 1358 2900 1105 2900 1106 2900 1358 2901 1106 2901 1981 2901 1981 2902 1106 2902 1389 2902 1981 2903 1389 2903 1359 2903 1359 2904 1389 2904 1394 2904 1359 2905 1394 2905 1360 2905 1360 2906 1394 2906 1361 2906 1360 2907 1361 2907 1983 2907 1983 2908 1361 2908 1965 2908 1983 2909 1965 2909 1985 2909 1985 2910 1965 2910 1402 2910 1985 2911 1402 2911 1986 2911 1986 2912 1402 2912 1401 2912 1986 2913 1401 2913 1987 2913 1987 2914 1401 2914 1107 2914 1987 2915 1107 2915 1362 2915 1362 2916 1107 2916 1400 2916 1362 2917 1400 2917 1989 2917 1989 2918 1400 2918 1363 2918 1989 2919 1363 2919 1364 2919 1364 2920 1363 2920 1391 2920 1364 2921 1391 2921 1365 2921 1365 2922 1391 2922 1403 2922 1365 2923 1403 2923 1366 2923 1366 2924 1403 2924 1397 2924 1366 2925 1397 2925 1367 2925 1367 2926 1397 2926 1368 2926 1367 2927 1368 2927 1990 2927 1990 2928 1368 2928 1392 2928 1990 2929 1392 2929 1992 2929 1992 2930 1392 2930 1393 2930 1992 2931 1393 2931 1994 2931 1994 2932 1393 2932 1369 2932 1994 2933 1369 2933 1995 2933 1995 2934 1369 2934 1395 2934 1995 2935 1395 2935 1996 2935 1996 2936 1395 2936 1396 2936 1996 2937 1396 2937 1370 2937 1370 2938 1396 2938 1109 2938 1370 2939 1109 2939 1998 2939 1998 2940 1109 2940 1108 2940 1998 2941 1108 2941 1371 2941 1371 2942 1108 2942 1404 2942 1371 2943 1404 2943 1999 2943 1999 2944 1404 2944 1372 2944 1999 2945 1372 2945 2000 2945 2000 2946 1372 2946 1110 2946 2000 2947 1110 2947 2001 2947 2001 2948 1110 2948 1111 2948 2001 2949 1111 2949 1373 2949 1373 2950 1111 2950 1112 2950 1373 2951 1112 2951 2003 2951 2003 2952 1112 2952 1974 2952 2003 2953 1974 2953 1374 2953 1374 2954 1974 2954 1113 2954 1374 2955 1113 2955 2004 2955 2004 2956 1113 2956 1375 2956 2004 2957 1375 2957 2005 2957 2005 2958 1375 2958 1388 2958 2005 2959 1388 2959 2007 2959 2007 2960 1388 2960 1114 2960 1376 2961 1382 2961 2050 2961 1376 2962 1387 2962 1382 2962 1378 2963 1377 2963 1376 2963 1376 2964 1377 2964 1387 2964 2049 2965 1377 2965 1378 2965 1380 2966 2122 2966 2049 2966 1379 2967 2124 2967 1380 2967 1380 2968 2124 2968 2122 2968 2124 2969 1379 2969 1381 2969 2124 2970 1381 2970 1866 2970 1386 2971 1975 2971 1381 2971 1866 2972 1381 2972 1975 2972 2050 2973 1382 2973 1383 2973 2050 2974 1383 2974 2047 2974 2047 2975 1383 2975 1976 2975 2047 2976 1976 2976 1384 2976 1384 2977 1976 2977 1386 2977 1384 2978 1386 2978 1385 2978 1385 2979 1386 2979 1381 2979 2065 2980 2043 2980 2121 2980 1846 2981 2125 2981 1866 2981 1866 2982 2125 2982 2124 2982 1869 2983 1387 2983 2123 2983 2123 2984 1387 2984 1377 2984 1133 2985 2120 2985 1388 2985 1133 2986 1388 2986 1113 2986 1133 2987 1113 2987 1974 2987 1135 2988 1963 2988 1398 2988 2120 2989 1114 2989 1388 2989 1394 2990 1390 2990 1361 2990 1361 2991 1390 2991 1965 2991 1136 2992 2120 2992 1133 2992 1400 2993 1969 2993 1363 2993 1391 2994 1363 2994 1968 2994 1391 2995 1968 2995 1403 2995 1403 2996 1140 2996 1142 2996 1393 2997 1146 2997 2119 2997 1147 2998 1146 2998 1393 2998 1147 2999 1393 2999 1392 2999 1147 3000 1392 3000 1368 3000 1967 3001 1390 3001 1394 3001 1967 3002 1394 3002 1960 3002 1389 3003 1960 3003 1394 3003 1966 3004 1137 3004 1400 3004 1393 3005 2119 3005 1369 3005 1369 3006 2119 3006 1395 3006 1971 3007 1108 3007 1396 3007 1971 3008 1396 3008 2119 3008 2119 3009 1396 3009 1395 3009 1149 3010 1973 3010 1112 3010 1403 3011 1142 3011 1368 3011 1403 3012 1368 3012 1397 3012 1404 3013 1108 3013 1131 3013 1135 3014 1398 3014 1399 3014 1135 3015 1399 3015 1114 3015 1137 3016 1969 3016 1400 3016 1966 3017 1400 3017 1401 3017 1966 3018 1401 3018 1402 3018 1966 3019 1402 3019 1965 3019 1968 3020 1140 3020 1403 3020 1971 3021 1131 3021 1108 3021 1973 3022 1133 3022 1112 3022 1112 3023 1133 3023 1974 3023 1372 3024 1149 3024 1112 3024 1372 3025 1112 3025 1110 3025 1963 3026 1959 3026 1398 3026 1398 3027 1959 3027 1105 3027 1105 3028 1959 3028 1106 3028 1106 3029 1959 3029 1389 3029 1972 3030 1131 3030 1971 3030 1688 3031 2115 3031 2106 3031 1409 3032 1822 3032 2104 3032 2104 3033 1822 3033 1405 3033 1676 3034 1656 3034 2105 3034 2105 3035 1656 3035 1406 3035 1407 3036 1408 3036 2103 3036 1656 3037 1408 3037 1407 3037 1690 3038 1691 3038 1130 3038 1130 3039 1691 3039 1820 3039 1676 3040 1409 3040 1408 3040 1408 3041 1409 3041 2104 3041 1408 3042 2104 3042 2103 3042 1151 3043 1692 3043 1410 3043 1410 3044 1692 3044 1130 3044 1677 3045 1676 3045 2105 3045 1411 3046 1412 3046 1413 3046 1411 3047 1413 3047 1416 3047 1419 3048 1414 3048 1842 3048 1419 3049 1842 3049 1415 3049 1415 3050 1843 3050 1417 3050 1417 3051 1843 3051 1844 3051 1417 3052 1416 3052 1413 3052 1417 3053 1413 3053 1415 3053 1415 3054 1413 3054 1543 3054 1418 3055 1117 3055 1695 3055 1418 3056 1695 3056 2098 3056 2107 3057 1419 3057 1684 3057 1684 3058 1419 3058 1415 3058 1420 3059 1418 3059 2100 3059 1862 3060 1421 3060 1422 3060 1421 3061 2063 3061 1422 3061 1858 3062 1665 3062 1425 3062 1858 3063 1425 3063 1423 3063 1424 3064 1856 3064 1857 3064 2063 3065 1856 3065 1424 3065 2101 3066 1697 3066 2111 3066 1425 3067 1422 3067 1424 3067 1424 3068 1422 3068 2063 3068 1681 3069 1425 3069 1665 3069 1189 3070 1428 3070 1429 3070 2058 3071 1428 3071 1189 3071 1426 3072 1429 3072 2058 3072 2058 3073 1429 3073 1428 3073 1429 3074 1426 3074 1549 3074 1430 3075 1561 3075 2096 3075 1437 3076 1436 3076 1431 3076 1432 3077 1437 3077 1431 3077 1433 3078 2099 3078 1118 3078 1655 3079 1118 3079 2099 3079 1435 3080 1655 3080 1434 3080 1435 3081 1436 3081 1437 3081 1439 3082 1728 3082 1438 3082 1438 3083 1728 3083 2059 3083 1438 3084 2059 3084 1731 3084 1155 3085 1433 3085 1118 3085 1686 3086 1439 3086 1440 3086 1442 3087 1578 3087 1775 3087 1441 3088 1775 3088 2118 3088 2118 3089 1775 3089 1578 3089 1773 3090 1441 3090 2118 3090 1443 3091 1442 3091 1775 3091 1445 3092 1116 3092 1771 3092 1116 3093 1772 3093 1771 3093 1444 3094 1116 3094 1445 3094 1444 3095 1445 3095 1579 3095 1460 3096 1767 3096 1768 3096 1460 3097 1766 3097 1767 3097 1460 3098 1768 3098 1446 3098 1770 3099 1582 3099 1768 3099 1768 3100 1582 3100 1446 3100 1765 3101 1127 3101 1447 3101 1127 3102 1448 3102 1447 3102 1447 3103 1448 3103 1450 3103 1449 3104 1450 3104 1448 3104 1453 3105 1761 3105 1452 3105 1452 3106 1761 3106 1464 3106 1451 3107 1465 3107 1453 3107 1451 3108 1453 3108 1452 3108 1589 3109 1867 3109 1662 3109 1455 3110 1351 3110 1454 3110 1454 3111 1351 3111 1350 3111 1455 3112 2037 3112 1871 3112 1506 3113 1468 3113 1663 3113 1849 3114 1506 3114 1663 3114 1455 3115 1456 3115 2037 3115 1350 3116 1506 3116 1849 3116 1350 3117 1849 3117 1454 3117 1773 3118 2118 3118 1592 3118 1443 3119 1774 3119 1457 3119 1457 3120 1774 3120 1592 3120 1592 3121 1774 3121 1773 3121 1772 3122 1116 3122 1593 3122 1459 3123 1445 3123 1458 3123 1459 3124 1458 3124 1593 3124 1593 3125 1458 3125 1772 3125 1461 3126 1769 3126 1766 3126 1769 3127 1461 3127 1596 3127 1769 3128 1596 3128 1770 3128 1595 3129 1122 3129 1596 3129 1596 3130 1122 3130 1770 3130 1597 3131 1764 3131 1763 3131 1765 3132 1764 3132 1597 3132 1763 3133 1462 3133 1449 3133 1763 3134 1449 3134 1597 3134 1760 3135 1463 3135 1464 3135 1463 3136 1760 3136 1602 3136 1602 3137 1760 3137 1465 3137 1867 3138 1619 3138 1466 3138 1867 3139 1466 3139 1662 3139 2038 3140 1467 3140 1872 3140 1468 3141 1848 3141 1663 3141 1348 3142 1467 3142 1848 3142 2038 3143 1456 3143 1467 3143 1348 3144 1848 3144 1468 3144 1348 3145 1468 3145 1506 3145 1471 3146 1469 3146 1472 3146 1470 3147 1472 3147 1569 3147 1569 3148 1472 3148 1469 3148 1473 3149 1471 3149 1472 3149 1475 3150 1474 3150 1790 3150 1790 3151 1474 3151 1789 3151 1571 3152 1474 3152 1475 3152 1571 3153 1475 3153 1476 3153 1479 3154 1480 3154 1478 3154 1494 3155 1477 3155 1479 3155 1479 3156 1477 3156 1480 3156 1788 3157 1481 3157 1785 3157 1785 3158 1481 3158 1573 3158 1496 3159 1481 3159 1788 3159 1573 3160 1786 3160 1785 3160 1782 3161 1482 3161 1484 3161 1484 3162 1482 3162 1783 3162 1483 3163 1661 3163 1782 3163 1483 3164 1782 3164 1484 3164 1577 3165 1868 3165 1485 3165 1577 3166 1485 3166 1499 3166 1354 3167 1353 3167 2046 3167 2046 3168 1353 3168 1486 3168 1354 3169 2040 3169 1355 3169 1851 3170 1352 3170 1850 3170 1352 3171 1502 3171 1850 3171 1354 3172 2039 3172 2040 3172 1486 3173 1352 3173 1851 3173 1486 3174 1851 3174 2046 3174 1791 3175 1488 3175 1792 3175 1470 3176 1488 3176 1791 3176 1473 3177 1792 3177 1487 3177 1487 3178 1792 3178 1488 3178 1489 3179 1490 3179 1580 3179 1580 3180 1490 3180 1789 3180 1491 3181 1475 3181 1489 3181 1491 3182 1489 3182 1580 3182 1581 3183 1492 3183 1478 3183 1492 3184 1581 3184 1493 3184 1492 3185 1493 3185 1494 3185 1496 3186 1787 3186 1584 3186 1787 3187 1786 3187 1584 3187 1786 3188 1495 3188 1583 3188 1786 3189 1583 3189 1584 3189 1497 3190 1588 3190 1783 3190 1588 3191 1497 3191 1498 3191 1498 3192 1497 3192 1661 3192 1499 3193 1793 3193 1590 3193 1504 3194 1501 3194 1500 3194 1852 3195 1502 3195 2112 3195 2112 3196 1503 3196 1852 3196 1505 3197 1501 3197 1503 3197 1504 3198 2039 3198 1501 3198 1505 3199 1503 3199 2112 3199 1505 3200 2112 3200 1506 3200 1510 3201 1508 3201 1507 3201 1811 3202 1507 3202 1508 3202 2116 3203 1811 3203 1508 3203 1509 3204 1510 3204 1507 3204 1512 3205 1557 3205 1511 3205 1557 3206 1527 3206 1511 3206 1558 3207 1557 3207 1512 3207 1558 3208 1512 3208 1513 3208 1807 3209 1559 3209 1806 3209 1807 3210 1515 3210 1559 3210 1515 3211 1514 3211 1559 3211 1804 3212 1516 3212 1803 3212 1803 3213 1516 3213 1560 3213 1659 3214 1516 3214 1804 3214 1560 3215 1533 3215 1803 3215 1517 3216 1801 3216 1519 3216 1519 3217 1801 3217 1535 3217 1518 3218 1660 3218 1517 3218 1518 3219 1517 3219 1519 3219 1865 3220 1864 3220 1658 3220 1520 3221 1522 3221 1521 3221 1521 3222 1522 3222 1525 3222 1520 3223 2041 3223 1523 3223 1855 3224 1556 3224 1853 3224 1520 3225 1524 3225 2041 3225 1525 3226 1556 3226 1855 3226 1525 3227 1855 3227 1521 3227 1810 3228 2116 3228 1812 3228 1507 3229 1812 3229 1570 3229 1570 3230 1812 3230 1526 3230 1526 3231 1812 3231 2116 3231 1529 3232 1809 3232 1527 3232 1528 3233 1512 3233 1529 3233 1528 3234 1529 3234 1530 3234 1530 3235 1529 3235 1527 3235 1532 3236 1808 3236 1572 3236 1572 3237 1808 3237 1806 3237 1532 3238 1572 3238 1531 3238 1531 3239 1515 3239 1532 3239 1659 3240 1805 3240 1534 3240 1805 3241 1533 3241 1534 3241 1533 3242 1574 3242 1534 3242 1800 3243 1536 3243 1535 3243 1536 3244 1800 3244 1576 3244 1576 3245 1800 3245 1660 3245 1538 3246 1868 3246 1537 3246 1538 3247 1537 3247 1658 3247 1542 3248 1539 3248 1870 3248 2110 3249 1854 3249 1853 3249 2110 3250 1540 3250 1854 3250 1541 3251 1539 3251 1540 3251 1542 3252 1524 3252 1539 3252 1541 3253 1540 3253 2110 3253 1541 3254 2110 3254 1352 3254 1543 3255 1841 3255 1545 3255 1545 3256 1841 3256 1544 3256 1545 3257 1544 3257 2115 3257 1838 3258 1837 3258 1840 3258 1546 3259 1432 3259 1838 3259 1546 3260 1838 3260 1547 3260 1547 3261 1838 3261 1840 3261 2057 3262 1833 3262 1548 3262 1548 3263 1833 3263 1834 3263 2057 3264 1548 3264 1549 3264 1561 3265 1831 3265 2091 3265 1561 3266 2091 3266 1550 3266 1561 3267 1430 3267 1831 3267 1830 3268 1120 3268 2091 3268 2091 3269 1120 3269 1550 3269 1551 3270 2111 3270 1825 3270 1552 3271 2111 3271 1551 3271 1552 3272 1551 3272 1566 3272 1566 3273 1551 3273 1657 3273 1846 3274 1567 3274 1568 3274 1846 3275 1568 3275 1847 3275 2042 3276 2045 3276 1553 3276 1553 3277 2045 3277 2062 3277 2109 3278 1861 3278 1862 3278 2109 3279 1860 3279 1859 3279 2109 3280 1859 3280 1861 3280 1555 3281 1554 3281 1860 3281 1555 3282 1860 3282 2109 3282 1555 3283 2109 3283 1556 3283 2115 3284 1508 3284 1545 3284 1545 3285 1508 3285 1510 3285 1545 3286 1510 3286 1543 3286 1543 3287 1510 3287 1509 3287 1547 3288 1557 3288 1558 3288 1547 3289 1558 3289 1546 3289 1546 3290 1558 3290 1513 3290 1548 3291 1559 3291 1514 3291 1548 3292 1514 3292 1549 3292 1120 3293 1560 3293 1550 3293 1550 3294 1560 3294 1516 3294 1550 3295 1516 3295 1561 3295 1124 3296 1562 3296 1564 3296 1564 3297 1562 3297 1563 3297 1564 3298 1563 3298 1565 3298 1564 3299 1565 3299 1820 3299 1566 3300 1518 3300 1519 3300 1566 3301 1519 3301 1552 3301 1552 3302 1519 3302 2111 3302 1567 3303 1865 3303 1568 3303 1526 3304 1569 3304 1469 3304 1526 3305 1469 3305 1471 3305 1526 3306 1471 3306 1570 3306 1530 3307 1474 3307 1571 3307 1530 3308 1571 3308 1528 3308 1528 3309 1571 3309 1476 3309 1572 3310 1480 3310 1477 3310 1572 3311 1477 3311 1531 3311 1574 3312 1573 3312 1481 3312 1574 3313 1481 3313 1534 3313 1575 3314 1797 3314 1798 3314 1575 3315 1798 3315 1817 3315 1576 3316 1483 3316 1484 3316 1576 3317 1484 3317 1536 3317 1868 3318 1577 3318 1537 3318 1537 3319 1577 3319 1590 3319 1488 3320 2118 3320 1578 3320 1488 3321 1578 3321 1442 3321 1488 3322 1442 3322 1487 3322 1580 3323 1116 3323 1444 3323 1580 3324 1444 3324 1579 3324 1580 3325 1579 3325 1491 3325 1581 3326 1460 3326 1446 3326 1581 3327 1446 3327 1582 3327 1581 3328 1582 3328 1493 3328 1495 3329 1449 3329 1448 3329 1495 3330 1448 3330 1583 3330 1583 3331 1448 3331 1584 3331 1584 3332 1448 3332 1127 3332 1585 3333 1125 3333 1777 3333 1585 3334 1777 3334 1587 3334 1585 3335 1587 3335 1586 3335 1586 3336 1587 3336 1128 3336 1498 3337 1451 3337 1452 3337 1498 3338 1452 3338 1588 3338 2118 3339 1591 3339 1592 3339 1592 3340 1591 3340 1606 3340 1592 3341 1606 3341 1457 3341 1116 3342 1608 3342 1593 3342 1593 3343 1608 3343 1610 3343 1593 3344 1610 3344 1611 3344 1593 3345 1611 3345 1459 3345 1460 3346 1594 3346 1461 3346 1461 3347 1594 3347 1614 3347 1461 3348 1614 3348 1595 3348 1461 3349 1595 3349 1596 3349 1449 3350 1617 3350 1598 3350 1449 3351 1598 3351 1597 3351 1597 3352 1598 3352 1599 3352 1597 3353 1599 3353 1127 3353 1125 3354 1600 3354 1781 3354 1781 3355 1600 3355 1601 3355 1602 3356 1603 3356 1618 3356 1602 3357 1618 3357 1463 3357 1619 3358 1604 3358 1466 3358 1466 3359 1604 3359 1625 3359 1606 3360 1591 3360 1880 3360 1605 3361 1880 3361 1591 3361 2117 3362 1605 3362 1591 3362 1607 3363 1606 3363 1880 3363 1608 3364 1115 3364 1609 3364 1612 3365 1608 3365 1609 3365 1610 3366 1608 3366 1612 3366 1610 3367 1612 3367 1611 3367 1611 3368 1612 3368 1613 3368 1877 3369 1594 3369 1652 3369 1594 3370 1877 3370 1614 3370 1877 3371 1653 3371 1595 3371 1877 3372 1595 3372 1614 3372 1615 3373 1599 3373 1616 3373 1599 3374 1598 3374 1616 3374 1616 3375 1598 3375 1617 3375 1630 3376 1599 3376 1615 3376 1617 3377 1629 3377 1616 3377 1886 3378 1887 3378 1618 3378 1618 3379 1887 3379 1888 3379 1603 3380 1633 3380 1886 3380 1603 3381 1886 3381 1618 3381 1604 3382 1619 3382 1882 3382 1604 3383 1882 3383 1651 3383 1623 3384 1621 3384 1622 3384 1622 3385 1621 3385 1624 3385 1623 3386 2036 3386 1349 3386 1891 3387 1620 3387 1889 3387 1620 3388 1637 3388 1889 3388 1623 3389 2035 3389 2036 3389 1624 3390 1620 3390 1891 3390 1624 3391 1891 3391 1622 3391 1606 3392 1881 3392 1640 3392 1640 3393 1881 3393 1639 3393 1879 3394 2117 3394 1881 3394 1639 3395 1881 3395 2117 3395 1639 3396 2117 3396 1625 3396 1626 3397 1878 3397 1115 3397 1626 3398 1641 3398 1611 3398 1641 3399 1626 3399 1115 3399 1641 3400 1115 3400 1627 3400 1644 3401 1876 3401 1652 3401 1876 3402 1644 3402 1643 3402 1876 3403 1643 3403 1628 3403 1595 3404 1628 3404 1643 3404 1645 3405 1629 3405 1617 3405 1630 3406 1631 3406 1126 3406 1126 3407 1631 3407 1645 3407 1126 3408 1645 3408 1646 3408 1631 3409 1629 3409 1645 3409 1948 3410 2113 3410 1649 3410 1632 3411 2113 3411 1888 3411 1649 3412 2113 3412 1632 3412 1649 3413 1632 3413 1633 3413 1649 3414 1633 3414 1603 3414 1882 3415 1650 3415 1651 3415 1634 3416 1636 3416 1635 3416 1890 3417 1637 3417 2113 3417 2113 3418 1892 3418 1890 3418 1346 3419 1636 3419 1892 3419 1634 3420 2035 3420 1636 3420 1346 3421 1892 3421 2113 3421 1346 3422 2113 3422 1638 3422 1956 3423 1639 3423 1625 3423 1956 3424 1640 3424 1639 3424 1627 3425 1954 3425 1955 3425 1627 3426 1955 3426 1641 3426 1641 3427 1955 3427 1930 3427 1641 3428 1930 3428 1611 3428 1642 3429 1644 3429 1119 3429 1642 3430 1643 3430 1644 3430 1643 3431 1642 3431 1935 3431 1643 3432 1935 3432 1595 3432 1617 3433 1936 3433 1645 3433 1645 3434 1936 3434 1646 3434 1941 3435 1648 3435 1940 3435 1940 3436 1648 3436 1647 3436 1648 3437 1941 3437 1601 3437 1948 3438 1649 3438 1944 3438 1944 3439 1649 3439 1603 3439 1650 3440 1958 3440 1625 3440 1701 3441 1429 3441 1702 3441 1427 3442 2057 3442 1426 3442 2093 3443 1831 3443 1430 3443 1684 3444 1117 3444 1671 3444 1678 3445 1679 3445 1680 3445 1187 3446 1683 3446 1188 3446 1155 3447 1672 3447 1420 3447 1155 3448 1420 3448 1664 3448 1155 3449 1664 3449 2099 3449 1666 3450 1187 3450 1665 3450 1161 3451 1162 3451 2065 3451 1160 3452 2043 3452 2065 3452 2065 3453 1162 3453 1667 3453 1667 3454 1162 3454 1161 3454 1668 3455 2087 3455 2065 3455 1667 3456 1161 3456 2065 3456 1667 3457 2065 3457 2087 3457 2087 3458 1669 3458 1667 3458 1667 3459 1669 3459 1670 3459 1670 3460 1669 3460 2114 3460 1670 3461 2114 3461 2107 3461 1670 3462 2107 3462 1671 3462 1420 3463 1672 3463 1671 3463 1672 3464 1155 3464 1673 3464 1673 3465 1686 3465 1685 3465 1673 3466 1685 3466 1183 3466 1155 3467 1118 3467 1673 3467 1673 3468 1118 3468 1686 3468 1184 3469 1158 3469 1674 3469 1183 3470 2097 3470 1184 3470 1184 3471 2097 3471 1158 3471 1158 3472 1123 3472 1674 3472 1674 3473 1123 3473 1151 3473 1152 3474 1151 3474 2108 3474 1152 3475 2108 3475 1151 3475 1674 3476 1151 3476 1410 3476 1674 3477 1410 3477 1675 3477 1675 3478 1410 3478 1676 3478 1675 3479 1676 3479 1677 3479 1675 3480 1677 3480 1678 3480 1677 3481 1406 3481 1679 3481 1677 3482 1679 3482 1678 3482 1681 3483 1187 3483 1680 3483 1681 3484 1680 3484 2111 3484 2111 3485 1680 3485 1679 3485 1681 3486 1665 3486 1187 3486 1666 3487 1682 3487 1187 3487 1187 3488 1682 3488 1683 3488 1160 3489 1683 3489 2086 3489 2043 3490 1160 3490 2086 3490 2043 3491 2086 3491 1172 3491 1701 3492 1157 3492 1183 3492 1671 3493 2107 3493 1684 3493 1666 3494 1727 3494 1682 3494 1183 3495 1157 3495 2097 3495 1157 3496 2092 3496 2097 3496 1429 3497 1701 3497 1183 3497 1183 3498 1189 3498 1429 3498 2060 3499 2058 3499 1189 3499 2060 3500 1189 3500 1183 3500 1183 3501 1685 3501 2060 3501 1117 3502 1420 3502 1671 3502 2115 3503 1687 3503 2106 3503 1688 3504 2106 3504 1845 3504 1691 3505 1826 3505 1689 3505 1690 3506 1826 3506 1691 3506 1692 3507 1827 3507 1828 3507 1692 3508 1828 3508 1130 3508 1693 3509 1690 3509 1130 3509 1693 3510 1130 3510 1694 3510 1695 3511 1117 3511 1839 3511 1695 3512 1839 3512 2098 3512 1117 3513 1840 3513 1839 3513 2100 3514 1654 3514 1696 3514 1418 3515 1654 3515 2100 3515 1418 3516 2098 3516 1696 3516 1654 3517 1418 3517 1696 3517 1698 3518 1825 3518 1697 3518 2102 3519 1699 3519 1824 3519 2101 3520 1700 3520 1823 3520 2095 3521 2091 3521 1703 3521 1704 3522 2095 3522 1703 3522 1818 3523 1829 3523 1705 3523 1159 3524 2097 3524 1707 3524 1707 3525 2097 3525 2092 3525 2108 3526 1708 3526 1706 3526 2094 3527 1707 3527 2092 3527 2090 3528 1707 3528 2094 3528 1708 3529 2108 3529 1706 3529 2095 3530 1704 3530 2094 3530 2094 3531 1704 3531 2090 3531 1158 3532 2097 3532 1159 3532 1711 3533 1178 3533 1713 3533 1337 3534 2064 3534 1180 3534 1337 3535 1180 3535 1292 3535 1713 3536 1178 3536 1709 3536 1709 3537 1178 3537 1710 3537 1709 3538 1710 3538 1291 3538 1291 3539 1710 3539 1175 3539 1291 3540 1175 3540 1290 3540 1711 3541 1713 3541 1712 3541 1712 3542 1713 3542 1714 3542 1712 3543 1714 3543 1180 3543 1714 3544 1292 3544 1180 3544 1289 3545 1174 3545 1288 3545 1288 3546 1174 3546 1715 3546 1288 3547 1715 3547 1717 3547 1288 3548 1717 3548 1716 3548 1716 3549 1717 3549 1718 3549 1716 3550 1718 3550 1287 3550 1287 3551 1718 3551 1719 3551 1290 3552 1175 3552 1720 3552 1290 3553 1720 3553 1721 3553 1290 3554 1721 3554 1722 3554 1722 3555 1721 3555 1724 3555 1722 3556 1724 3556 1723 3556 1723 3557 1724 3557 1725 3557 1723 3558 1725 3558 1289 3558 1289 3559 1725 3559 1174 3559 2061 3560 1859 3560 2062 3560 2044 3561 1726 3561 1727 3561 1682 3562 1726 3562 1683 3562 1834 3563 1832 3563 1728 3563 2059 3564 1728 3564 1832 3564 1729 3565 1440 3565 1439 3565 1729 3566 1439 3566 1730 3566 1835 3567 1836 3567 1438 3567 1835 3568 1438 3568 1731 3568 1312 3569 1310 3569 1317 3569 1317 3570 1310 3570 1732 3570 1317 3571 1732 3571 1326 3571 1326 3572 1732 3572 1733 3572 1326 3573 1733 3573 1316 3573 1316 3574 1733 3574 1324 3574 1324 3575 1733 3575 1309 3575 1324 3576 1309 3576 1323 3576 1323 3577 1309 3577 1734 3577 1323 3578 1734 3578 1735 3578 2054 3579 1736 3579 1287 3579 1315 3580 1303 3580 1314 3580 1314 3581 1303 3581 1737 3581 1314 3582 1737 3582 1333 3582 1333 3583 1737 3583 1302 3583 1333 3584 1302 3584 1313 3584 1313 3585 1302 3585 1738 3585 1313 3586 1738 3586 1331 3586 1331 3587 1738 3587 1311 3587 1331 3588 1311 3588 1328 3588 1328 3589 1311 3589 1739 3589 1328 3590 1739 3590 1312 3590 1312 3591 1739 3591 1310 3591 1306 3592 1740 3592 1304 3592 1304 3593 1740 3593 1293 3593 1304 3594 1293 3594 1305 3594 1302 3595 1741 3595 1299 3595 1302 3596 1299 3596 1301 3596 1301 3597 1299 3597 1298 3597 1301 3598 1298 3598 1297 3598 1301 3599 1297 3599 1300 3599 1300 3600 1297 3600 1742 3600 1300 3601 1742 3601 1743 3601 1743 3602 1742 3602 1296 3602 1743 3603 1296 3603 1295 3603 1743 3604 1295 3604 1744 3604 1745 3605 1744 3605 1294 3605 1745 3606 1294 3606 1308 3606 1307 3607 1308 3607 1746 3607 1307 3608 1746 3608 1306 3608 1306 3609 1746 3609 1740 3609 2085 3610 1750 3610 1336 3610 1753 3611 1749 3611 1747 3611 1255 3612 1750 3612 1748 3612 1748 3613 1750 3613 2085 3613 1747 3614 1749 3614 1255 3614 1255 3615 1749 3615 1750 3615 1752 3616 1751 3616 1759 3616 1759 3617 1751 3617 1163 3617 1754 3618 1755 3618 1751 3618 1754 3619 1751 3619 1752 3619 1256 3620 1168 3620 1749 3620 1256 3621 1749 3621 1753 3621 1757 3622 1276 3622 1258 3622 1756 3623 1755 3623 1754 3623 1276 3624 1168 3624 1258 3624 1258 3625 1168 3625 1256 3625 2055 3626 1755 3626 1756 3626 1758 3627 1272 3627 1757 3627 1757 3628 1272 3628 1276 3628 1261 3629 1272 3629 1758 3629 1759 3630 1163 3630 1261 3630 1261 3631 1163 3631 1272 3631 1755 3632 2055 3632 2056 3632 1453 3633 1465 3633 1760 3633 1453 3634 1760 3634 1761 3634 1761 3635 1760 3635 1464 3635 1776 3636 1780 3636 1762 3636 1776 3637 1762 3637 1778 3637 1778 3638 1762 3638 1779 3638 1450 3639 1462 3639 1763 3639 1450 3640 1763 3640 1447 3640 1447 3641 1763 3641 1764 3641 1447 3642 1764 3642 1765 3642 1767 3643 1766 3643 1769 3643 1767 3644 1769 3644 1768 3644 1768 3645 1769 3645 1770 3645 1771 3646 1772 3646 1458 3646 1771 3647 1458 3647 1445 3647 1441 3648 1773 3648 1775 3648 1775 3649 1773 3649 1774 3649 1775 3650 1774 3650 1443 3650 1125 3651 1780 3651 1776 3651 1778 3652 1125 3652 1776 3652 1125 3653 1778 3653 1777 3653 1779 3654 1128 3654 1778 3654 1778 3655 1128 3655 1587 3655 1778 3656 1587 3656 1777 3656 1780 3657 1125 3657 1781 3657 1780 3658 1781 3658 1762 3658 1762 3659 1781 3659 1779 3659 1128 3660 1779 3660 1601 3660 1601 3661 1779 3661 1781 3661 1782 3662 1661 3662 1497 3662 1782 3663 1497 3663 1482 3663 1482 3664 1497 3664 1783 3664 1794 3665 1799 3665 1795 3665 1795 3666 1799 3666 1784 3666 1795 3667 1784 3667 1796 3667 1785 3668 1786 3668 1787 3668 1785 3669 1787 3669 1788 3669 1788 3670 1787 3670 1496 3670 1479 3671 1478 3671 1492 3671 1479 3672 1492 3672 1494 3672 1789 3673 1490 3673 1790 3673 1790 3674 1490 3674 1489 3674 1790 3675 1489 3675 1475 3675 1470 3676 1791 3676 1472 3676 1472 3677 1791 3677 1792 3677 1472 3678 1792 3678 1473 3678 1485 3679 1793 3679 1499 3679 1795 3680 1797 3680 1794 3680 1795 3681 1796 3681 1797 3681 1796 3682 1798 3682 1797 3682 1784 3683 1799 3683 1585 3683 1585 3684 1799 3684 1794 3684 1784 3685 1585 3685 1586 3685 1586 3686 1796 3686 1784 3686 1517 3687 1660 3687 1800 3687 1517 3688 1800 3688 1801 3688 1801 3689 1800 3689 1535 3689 1814 3690 1802 3690 1813 3690 1813 3691 1802 3691 1816 3691 1813 3692 1816 3692 1815 3692 1803 3693 1533 3693 1805 3693 1803 3694 1805 3694 1804 3694 1804 3695 1805 3695 1659 3695 1806 3696 1808 3696 1807 3696 1807 3697 1808 3697 1532 3697 1807 3698 1532 3698 1515 3698 1511 3699 1527 3699 1809 3699 1511 3700 1809 3700 1529 3700 1511 3701 1529 3701 1512 3701 1811 3702 2116 3702 1810 3702 1811 3703 1810 3703 1812 3703 1811 3704 1812 3704 1507 3704 1864 3705 1538 3705 1658 3705 1813 3706 1562 3706 1814 3706 1813 3707 1815 3707 1562 3707 1815 3708 1565 3708 1563 3708 1815 3709 1563 3709 1562 3709 1816 3710 1802 3710 1575 3710 1575 3711 1802 3711 1814 3711 1816 3712 1575 3712 1817 3712 1817 3713 1815 3713 1816 3713 1124 3714 1819 3714 1829 3714 1124 3715 1829 3715 1818 3715 1124 3716 1564 3716 1819 3716 1819 3717 1564 3717 1821 3717 1820 3718 1821 3718 1564 3718 1822 3719 1657 3719 1551 3719 1407 3720 1406 3720 1656 3720 1551 3721 1698 3721 1699 3721 1551 3722 1699 3722 1406 3722 1699 3723 1823 3723 1700 3723 1699 3724 1700 3724 1824 3724 1698 3725 1551 3725 1825 3725 1406 3726 1407 3726 1551 3726 1551 3727 1407 3727 1405 3727 1551 3728 1405 3728 1822 3728 1827 3729 1693 3729 1694 3729 1827 3730 1694 3730 1828 3730 1829 3731 1819 3731 1826 3731 1826 3732 1819 3732 1689 3732 1689 3733 1819 3733 1821 3733 1827 3734 2108 3734 1693 3734 1693 3735 2108 3735 1826 3735 1826 3736 2108 3736 1829 3736 2092 3737 1157 3737 1702 3737 2092 3738 1702 3738 2091 3738 2091 3739 1702 3739 1830 3739 1831 3740 1703 3740 2091 3740 2093 3741 1156 3741 1707 3741 2093 3742 1707 3742 1703 3742 2093 3743 1703 3743 1831 3743 1833 3744 2057 3744 1832 3744 2060 3745 1729 3745 2058 3745 2058 3746 1729 3746 1835 3746 2058 3747 1835 3747 1832 3747 2058 3748 1832 3748 2057 3748 1833 3749 1832 3749 1834 3749 1835 3750 1729 3750 1836 3750 1836 3751 1729 3751 1730 3751 1434 3752 2099 3752 1664 3752 1837 3753 1431 3753 1434 3753 1837 3754 1838 3754 1431 3754 1431 3755 1838 3755 1432 3755 1664 3756 1696 3756 1837 3756 1664 3757 1837 3757 1434 3757 2099 3758 1434 3758 1655 3758 1839 3759 1840 3759 1837 3759 1839 3760 1837 3760 1696 3760 1411 3761 1544 3761 1841 3761 1843 3762 1842 3762 1414 3762 1843 3763 1414 3763 1844 3763 1687 3764 1844 3764 1845 3764 1414 3765 1153 3765 1845 3765 1411 3766 1841 3766 1412 3766 1411 3767 1687 3767 1544 3767 1844 3768 1414 3768 1845 3768 2121 3769 2125 3769 2065 3769 2065 3770 2125 3770 1846 3770 2065 3771 1846 3771 1847 3771 2065 3772 1847 3772 1668 3772 1849 3773 1663 3773 1848 3773 1849 3774 1848 3774 1454 3774 1850 3775 1502 3775 1852 3775 1850 3776 1852 3776 1851 3776 1851 3777 1852 3777 1503 3777 1851 3778 1503 3778 2046 3778 1853 3779 1854 3779 1855 3779 1855 3780 1854 3780 1540 3780 1855 3781 1540 3781 1521 3781 1856 3782 1858 3782 1857 3782 1857 3783 1858 3783 1423 3783 1861 3784 1859 3784 1421 3784 1666 3785 1858 3785 1727 3785 1727 3786 1858 3786 1856 3786 1727 3787 1856 3787 1421 3787 1727 3788 1421 3788 1859 3788 1861 3789 1421 3789 1862 3789 1975 3790 1150 3790 1866 3790 1866 3791 1150 3791 1863 3791 1882 3792 1866 3792 1863 3792 1882 3793 1863 3793 1650 3793 1650 3794 1863 3794 1958 3794 1864 3795 1865 3795 1567 3795 1882 3796 1619 3796 1867 3796 1882 3797 1867 3797 1866 3797 1589 3798 1590 3798 1867 3798 1867 3799 1590 3799 1793 3799 1867 3800 1793 3800 1866 3800 1866 3801 1793 3801 1485 3801 1485 3802 1868 3802 1538 3802 1485 3803 1538 3803 1866 3803 1866 3804 1538 3804 1864 3804 1866 3805 1864 3805 1846 3805 1846 3806 1864 3806 1567 3806 1873 3807 1962 3807 1382 3807 1387 3808 1869 3808 2042 3808 1553 3809 1523 3809 2042 3809 2042 3810 1523 3810 2041 3810 2042 3811 2041 3811 1387 3811 1870 3812 1355 3812 1542 3812 1542 3813 1355 3813 2040 3813 1504 3814 1500 3814 1871 3814 1871 3815 2037 3815 1504 3815 1504 3816 2037 3816 1382 3816 1504 3817 1382 3817 2040 3817 2040 3818 1382 3818 1387 3818 2040 3819 1387 3819 1542 3819 1542 3820 1387 3820 2041 3820 1872 3821 1349 3821 2038 3821 2038 3822 1349 3822 2036 3822 1634 3823 1635 3823 1347 3823 1347 3824 1873 3824 1634 3824 1634 3825 1873 3825 1382 3825 1634 3826 1382 3826 2036 3826 2036 3827 1382 3827 2038 3827 2038 3828 1382 3828 2037 3828 1883 3829 1874 3829 1884 3829 1884 3830 1874 3830 1875 3830 1884 3831 1875 3831 1885 3831 1616 3832 1629 3832 1631 3832 1616 3833 1631 3833 1615 3833 1615 3834 1631 3834 1630 3834 1877 3835 1652 3835 1876 3835 1877 3836 1876 3836 1628 3836 1877 3837 1628 3837 1653 3837 1609 3838 1115 3838 1878 3838 1609 3839 1878 3839 1612 3839 1612 3840 1878 3840 1626 3840 1612 3841 1626 3841 1613 3841 1605 3842 2117 3842 1879 3842 1605 3843 1879 3843 1880 3843 1880 3844 1879 3844 1881 3844 1880 3845 1881 3845 1607 3845 1884 3846 1600 3846 1883 3846 1884 3847 1885 3847 1601 3847 1884 3848 1601 3848 1600 3848 1875 3849 1874 3849 1647 3849 1647 3850 1874 3850 1883 3850 1875 3851 1647 3851 1648 3851 1601 3852 1875 3852 1648 3852 1886 3853 1633 3853 1632 3853 1886 3854 1632 3854 1887 3854 1887 3855 1632 3855 1888 3855 1889 3856 1637 3856 1890 3856 1889 3857 1890 3857 1891 3857 1891 3858 1890 3858 1892 3858 1891 3859 1892 3859 1622 3859 1900 3860 1895 3860 1893 3860 1895 3861 1894 3861 1893 3861 1893 3862 1894 3862 2028 3862 2032 3863 2028 3863 1894 3863 2026 3864 2033 3864 2027 3864 2027 3865 2033 3865 1896 3865 2027 3866 1896 3866 2025 3866 2025 3867 1897 3867 1899 3867 1899 3868 1897 3868 1898 3868 1899 3869 1898 3869 1900 3869 2031 3870 1195 3870 1196 3870 1250 3871 1907 3871 1908 3871 1913 3872 1196 3872 1251 3872 1250 3873 1908 3873 1247 3873 1250 3874 1247 3874 1904 3874 1246 3875 1904 3875 1902 3875 1902 3876 1904 3876 1247 3876 1904 3877 1246 3877 1245 3877 1903 3878 1245 3878 1905 3878 1905 3879 1245 3879 1246 3879 1917 3880 1248 3880 1907 3880 1907 3881 1248 3881 1906 3881 1907 3882 1906 3882 1908 3882 1913 3883 1240 3883 1910 3883 1913 3884 1910 3884 1911 3884 1912 3885 1915 3885 1243 3885 1243 3886 1915 3886 1916 3886 1251 3887 1915 3887 1914 3887 1251 3888 1914 3888 1913 3888 1913 3889 1914 3889 1240 3889 1911 3890 1190 3890 1913 3890 1913 3891 1190 3891 1907 3891 1912 3892 1914 3892 1915 3892 1915 3893 1904 3893 1916 3893 1916 3894 1904 3894 1245 3894 1917 3895 1907 3895 1909 3895 1909 3896 1907 3896 1190 3896 1920 3897 1919 3897 1235 3897 1920 3898 1235 3898 1233 3898 1921 3899 1923 3899 1223 3899 1920 3900 1332 3900 1919 3900 1919 3901 1332 3901 1239 3901 1239 3902 1332 3902 1330 3902 1239 3903 1330 3903 1237 3903 1237 3904 1330 3904 1329 3904 1237 3905 1329 3905 1236 3905 1918 3906 1920 3906 1334 3906 1334 3907 1920 3907 1233 3907 1922 3908 1334 3908 1921 3908 1921 3909 1924 3909 1321 3909 1921 3910 1321 3910 1320 3910 1242 3911 1334 3911 1233 3911 1921 3912 1334 3912 1242 3912 1921 3913 1223 3913 1922 3913 1229 3914 1924 3914 1921 3914 1229 3915 1921 3915 1244 3915 1244 3916 1921 3916 1242 3916 1924 3917 1229 3917 1925 3917 1924 3918 1925 3918 1926 3918 1926 3919 1925 3919 1929 3919 1329 3920 1927 3920 1236 3920 1236 3921 1927 3921 1226 3921 1226 3922 1927 3922 1327 3922 1226 3923 1327 3923 1928 3923 1928 3924 1327 3924 1227 3924 1227 3925 1327 3925 1325 3925 1227 3926 1325 3926 1929 3926 1929 3927 1325 3927 1926 3927 1957 3928 1958 3928 1863 3928 1955 3929 1145 3929 1930 3929 1930 3930 1145 3930 1931 3930 1930 3931 1931 3931 1119 3931 1145 3932 1955 3932 1144 3932 1931 3933 1145 3933 1932 3933 1119 3934 1931 3934 1932 3934 1119 3935 1932 3935 1642 3935 1642 3936 1932 3936 1934 3936 1933 3937 1134 3937 1934 3937 1134 3938 1936 3938 1122 3938 1134 3939 1122 3939 1935 3939 1134 3940 1935 3940 1934 3940 1934 3941 1935 3941 1642 3941 1134 3942 1933 3942 1937 3942 1936 3943 1134 3943 1937 3943 1939 3944 1938 3944 1940 3944 1936 3945 1937 3945 1938 3945 1936 3946 1938 3946 1646 3946 1646 3947 1938 3947 1939 3947 1646 3948 1939 3948 1940 3948 1942 3949 1941 3949 1940 3949 1942 3950 1940 3950 1938 3950 1941 3951 1942 3951 1943 3951 1941 3952 1943 3952 1129 3952 1129 3953 1943 3953 1944 3953 1944 3954 1945 3954 1139 3954 1944 3955 1139 3955 1948 3955 1945 3956 1944 3956 1943 3956 1945 3957 1943 3957 1946 3957 1946 3958 1943 3958 1942 3958 1951 3959 1948 3959 1947 3959 1139 3960 1947 3960 1948 3960 1948 3961 1951 3961 2113 3961 1949 3962 1950 3962 1873 3962 1949 3963 1873 3963 1347 3963 1953 3964 1950 3964 1949 3964 1949 3965 1345 3965 1953 3965 1953 3966 1345 3966 1951 3966 1953 3967 1951 3967 1952 3967 1952 3968 1951 3968 1947 3968 1954 3969 1143 3969 1144 3969 1143 3970 1132 3970 1148 3970 1954 3971 1144 3971 1955 3971 1132 3972 1954 3972 1116 3972 1132 3973 1116 3973 1640 3973 1132 3974 1640 3974 1148 3974 1148 3975 1640 3975 1956 3975 1148 3976 1956 3976 1957 3976 1958 3977 1957 3977 1625 3977 1625 3978 1957 3978 1956 3978 1960 3979 1389 3979 1959 3979 1147 3980 1134 3980 1142 3980 1134 3981 1147 3981 1368 3981 1134 3982 1368 3982 1142 3982 1132 3983 1404 3983 1131 3983 1131 3984 1972 3984 1961 3984 1131 3985 1961 3985 1149 3985 1131 3986 1149 3986 1404 3986 1131 3987 1404 3987 1132 3987 1962 3988 1136 3988 1383 3988 1962 3989 1383 3989 1382 3989 1136 3990 1964 3990 2120 3990 1964 3991 1135 3991 2120 3991 1390 3992 1966 3992 1965 3992 1138 3993 1390 3993 1967 3993 1939 3994 1969 3994 1968 3994 1968 3995 1969 3995 1137 3995 1969 3996 1939 3996 1363 3996 1363 3997 1939 3997 1968 3997 1142 3998 1140 3998 1141 3998 1931 3999 2119 3999 1971 3999 1971 4000 2119 4000 1970 4000 1970 4001 2119 4001 1146 4001 1133 4002 1957 4002 1974 4002 1975 4003 1386 4003 1150 4003 1150 4004 1386 4004 1976 4004 1150 4005 1976 4005 1133 4005 1133 4006 1976 4006 1136 4006 1136 4007 1976 4007 1383 4007 2006 4008 1356 4008 1264 4008 1264 4009 1356 4009 1978 4009 1264 4010 1978 4010 1977 4010 1977 4011 1978 4011 1357 4011 1977 4012 1357 4012 1979 4012 1979 4013 1357 4013 1358 4013 1979 4014 1358 4014 1980 4014 1980 4015 1358 4015 1981 4015 1980 4016 1981 4016 1982 4016 1982 4017 1981 4017 1359 4017 1982 4018 1359 4018 1266 4018 1266 4019 1359 4019 1360 4019 1266 4020 1360 4020 1267 4020 1267 4021 1360 4021 1983 4021 1267 4022 1983 4022 1984 4022 1984 4023 1983 4023 1985 4023 1984 4024 1985 4024 1269 4024 1269 4025 1985 4025 1986 4025 1269 4026 1986 4026 1268 4026 1268 4027 1986 4027 1987 4027 1268 4028 1987 4028 1270 4028 1270 4029 1987 4029 1362 4029 1270 4030 1362 4030 1988 4030 1988 4031 1362 4031 1989 4031 1988 4032 1989 4032 1271 4032 1271 4033 1989 4033 1364 4033 1271 4034 1364 4034 1273 4034 1273 4035 1364 4035 1365 4035 1273 4036 1365 4036 1274 4036 1274 4037 1365 4037 1366 4037 1274 4038 1366 4038 1275 4038 1275 4039 1366 4039 1367 4039 1275 4040 1367 4040 1277 4040 1277 4041 1367 4041 1990 4041 1277 4042 1990 4042 1991 4042 1991 4043 1990 4043 1992 4043 1991 4044 1992 4044 1993 4044 1993 4045 1992 4045 1994 4045 1993 4046 1994 4046 1279 4046 1279 4047 1994 4047 1995 4047 1279 4048 1995 4048 1997 4048 1997 4049 1995 4049 1996 4049 1997 4050 1996 4050 1280 4050 1280 4051 1996 4051 1370 4051 1280 4052 1370 4052 1282 4052 1282 4053 1370 4053 1998 4053 1282 4054 1998 4054 1281 4054 1281 4055 1998 4055 1371 4055 1281 4056 1371 4056 1283 4056 1283 4057 1371 4057 1999 4057 1283 4058 1999 4058 1285 4058 1285 4059 1999 4059 2000 4059 1285 4060 2000 4060 1284 4060 1284 4061 2000 4061 2001 4061 1284 4062 2001 4062 2002 4062 2002 4063 2001 4063 1373 4063 2002 4064 1373 4064 1286 4064 1286 4065 1373 4065 2003 4065 1286 4066 2003 4066 1374 4066 1263 4067 2005 4067 2007 4067 1263 4068 2007 4068 2006 4068 2006 4069 2007 4069 1356 4069 2008 4070 1219 4070 2009 4070 2013 4071 1204 4071 1206 4071 1204 4072 2013 4072 2011 4072 1204 4073 2011 4073 2010 4073 2010 4074 2011 4074 1219 4074 2011 4075 2013 4075 1222 4075 1206 4076 2012 4076 2013 4076 2013 4077 2012 4077 1221 4077 2013 4078 1221 4078 1222 4078 2012 4079 2014 4079 1221 4079 1221 4080 2014 4080 2015 4080 1221 4081 2015 4081 2016 4081 2016 4082 2015 4082 2017 4082 2016 4083 2017 4083 1220 4083 1220 4084 2017 4084 2018 4084 1220 4085 2018 4085 1257 4085 1257 4086 2018 4086 2019 4086 1257 4087 2019 4087 1259 4087 1259 4088 2019 4088 1213 4088 1217 4089 2020 4089 1216 4089 1216 4090 2020 4090 1224 4090 1216 4091 1224 4091 2021 4091 1217 4092 2009 4092 2020 4092 2020 4093 2009 4093 1219 4093 2020 4094 1219 4094 1262 4094 1262 4095 1219 4095 2011 4095 2021 4096 1224 4096 1225 4096 2021 4097 1225 4097 2022 4097 2022 4098 1225 4098 2023 4098 2022 4099 2023 4099 1214 4099 1214 4100 2023 4100 1213 4100 1213 4101 2023 4101 1259 4101 1210 4102 2024 4102 1203 4102 2024 4103 1210 4103 1209 4103 2025 4104 2024 4104 1209 4104 2025 4105 1209 4105 1199 4105 2025 4106 1199 4106 1208 4106 1218 4107 1198 4107 1205 4107 2026 4108 2027 4108 1208 4108 1900 4109 2029 4109 2024 4109 2024 4110 2029 4110 1203 4110 1201 4111 1198 4111 1218 4111 2027 4112 2025 4112 1208 4112 2026 4113 1208 4113 1207 4113 2026 4114 1207 4114 1205 4114 2026 4115 1205 4115 1198 4115 2025 4116 1899 4116 2024 4116 2024 4117 1899 4117 1900 4117 2028 4118 1198 4118 1201 4118 2028 4119 1201 4119 1215 4119 2028 4120 1215 4120 1202 4120 2029 4121 1900 4121 1893 4121 2029 4122 1893 4122 1202 4122 1202 4123 1893 4123 2028 4123 1897 4124 1896 4124 1195 4124 2030 4125 2034 4125 1191 4125 1900 4126 2031 4126 1193 4126 1900 4127 1193 4127 1895 4127 2032 4128 1894 4128 1193 4128 1193 4129 1894 4129 1895 4129 2031 4130 1900 4130 1898 4130 2031 4131 1898 4131 1195 4131 2034 4132 2030 4132 2026 4132 2035 4133 1634 4133 2036 4133 1622 4134 1892 4134 1636 4134 1622 4135 1636 4135 1623 4135 2037 4136 1456 4136 2038 4136 2040 4137 2039 4137 1504 4137 2041 4138 1524 4138 1542 4138 2042 4139 2043 4139 2045 4139 2045 4140 2043 4140 1172 4140 2042 4141 1869 4141 2043 4141 2043 4142 1869 4142 2123 4142 2062 4143 1860 4143 1554 4143 1726 4144 2062 4144 1683 4144 1683 4145 2062 4145 1172 4145 1172 4146 2062 4146 2045 4146 1521 4147 1540 4147 1539 4147 1521 4148 1539 4148 1520 4148 2046 4149 1503 4149 1501 4149 2046 4150 1501 4150 1354 4150 1454 4151 1848 4151 1467 4151 1454 4152 1467 4152 1455 4152 1384 4153 1385 4153 2048 4153 2048 4154 1385 4154 1381 4154 2048 4155 1381 4155 1379 4155 2048 4156 1379 4156 1380 4156 2048 4157 1380 4157 2049 4157 1376 4158 2049 4158 1378 4158 2051 4159 2052 4159 1341 4159 1341 4160 2052 4160 2048 4160 1341 4161 2048 4161 1252 4161 1252 4162 2053 4162 1254 4162 1292 4163 1303 4163 2085 4163 2085 4164 1303 4164 1315 4164 2085 4165 1315 4165 1223 4165 1223 4166 1315 4166 1922 4166 2055 4167 1923 4167 2054 4167 2055 4168 2054 4168 1287 4168 1292 4169 2085 4169 1336 4169 2055 4170 1287 4170 2056 4170 2056 4171 1287 4171 1719 4171 1340 4172 1336 4172 2088 4172 1665 4173 1858 4173 1666 4173 2063 4174 1421 4174 1856 4174 2061 4175 1727 4175 1859 4175 1440 4176 1729 4176 2060 4176 2058 4177 2057 4177 1427 4177 1731 4178 2059 4178 1835 4178 1835 4179 2059 4179 1832 4179 1427 4180 1426 4180 2058 4180 1686 4181 1440 4181 1685 4181 1685 4182 1440 4182 2060 4182 1727 4183 2061 4183 1726 4183 1726 4184 2061 4184 2062 4184 1682 4185 1727 4185 1726 4185 2084 4186 1186 4186 2067 4186 2067 4187 1186 4187 2066 4187 2067 4188 2066 4188 1173 4188 1173 4189 2066 4189 2068 4189 1173 4190 2068 4190 2069 4190 1173 4191 2069 4191 2071 4191 2071 4192 2069 4192 2070 4192 2071 4193 2070 4193 2072 4193 2072 4194 2070 4194 2073 4194 2072 4195 2073 4195 2074 4195 1338 4196 1188 4196 1160 4196 1338 4197 1160 4197 1335 4197 1335 4198 1160 4198 2065 4198 1335 4199 2065 4199 2064 4199 2064 4200 2065 4200 1667 4200 2064 4201 1667 4201 2075 4201 2075 4202 1667 4202 2076 4202 2075 4203 2076 4203 2077 4203 2077 4204 2076 4204 2078 4204 2077 4205 2078 4205 1179 4205 1179 4206 2078 4206 2080 4206 1179 4207 2080 4207 2079 4207 2079 4208 2080 4208 1181 4208 2079 4209 1181 4209 1177 4209 1177 4210 1181 4210 2081 4210 1177 4211 2081 4211 1176 4211 1176 4212 2081 4212 1182 4212 1176 4213 1182 4213 2082 4213 2082 4214 1182 4214 1185 4214 2082 4215 1185 4215 2083 4215 2083 4216 1185 4216 1186 4216 2083 4217 1186 4217 2084 4217 2075 4218 1180 4218 2064 4218 1683 4219 1172 4219 2086 4219 1339 4220 2056 4220 1719 4220 2089 4221 2056 4221 1339 4221 2088 4222 2056 4222 2089 4222 1704 4223 1703 4223 2090 4223 2090 4224 1703 4224 1707 4224 2093 4225 1430 4225 2096 4225 2094 4226 2092 4226 2095 4226 2095 4227 2092 4227 2091 4227 1121 4228 1830 4228 1702 4228 1701 4229 1702 4229 1157 4229 1156 4230 2093 4230 2096 4230 1156 4231 2096 4231 1158 4231 2104 4232 1405 4232 2103 4232 2103 4233 1405 4233 1407 4233 1697 4234 1823 4234 1698 4234 1698 4235 1823 4235 1699 4235 1679 4236 1406 4236 1699 4236 1696 4237 2098 4237 1839 4237 1431 4238 1436 4238 1434 4238 1434 4239 1436 4239 1435 4239 1664 4240 2100 4240 1696 4240 1420 4241 2100 4241 1664 4241 1823 4242 1697 4242 2101 4242 1679 4243 1699 4243 2102 4243 1677 4244 2105 4244 1406 4244 1705 4245 1829 4245 1708 4245 1708 4246 1829 4246 2108 4246 1690 4247 1693 4247 1826 4247 1692 4248 2108 4248 1827 4248 1845 4249 2106 4249 1687 4249 1411 4250 1416 4250 1844 4250 1844 4251 1416 4251 1417 4251 1844 4252 1687 4252 1411 4252 1688 4253 1845 4253 1153 4253 2107 4254 1688 4254 1153 4254 1153 4255 1414 4255 1419 4255 1419 4256 2107 4256 1153 4256 2108 4257 1692 4257 1151 4257 1425 4258 1681 4258 2111 4258 2111 4259 1679 4259 2102 4259 2111 4260 1588 4260 1452 4260 1618 4261 1888 4261 2113 4261 1452 4262 1464 4262 1463 4262 1452 4263 1463 4263 2111 4263 2111 4264 1463 4264 1618 4264 2111 4265 1618 4265 2113 4265 1484 4266 1783 4266 1588 4266 1519 4267 1535 4267 1536 4267 1519 4268 1536 4268 2111 4268 2111 4269 1536 4269 1484 4269 2111 4270 1484 4270 1588 4270 1697 4271 1825 4271 2111 4271 1824 4272 1700 4272 2102 4272 2102 4273 1700 4273 2101 4273 2102 4274 2101 4274 2111 4274 1556 4275 2109 4275 2111 4275 1424 4276 1857 4276 1423 4276 1424 4277 1423 4277 1425 4277 1425 4278 2111 4278 1422 4278 1422 4279 2111 4279 2109 4279 1422 4280 2109 4280 1862 4280 2110 4281 1853 4281 1556 4281 2110 4282 1556 4282 2111 4282 2110 4283 2111 4283 1352 4283 1352 4284 2111 4284 2112 4284 1352 4285 2112 4285 1502 4285 2113 4286 1637 4286 1620 4286 2113 4287 1620 4287 1506 4287 2113 4288 1506 4288 2111 4288 2111 4289 1506 4289 2112 4289 1688 4290 2107 4290 2114 4290 1568 4291 1625 4291 2114 4291 1590 4292 1589 4292 1625 4292 1604 4293 1651 4293 1650 4293 1604 4294 1650 4294 1625 4294 1589 4295 1662 4295 1466 4295 1589 4296 1466 4296 1625 4296 1577 4297 1499 4297 1590 4297 1865 4298 1658 4298 1537 4298 1865 4299 1537 4299 1568 4299 1568 4300 1537 4300 1625 4300 1625 4301 1537 4301 1590 4301 1668 4302 1847 4302 1568 4302 1668 4303 1568 4303 1669 4303 1669 4304 1568 4304 2114 4304 1508 4305 2115 4305 2114 4305 1688 4306 2114 4306 2115 4306 2115 4307 1544 4307 1687 4307 2116 4308 1508 4308 1526 4308 1526 4309 1508 4309 2114 4309 1526 4310 2114 4310 1569 4310 1569 4311 2114 4311 1488 4311 1569 4312 1488 4312 1470 4312 2117 4313 1591 4313 1625 4313 1625 4314 1591 4314 2118 4314 1625 4315 2118 4315 2114 4315 2114 4316 2118 4316 1488 4316 1149 4317 1372 4317 1404 4317 2121 4318 2043 4318 2123 4318 2122 4319 2124 4319 2121 4319 1377 4320 2049 4320 2122 4320 1377 4321 2122 4321 2121 4321 1377 4322 2121 4322 2123 4322 2125 4323 2121 4323 2124 4323 2126 4324 2165 4324 2127 4324 2432 4325 2433 4325 2128 4325 2432 4326 2128 4326 2159 4326 2159 4327 2128 4327 2432 4327 2432 4328 2128 4328 2433 4328 2401 4329 2222 4329 2404 4329 2404 4330 2222 4330 2398 4330 2398 4331 2222 4331 2129 4331 2398 4332 2129 4332 2229 4332 2229 4333 2129 4333 2230 4333 2372 4334 2218 4334 2243 4334 2372 4335 2243 4335 2131 4335 2131 4336 2243 4336 2376 4336 2371 4337 2132 4337 2133 4337 2371 4338 2133 4338 2219 4338 2372 4339 2219 4339 2218 4339 2325 4340 2134 4340 2324 4340 2324 4341 2134 4341 2143 4341 2143 4342 2134 4342 2207 4342 2326 4343 2207 4343 2135 4343 2326 4344 2135 4344 2141 4344 2141 4345 2135 4345 2136 4345 2141 4346 2136 4346 2146 4346 2146 4347 2136 4347 2328 4347 2328 4348 2136 4348 2206 4348 2328 4349 2206 4349 2137 4349 2137 4350 2206 4350 2204 4350 2137 4351 2204 4351 2325 4351 2325 4352 2204 4352 2134 4352 2140 4353 2235 4353 2151 4353 2151 4354 2235 4354 2238 4354 2151 4355 2238 4355 2318 4355 2318 4356 2238 4356 2320 4356 2320 4357 2238 4357 2237 4357 2320 4358 2237 4358 2321 4358 2321 4359 2237 4359 2236 4359 2321 4360 2236 4360 2148 4360 2148 4361 2236 4361 2138 4361 2138 4362 2236 4362 2139 4362 2138 4363 2139 4363 2317 4363 2317 4364 2139 4364 2241 4364 2317 4365 2241 4365 2140 4365 2140 4366 2241 4366 2235 4366 2141 4367 2373 4367 2326 4367 2326 4368 2373 4368 2374 4368 2326 4369 2374 4369 2142 4369 2142 4370 2374 4370 2375 4370 2142 4371 2375 4371 2143 4371 2143 4372 2375 4372 2324 4372 2324 4373 2375 4373 2144 4373 2324 4374 2144 4374 2370 4374 2324 4375 2370 4375 2323 4375 2323 4376 2370 4376 2145 4376 2323 4377 2145 4377 2327 4377 2327 4378 2145 4378 2368 4378 2327 4379 2368 4379 2146 4379 2146 4380 2368 4380 2369 4380 2146 4381 2369 4381 2141 4381 2141 4382 2369 4382 2373 4382 2400 4383 2151 4383 2403 4383 2403 4384 2151 4384 2402 4384 2402 4385 2151 4385 2318 4385 2402 4386 2318 4386 2147 4386 2147 4387 2318 4387 2319 4387 2147 4388 2319 4388 2397 4388 2397 4389 2319 4389 2148 4389 2397 4390 2148 4390 2396 4390 2396 4391 2148 4391 2399 4391 2399 4392 2148 4392 2322 4392 2399 4393 2322 4393 2149 4393 2149 4394 2322 4394 2150 4394 2149 4395 2150 4395 2400 4395 2400 4396 2150 4396 2151 4396 2438 4397 2386 4397 2437 4397 2437 4398 2386 4398 2387 4398 2437 4399 2387 4399 2438 4399 2438 4400 2387 4400 2386 4400 2153 4401 2391 4401 2152 4401 2152 4402 2391 4402 2393 4402 2152 4403 2393 4403 2435 4403 2435 4404 2393 4404 2391 4404 2435 4405 2391 4405 2153 4405 2389 4406 2155 4406 2434 4406 2389 4407 2434 4407 2385 4407 2385 4408 2434 4408 2154 4408 2385 4409 2154 4409 2155 4409 2385 4410 2155 4410 2389 4410 2190 4411 2156 4411 2382 4411 2382 4412 2156 4412 2383 4412 2383 4413 2156 4413 2425 4413 2383 4414 2425 4414 2424 4414 2383 4415 2424 4415 2190 4415 2190 4416 2424 4416 2156 4416 2427 4417 2426 4417 2157 4417 2157 4418 2426 4418 2158 4418 2157 4419 2158 4419 2427 4419 2395 4420 2429 4420 2392 4420 2392 4421 2429 4421 2428 4421 2392 4422 2428 4422 2390 4422 2390 4423 2428 4423 2436 4423 2390 4424 2436 4424 2395 4424 2395 4425 2436 4425 2429 4425 2159 4426 2432 4426 2445 4426 2443 4427 2432 4427 2159 4427 2443 4428 2159 4428 2175 4428 2345 4429 2214 4429 2159 4429 2159 4430 2214 4430 2175 4430 2258 4431 2261 4431 2159 4431 2159 4432 2261 4432 2345 4432 2258 4433 2159 4433 2445 4433 2345 4434 2160 4434 2266 4434 2266 4435 2160 4435 2161 4435 2266 4436 2161 4436 2267 4436 2267 4437 2161 4437 2162 4437 2267 4438 2162 4438 2163 4438 2163 4439 2162 4439 2269 4439 2269 4440 2162 4440 2340 4440 2446 4441 2127 4441 2165 4441 2164 4442 2165 4442 2170 4442 2337 4443 2167 4443 2166 4443 2166 4444 2167 4444 2203 4444 2166 4445 2203 4445 2288 4445 2288 4446 2203 4446 2308 4446 2288 4447 2308 4447 2164 4447 2164 4448 2308 4448 2165 4448 2165 4449 2308 4449 2171 4449 2168 4450 2255 4450 2180 4450 2180 4451 2255 4451 2254 4451 2126 4452 2312 4452 2430 4452 2431 4453 2406 4453 2126 4453 2126 4454 2406 4454 2248 4454 2312 4455 2126 4455 2313 4455 2313 4456 2126 4456 2248 4456 2128 4457 2433 4457 2169 4457 2407 4458 2442 4458 2405 4458 2405 4459 2442 4459 2128 4459 2405 4460 2128 4460 2249 4460 2128 4461 2316 4461 2249 4461 2316 4462 2128 4462 2169 4462 2444 4463 2384 4463 2174 4463 2174 4464 2384 4464 2192 4464 2171 4465 2446 4465 2165 4465 2172 4466 2188 4466 2177 4466 2177 4467 2188 4467 2394 4467 2189 4468 2172 4468 2173 4468 2189 4469 2173 4469 2446 4469 2189 4470 2446 4470 2171 4470 2170 4471 2174 4471 2192 4471 2194 4472 2444 4472 2443 4472 2194 4473 2443 4473 2175 4473 2258 4474 2445 4474 2176 4474 2177 4475 2394 4475 2176 4475 2178 4476 2253 4476 2179 4476 2255 4477 2168 4477 2179 4477 2430 4478 2178 4478 2439 4478 2439 4479 2178 4479 2179 4479 2439 4480 2179 4480 2168 4480 2181 4481 2233 4481 2314 4481 2314 4482 2169 4482 2441 4482 2314 4483 2441 4483 2181 4483 2181 4484 2441 4484 2180 4484 2181 4485 2180 4485 2254 4485 2182 4486 2406 4486 2431 4486 2182 4487 2442 4487 2407 4487 2190 4488 2184 4488 2212 4488 2212 4489 2184 4489 2183 4489 2184 4490 2388 4490 2183 4490 2183 4491 2388 4491 2389 4491 2190 4492 2382 4492 2184 4492 2185 4493 2187 4493 2256 4493 2195 4494 2196 4494 2247 4494 2247 4495 2196 4495 2256 4495 2256 4496 2196 4496 2185 4496 2185 4497 2186 4497 2187 4497 2187 4498 2186 4498 2427 4498 2189 4499 2188 4499 2172 4499 2189 4500 2256 4500 2187 4500 2189 4501 2187 4501 2188 4501 2256 4502 2189 4502 2303 4502 2189 4503 2171 4503 2303 4503 2292 4504 2192 4504 2190 4504 2292 4505 2190 4505 2212 4505 2192 4506 2292 4506 2215 4506 2192 4507 2215 4507 2191 4507 2192 4508 2191 4508 2164 4508 2192 4509 2164 4509 2170 4509 2183 4510 2384 4510 2194 4510 2212 4511 2183 4511 2211 4511 2194 4512 2384 4512 2444 4512 2183 4513 2194 4513 2211 4513 2211 4514 2194 4514 2193 4514 2193 4515 2194 4515 2213 4515 2194 4516 2175 4516 2213 4516 2394 4517 2195 4517 2176 4517 2176 4518 2195 4518 2247 4518 2176 4519 2247 4519 2258 4519 2195 4520 2392 4520 2390 4520 2195 4521 2390 4521 2196 4521 2217 4522 2197 4522 2198 4522 2198 4523 2197 4523 2416 4523 2198 4524 2416 4524 2199 4524 2199 4525 2416 4525 2249 4525 2250 4526 2200 4526 2311 4526 2311 4527 2200 4527 2202 4527 2311 4528 2202 4528 2201 4528 2224 4529 2201 4529 2202 4529 2204 4530 2280 4530 2134 4530 2204 4531 2206 4531 2280 4531 2136 4532 2278 4532 2205 4532 2136 4533 2205 4533 2206 4533 2136 4534 2135 4534 2278 4534 2278 4535 2135 4535 2207 4535 2278 4536 2207 4536 2279 4536 2279 4537 2207 4537 2134 4537 2280 4538 2279 4538 2134 4538 2232 4539 2240 4539 2230 4539 2230 4540 2240 4540 2231 4540 2231 4541 2240 4541 2302 4541 2231 4542 2302 4542 2227 4542 2227 4543 2302 4543 2301 4543 2227 4544 2301 4544 2228 4544 2228 4545 2301 4545 2300 4545 2300 4546 2298 4546 2222 4546 2206 4547 2205 4547 2283 4547 2283 4548 2205 4548 2331 4548 2251 4549 2208 4549 2210 4549 2210 4550 2208 4550 2265 4550 2265 4551 2208 4551 2212 4551 2251 4552 2210 4552 2209 4552 2209 4553 2210 4553 2274 4553 2293 4554 2251 4554 2226 4554 2226 4555 2225 4555 2297 4555 2297 4556 2294 4556 2226 4556 2226 4557 2294 4557 2293 4557 2209 4558 2274 4558 2220 4558 2276 4559 2234 4559 2220 4559 2276 4560 2220 4560 2274 4560 2193 4561 2272 4561 2211 4561 2211 4562 2272 4562 2212 4562 2214 4563 2213 4563 2175 4563 2212 4564 2208 4564 2292 4564 2288 4565 2164 4565 2216 4565 2216 4566 2164 4566 2191 4566 2216 4567 2191 4567 2215 4567 2246 4568 2377 4568 2218 4568 2218 4569 2377 4569 2408 4569 2408 4570 2252 4570 2218 4570 2315 4571 2410 4571 2217 4571 2218 4572 2219 4572 2246 4572 2246 4573 2219 4573 2133 4573 2408 4574 2410 4574 2252 4574 2252 4575 2410 4575 2315 4575 2132 4576 2244 4576 2245 4576 2132 4577 2245 4577 2133 4577 2242 4578 2376 4578 2243 4578 2376 4579 2242 4579 2244 4579 2376 4580 2244 4580 2132 4580 2234 4581 2243 4581 2218 4581 2234 4582 2218 4582 2220 4582 2220 4583 2218 4583 2252 4583 2220 4584 2252 4584 2209 4584 2226 4585 2251 4585 2221 4585 2129 4586 2222 4586 2221 4586 2420 4587 2223 4587 2224 4587 2222 4588 2225 4588 2221 4588 2221 4589 2225 4589 2226 4589 2401 4590 2300 4590 2222 4590 2330 4591 2129 4591 2419 4591 2419 4592 2129 4592 2221 4592 2130 4593 2227 4593 2401 4593 2401 4594 2227 4594 2228 4594 2401 4595 2228 4595 2300 4595 2223 4596 2420 4596 2221 4596 2221 4597 2420 4597 2419 4597 2229 4598 2230 4598 2130 4598 2130 4599 2230 4599 2231 4599 2130 4600 2231 4600 2227 4600 2232 4601 2230 4601 2129 4601 2232 4602 2129 4602 2330 4602 2252 4603 2315 4603 2314 4603 2252 4604 2314 4604 2233 4604 2253 4605 2178 4605 2310 4605 2310 4606 2223 4606 2221 4606 2281 4607 2243 4607 2276 4607 2276 4608 2243 4608 2234 4608 2239 4609 2235 4609 2357 4609 2357 4610 2235 4610 2241 4610 2237 4611 2301 4611 2236 4611 2237 4612 2299 4612 2301 4612 2239 4613 2299 4613 2238 4613 2238 4614 2299 4614 2237 4614 2239 4615 2238 4615 2235 4615 2236 4616 2240 4616 2139 4616 2139 4617 2240 4617 2241 4617 2241 4618 2240 4618 2357 4618 2301 4619 2302 4619 2236 4619 2236 4620 2302 4620 2240 4620 2279 4621 2242 4621 2281 4621 2281 4622 2242 4622 2243 4622 2242 4623 2279 4623 2244 4623 2244 4624 2279 4624 2280 4624 2244 4625 2280 4625 2245 4625 2245 4626 2282 4626 2133 4626 2133 4627 2282 4627 2283 4627 2133 4628 2283 4628 2331 4628 2133 4629 2331 4629 2246 4629 2306 4630 2259 4630 2304 4630 2304 4631 2259 4631 2247 4631 2305 4632 2329 4632 2309 4632 2309 4633 2329 4633 2260 4633 2297 4634 2225 4634 2298 4634 2298 4635 2225 4635 2222 4635 2405 4636 2249 4636 2248 4636 2248 4637 2249 4637 2250 4637 2248 4638 2250 4638 2313 4638 2200 4639 2250 4639 2414 4639 2249 4640 2416 4640 2250 4640 2250 4641 2416 4641 2414 4641 2310 4642 2221 4642 2251 4642 2252 4643 2233 4643 2209 4643 2209 4644 2233 4644 2181 4644 2255 4645 2179 4645 2251 4645 2251 4646 2179 4646 2253 4646 2251 4647 2253 4647 2310 4647 2209 4648 2181 4648 2254 4648 2209 4649 2254 4649 2251 4649 2251 4650 2254 4650 2255 4650 2256 4651 2304 4651 2247 4651 2259 4652 2306 4652 2260 4652 2260 4653 2306 4653 2309 4653 2348 4654 2257 4654 2346 4654 2346 4655 2257 4655 2361 4655 2305 4656 2346 4656 2329 4656 2329 4657 2346 4657 2361 4657 2247 4658 2259 4658 2262 4658 2247 4659 2262 4659 2258 4659 2261 4660 2258 4660 2262 4660 2259 4661 2260 4661 2262 4661 2260 4662 2329 4662 2262 4662 2262 4663 2263 4663 2261 4663 2212 4664 2272 4664 2270 4664 2264 4665 2213 4665 2345 4665 2345 4666 2213 4666 2214 4666 2212 4667 2270 4667 2265 4667 2265 4668 2270 4668 2210 4668 2342 4669 2273 4669 2344 4669 2344 4670 2273 4670 2269 4670 2269 4671 2273 4671 2268 4671 2345 4672 2266 4672 2264 4672 2264 4673 2266 4673 2268 4673 2268 4674 2266 4674 2267 4674 2268 4675 2267 4675 2163 4675 2268 4676 2163 4676 2269 4676 2272 4677 2271 4677 2270 4677 2270 4678 2271 4678 2268 4678 2270 4679 2268 4679 2210 4679 2210 4680 2268 4680 2274 4680 2274 4681 2268 4681 2273 4681 2271 4682 2272 4682 2193 4682 2268 4683 2271 4683 2264 4683 2264 4684 2271 4684 2193 4684 2264 4685 2193 4685 2213 4685 2273 4686 2342 4686 2277 4686 2205 4687 2278 4687 2342 4687 2342 4688 2278 4688 2277 4688 2277 4689 2276 4689 2274 4689 2273 4690 2277 4690 2274 4690 2278 4691 2275 4691 2277 4691 2281 4692 2276 4692 2277 4692 2281 4693 2277 4693 2275 4693 2282 4694 2206 4694 2283 4694 2282 4695 2280 4695 2206 4695 2275 4696 2278 4696 2279 4696 2245 4697 2280 4697 2282 4697 2281 4698 2275 4698 2279 4698 2286 4699 2284 4699 2289 4699 2289 4700 2284 4700 2285 4700 2290 4701 2208 4701 2251 4701 2290 4702 2251 4702 2289 4702 2289 4703 2251 4703 2293 4703 2208 4704 2290 4704 2292 4704 2284 4705 2337 4705 2285 4705 2286 4706 2289 4706 2335 4706 2335 4707 2289 4707 2287 4707 2339 4708 2287 4708 2338 4708 2338 4709 2287 4709 2293 4709 2337 4710 2166 4710 2285 4710 2285 4711 2166 4711 2288 4711 2285 4712 2288 4712 2216 4712 2216 4713 2291 4713 2285 4713 2287 4714 2289 4714 2293 4714 2291 4715 2216 4715 2215 4715 2289 4716 2285 4716 2290 4716 2290 4717 2285 4717 2291 4717 2290 4718 2291 4718 2215 4718 2290 4719 2215 4719 2292 4719 2293 4720 2294 4720 2295 4720 2293 4721 2295 4721 2338 4721 2295 4722 2294 4722 2297 4722 2297 4723 2296 4723 2295 4723 2297 4724 2298 4724 2296 4724 2295 4725 2296 4725 2299 4725 2295 4726 2299 4726 2239 4726 2296 4727 2298 4727 2299 4727 2299 4728 2298 4728 2300 4728 2299 4729 2300 4729 2301 4729 2240 4730 2360 4730 2357 4730 2240 4731 2232 4731 2360 4731 2303 4732 2171 4732 2308 4732 2303 4733 2308 4733 2307 4733 2303 4734 2307 4734 2256 4734 2306 4735 2304 4735 2307 4735 2307 4736 2304 4736 2256 4736 2347 4737 2307 4737 2203 4737 2307 4738 2347 4738 2305 4738 2309 4739 2306 4739 2307 4739 2308 4740 2203 4740 2307 4740 2307 4741 2305 4741 2309 4741 2310 4742 2178 4742 2430 4742 2313 4743 2250 4743 2311 4743 2310 4744 2430 4744 2223 4744 2311 4745 2201 4745 2313 4745 2223 4746 2430 4746 2312 4746 2223 4747 2312 4747 2224 4747 2224 4748 2312 4748 2313 4748 2224 4749 2313 4749 2201 4749 2249 4750 2198 4750 2199 4750 2169 4751 2314 4751 2315 4751 2169 4752 2315 4752 2316 4752 2316 4753 2315 4753 2217 4753 2316 4754 2217 4754 2249 4754 2249 4755 2217 4755 2198 4755 2322 4756 2317 4756 2150 4756 2150 4757 2317 4757 2140 4757 2150 4758 2140 4758 2151 4758 2318 4759 2320 4759 2319 4759 2319 4760 2320 4760 2321 4760 2319 4761 2321 4761 2148 4761 2322 4762 2148 4762 2138 4762 2322 4763 2138 4763 2317 4763 2327 4764 2137 4764 2323 4764 2323 4765 2137 4765 2325 4765 2323 4766 2325 4766 2324 4766 2143 4767 2207 4767 2142 4767 2142 4768 2207 4768 2326 4768 2327 4769 2146 4769 2328 4769 2327 4770 2328 4770 2137 4770 2257 4771 2262 4771 2329 4771 2332 4772 2330 4772 2331 4772 2377 4773 2246 4773 2331 4773 2377 4774 2331 4774 2330 4774 2331 4775 2367 4775 2332 4775 2349 4776 2363 4776 2333 4776 2349 4777 2333 4777 2348 4777 2335 4778 2352 4778 2354 4778 2335 4779 2354 4779 2286 4779 2286 4780 2354 4780 2336 4780 2334 4781 2337 4781 2336 4781 2336 4782 2337 4782 2284 4782 2336 4783 2284 4783 2286 4783 2334 4784 2167 4784 2337 4784 2357 4785 2355 4785 2239 4785 2339 4786 2338 4786 2355 4786 2355 4787 2338 4787 2295 4787 2355 4788 2295 4788 2239 4788 2335 4789 2287 4789 2352 4789 2352 4790 2287 4790 2339 4790 2355 4791 2358 4791 2339 4791 2339 4792 2358 4792 2356 4792 2339 4793 2356 4793 2352 4793 2365 4794 2343 4794 2340 4794 2340 4795 2343 4795 2344 4795 2340 4796 2344 4796 2269 4796 2341 4797 2342 4797 2343 4797 2343 4798 2342 4798 2344 4798 2341 4799 2205 4799 2342 4799 2261 4800 2263 4800 2345 4800 2160 4801 2345 4801 2263 4801 2305 4802 2347 4802 2346 4802 2346 4803 2347 4803 2348 4803 2347 4804 2203 4804 2167 4804 2349 4805 2351 4805 2353 4805 2353 4806 2351 4806 2350 4806 2347 4807 2350 4807 2351 4807 2347 4808 2351 4808 2348 4808 2348 4809 2351 4809 2349 4809 2347 4810 2167 4810 2350 4810 2350 4811 2167 4811 2334 4811 2350 4812 2334 4812 2353 4812 2353 4813 2334 4813 2336 4813 2352 4814 2359 4814 2353 4814 2359 4815 2330 4815 2332 4815 2354 4816 2352 4816 2353 4816 2354 4817 2353 4817 2336 4817 2353 4818 2359 4818 2332 4818 2358 4819 2355 4819 2359 4819 2352 4820 2356 4820 2359 4820 2360 4821 2232 4821 2330 4821 2359 4822 2355 4822 2357 4822 2356 4823 2358 4823 2359 4823 2359 4824 2360 4824 2330 4824 2359 4825 2357 4825 2360 4825 2329 4826 2361 4826 2257 4826 2257 4827 2263 4827 2262 4827 2333 4828 2363 4828 2364 4828 2257 4829 2364 4829 2263 4829 2364 4830 2257 4830 2333 4830 2364 4831 2362 4831 2263 4831 2263 4832 2362 4832 2160 4832 2365 4833 2362 4833 2367 4833 2365 4834 2367 4834 2366 4834 2366 4835 2367 4835 2331 4835 2205 4836 2343 4836 2366 4836 2205 4837 2366 4837 2331 4837 2205 4838 2341 4838 2343 4838 2366 4839 2343 4839 2365 4839 2367 4840 2349 4840 2353 4840 2367 4841 2353 4841 2332 4841 2349 4842 2367 4842 2363 4842 2367 4843 2364 4843 2363 4843 2367 4844 2362 4844 2364 4844 2348 4845 2333 4845 2257 4845 2369 4846 2372 4846 2373 4846 2370 4847 2371 4847 2145 4847 2145 4848 2371 4848 2368 4848 2368 4849 2371 4849 2219 4849 2368 4850 2219 4850 2369 4850 2369 4851 2219 4851 2372 4851 2144 4852 2132 4852 2370 4852 2370 4853 2132 4853 2371 4853 2373 4854 2372 4854 2374 4854 2374 4855 2372 4855 2131 4855 2374 4856 2131 4856 2375 4856 2375 4857 2131 4857 2376 4857 2375 4858 2376 4858 2144 4858 2144 4859 2376 4859 2132 4859 2377 4860 2379 4860 2408 4860 2330 4861 2378 4861 2377 4861 2377 4862 2378 4862 2379 4862 2379 4863 2378 4863 2409 4863 2409 4864 2378 4864 2423 4864 2409 4865 2423 4865 2422 4865 2409 4866 2422 4866 2412 4866 2412 4867 2422 4867 2418 4867 2412 4868 2418 4868 2413 4868 2413 4869 2418 4869 2380 4869 2380 4870 2418 4870 2417 4870 2415 4871 2380 4871 2381 4871 2381 4872 2380 4872 2417 4872 2415 4873 2381 4873 2414 4873 2387 4874 2388 4874 2382 4874 2384 4875 2383 4875 2192 4875 2192 4876 2383 4876 2190 4876 2389 4877 2385 4877 2384 4877 2384 4878 2385 4878 2386 4878 2384 4879 2386 4879 2383 4879 2383 4880 2386 4880 2387 4880 2383 4881 2387 4881 2382 4881 2386 4882 2385 4882 2387 4882 2387 4883 2385 4883 2388 4883 2388 4884 2385 4884 2389 4884 2393 4885 2394 4885 2188 4885 2186 4886 2157 4886 2427 4886 2157 4887 2186 4887 2391 4887 2391 4888 2186 4888 2390 4888 2391 4889 2390 4889 2395 4889 2157 4890 2391 4890 2393 4890 2157 4891 2393 4891 2188 4891 2188 4892 2427 4892 2157 4892 2391 4893 2395 4893 2393 4893 2393 4894 2395 4894 2394 4894 2394 4895 2395 4895 2392 4895 2396 4896 2130 4896 2397 4896 2397 4897 2130 4897 2401 4897 2400 4898 2398 4898 2149 4898 2149 4899 2398 4899 2229 4899 2149 4900 2229 4900 2399 4900 2399 4901 2229 4901 2396 4901 2396 4902 2229 4902 2130 4902 2403 4903 2398 4903 2400 4903 2397 4904 2401 4904 2147 4904 2147 4905 2401 4905 2402 4905 2402 4906 2401 4906 2404 4906 2402 4907 2404 4907 2403 4907 2403 4908 2404 4908 2398 4908 2407 4909 2405 4909 2406 4909 2406 4910 2405 4910 2248 4910 2407 4911 2406 4911 2182 4911 2379 4912 2411 4912 2408 4912 2411 4913 2379 4913 2409 4913 2408 4914 2411 4914 2410 4914 2412 4915 2411 4915 2409 4915 2411 4916 2412 4916 2413 4916 2415 4917 2411 4917 2413 4917 2415 4918 2413 4918 2380 4918 2410 4919 2411 4919 2415 4919 2415 4920 2416 4920 2197 4920 2415 4921 2197 4921 2410 4921 2410 4922 2197 4922 2217 4922 2414 4923 2416 4923 2415 4923 2414 4924 2381 4924 2200 4924 2224 4925 2202 4925 2420 4925 2381 4926 2417 4926 2200 4926 2417 4927 2418 4927 2200 4927 2200 4928 2418 4928 2421 4928 2200 4929 2421 4929 2202 4929 2202 4930 2421 4930 2419 4930 2202 4931 2419 4931 2420 4931 2419 4932 2421 4932 2378 4932 2422 4933 2421 4933 2418 4933 2422 4934 2423 4934 2421 4934 2423 4935 2378 4935 2421 4935 2378 4936 2330 4936 2419 4936 2392 4937 2195 4937 2394 4937 2427 4938 2188 4938 2187 4938 2389 4939 2384 4939 2183 4939 2186 4940 2185 4940 2390 4940 2390 4941 2185 4941 2196 4941 2388 4942 2184 4942 2382 4942 2440 4943 2153 4943 2152 4943 2437 4944 2155 4944 2438 4944 2438 4945 2155 4945 2154 4945 2434 4946 2443 4946 2154 4946 2437 4947 2156 4947 2430 4947 2430 4948 2156 4948 2424 4948 2156 4949 2437 4949 2438 4949 2156 4950 2438 4950 2425 4950 2174 4951 2424 4951 2425 4951 2435 4952 2153 4952 2426 4952 2440 4953 2158 4953 2153 4953 2153 4954 2158 4954 2426 4954 2427 4955 2158 4955 2172 4955 2435 4956 2426 4956 2177 4956 2177 4957 2426 4957 2172 4957 2172 4958 2426 4958 2427 4958 2440 4959 2428 4959 2177 4959 2436 4960 2428 4960 2440 4960 2429 4961 2436 4961 2152 4961 2173 4962 2431 4962 2174 4962 2440 4963 2445 4963 2432 4963 2440 4964 2432 4964 2433 4964 2433 4965 2432 4965 2169 4965 2174 4966 2430 4966 2424 4966 2443 4967 2434 4967 2432 4967 2432 4968 2434 4968 2155 4968 2432 4969 2155 4969 2169 4969 2177 4970 2428 4970 2429 4970 2158 4971 2173 4971 2172 4971 2177 4972 2429 4972 2152 4972 2177 4973 2152 4973 2435 4973 2173 4974 2158 4974 2431 4974 2152 4975 2436 4975 2440 4975 2158 4976 2440 4976 2431 4976 2177 4977 2445 4977 2440 4977 2437 4978 2430 4978 2155 4978 2155 4979 2430 4979 2169 4979 2154 4980 2174 4980 2438 4980 2438 4981 2174 4981 2425 4981 2126 4982 2430 4982 2174 4982 2126 4983 2174 4983 2431 4983 2168 4984 2430 4984 2439 4984 2440 4985 2442 4985 2182 4985 2440 4986 2182 4986 2431 4986 2180 4987 2430 4987 2168 4987 2430 4988 2180 4988 2169 4988 2169 4989 2180 4989 2441 4989 2440 4990 2433 4990 2442 4990 2442 4991 2433 4991 2128 4991 2443 4992 2444 4992 2154 4992 2174 4993 2154 4993 2444 4993 2177 4994 2176 4994 2445 4994 2174 4995 2170 4995 2173 4995 2446 4996 2173 4996 2127 4996 2127 4997 2173 4997 2126 4997 2165 4998 2126 4998 2173 4998 2173 4999 2170 4999 2165 4999

+
+
+
+
+ + + + + + + + + + + + + + +
diff --git a/descriptions/deep_robotics/x30_description/meshes/r_thigh.dae b/descriptions/deep_robotics/x30_description/meshes/r_thigh.dae new file mode 100755 index 0000000..ad46482 --- /dev/null +++ b/descriptions/deep_robotics/x30_description/meshes/r_thigh.dae @@ -0,0 +1,63 @@ + + + + + VCGLab + VCGLib | MeshLab + + Y_UP + 周四 11月 23 02:58:54 2023 + 周四 11月 23 02:58:54 2023 + + + + + + + + + 0.0522824 0.0507959 0.00478035 -0.0522704 0.0507771 0.00490966 -0.0190265 0.0508364 -0.0489315 -8.22516e-05 0.0507543 -0.0525014 -0.0345969 0.0787541 -0.04331 -0.0404468 0.0722501 -0.0471124 -0.0294053 0.05375 -0.0471872 -0.0547183 0.0837528 -0.00972828 -0.0551606 0.0637492 -0.00595232 -0.054878 0.05375 -0.00758694 -0.0449732 0.0622387 0.0324536 -0.0518674 0.0837347 0.0339145 -0.00369853 0.0829079 0.0616278 -0.00758694 0.08575 0.054878 0.0324513 0.0622396 0.0449757 0.0404468 0.0572501 0.0471124 0.0349879 0.0772509 0.0430653 0.0287944 0.0824109 0.0476747 0.0341138 0.053707 0.0455431 -0.0101616 0.0536512 0.0573758 0.00840376 0.0507515 -0.0623008 -0.0426899 0.05375 0.0357237 0.0506243 0.0507497 -0.0377473 0.035801 0.05375 0.0520608 0.06274 0.0507517 0.00590139 0.062789 0.05375 -0.005152 -0.0290847 0.05375 0.0561741 -0.0393968 0.0537469 -0.0494889 -0.0391694 0.05075 -0.0494992 -0.0629651 0.05375 0.00209729 -0.0608931 0.050748 0.0168537 -0.0603756 0.05375 0.0186829 -0.0514406 0.0507445 0.0367348 -0.0261923 0.05075 -0.0572971 0.0106939 0.0537478 -0.0623951 0.00684284 0.08575 0.0564071 0.00225813 0.07875 0.0557879 0.00766068 0.0852401 0.0583066 -0.00671834 0.0840072 -0.0581637 -0.00502813 0.0787501 -0.0619102 0.0486734 0.08575 0.0298351 0.0500405 0.0774989 0.0293249 -0.0511532 0.085303 -0.0299556 -0.0387124 0.0853058 0.0430149 -0.0199771 0.0838681 0.0546234 -0.0422659 0.0831532 0.0440913 0.0498013 0.0827495 -0.0155718 0.0478066 0.0823045 0.0213558 0.0361011 0.0824455 0.0374558 -0.0518995 0.0827485 0.00972376 -0.0361012 0.0824455 -0.0374558 -0.0279773 0.08275 -0.0440503 -0.012364 0.0822441 -0.0508721 -0.0212993 0.0827498 0.0476112 -0.00686932 0.0827491 0.0517243 0.0520568 0.0824248 0.00406071 -0.0509555 0.0824092 -0.0106613 0.0151602 0.0840619 -0.0563502 0.0441003 0.08435 -0.0239754 0.043334 0.08575 -0.0245033 0.0498088 0.08435 -0.00622417 0.0492881 0.08575 -0.00699527 0.0230648 0.08435 0.044982 0.0204999 0.08575 0.0458193 -0.0357902 0.08575 0.0356991 -0.0374373 0.08435 0.0339677 -0.0272201 0.08575 -0.0421749 -0.015155 0.08575 -0.0502651 -0.0452622 0.0843582 0.027809 -0.00461559 0.0843543 0.0529077 0.0297351 0.0857527 0.0435916 0.0467757 0.0857528 0.0252919 0.052547 0.08435 0.0040533 0.0499087 0.08575 -0.0169333 0.0504416 0.08435 -0.0152727 0.0339084 0.08435 -0.0392896 -0.0516738 0.0848879 0.0236441 0.0535346 0.0846299 -0.0222225 -0.0550496 0.0852397 0.0219081 0.0317054 0.0417315 -0.0670286 -0.0113979 0.06575 -0.00235883 -0.00951333 0.0627273 0.0114658 0.00521671 0.0572815 -0.0111287 -0.00636255 0.057308 -0.0109006 2.87572e-05 0.0573096 0.01265 0.0116717 0.0586317 -0.00430049 0.00390324 0.077256 -0.0378613 0.0110798 0.0632581 0.00498012 -0.00398822 0.0632655 0.0114817 -0.0093387 0.0612523 0.00753126 -0.012324 0.0594725 0.000162703 0.0136159 0.0627499 0.00602442 -0.0170062 0.0627677 -0.0223042 0.0175446 0.062761 -0.0220618 0.0270607 0.0636573 -0.00752559 0.0225538 0.0627596 0.0170248 -0.00232 0.0627567 0.0281638 0.0174194 0.07725 -0.0219218 0.0114205 0.07725 -0.0255651 0.00580139 0.0627677 -0.0276562 -0.00824148 0.0627602 -0.02703 -0.0154659 0.07725 -0.0233411 -0.0245098 0.0627604 -0.0140638 -0.0231499 0.0772501 -0.0161323 -0.0272522 0.07725 -0.00642774 -0.0282537 0.0628348 -0.000517146 -0.026505 0.0638419 0.00919402 -0.0231777 0.0627717 0.0157818 -0.015598 0.0637447 0.0235685 0.00924629 0.0772501 0.0266585 0.027981 0.0627873 0.00396656 0.0277047 0.07725 -0.00405585 0.0258257 0.07725 -0.0108183 0.0223239 0.07725 -0.016901 -0.0265757 0.0782298 -0.0273792 -0.027661 0.0772772 0.0260878 0.0201188 0.0797296 0.0156898 0.0252597 0.07875 0.00349219 0.0204819 0.0796219 -0.0152387 0.0156542 0.07875 -0.0201295 -0.0153727 0.0797159 -0.0203619 -0.0247972 0.0797264 0.00699396 -0.00827103 0.06575 -0.0241341 -0.00695613 0.0797297 -0.0247647 0.00263519 0.06575 -0.0254819 0.010127 0.0796866 -0.0234361 0.0236217 0.07875 -0.00960555 0.0253598 0.0796862 -0.00294782 0.0253029 0.06575 -0.00316451 0.0234952 0.06575 0.0099109 0.0201295 0.06575 0.0156542 0.0153723 0.0797351 0.0203625 0.00940579 0.0797316 0.023736 0.015392 0.06575 0.0203307 0.00316451 0.07875 0.0253029 -0.00372239 0.0797319 0.0252589 -0.00739351 0.06575 0.0246066 -0.00991089 0.07875 0.0234952 -0.01569 0.0797351 0.0201187 -0.0142333 0.0573411 0.00314263 0.0432207 0.0442864 -0.0624596 0.0360673 0.0443094 -0.0569197 0.0400001 0.050892 -0.0663615 0.0123244 0.0797205 -0.0363616 -0.0133782 0.0772566 -0.0357009 -0.0210715 0.0827499 -0.0323097 -0.0344704 0.08275 -0.0164903 -0.0377582 0.077267 -0.00423781 -0.0355991 0.0772784 0.0143576 -0.0145547 0.0772569 0.0352935 -0.00137439 0.0827277 0.0382791 0.0118305 0.0772632 0.0359574 0.0235134 0.0772734 0.0299593 0.0383473 0.07727 -0.00283637 0.0379314 0.0827499 0.00462065 0.0465202 0.07475 -0.0232351 0.0517728 0.0747721 -0.0048647 0.0500323 0.07475 0.0141695 0.0465767 0.07475 0.0231216 0.035079 0.07475 0.0383857 0.0274284 0.07475 0.0441779 0.0188437 0.07475 0.0484656 0.012364 0.082244 0.0508721 6.34136e-05 0.07475 0.052 -0.00949263 0.07475 0.0511262 -0.0273205 0.07475 0.0442446 -0.0349853 0.07475 0.0384712 -0.0349902 0.0820978 0.0387382 -0.0465202 0.07475 0.0232351 -0.0433881 0.0823549 0.0287805 -0.0517728 0.0747721 0.00486467 -0.051784 0.07475 -0.0047348 -0.035079 0.07475 -0.0383857 -0.0415351 0.07475 -0.0312864 -0.0466693 0.0821797 -0.0234255 -0.0274284 0.07475 -0.0441779 -6.34136e-05 0.07475 -0.052 0.00686937 0.082749 -0.0517243 0.0408739 0.0823139 -0.0324249 0.0354602 0.088177 -0.0206678 0.0406281 0.08575 0.00346256 0.0334579 0.08575 0.0246623 -0.0131162 0.08575 0.0394414 -0.0378543 0.08575 -0.0171671 0.0125462 0.08575 -0.0396901 0.0395967 0.0881742 0.0112274 0.0100757 0.0881787 0.0399048 -0.022914 0.0881739 0.0341892 -0.039597 0.0881694 -0.0112283 -0.0316067 0.0881686 -0.0263633 0.0270895 0.0869208 -0.0294485 -0.0388724 0.0881993 -0.000697214 -0.0219117 0.0881925 -0.0325462 0.033723 0.0868653 -0.0188877 0.0250963 0.0883436 0.0315146 0.0329497 0.0881913 0.0206342 0.00182075 0.0857557 0.0390056 0.0124104 0.086692 -0.0379234 0.0370587 0.0858514 0.00860259 -0.0273725 0.0871465 0.0271979 -0.0372531 0.0857511 0.011813 -0.0305159 0.0857509 -0.0238244 -0.0176918 0.0857509 -0.0344357 -0.0354045 0.0855296 0.00494862 0.0101848 0.085371 -0.0342232 0.0242535 0.0855421 0.0264191 -0.0073776 0.0797709 0.0348211 -0.0184905 0.0855746 0.0306236 0.0292947 0.0797499 -0.0200528 0.0348573 0.0797499 -0.00778016 0.0343313 0.0847154 -0.0100886 0.0352922 0.07975 0.00383518 0.0353287 0.0847138 0.00569545 0.0321101 0.079757 0.0153602 0.0104815 0.0855399 0.0342951 -0.0035212 0.0855787 0.0356066 -0.0261068 0.0847035 0.0244596 -0.0321035 0.0855339 0.0155896 -0.0317416 0.0797499 0.0163609 -0.0355749 0.0797735 0.00101909 -0.0340781 0.0855249 -0.010765 -0.0325549 0.0797782 -0.014375 -0.0261186 0.0855206 -0.0243761 -0.0182578 0.0853899 -0.0307851 0.00312937 0.0797499 -0.0353094 0.030472 0.0844386 -0.049632 0.0332531 0.05075 -0.0603581 0.034158 0.0450315 -0.0670942 0.0397241 0.0519771 -0.0590099 0.0305571 0.082733 -0.0420046 0.0339245 0.0507411 -0.0664196 0.0362469 0.0505836 -0.0675726 0.0416141 0.0507877 -0.0628011 0.0045686 0.0679994 -0.0619494 0.00386544 0.077314 -0.0621975 0.00442803 0.0829202 -0.0590116 0.0554343 0.05725 -0.00269894 0.0541629 0.05725 -0.0121092 0.0553701 0.05375 -0.00619152 0.0483324 0.05725 -0.0276818 0.0513059 0.05375 -0.0211649 0.0444706 0.05375 -0.0335706 0.0556652 0.06225 0.00172655 0.0554755 0.05875 0.00207836 0.0541629 0.05875 -0.0121092 0.0541629 0.06225 -0.0121092 0.0342743 0.05875 -0.0436523 0.0541629 0.06375 -0.0121092 0.0554343 0.06725 -0.00269894 0.0541629 0.06725 -0.0121092 0.0513059 0.06375 -0.0211649 0.0342743 0.06725 -0.0436523 0.0554755 0.06875 0.00207836 0.0513059 0.06875 -0.0211649 0.0554755 0.07375 0.00207834 0.0554343 0.07725 -0.00269894 0.0541629 0.07725 -0.0121092 0.0483318 0.0772501 -0.0276826 0.0469675 0.07475 -0.0234586 0.0469671 0.0507802 -0.0234603 0.0504783 0.07475 -0.0144289 0.0522819 0.07475 0.00478034 0.0505133 0.07475 0.0143057 0.0470246 0.07475 0.0233439 0.0419345 0.07475 0.0315872 0.0419359 0.0507808 0.0315861 0.0354174 0.050775 0.0387545 0.0277004 0.0507665 0.0445984 0.0190265 0.0508364 0.0489315 0.00970977 0.05125 0.0515943 -0.0189055 0.07475 0.0489779 -0.00958065 0.0507929 0.051619 -0.0275832 0.07475 0.0446701 -0.0418573 0.07475 0.0316894 -0.0418568 0.0507636 0.0316909 -0.0469672 0.0507802 0.0234603 -0.0504783 0.07475 0.0144289 -0.0522824 0.0507686 -0.00478038 -0.0470246 0.07475 -0.0233439 -0.0470246 0.05125 -0.0233439 -0.0419345 0.07475 -0.0315872 -0.0354163 0.07475 -0.0387548 -0.027695 0.050756 -0.0446015 -0.0190249 0.07475 -0.0489316 -0.00970977 0.07475 -0.0515943 -6.4024e-05 0.07475 -0.0525 -0.00970977 0.05125 -0.0515943 0.00958391 0.07475 -0.0516178 0.00957996 0.0507992 -0.0516191 0.0189055 0.07475 -0.0489779 0.0189042 0.0508321 -0.0489789 0.0275832 0.05125 -0.0446701 0.0418573 0.07475 -0.0316894 0.0443074 0.03675 -0.0642116 0.0333471 0.0555518 -0.0697235 0.0331356 0.03675 -0.0694637 0.0367019 0.0405192 -0.070148 0.0305557 0.03675 -0.0669677 0.0409872 0.0507363 -0.056498 0.0306364 0.03675 -0.0588503 0.0308099 0.0581848 -0.067402 0.0443603 0.0544008 -0.0643693 0.0375794 0.0795165 -0.0493143 0.0354159 0.0828891 -0.051032 0.0346482 0.0855903 -0.052094 0.0353098 0.0508121 -0.0388538 0.0506585 0.0507604 0.0138589 0.0470259 0.0507521 0.0233425 -0.0189042 0.0508321 0.0489789 -0.0275819 0.0507525 0.0446715 -0.0504783 0.0507527 0.0144308 -0.0505139 0.0509414 -0.0143047 -0.0353207 0.050779 0.0388426 0.0504783 0.0507527 -0.0144308 8.22515e-05 0.0507543 0.0525014 -0.0419458 0.0508305 -0.0315744 -0.0354178 0.0508144 -0.038754 0.0522704 0.0507771 -0.00490963 -0.00380678 0.08142 -0.0555949 0.0359801 0.07875 0.0423952 0.0522915 0.0787505 0.0335659 0.0527524 0.0838738 0.0321659 0.0457554 0.08375 0.0320604 0.0522995 0.08225 0.0337809 0.036203 0.08225 0.0424306 0.0115506 0.08375 0.0548618 -0.0106137 0.07875 -0.0615057 -0.010407 0.08375 -0.0613952 -0.0322161 0.08225 -0.0534911 -0.0106155 0.08225 -0.0611627 -0.0301943 0.0828868 -0.0466471 -0.0106272 0.08225 -0.0548925 -0.030201 0.07875 -0.0469935 -0.0120953 0.0837499 -0.0546418 -0.0248594 0.08575 -0.0497513 -0.0454795 0.08575 -0.03297 0.055688 0.07875 0.00148403 0.0555628 0.0837483 0.00208041 0.0585573 0.08225 -0.0211484 0.0559354 0.08225 0.00137267 0.0533143 0.0805 -0.016815 0.0555665 0.08575 -0.00326132 -0.0499396 0.0792382 0.0243697 -0.0441555 0.0822754 0.0336244 -0.0148777 0.0787466 0.0536122 -0.0493304 0.07875 -0.0254316 -0.0554067 0.08375 -0.0285564 -0.0503924 0.08375 -0.0243507 -0.054974 0.0822504 -0.0287874 -0.0503738 0.08225 -0.0245587 -0.0540224 0.07875 -0.013155 -0.0554456 0.07875 -0.00326598 -0.0557589 0.08225 -0.00338108 -0.0502992 0.08575 -0.0261109 -0.00109992 0.06375 -0.0621614 -0.0209887 0.06375 -0.0585098 -0.00503949 0.06375 -0.0554147 -0.0339471 0.0637499 -0.0518641 -0.0232943 0.06375 -0.0506422 -0.0544722 0.06375 -0.030542 -0.0453438 0.06375 -0.0326959 -0.0618969 0.06375 0.00741486 -0.0497206 0.06375 0.0253264 -0.0526035 0.06375 0.033596 -0.030542 0.06375 0.0544722 -0.0254934 0.06375 0.049751 -0.0460525 0.06375 0.0414786 0.0530662 0.06375 0.0172492 0.0428397 0.06375 0.0453932 0.0554755 0.06375 0.00207836 0.0443852 0.06375 -0.0336421 0.0342743 0.06375 -0.0436523 0.0527164 0.06375 -0.0333723 0.0618969 0.06375 -0.00741487 0.00360117 0.0622502 -0.0623125 -0.00159484 0.06225 -0.0559124 -0.0548017 0.06225 0.0110389 -0.0388804 0.0626792 0.0395942 -0.0325964 0.06225 0.0532683 -0.0235799 0.06225 0.050686 0.0532818 0.06225 0.0162686 0.0532683 0.06225 0.0325964 0.0409113 0.0622501 0.0463664 0.0342743 0.06225 -0.0436523 0.0462662 0.06225 -0.0315619 0.0607155 0.06225 -0.0146172 -0.0169212 0.06875 -0.0601141 0.00328786 0.06875 -0.0554447 -0.0232943 0.06875 -0.0506422 -0.0339471 0.0687499 -0.0518641 -0.0405743 0.0680044 -0.0470353 -0.0544722 0.06875 -0.030542 -0.054141 0.0674837 -0.0125113 -0.061005 0.06875 0.0119294 -0.0619494 0.0680044 -0.0045686 -0.0556971 0.06875 0.00120212 -0.0526035 0.06875 0.033596 -0.0172492 0.06875 0.0530662 -0.0427488 0.06875 0.0446594 0.0402338 0.06875 0.0385338 0.0446594 0.06875 0.0427488 0.0530662 0.06875 0.0172492 0.0108103 0.06875 -0.0547133 0.0443852 0.06875 -0.0336421 0.0342743 0.06875 -0.0436523 0.061005 0.06875 -0.0119294 0.0541629 0.06875 -0.0121092 0.0527164 0.06875 -0.0333723 -0.0294208 0.06725 -0.0547692 -0.0590043 0.06725 -0.0184535 -0.048381 0.06725 -0.0274858 -0.0373848 0.06725 -0.0411691 -0.0491795 0.06725 0.0261723 -0.0411691 0.06725 0.0373848 -0.0315971 0.06725 0.0456276 -0.046608 0.06725 0.0415152 -0.0124106 0.0680006 0.0608652 0.0373848 0.06725 0.0411691 0.0415152 0.06725 0.046608 0.021478 0.0672514 -0.0517351 0.0130943 0.0672517 -0.0603034 0.0462662 0.06725 -0.0315619 0.0518304 0.06725 -0.034256 0.0607155 0.06725 -0.0146172 -0.033596 0.07375 -0.0526035 -0.0456276 0.07375 -0.0315971 -0.0544722 0.07375 -0.030542 -0.0527333 0.07375 -0.018147 -0.0497206 0.07375 0.0253264 -0.0556971 0.07375 0.00120214 -0.0172492 0.07375 0.0530662 -0.0427488 0.07375 0.0446594 -0.0385338 0.07375 0.0402339 0.0562139 0.07375 0.0265314 0.0402339 0.07375 0.0385338 0.0446594 0.07375 0.0427488 0.020525 0.07375 -0.0517133 0.0513059 0.07375 -0.0211649 0.0443852 0.07375 -0.0336421 0.0541629 0.07375 -0.0121092 0.0527164 0.07375 -0.0333723 0.00471326 0.0722501 -0.0619137 -0.0532818 0.07225 -0.0162686 -0.0491796 0.07225 0.0261723 -0.0378664 0.07225 0.0409841 0.0409841 0.07225 0.0378665 0.02471 0.07225 -0.0570013 0.0106501 0.07225 -0.0545254 0.0342743 0.07225 -0.0436523 0.0462662 0.07225 -0.0315619 0.0541629 0.07225 -0.0121092 0.0554343 0.07225 -0.00269894 -0.0239597 0.0772513 -0.0502543 -0.00652672 0.07725 -0.0552593 -0.0557557 0.07725 0.00220451 -0.0491504 0.0772503 0.0262333 -0.0119262 0.0772506 0.0542009 0.0608652 0.0779956 0.0124106 0.0532272 0.0772503 0.0326309 0.0342743 0.07725 -0.0436523 0.0518304 0.07725 -0.034256 0.0469572 0.0772494 -0.0406656 0.0623921 0.0784513 0.0029453 -0.0012021 0.07375 -0.0556971 -0.0180324 0.07375 -0.0524889 -0.0294818 0.07375 -0.0471523 -0.0368805 0.07375 -0.0415302 -0.0416046 0.07725 -0.0371372 -0.0532818 0.07725 -0.0162686 -0.0431252 0.07725 0.0348414 -0.0309449 0.07725 0.0465563 0.00120213 0.07375 0.0556972 0.0110389 0.07725 0.0548017 0.0436893 0.07725 0.0344591 0.0530662 0.07375 0.0172492 0.0519688 0.07725 0.0198854 0.0213327 0.07725 -0.0512364 -0.00315891 0.07225 -0.0556789 -0.00992108 0.06875 -0.0546061 -0.0261723 0.07225 -0.0491795 -0.0368805 0.06875 -0.0415302 -0.0416046 0.07225 -0.0371372 -0.0476249 0.06875 -0.0287759 -0.0557557 0.07225 0.00220451 -0.0497205 0.06875 0.0253264 -0.0385338 0.06875 0.0402339 -0.0162686 0.07225 0.0532818 0.0253264 0.06875 0.0497205 0.0532818 0.07225 0.0162686 -0.00220448 0.06725 -0.0557557 -0.0261723 0.06725 -0.0491795 -0.0534661 0.0623322 -0.0154408 -0.0554147 0.06375 0.00503952 -0.0557557 0.06725 0.00220449 -0.0162686 0.06725 0.0532818 0.0253264 0.06375 0.0497206 0.0423802 0.0622806 0.0361768 0.0456276 0.06375 0.0315971 0.0456276 0.06725 0.0315971 0.0532818 0.06725 0.0162686 0.0205311 0.06375 -0.0518995 -0.0261723 0.06225 -0.0491795 -0.0257277 0.0587487 -0.0496295 -0.0368805 0.05875 -0.0415302 -0.0347955 0.0637492 -0.0432133 -0.0436893 0.06225 -0.0344591 -0.0522744 0.0587194 -0.019293 -0.0385338 0.05875 0.0402339 -0.012495 0.05875 0.0541885 -0.00945044 0.0637492 0.0546682 0.0234784 0.0587572 0.0505083 0.0110389 0.06225 0.0548017 0.0213327 0.0605 -0.0512364 0.0108103 0.05875 -0.0547133 -0.00992108 0.05875 -0.0546061 0.00373483 0.05875 -0.0619489 -0.0169212 0.05875 -0.0601141 0.00328786 0.05875 -0.0554447 -0.0339471 0.0587499 -0.0518641 -0.0456276 0.05875 -0.0315971 -0.0544722 0.05875 -0.030542 -0.0411636 0.05875 -0.0464454 -0.0604464 0.0587499 -0.0130316 -0.0619494 0.0580044 -0.0045686 -0.0556971 0.05875 0.00120212 -0.0505083 0.0587572 0.0234784 -0.0243645 0.05875 0.0498661 0.0562139 0.05875 0.0265314 0.0395797 0.0587194 0.0391744 0.0530662 0.05875 0.0172492 0.0446594 0.05875 0.0427488 0.0513059 0.05875 -0.0211649 0.0619494 0.0580044 0.0045686 0.0375879 0.05875 -0.0493067 0.0527164 0.05875 -0.0333723 -0.0317929 0.05725 -0.0536589 -0.0506205 0.05725 -0.0360761 -0.0404468 0.05725 -0.0471124 -0.0605397 0.05725 -0.0151896 -0.0535487 0.05725 0.0320674 -0.0557117 0.05725 0.000928003 -0.0524889 0.05725 0.0180324 -0.0371372 0.05725 0.0416046 -0.0124106 0.0580006 0.0608652 -0.0156295 0.05725 0.053708 -0.0325964 0.05725 0.0532683 -0.0471124 0.0572501 0.0404468 0.0532683 0.05725 0.0325964 0.0247709 0.0579879 -0.0571192 0.0440197 0.0574148 -0.0341828 0.0462692 0.0586302 -0.0414761 -0.00577845 0.05725 -0.0552923 -0.0222192 0.0572509 -0.0510553 -0.0425057 0.05375 -0.0359475 -0.0416046 0.05725 -0.0371372 -0.0498661 0.05725 -0.0243645 -0.0164828 0.0538379 0.0529961 0.0180324 0.05725 0.0524889 0.000979014 0.0572512 0.0557153 -0.00358201 0.05375 0.0554282 0.0429542 0.0537509 0.0354982 0.0466601 0.0572482 0.0308653 0.0210377 0.05725 -0.0516661 -0.0519567 0.0587499 0.0335273 -0.060533 0.0824406 -0.0132655 0.0406705 0.083546 0.0469279 0.013058 0.08575 -0.0604352 0.0123161 0.0772471 -0.0608842 -0.0623921 0.0784513 -0.0029453 -0.0608889 0.0787492 -0.0122526 -0.0561525 0.07875 0.0260252 0.0405743 0.0779994 0.0470353 -0.0411636 0.07375 -0.0464454 -0.0608701 0.0737499 -0.0122617 -0.0124106 0.0730006 0.0608652 0.0342626 0.0724508 0.0518139 0.0619494 0.0730044 0.0045686 -0.0608701 0.0687499 -0.0122617 0.0619494 0.0680044 0.0045686 0.01227 0.0622656 -0.0608039 -0.0237821 0.06225 -0.0576248 -0.0122526 0.0637492 0.0608889 -0.0140592 0.06225 0.0602962 -0.00385732 0.06225 0.0617147 0.0541926 0.08575 -0.0197492 0.0198512 0.0856892 -0.0539894 0.0175716 0.0857506 -0.0502131 -0.00274362 0.08575 -0.0525527 0.0188245 0.0845711 -0.0561141 -0.00899728 0.0857503 -0.0560024 -0.00521536 0.0857522 -0.0566317 -0.0292177 0.08575 -0.0438628 -0.0462512 0.08575 -0.0260241 -0.0530629 0.08575 0.00296157 -0.0119166 0.0857477 0.0517199 -0.0183785 0.0857502 0.0538886 0.0132136 0.08575 0.0509236 0.0248593 0.08575 0.0497514 0.0346158 0.0837641 0.0433649 0.0508177 0.0857499 0.0242647 0.0526523 0.08575 0.00231249 0.0498779 0.08575 -0.0251683 0.0432662 0.0849534 -0.0372769 0.0468082 0.0857042 -0.040808 0.0348493 0.08575 -0.0418817 0.0383343 0.0851953 -0.0435256 -0.0384754 0.0857441 0.0367613 -0.0555433 0.08575 0.00364868 -0.00477553 0.0823801 -0.061699 0.0102785 0.0787505 0.0613315 0.0285351 0.07875 0.048129 0.00680398 0.0837481 0.0619703 0.0100734 0.08225 0.0613204 -0.0407557 0.07875 -0.0376725 -0.0387035 0.0830486 -0.0398338 0.0550253 0.0787509 0.029114 0.0510882 0.07875 0.0221225 0.0548227 0.0837499 0.0105711 0.0503923 0.08375 0.0243507 0.0564217 0.0837501 0.0259974 0.0521027 0.0822736 0.0195934 0.0605139 0.08225 0.0144604 -0.0406572 0.07875 0.0382816 -0.0227413 0.07875 0.051034 -0.0333226 0.0840787 0.0448705 -0.0236067 0.0829504 0.0576675 -0.0334093 0.08225 0.0447823 -0.0227204 0.08225 0.0511549 0.00227627 0.0829899 0.0557906 0.0236609 0.08575 -0.048954 0.0266017 0.0844868 -0.0509165 0.0317596 0.0845079 -0.0462592 -0.0437773 0.08575 -0.0252766 -0.0407153 0.08575 0.00836175 -0.049622 0.08575 -0.00398889 -0.0476542 0.08575 0.0143988 -0.0242495 0.08575 -0.0333093 -0.00860497 0.08575 -0.0402927 -0.00570304 0.08575 -0.0502279 0.0181214 0.08575 -0.0472835 0.0380571 0.08575 -0.0167694 0.0304541 0.08575 -0.0410812 -0.030592 0.08575 0.0275985 -0.0161037 0.08575 0.0475429 0.0125719 0.08575 0.0396182 0.00236103 0.08575 0.0501406 0.0349282 0.08575 0.0354721 0.045466 0.08575 0.0202755 0.0431598 0.0780726 -0.0351861 0.0509379 0.07875 -0.0250503 0.0521179 0.08375 -0.0334538 0.0564593 0.0827454 -0.0248231 -0.05853 0.0787501 0.020671 -0.0597975 0.08375 0.0175897 -0.0619451 0.08375 -0.00402016 -0.053246 0.0847775 0.0197573 -0.0554953 0.0837474 -0.00199454 -0.0586633 0.08225 0.02067 -0.0185283 0.0857533 0.0340355 0.0213112 0.0857511 0.0323211 0.0329128 0.0857511 0.0203855 0.0381914 0.0858731 -0.00349009 -0.00329831 0.0854636 -0.0356483 -0.00210349 0.0858079 -0.0385938 -0.0376991 0.0857508 -0.00880918 0.0398514 0.0883541 -0.0057235 -0.0017302 0.0882583 -0.0410379 -0.0181512 0.088168 -0.0369397 -0.0349868 0.0882004 -0.0169554 -0.0407404 0.0881706 0.00584816 -0.0339677 0.0883122 0.0218247 -0.00586889 0.0883112 0.0401595 0.00506214 0.0882137 0.038625 0.0353777 0.0882854 0.0204659 -0.00157684 0.0827499 -0.0381792 0.0210346 0.0827499 0.0319012 0.0324854 0.08275 0.0201206 0.0273051 0.0827501 0.0443913 -0.0382086 0.0827499 -0.000492452 -0.034884 0.0827499 0.0155965 0.0355062 0.0827502 -0.0149049 -0.0141346 0.08275 0.0352734 -0.0251111 0.0827499 0.0288024 0.010094 0.08275 0.0366348 0.0260602 0.08275 -0.0276562 0.0562139 0.06375 0.0265314 0.0608652 0.0629956 0.0124106 0.0102845 0.06225 0.0613037 0.033596 0.06375 0.0526035 -0.0463664 0.0622501 0.0409114 -0.0628687 0.06225 -0.0011702 -0.0545827 0.06225 0.0290285 -0.0411636 0.06375 -0.0464454 -0.0436274 0.06225 -0.0452824 -0.0590043 0.06225 -0.0184535 -0.0608701 0.0637499 -0.0122617 0.0247707 0.0629879 -0.0571193 0.00741489 0.06375 0.0618969 0.00503949 0.06375 0.0554147 -0.00595233 0.0637492 0.0551606 0.0294208 0.06225 0.0547692 0.0562139 0.06875 0.0265314 0.0554801 0.06725 0.0280335 0.0608652 0.0679956 0.0124106 -0.0045686 0.0680044 0.0619494 0.0294208 0.06725 0.0547692 -0.0280336 0.06725 0.0554801 -0.0265314 0.06875 0.0562139 -0.0613037 0.06725 0.0102845 -0.0545827 0.06725 0.0290285 -0.0506205 0.06725 -0.0360761 -0.0102845 0.06725 -0.0613037 0.02471 0.06725 -0.0570013 0.0119294 0.06875 0.061005 0.033596 0.06875 0.0526035 0.00120211 0.06875 0.0556972 0.0102845 0.06725 0.0613037 0.00220448 0.06725 0.0557557 0.0261723 0.06725 0.0491795 0.0415152 0.07225 0.046608 0.0554801 0.07225 0.0280335 0.0608652 0.0729956 0.0124106 -0.046608 0.07225 0.0415152 -0.0265314 0.07375 0.0562139 -0.0280336 0.07225 0.0554801 -0.0619494 0.0730044 -0.0045686 -0.0613037 0.07225 0.0102845 -0.061005 0.07375 0.0119294 -0.0526035 0.07375 0.033596 -0.0545827 0.07225 0.0290285 -0.0506205 0.07225 -0.0360761 -0.0590043 0.07225 -0.0184535 -0.00741489 0.07375 -0.0618969 -0.0102845 0.07225 -0.0613037 -0.0294208 0.07225 -0.0547692 0.0248102 0.07375 -0.0571976 0.01227 0.0722656 -0.0608039 0.0294818 0.07375 0.0471523 0.00109993 0.07375 0.0621614 0.0209887 0.07375 0.0585098 0.0180324 0.07375 0.0524889 0.0194076 0.07225 0.0590531 -0.00360116 0.0722502 0.0623125 0.0022045 0.07225 0.0557557 0.0261723 0.07225 0.0491796 -0.00515563 0.07725 0.0551725 -0.00392675 0.0781334 0.0618991 0.0276904 0.0772889 0.0480656 0.0298877 0.07725 0.0550603 0.0339242 0.0837499 0.0524384 0.0322161 0.08225 0.0534911 0.033596 0.0787498 0.0526035 0.00558445 0.0773291 0.0617271 -0.0232063 0.07875 0.0577548 -0.0442688 0.077273 0.0430644 -0.0545827 0.07725 0.0290285 -0.0612668 0.0772494 0.0107106 -0.0623125 0.0822502 -0.00360117 -0.0414324 0.0831566 -0.0464192 -0.0551129 0.0787506 -0.0288791 -0.0520398 0.0787503 -0.0343362 -0.0415869 0.0772496 -0.0467845 -0.0562479 0.07725 -0.0249004 -0.0520466 0.0822504 -0.0339567 -0.0339242 0.0837499 -0.0524384 -0.033596 0.0787498 -0.0526035 -0.0330712 0.07725 -0.0524175 -0.0197019 0.0772499 -0.0589333 0.0245131 0.0773672 -0.0572538 0.061839 0.06225 0.00426883 0.0518304 0.06225 -0.034256 0.061005 0.07375 -0.0119294 0.0607155 0.07225 -0.0146172 0.0518304 0.07225 -0.034256 0.0623125 0.0822502 0.00360117 0.0597975 0.08375 -0.0175897 0.0565333 0.0772741 -0.0253667 0.0584105 0.0787502 -0.0211362 0.0612668 0.0772494 -0.0107106 0.0251556 0.05375 -0.0577598 0.021355 0.05375 -0.0516532 0.0248102 0.06875 -0.0571976 0.0213327 0.0705 -0.0512364 0.0342743 0.07375 -0.0436523 0.0375879 0.06725 -0.0493067 0.0376526 0.06875 -0.0494168 0.0342743 0.05725 -0.0436523 0.0375879 0.05725 -0.0493067 0.0380971 0.05375 -0.0501758 0.0320674 0.05725 0.0535487 -0.0427488 0.05875 0.0446594 -0.0265314 0.05875 0.0562139 -0.0613037 0.05725 0.0102844 -0.0601141 0.05875 0.0169212 -0.0102845 0.05725 -0.0613037 0.01227 0.0572656 -0.0608039 -0.0045686 0.0580044 0.0619494 0.0169212 0.05875 0.0601141 0.0012021 0.05875 0.0556972 0.0335273 0.0587499 0.0519567 0.0102845 0.05725 0.0613037 0.0608652 0.0579956 0.0124106 0.061005 0.05875 -0.0119294 0.0607155 0.05725 -0.0146172 0.0518304 0.05725 -0.034256 0.00562179 0.0572946 0.0134247 -0.00305504 0.0573701 0.0146822 -0.00690085 0.0626881 -0.0131003 0.00108391 0.057308 -0.0146011 -0.00947138 0.063423 -0.00714544 0.0114801 0.0632607 -0.002419 -0.00829314 0.06575 0.00860999 0.00394166 0.0657022 0.0112484 0.0109046 0.06575 0.00365897 0.0252597 0.06575 0.00349219 0.0237787 0.06575 -0.00912929 0.00590032 0.06575 0.0250067 -0.0203307 0.06575 0.015392 -0.0176132 0.06575 -0.0187062 0.0156542 0.06575 -0.0201295 -0.0027096 0.0653394 -0.0111181 -0.0246066 0.06575 -0.0073935 0.00991089 0.06575 -0.0234952 0.00442025 0.065691 -0.0111297 0.0203307 0.06575 -0.015392 -0.0156542 0.06575 0.0201295 -0.0251322 0.0657466 0.0061881 -0.0224669 0.0797319 -0.0124918 -0.00955475 0.0797498 -0.0344021 -0.0252683 0.0797296 -0.00352838 -0.0203623 0.079729 0.0153724 -0.0234063 0.0797499 -0.0269641 0.00355168 0.0796418 -0.0252599 0.0234941 0.0797131 0.00994745 -0.0216391 0.0797499 0.0284084 0.00837958 0.0797499 0.034716 0.0224768 0.0797499 0.0277536 -0.0471935 0.0537486 0.0418697 -0.0620392 0.053749 -0.0119806 -0.0519291 0.05375 -0.0202399 -0.0529899 0.0537495 0.018555 -0.0517613 0.05375 0.0358511 -0.0287759 0.05375 0.0476249 -0.00662023 0.0537507 0.0628748 0.0150495 0.05375 0.0613823 0.024238 0.0537503 0.0500195 0.010692 0.05375 0.0545236 0.0574772 0.05375 0.0257948 0.0499762 0.05375 0.0386866 0.0624574 0.0537504 0.00904395 0.0541471 0.0537712 0.0128688 0.0493835 0.05375 -0.0394227 0.0342743 0.05375 -0.0436523 0.0593973 0.05375 -0.0215923 -0.0542263 0.05375 -0.0324619 -0.0339005 0.05375 -0.0459421 -0.0130862 0.05375 -0.0618883 -0.0135894 0.0537495 -0.0540573 0.0609796 0.05075 0.0158267 -0.0456973 0.0508308 0.0341497 -0.0620297 0.0507493 -0.0126259 -0.0556691 0.0536962 -0.00578765 0.0439753 0.0575091 -0.0602214 0.0380971 0.05075 -0.0501758 0.0418683 0.0508021 -0.0316782 0.0608654 0.0507476 -0.0174134 0.0456497 0.05075 0.0434116 0.0547995 0.0507481 0.031448 -0.00526681 0.0507496 0.0626106 0.0131838 0.0507475 0.0617934 0.0351322 0.0507493 0.0526039 -0.0407851 0.0507492 0.0480095 -0.0629639 0.050749 0.00187087 -0.0532402 0.0507486 -0.0340375 -0.0101688 0.0507483 -0.0623604 0.0151961 0.0507498 -0.0611346 0.0304382 0.05075 -0.066774 0.0292687 0.0507476 -0.0616645 0.0251334 0.0507479 -0.0577235 0.0339653 0.05075 -0.0558917 0.0499975 0.07475 -0.0142915 0.051784 0.07475 0.00473481 0.0522701 0.07475 -0.00490783 0.0415351 0.07475 0.0312864 0.0354163 0.07475 0.0387548 0.0276921 0.07475 0.0446027 0.0190249 0.07475 0.0489316 0.0096173 0.07475 0.0511029 0.00970977 0.07475 0.0515943 6.4024e-05 0.07475 0.0525 -0.00958391 0.07475 0.0516178 -0.0187254 0.07475 0.0485114 -0.0353217 0.07475 0.0388411 -0.0414587 0.07475 0.0313876 -0.0469675 0.07475 0.0234586 -0.0499858 0.0747965 0.0143252 -0.0522701 0.07475 0.00490784 -0.0522819 0.07475 -0.00478033 -0.0500323 0.07475 -0.0141695 -0.0505133 0.07475 -0.0143057 -0.0465767 0.07475 -0.0231216 -0.0276921 0.07475 -0.0446027 -0.0188437 0.07475 -0.0484656 -0.0096173 0.07475 -0.0511029 0.00949263 0.07475 -0.0511262 0.027505 0.0752144 -0.0447019 0.0414587 0.07475 -0.0313876 0.0351907 0.0754704 -0.038921 0.00470388 0.07725 -0.0276021 -0.00230825 0.07725 -0.0279047 -0.00917535 0.07725 -0.026454 -0.0352825 0.0772651 -0.0142816 -0.0279189 0.0772501 0.0040872 -0.0224965 0.0772501 0.0170317 0.0274629 0.0772501 0.00647744 0.0339194 0.0772699 0.0173174 0.0302626 0.0772593 -0.0234042 0.0254874 0.07725 -0.0192448 0.0209454 0.0772501 0.0189066 -0.00474024 0.0772501 0.0278154 -0.0145346 0.07725 0.0239321 -0.0207979 0.06275 0.00563101 0.0234125 0.0628318 -0.0154532 0.0148785 0.0627358 -0.0021264 -0.0133114 0.0627375 -0.00628777 -0.0147047 0.0627566 0.0021429 0.0115623 0.0627613 0.0257844 0.00536659 0.0627472 0.0142072 0.0106379 0.0572162 0.00685857 0.0127955 0.0573324 -0.00692793 0.00723803 0.0627517 -0.0131909 0.0376532 0.06375 -0.0494162 0.0378717 0.0622914 -0.0496552 0.0465251 0.0675799 -0.0411782 0.0465251 0.0725799 -0.0411782 0.0376532 0.07375 -0.0494162 0.0375879 0.07225 -0.0493067 0.0376701 0.07725 -0.0494447 0.0355985 0.03675 -0.0557404 0.0294311 0.03675 -0.0635587 0.0438916 0.0366208 -0.0610859 0.0404879 0.036589 -0.056251 0.040772 0.0421078 -0.0578794 0.0313696 0.0442711 -0.0598664 0.0405562 0.044302 -0.0678833 0.0107226 0.08275 -0.0367457 -0.0561772 0.0824946 0.0259419 -0.0528621 0.08225 0.0177505 -0.0530143 0.07875 0.0179054 0.047168 0.0829012 -0.0290369 0.0532885 0.08375 -0.0167829 0.0165838 0.0843415 -0.0489178 0.0195901 0.08435 0.0489269 0.0360212 0.0843485 0.0384606 0.0407668 0.08435 0.0292869 0.0475949 0.0843533 0.0227155 0.048644 0.08435 0.0123859 0.0436652 0.0854023 -0.0291358 0.0293397 0.0854099 -0.0556508 0.00103684 0.08435 -0.0501854 -0.0173528 0.08435 -0.0471013 -0.000280399 0.0843475 -0.0526736 -0.0190108 0.08435 -0.0491549 -0.0322489 0.08435 -0.0399614 -0.0397361 0.08435 -0.0306707 -0.0495702 0.08435 -0.00990722 -0.0421062 0.08435 -0.0316967 -0.0507329 0.08435 -0.0142753 -0.0524569 0.08435 0.00508839 -0.0482859 0.08435 0.0137158 -0.0273955 0.08435 0.0450234 -0.0176793 0.08435 0.0469797 0.000688608 0.08435 0.0501914 0.029075 0.08275 -0.0328017 0.0101114 0.07975 -0.0341273 0.0260735 0.0854786 -0.0247253 0.0244833 0.0797538 -0.0263572 0.0408577 0.0824205 -0.0413756 0.0359312 0.050737 -0.0583787 0.0246041 0.0801293 -0.0458791 0.0324191 0.0507829 -0.0623491 0.0226562 0.0827976 -0.0473889 -0.0387966 0.0772642 0.0485049 -0.0392012 0.0835142 0.0480073 -0.0179548 0.0774892 0.0593899 -0.033525 0.07875 0.0448232 -0.017921 0.0831509 0.0593091 -0.0139092 0.0827438 0.0537583 -0.0462968 0.0805 -0.0306082 -0.0457505 0.08375 -0.0321774 0.0543886 0.08225 0.0293483 0.0457554 0.07875 0.0320604 0.0458728 0.08225 0.0320629 -0.0101279 0.07875 -0.0548603 0.0113865 0.0805 0.0547312 0.0545719 0.0772505 0.00974052 0.0619451 0.08375 0.00402016 0.054878 0.08575 0.00758695 0.0551529 0.07725 0.00516789 0.0551529 0.07225 0.00516789 0.0551529 0.06725 0.00516789 0.0549937 0.0572496 0.00734875 0.0106501 0.06225 -0.0545254 0.00996787 0.0772475 -0.0547688 0.0116876 0.08575 -0.0555829 0.00463551 0.053748 -0.0555199 0.00538152 0.0786247 -0.0552182 0.00758694 0.08575 -0.054878 0.00471326 0.0572501 -0.0619137 0.0070751 0.0572156 -0.0550539 0.00595233 0.0637492 -0.0551606 -0.0179169 0.0507474 0.0607033 -0.0355697 0.0507501 -0.0455406 0.0415438 0.0366741 -0.0687837 0.0397771 0.0505595 -0.0700931 0.0437474 0.053432 -0.0658438 0.0273052 0.0827954 -0.055831 0.0261816 0.0824656 -0.0562042 -0.00643736 -0.0197501 -0.0122169 0.0659987 0.023272 -0.0300069 0.0686007 -0.01975 -0.0234561 0.0627939 0.0230022 -0.0362378 0.0536656 -0.01975 -0.0487468 0.0529795 0.0225937 -0.0495714 0.0609472 0.02525 0.00100954 0.0601146 0.02525 0.00287768 -0.0299614 -0.01975 0.0490772 -0.0223275 -0.01975 0.052988 -0.0141969 -0.01975 0.0557198 -0.0223275 0.02525 0.052988 -0.0403002 0.02525 0.0480984 -0.0310243 0.02525 0.054544 0.0235141 0.02525 0.0581778 0.0425245 0.02525 0.0461436 0.0602111 0.02525 0.0176689 0.0560679 0.0252777 0.0281771 0.0625733 0.02525 -0.00470604 0.0384406 -0.02575 -0.0323216 0.0444568 -0.02575 -0.0228821 0.0478095 -0.02575 -0.0146372 0.0461765 -0.01975 -0.0196378 0.0384193 -0.01975 -0.0322973 0.0043268 -0.02575 -0.0500365 0.0234564 -0.02575 -0.0441565 0.0234564 -0.01975 -0.0441565 0.0152556 -0.02575 -0.0476158 -0.018161 -0.02575 -0.0467771 -0.0500318 -0.02575 -0.00432678 -0.0458862 -0.02575 -0.019356 -0.0444568 -0.02575 0.0228821 -0.0478096 -0.02575 0.0146372 -0.0122352 -0.02575 0.00645512 -0.050056 -0.02575 0.00368047 -0.0198672 -0.01975 0.0461994 -0.0234564 -0.02575 0.0441565 -0.0320008 -0.02575 0.037211 -0.0152556 -0.02575 0.0476158 0.0146372 -0.02575 0.0478096 0.0441565 -0.02575 0.0234564 0.00395138 -0.02575 0.00973778 0.0228821 -0.02575 0.0444568 0.0323216 -0.02575 0.0384406 0.0268805 -0.01975 -0.05083 0.00513048 0.0297501 -0.0890974 0.0187405 0.02975 -0.0598862 -0.0548353 0.02975 -0.0833241 -0.0611599 0.02975 -0.0140366 -0.0626989 0.0299372 -0.00338404 -0.0448259 0.02975 -0.0439113 -0.0520741 0.02975 -0.0350121 0.0625438 0.0298426 -0.00525218 0.0604283 0.0299112 0.0167986 0.0247667 0.030145 0.0576549 0.0500773 0.0300329 0.0378237 -0.00984578 0.0302083 0.0619902 0.0710551 0.0258406 -0.0254119 0.0720826 0.02375 -0.0357525 0.0624701 0.0298901 0.00598142 0.0745329 0.0238384 0.000847672 0.0685888 0.02375 0.0146336 0.061626 0.0239286 0.0277506 0.0424399 0.0302976 0.0462491 0.0553437 0.0238273 0.0373842 0.0339375 0.0304426 0.0527811 0.0421377 0.023901 0.0518177 0.00811546 0.0298864 0.0624646 0.0122718 0.0237493 0.0661664 -0.0203885 0.0303259 0.0593425 -0.0300742 0.030373 0.0550559 -0.0243181 0.0236254 0.0621524 -0.0542671 0.0304117 0.0314888 -0.0487273 0.0236383 0.0453132 -0.0421478 0.02375 0.0512161 -0.0402819 0.0301953 0.0481419 -0.0543813 0.02375 0.0386371 -0.0625028 0.02375 0.0246503 -0.0593106 0.0301345 0.0205069 -0.0648174 0.023879 0.0180113 -0.0686553 0.02375 -0.0103739 -0.0624132 0.02975 -0.0236601 -0.0689429 0.02375 -0.0202676 -0.0614094 0.02975 -0.0621953 0.0578969 0.0237415 -0.052519 0.067896 0.0237628 -0.0413429 0.0626508 0.0251437 -0.0420433 0.0425488 0.02375 -0.0677019 0.0500616 0.0249725 -0.0566623 0.0325365 0.02975 -0.0632135 0.02926 0.0264695 -0.0750638 0.0607475 0.02525 -0.00102596 0.0608112 0.0253918 -0.0158772 0.0014806 0.02525 0.0627325 0.000547174 0.02525 0.0608924 -0.0483868 0.02525 0.0399535 0.0166245 0.02525 -0.0550443 0.0268805 0.02525 -0.05083 0.050108 0.02525 0.0377723 0.0490597 0.02525 0.0299899 0.033563 0.02525 0.0530197 -0.0293516 0.02525 -0.0494443 0.00751925 0.02525 -0.0622979 0.0624032 0.02525 0.00658817 -0.0494443 0.02525 0.0293515 -0.0548546 0.02525 0.0304719 -0.0600329 0.02525 0.00224012 -0.036078 0.02525 -0.0513414 0.0557171 0.02525 0.0142077 -0.00133634 0.02525 0.0608802 -0.0299614 0.02525 0.0490771 -0.0439937 0.02525 0.0421039 -0.0445567 0.02525 0.0403064 -0.0575802 0.02525 -0.0249416 -0.026123 0.02525 -0.0570539 -0.00978989 0.02525 0.0619816 -0.0141969 0.02525 0.0557198 -0.0207432 0.02525 0.0592223 -0.0520741 0.02525 -0.0350121 -0.0435278 0.02525 -0.0376855 0.0293516 0.02525 0.0494443 0.0127031 0.02525 0.0614507 0.0134844 0.02525 0.0558965 -0.0611599 0.02525 -0.0140366 -0.0371244 0.02525 -0.0440102 -0.0532646 0.02525 0.0216596 -0.0558965 0.02525 0.0134844 -0.0183931 0.02525 -0.0546322 0.0293348 0.02975 -0.055471 0.0187405 0.02525 -0.0598862 0.00751925 0.02975 -0.0622979 -0.00395358 0.02975 -0.0626253 -0.0152941 0.02525 -0.0608576 -0.021842 0.02975 -0.0590784 -0.036078 0.02975 -0.0513414 -0.0575802 0.02975 -0.0249416 -0.0626935 0.02525 -0.00266199 -0.0621241 0.0300329 0.00885438 -0.0621296 0.02525 0.00880166 -0.0594872 0.02525 0.0199708 -0.0483877 0.0302514 0.0399751 0.0216596 -0.01975 0.0532645 0.0216596 0.02525 0.0532646 0.0490597 -0.01975 0.0299899 0.0529794 -0.01975 0.0223481 0.0529794 0.02525 0.0223481 0.0557171 -0.01975 0.0142077 -0.0558965 -0.01975 0.0134844 -0.0532646 -0.01975 0.0216596 -0.0494443 -0.01975 0.0293515 -0.0512614 0.0252523 -0.0262624 -0.0557171 0.02525 -0.0142077 -0.0557171 -0.01975 -0.0142077 -0.010838 0.01825 -0.0564127 -0.0249535 0.01825 -0.0519644 0.00112824 -0.0242036 -0.0947503 0.0384937 -0.0239876 -0.0715387 0.0480425 0.02375 -0.0624058 0.0581245 -0.0229536 -0.0522409 0.068995 -0.0220428 -0.0399013 0.0761973 0.0237391 -0.0291687 0.072802 -0.0216521 -0.0347304 0.0783698 0.02375 -0.0118939 0.07895 0.02375 -0.0167321 0.0789682 -0.0204429 -0.0179611 0.0785677 0.0237181 -0.0221724 0.0784453 -0.0207795 -0.0229473 0.0770682 0.02375 -0.00671556 0.0740693 -0.0190193 0.00196016 0.0705719 -0.0183989 0.0103983 0.0645833 -0.0175124 0.0227632 0.0335262 0.0238868 0.0580601 0.0488455 0.0238609 0.0453563 0.0350297 -0.0154232 0.0571261 0.00266972 0.0237586 0.0672288 0.0111149 -0.0152425 0.0663695 0.0245515 -0.0152198 0.0626202 0.023914 0.0238056 0.0628831 -0.0138253 -0.0158513 0.0655882 -0.00388152 -0.0155718 0.0671018 -0.00758813 0.0236991 0.0667854 -0.0348484 -0.0169301 0.0566106 -0.0347992 0.0237249 0.0565875 -0.0243295 -0.0163386 0.0621102 -0.0421537 -0.0174961 0.0512104 -0.0585858 0.0236853 0.0326403 -0.0546784 -0.0186679 0.0382757 -0.048657 -0.0180534 0.045352 -0.0651649 -0.020331 0.0167824 -0.067502 0.0236568 0.00471159 -0.0688944 0.02375 -0.0336778 -0.0683333 0.02375 -0.0509146 -0.0676285 -0.0241682 -0.0642649 -0.0673922 0.02375 -0.068035 -0.066427 -0.024242 -0.078462 -0.0651353 0.023755 -0.0824718 -0.0631759 0.0237526 -0.085425 -0.0605728 0.0237538 -0.0873307 -0.06031 -0.0242279 -0.0875699 -0.0529211 -0.01975 -0.0894959 -0.0529203 0.01825 -0.0895327 -0.0602161 0.0297501 -0.0781287 -0.0665334 0.0237372 -0.0781603 -0.0556464 0.0238253 -0.0892038 0.0214463 0.0237459 -0.0872943 0.019018 0.02975 -0.0822437 0.0150451 0.0240139 -0.0916167 0.00044363 0.0237439 -0.0946829 0.00862527 0.02375 -0.093941 0.00589815 -0.0197498 -0.094409 0.0145232 -0.0242057 -0.0918745 0.011195 0.02375 -0.0932369 0.0101533 -0.02423 -0.0935711 0.0251616 -0.0242073 -0.0838604 0.005883 0.01825 -0.0944518 0.0194422 -0.0242229 -0.0888417 -0.0684238 -0.023874 -0.0488346 -0.068424 -0.0218588 -0.00623074 -0.0686694 -0.02213 -0.0106948 -0.0689351 -0.0226425 -0.0197038 -0.0611913 -0.0302073 -0.0174131 -0.0688938 -0.0233263 -0.0336778 -0.0674058 -0.0211457 0.00501378 -0.0574144 -0.0302077 0.00856958 -0.0621443 -0.0196453 0.0256402 -0.0583724 -0.0191062 0.0329018 -0.0367385 -0.0302073 0.0394275 -0.0323897 -0.0302073 0.0425315 -0.0254001 -0.0302073 0.0464466 -0.0180138 -0.0302073 0.0495546 0.00501243 -0.0153208 0.0671277 0.00307498 -0.0302073 0.0523282 0.0136071 -0.0302073 0.0504498 0.0161422 -0.0152069 0.0653262 0.0325898 -0.0302073 0.0407912 0.0419376 -0.0156927 0.0518953 0.0461784 -0.0159021 0.048023 0.0366817 -0.0302073 0.0373416 0.0501188 -0.016141 0.0438574 0.056645 -0.0166343 0.0356588 0.0764867 -0.019514 -0.00476176 0.0636829 -0.0302073 -0.00217296 0.0785452 -0.0200536 -0.0123673 0.0764524 -0.0211758 -0.0283676 0.0689131 -0.0302074 -0.0235234 0.0645122 -0.0224529 -0.0452788 0.0496683 -0.0234943 -0.060811 0.0366256 -0.0302073 -0.064631 -0.0502973 -0.0242071 -0.0897939 -0.0561421 -0.0242145 -0.0889339 -0.0630395 -0.024208 -0.0854665 -0.0649614 -0.0242114 -0.0829094 -0.067006 -0.0242087 -0.0737688 0.00151617 -0.0302072 -0.0887614 -0.0600935 -0.0302073 -0.00677239 -0.0618309 -0.0302073 -0.0280966 -0.0427185 -0.0302073 0.0341026 -0.0512959 -0.0302074 0.0238758 0.0513071 -0.0302073 -0.049039 0.0150873 -0.0302074 -0.0850765 -0.0607784 -0.0302188 -0.0792833 -0.0620832 -0.0302073 -0.0495123 -0.00791584 -0.0302073 0.0521645 0.0588266 -0.0302073 0.00734949 -0.0171572 -0.0302072 -0.0813826 -0.0534937 -0.0302073 -0.0834609 0.0211233 -0.0302073 0.047633 -0.0472052 -0.0302073 -0.0372762 0.00838814 -0.0302073 0.0516563 0.0533986 -0.0302073 0.0165602 0.0422632 -0.0302073 0.0315805 0.0282117 -0.0302073 0.0438719 0.0628795 -0.0302073 -0.0343357 -0.0156493 -0.0302073 -0.0728648 0.0681871 -0.0302073 -0.0133056 -0.0559462 -0.0302073 -0.0406257 -0.0526049 -0.0282073 -0.0754074 -0.0556764 -0.0302064 -0.0781445 -0.0145402 -0.0282069 -0.0785237 -0.0528313 -0.0282073 -0.0406055 -0.00367792 -0.01975 -0.0500884 -0.0530137 -0.01975 -0.0763422 -0.0228821 -0.01975 -0.0444568 -0.0146372 -0.01975 -0.0478096 -0.00390605 -0.01975 -0.0145109 -0.0438589 -0.01975 -0.0241575 -0.0476158 -0.01975 -0.0152556 -0.0608802 -0.01975 -0.00133633 -0.0608924 -0.01975 0.000547165 -0.0600412 -0.01975 0.00222744 -0.0379453 -0.01975 -0.0327433 0.0465378 -0.01975 0.0187657 0.00968574 -0.01975 0.00407725 0.0196377 -0.01975 0.0461765 0.0134844 -0.01975 0.0558965 0.00396579 -0.01975 0.00973191 0.0380198 -0.01975 0.0328187 -0.0320016 -0.01975 0.0372109 -0.0376973 -0.01975 0.043526 -0.0445567 -0.01975 0.0403064 -0.0461765 -0.01975 0.0196378 -0.013671 -0.01975 0.00391203 0.0500041 -0.01975 0.00432892 0.0314687 -0.01975 -0.0595061 0.0152556 -0.01975 -0.0476158 0.0233523 -0.01975 -0.0538124 0.0245269 -0.01975 -0.0520374 0.0040773 -0.01975 -0.00968682 0.0651324 -0.01975 -0.0170006 0.0597785 -0.01975 -0.0410217 0.055636 -0.01975 -0.0145219 0.0647877 -0.01975 -0.0325393 0.0682742 -0.01975 -0.0194721 0.0688529 -0.01975 -0.0214301 0.0609472 -0.01975 0.00100954 0.0606278 -0.01975 -0.001389 0.0601042 -0.01975 0.00289401 0.0435253 -0.01975 0.0376917 0.0371182 -0.01975 0.0440125 0.0434443 -0.01975 0.0426705 0.0293516 -0.01975 0.0494443 -0.00133634 -0.01975 0.0608802 -0.00561697 -0.01975 -0.094107 0.0124915 -0.01975 -0.0759242 0.0328171 -0.01975 -0.0380185 0.046562 -0.01975 -0.0555719 0.0385471 -0.01975 -0.0614033 0.0327716 -0.01975 -0.061078 0.0345942 -0.01975 -0.0619982 -0.0534701 0.0182499 -0.0214782 -0.0642383 -0.01975 -0.0404156 -0.0640759 -0.01975 -0.0654096 -0.0642391 0.01825 -0.0404176 0.0166245 0.01825 -0.0550443 0.0233555 0.01825 -0.0537013 0.0234146 0.01825 -0.064848 -0.0640756 0.01825 -0.0654141 -0.00561697 0.01825 -0.094107 -0.0490597 0.01825 -0.0299899 0.00248502 0.01825 -0.060532 -0.0429422 0.01825 -0.0439659 -0.00142766 0.01825 -0.0604482 -0.000296278 0.02525 -0.0625372 -0.0440799 0.02525 -0.044345 -0.0608924 0.02525 0.000547167 -0.0608802 0.02525 -0.00133633 -0.0600073 0.02525 -0.00300542 -0.0599988 -0.01975 -0.00301799 -0.0408656 0.02525 0.0440337 -0.0408805 -0.01975 0.0440306 -0.0426705 0.02525 0.0434443 -0.0426705 -0.01975 0.0434443 -0.0439937 -0.01975 0.0421039 0.00412508 -0.01975 0.0574291 0.00222744 -0.01975 0.0600412 0.00224013 0.02525 0.0600329 0.000547174 -0.01975 0.0608924 -0.00300543 0.02525 0.0600073 -0.00488073 0.02525 0.0573674 0.0440337 0.02525 0.0408656 0.0440306 -0.01975 0.0408805 0.0434443 0.02525 0.0426705 0.0421038 -0.01975 0.0439937 0.0421038 0.02525 0.0439937 0.0403064 -0.01975 0.0445568 0.0403064 0.02525 0.0445568 0.00418936 0.02525 0.0574168 -0.00300229 -0.01975 0.0600088 -0.00493976 -0.01975 0.0573558 -0.0379093 0.02525 0.0435579 -0.0440125 -0.01975 0.0371182 -0.0440102 0.02525 0.0371244 -0.0574291 -0.01975 0.00412507 -0.0574167 0.02525 0.00418939 -0.0573576 -0.01975 -0.00493317 -0.0573708 0.02525 -0.00486902 -0.0435254 0.01825 -0.0376916 -0.0371182 0.01825 -0.0440125 -0.00422444 0.0252499 -0.0574116 0.00490616 0.01825 -0.0573808 0.00486712 0.02525 -0.0573895 0.0595677 0.02525 -0.00269665 0.0574219 0.02525 -0.00420342 0.0574526 -0.01975 -0.00403936 0.0435621 0.02525 0.0376374 0.0371244 0.02525 0.0440102 0.0573576 -0.01975 0.0049332 0.0573653 0.02525 0.00489906 -0.0534646 -0.01975 -0.0214653 -0.05301 0.01825 -0.07635 0.0124932 0.01825 -0.0759211 0.0234086 -0.01975 -0.064858 0.0246 0.0181314 -0.0519781 0.0293348 0.02525 -0.055471 0.046562 0.0228814 -0.0555719 0.055636 0.02525 -0.0145219 0.0366327 -0.01975 -0.062113 0.0669611 -0.01975 -0.0179087 0.0681833 0.0241852 -0.0192273 0.037541 0.0240883 -0.0620394 0.0379705 0.0264969 -0.0653556 0.0337339 0.0263593 -0.061794 0.0318092 0.0297452 -0.06014 0.0426461 0.0232725 -0.0586307 0.0589043 0.0227372 -0.0423678 0.0690116 0.0234655 -0.0223665 0.0661473 0.025271 -0.0172999 0.069357 0.0270268 -0.0163256 0.0476158 -0.02575 0.0152556 0.0379998 -0.02575 0.0327954 -0.00409161 -0.02575 0.00967971 -0.0384149 -0.01975 0.0322918 -0.0499954 -0.01975 -0.00432888 -0.00967971 -0.02575 -0.0040916 -0.00394601 -0.02575 -0.00971027 -0.0322973 -0.01975 -0.0384193 -0.0323216 -0.02575 -0.0384407 -0.00368047 -0.02575 -0.0500561 -0.00968576 -0.01975 -0.00407727 -0.0380037 -0.02575 -0.0327988 0.00967969 -0.02575 0.00409159 0.0500365 -0.02575 0.0043268 0.0322972 -0.01975 0.0384193 0.00368055 -0.02575 0.0500569 0.00367797 -0.01975 0.0500888 -0.00407727 -0.01975 0.00968576 -0.0500884 -0.01975 0.00367793 -0.0124368 -0.01975 0.00665563 -0.013964 -0.02575 0.00390969 -0.0384384 -0.02575 0.0323188 0.050056 -0.02575 -0.00368048 0.0500884 -0.01975 -0.00367794 0.0140401 -0.01975 -0.00390928 0.0121327 -0.01975 -0.00635464 0.00973778 -0.02575 -0.00395139 0.00409167 -0.02575 -0.00968031 0.00432893 -0.01975 -0.0500041 0.0327925 -0.02575 -0.0379974 -0.00432892 -0.01975 0.0500041 -0.00432679 -0.02575 0.0500365 -0.0629982 0.0252601 -0.000409923 -0.06197 0.0252598 -0.0113432 -0.0543551 0.0252542 -0.0318508 0.0219235 0.0252604 -0.0590611 0.0481889 0.0497499 0.0229706 0.0320874 0.0349114 -0.0493427 0.028013 0.0497498 -0.0524413 -0.00620529 0.0454543 0.0561158 0.00404408 0.01825 0.0430669 0.014179 0.010745 0.0391033 0.0324486 0.0107464 0.0260948 0.0414791 0.01075 0.000268809 -0.00549022 0.0156057 0.0522078 -0.00193887 0.0211494 0.0573987 0.000693245 0.0177155 0.0528455 -0.0586356 -0.00821166 -0.0472988 -0.0562575 0.0115079 -0.0623659 -0.0586356 0.0137883 -0.0472988 0.0193306 0.0124408 -0.0509535 -0.0509463 -0.0166776 0.0193583 -0.0465217 -0.0167045 0.0283903 0.0145835 -0.016583 0.0525121 0.0239761 -0.01625 0.0489428 0.0461508 -0.016689 0.0289894 0.0506917 -0.0167185 0.0200156 0.0379151 0.0212492 0.0163456 0.0231951 0.021249 0.0335819 0.00599646 0.0212488 0.0404444 -0.0194129 0.0212479 0.0360752 -0.0319908 0.0212489 0.0250992 -0.0385179 0.0212501 0.0139236 0.0598528 -0.0138749 0.00020804 -0.000663198 -0.0153017 0.0596599 -0.0598505 -0.0139835 -0.000210249 -0.0278667 0.0327782 0.0521758 0.0306437 0.0285232 -0.0487358 0.0459167 0.0344742 0.0265113 -0.0126178 0.0342991 -0.0517003 0.0529437 0.03485 -0.0175475 0.0547601 0.0312869 -0.0138709 0.052865 0.0497501 -0.0333859 -0.0105024 0.049751 0.0570466 -0.0453225 0.049795 0.0344514 0.0474314 0.0495477 -0.0336905 -0.0478121 0.040079 0.033915 -0.0466043 0.0500172 0.0375378 -0.0598509 0.0485433 -0.00687998 -0.0564474 0.0497612 -0.0085915 0.0480923 0.02125 0.0149296 0.02445 0.02265 0.0445506 -0.00619427 0.02125 0.05044 -0.0434544 0.02125 0.0271042 0.0481279 0.0349043 0.022382 0.0519144 0.0497499 0.0268415 0.0274408 0.03485 -0.0521294 0.0449644 0.02265 0.0282455 0.0390087 0.02265 0.0360268 -0.0314085 0.0497494 0.0429647 -0.0255242 0.0329705 0.0465588 -0.0453267 0.02265 0.0276604 -0.0496375 0.02265 0.0188607 0.0530989 0.02265 0.000344112 0.0493889 0.02265 0.0195024 0.0317246 0.02265 0.0425812 0.0233602 0.02265 0.0476856 0.00868963 0.0349156 0.0523788 0.0045567 0.02265 0.0529041 -0.00524199 0.02265 0.0528406 -0.0135395 0.049751 0.0514368 -0.0149146 0.0226564 0.0509592 -0.0322738 0.02265 0.0421665 -0.0394724 0.02265 0.0355182 0.0621115 0.0252603 -0.0105374 0.0485176 0.0252604 -0.0401835 0.0408075 0.05075 -0.0479974 0.0114039 0.0497727 -0.0619606 0.000408268 0.05075 -0.0629987 -0.0311224 0.0252593 -0.054773 -0.048 0.0252596 -0.0408029 -0.0590598 0.02575 -0.0219305 -0.0576364 0.0252513 -0.000353391 -0.0530713 0.02525 -0.0221289 -0.0342366 0.0252171 -0.0461545 -0.0460291 0.0252477 -0.0349633 -0.0195884 0.0252486 -0.0542978 0.025588 0.02525 -0.0514927 0.0158519 0.02525 -0.0552718 0.0574904 -0.01175 -0.00105343 0.048597 -0.0167992 -0.030733 0.0533536 0.02525 -0.0214392 0.0563515 -0.01675 -0.0114349 0.0354549 -0.016731 -0.0453989 0.00162662 0.0116688 0.0379048 0.0233859 0.0107572 0.0312166 0.0387365 0.0107611 0.00452218 0.0325476 0.0107635 -0.0198355 0.0207181 0.0107634 -0.0319932 0.00249147 0.0113022 -0.0383466 -0.0364699 0.0107618 -0.0115959 -0.00851876 0.0107577 -0.0373162 0.0399536 -0.0166744 0.0370625 0.032561 -0.0167032 0.0437042 0.0145746 0.01825 0.0525151 -0.0536359 -0.016702 0.00966775 -0.0536358 0.01825 0.00966697 -0.0405131 0.01825 0.0364546 -0.040482 -0.0166911 0.036492 -0.0331244 -0.0165181 0.0432786 -0.0331247 0.01825 0.0432782 -0.0117386 0.01435 0.0387622 -0.0247327 0.0121269 0.0313076 -0.0380263 0.01435 0.0128729 0.0306253 0.01625 0.0265017 0.00842298 0.01625 0.0396144 -0.0171937 0.01625 0.0366691 -0.0350951 0.0121327 0.0188079 -0.00903838 0.0119391 0.0366864 0.029167 0.0121328 0.0273652 0.00905831 0.0056114 -0.0749355 -0.050917 0.0159043 -0.0753349 -0.0350037 0.0497861 -0.0454257 -0.0574593 0.0488791 -0.00970272 -0.05435 0.05075 -0.0318548 -0.0479974 0.05075 -0.0408075 -0.0547626 0.05075 0.0311458 -0.0621065 0.049807 0.0105569 -0.0318544 0.0507481 0.0543499 -0.0408075 0.05075 0.0479974 -0.0482018 0.0507507 0.0406443 0.0105411 0.05075 0.0621098 -0.000408268 0.05075 0.0629987 0.0407406 0.0507505 0.0481061 0.0335765 0.0498629 0.0466253 0.0574115 0.0497746 0.00985829 0.0479974 0.05075 0.0408075 0.0619731 0.0507499 0.0113264 0.0695501 0.0502846 -0.0123488 0.0590268 0.0507323 -0.0240596 0.0543042 0.0507515 -0.0321712 0.0482264 0.0503421 -0.0371987 0.00708493 0.049771 -0.0618088 -0.0105411 0.05075 -0.0621098 -0.0324603 0.0498341 -0.0541317 -0.0265806 0.0107638 -0.0273178 -0.0103738 0.01075 -0.0401619 -0.018466 0.01075 0.0371429 -0.0223625 0.0107576 0.03102 -0.0316659 0.01075 0.0267929 -0.0396876 0.01075 0.0120616 0.00333222 0.0107499 0.0413457 0.0399221 0.0107435 -0.0119953 0.0397291 0.0107463 0.0124679 0.0244819 0.01075 0.0334848 0.000613633 -0.0064932 -0.055764 0.000276164 0.00675447 -0.0557727 -0.0093896 -0.00875 -0.0549805 -0.00265911 -0.00875 -0.0557131 0.00246823 -0.00875 -0.0381678 0.0129034 0.01825 -0.0412867 0.016021 0.0182498 0.0403247 0.0460602 0.01825 -0.0291326 0.032681 0.01825 -0.0436142 0.0246797 0.0182496 -0.0357929 0.0102551 0.01825 0.0535155 0.0239761 0.01825 0.0489428 0.032561 0.01825 0.0437039 0.0255301 0.01825 0.0349185 0.0400372 0.01825 0.0369767 0.0461499 0.01825 0.0289902 0.0506911 0.01825 0.0200166 0.0347301 0.0182497 0.0260718 0.053506 0.01825 0.0103613 0.0418451 0.0182497 0.0116147 0.0411312 0.0182496 -0.0140867 -0.00342159 0.0164713 -0.0402224 0.00956734 0.0164225 -0.0395099 0.0371046 0.01625 -0.0162327 -0.00630663 0.0168634 0.0399941 -0.0155859 0.0163722 -0.0375496 -0.0269042 0.01625 -0.0302724 -0.0322431 0.0164459 -0.0243173 -0.0382709 0.0163919 -0.0137338 -0.0405486 0.0164772 0.00437196 -0.0340702 0.0164689 0.0221549 -0.0248245 0.0164318 0.031859 0.033054 0.0164925 -0.0231712 0.0248271 0.0164276 -0.0321682 0.020417 0.0164293 0.035141 0.035399 0.0164802 0.0194103 0.0386746 0.0164401 0.0117764 0.040652 0.0164386 -0.00209858 -0.0104694 0.0144146 0.036366 -0.0295029 0.01435 0.0272267 -0.0267658 0.014442 0.0264343 -0.0355857 0.0144444 0.0122027 -0.0399747 0.01435 -0.00370671 -0.0317286 0.0144516 -0.0202175 0.0169412 0.0144394 -0.0340123 0.0399747 0.01435 0.00370671 0.0342899 0.0145342 0.019465 0.0264343 0.0144536 0.026772 0.0239937 0.01435 0.0321872 0.0121997 0.0144574 0.035592 0.00882756 0.01435 0.0391636 -0.035011 0.01435 -0.0196454 -0.0378563 0.01215 -0.0133647 -0.0239937 0.01435 -0.0321872 -0.0050423 0.01435 -0.0401855 0.0144796 0.0121193 -0.0364438 0.0158781 0.01435 -0.0368727 0.0295029 0.01435 -0.0272267 0.0380263 0.01435 -0.0128729 0.00101235 0.01215 -0.0401334 -0.0153989 0.01215 -0.0370754 -0.0122226 0.0121152 -0.0357836 -0.0290339 0.01215 -0.0272591 -0.0395758 0.0121169 0.00386314 -0.00556271 0.01215 0.0401168 0.0153989 0.01215 0.0370754 0.0376614 0.0121464 0.0133543 0.0345621 0.01215 -0.0199773 0.0396903 0.0121483 -0.00267232 0.0244088 0.01215 -0.0318736 -0.0123609 0.0182684 -0.0420252 -0.0140646 0.01825 -0.048013 -0.0395482 0.01825 -0.0374992 -0.0503023 0.01825 -0.0209744 -0.0354327 0.0182496 0.0251637 -0.0465218 0.01825 0.0283897 -0.0509463 0.01825 0.0193579 -0.0246084 0.01825 0.0486279 -0.031853 0.00550046 -0.0442943 0.024253 0.01825 -0.0488062 0.0177045 0.00799561 -0.0516502 0.0146954 0.012641 -0.0524844 0.0186432 -0.00849131 -0.0512617 -0.032113 0.01825 -0.0440341 -0.0299349 0.00697893 -0.0455375 -0.0102237 0.01825 -0.0539807 -0.0282944 0.0127267 -0.0465863 -0.0236184 0.01825 -0.0491164 -0.0456788 0.01825 -0.0297271 -0.0456788 0.0055 -0.0297271 -0.0395482 -0.0055 -0.0374992 -0.0299038 -0.00698781 -0.0455784 -0.0276635 -0.0127512 -0.0473636 0.000306947 -0.00875084 -0.054945 -0.000545076 -0.0127465 -0.054967 0.0545312 0.0182505 -5.67015e-05 0.0534114 0.01825 -0.0108383 -0.0545527 0.0182502 -0.000993127 -0.0533816 -0.0167141 -0.0110856 -0.0532665 0.01825 -0.0115297 -0.0513256 0.00549914 -0.0188671 0.0400309 0.01825 -0.0369834 0.05057 0.01825 -0.0203206 -0.0356233 0.0107592 0.0146154 0.0535064 -0.016697 0.0103606 0.0561986 -0.01675 0.0121643 0.0530713 -0.01675 0.0221289 0.0249185 -0.01675 0.0518201 -0.00537385 -0.0166744 0.0542362 -3.9721e-05 -0.0166686 0.0575302 0.00468091 -0.0165075 0.0542997 -0.0427052 -0.0165973 0.0387931 -0.0152106 -0.0167224 0.0523332 -0.0246242 -0.0167142 0.0486182 -0.032382 -0.0165387 -0.043864 -0.0408977 -0.01675 -0.0415233 -0.0459444 -0.0166242 -0.0293883 0.000524775 -0.0167502 -0.0565935 0.0533522 -0.01679 -0.0214421 -0.0556585 -0.01675 0.0144355 -0.0575068 -0.0167597 0.00328357 -0.0561986 -0.01675 -0.0121643 -0.0563515 -0.01675 0.0114349 -0.0573318 -0.01425 -0.00498641 -0.0484662 -0.01675 -0.0748156 -0.0207301 -0.01675 -0.0690521 0.00808992 -0.0167438 -0.0749333 -0.00559287 0.02525 0.0572274 -0.00795869 0.0105175 0.0568051 -0.0158519 0.02525 0.0552718 -0.0122207 0.0184682 0.0561688 0.0417252 0.02525 0.0395633 0.0338807 0.02525 0.046458 -0.0422345 0.02525 0.0390192 -0.03448 0.02525 0.046015 -0.0574904 -0.01175 0.00105343 -0.0563515 0.02525 0.0114349 -0.0533536 -0.01675 0.0214392 -0.0485956 -0.01675 0.0307362 -0.0485956 0.02525 0.0307362 -0.0342023 -0.0167231 0.0464396 -0.025588 0.02525 0.0514927 -0.025588 -0.01675 0.0514927 -0.0158519 -0.01675 0.0552718 0.0347031 -0.0167046 0.0459563 0.0151342 -0.01675 0.0554726 0.0481932 -0.01675 0.0313635 0.0616451 0.0453731 -0.0340765 0.0623504 0.050524 -0.0345383 -0.0629988 0.0498004 -0.000472193 0.0324628 0.0498248 0.0541301 0.0543499 0.05075 0.0318549 0.0590209 0.0498249 0.022063 0.0629987 0.05075 0.00040827 -0.0395482 0.0055 -0.0374992 -0.0456788 -0.0055 -0.0297271 -0.0449644 0.02265 -0.0282455 -0.0233602 0.02265 -0.0476856 0.0496324 0.0348512 -0.0189733 0.0496375 0.02265 -0.0188607 0.052258 0.02265 -0.00941864 0.0530991 0.0497472 0.00035615 -0.0493889 0.02265 -0.0195024 -0.0390087 0.02265 -0.0360268 -0.0299496 0.0497505 -0.043933 -0.0187667 0.0355802 -0.0498648 -0.00812185 0.0497499 -0.052588 -0.0045567 0.02265 -0.0529041 0.00524199 0.02265 -0.0528406 0.0135395 0.049751 -0.0514368 0.0149146 0.0226564 -0.0509592 0.0255234 0.0328907 -0.0465547 0.0322738 0.02265 -0.0421665 0.0314279 0.0497494 -0.0429466 0.0452 0.04955 -0.0278659 -0.0314841 0.04975 0.0463913 -0.0321431 0.03485 0.0492346 -0.0173682 0.0336562 -0.055859 0.057448 0.0348874 -0.012112 0.0117457 0.03485 0.0571407 -0.0234218 0.03485 0.0484945 -0.0434907 0.0497499 -0.0307274 -0.0176993 0.04975 -0.053226 -0.0088067 0.0349156 -0.0523622 0.049878 0.0497494 -0.0185275 -0.0525045 0.0497499 0.00905049 -0.0354847 0.0212476 -0.0199583 -0.0403915 0.0212479 -0.00453267 -0.0480923 0.02125 -0.0149296 -0.0501448 0.02125 0.00461092 -0.0240251 0.02125 0.0442556 0.0135798 0.02125 0.0489709 0.0350609 0.02125 0.0373317 0.0404389 0.0212475 -0.00471077 0.0501448 0.02125 -0.00461092 0.0297743 0.02125 -0.0416703 0.0235581 0.0212475 -0.0332041 -0.0373572 0.0144477 -0.00444719 -0.019814 0.0144556 -0.031984 -0.00398075 0.0144366 -0.0374056 0.0319775 0.0144431 -0.0198154 0.0374095 0.0144459 -0.00397766 0.000554952 0.0252493 -0.0577032 0.0113432 0.0252604 -0.06197 0.0318561 0.0252604 -0.0543517 0.03448 0.02525 -0.046015 0.0408029 0.0252604 -0.048 0.0422345 0.02525 -0.0390192 0.0485956 0.02525 -0.0307362 0.0547741 0.0252602 -0.0311196 0.0593393 0.0252603 -0.0211602 0.0563515 0.02525 -0.0114349 -0.0561986 0.02525 -0.0121643 -0.0401874 0.0252595 -0.0485139 -0.0211615 0.0252593 -0.0593392 -0.0105359 0.0252635 -0.0621123 0.000409922 0.0252604 -0.0629982 -0.0533536 0.02525 0.0214392 -0.0318561 0.0252604 0.0543517 0.0048507 0.02525 0.057295 0.0151342 0.02525 0.0554726 0.0249185 0.02525 0.0518201 0.0401874 0.0252595 0.0485139 0.048 0.0252596 0.0408029 0.0481932 0.02525 0.0313635 0.0530713 0.02525 0.0221289 0.0561986 0.02525 0.0121643 0.0576364 0.0252513 0.000353391 -0.0142002 0.02265 -0.051166 -0.0317246 0.02265 -0.0425812 -0.0522533 0.0226487 0.0091758 -0.0445506 0.02265 0.02445 -0.0276651 0.02265 0.0430994 -0.0239762 0.02265 0.0473788 0.000942077 0.02265 0.0512058 0.0142002 0.02265 0.051166 0.0396376 0.02265 0.0318028 0.0487908 0.02265 0.0142133 0.052221 0.0227278 0.00973067 0.0445506 0.02265 -0.02445 0.0453267 0.02265 -0.0276604 0.0394724 0.02265 -0.0355182 0.0239762 0.02265 -0.0473788 -0.0506262 0.02265 -0.00442163 -0.0450804 0.02265 -0.0234588 -0.0350609 0.02125 -0.0373317 -0.0326715 0.02265 -0.0389247 -0.0152887 0.02265 -0.0484646 -0.0135798 0.02125 -0.0489709 0.00906577 0.02265 -0.0504057 0.00619427 0.02125 -0.05044 0.0318028 0.02265 -0.0396376 0.0445632 0.02125 -0.0234495 0.050516 0.02265 -0.00554003 0.0375884 0.0497731 0.0468131 0.033915 0.040079 0.0478121 0.0577727 0.0398844 0.00901872 0.0451721 0.0492443 -0.0358905 -0.0348404 0.040079 -0.0453418 -0.0363924 0.0502265 -0.0488597 -0.0524458 0.0348454 0.00894587 -0.0498643 0.0348523 0.018477 -0.0580011 0.03485 0.0129787 -0.0555348 0.03485 0.0176129 -0.0518456 0.03485 -0.0268177 -0.04818 0.034905 -0.0222931 -0.0458043 0.0339439 -0.0267452 -0.0433542 0.0349561 -0.0307859 -0.0502962 0.0345335 -0.0316811 -0.0130685 0.0348987 -0.058045 0.022894 0.0496366 -0.0481744 0.0308819 0.0348958 -0.044695 0.0525361 0.0348691 -0.00837073 0.057204 0.03485 -0.0164197 0.0496493 0.0332776 0.0316972 0.0433544 0.034958 0.0307859 0.0524062 0.03485 0.0276317 0.0133298 0.0348496 0.0514562 0.0181581 0.0350322 0.0499671 0.0170631 0.03485 0.0571725 -0.0593292 0.0498828 0.0211777 0.0592489 0.0497675 0.00632287 0.0222798 0.0507501 -0.0589625 -0.0211587 0.05075 -0.0593398 -0.0105409 0.0497499 -0.0550662 -0.0112548 0.0498085 0.0619848 0.0129539 0.0497499 0.0579447 0.0211695 0.0498541 0.0593336 -0.0160428 0.04975 -0.0579047 0.0480039 0.04975 0.0396344 -0.0222654 0.0498073 0.0589656 -0.0434127 0.04975 0.0450889 -0.00535571 0.049753 0.0581292 0.0609486 0.04975 -0.0085183 -0.0590185 0.0498218 -0.0220719 -0.0182772 0.04975 -0.0502407 0.053316 0.0497499 -0.0176992 0.0318631 0.0498577 -0.0543426 0.048131 0.049812 -0.0407135 -0.0407466 0.0497778 -0.0480968 -0.0496416 0.0497879 0.0359204 -0.0619698 0.0498217 -0.0113414 -0.0541846 0.0268586 0.014143 0.0145013 0.0320621 0.0547009 -0.0305584 0.0284065 0.0467251 -0.0308289 0.03485 0.0447529 -0.0510471 -0.0055 -0.0623321 -0.0608816 0.0131619 -0.0623958 -0.049186 0.00550084 -0.0752051 -0.0510471 0.0055 -0.0623321 0.0154616 0.0086788 -0.0619011 0.0184375 0.0136914 -0.0618822 0.00913458 -0.00721325 -0.0619421 0.0165656 -0.013585 -0.0618941 0.00908716 -0.016741 -0.0619426 0.0200895 -0.0110002 -0.0618713 0.00673266 0.01675 -0.0744579 -0.0484662 0.01675 -0.0748157 0.00665166 0.01675 -0.0619582 -0.0425648 -0.0142516 0.0423384 0.0433169 -0.0167473 0.0379239 0.0411087 -0.016679 0.0403395 0.0420327 -0.0141585 0.0428438 0.0575067 -0.0167523 -0.00328441 0.042732 -0.0163366 -0.0387626 0.0350267 0.0212475 -0.0207515 0.0128091 0.0212476 -0.0384354 -0.00045793 0.0212479 -0.0407098 -0.0169765 0.0212476 -0.0370039 -0.0268814 0.0212477 -0.0303107 0.0544989 -0.01625 0.000353184 0.0535236 -0.01625 -0.0102527 0.0509463 -0.01625 -0.0193579 0.0485459 -0.01625 -0.0243552 0.0402123 -0.0167054 -0.0368486 0.0246163 -0.016679 -0.0486123 0.0151583 -0.016713 -0.0523694 -0.00525857 -0.0167491 -0.054263 -0.0238824 -0.0167473 -0.0490031 -0.0390759 -0.0165685 -0.0381285 -0.0505384 -0.0162459 -0.0205173 -0.0544985 -0.0166863 -0.000345769 0.0426158 -0.0152861 -0.0424119 0.0573719 -0.016615 0.00455638 -0.00557294 -0.01175 0.0572293 -0.0513179 -0.00549991 -0.0185976 0.000422485 -0.00715361 -0.0749987 4.93671e-05 -0.0127417 -0.0749684 -0.0209765 -0.01275 -0.0693508 -0.0143062 -0.0127549 -0.0525616 -0.0178344 0.01275 -0.0513673 -0.0093896 0.01275 -0.0549805 -0.0025353 0.0127503 -0.0557249 -0.0103844 0.01275 -0.0535015 0.0660476 0.04475 -0.0166725 0.0622536 0.0447513 -0.00983515 0.0697196 0.0450046 -0.0123986 0.0658165 0.0505803 -0.0168752 0.0593428 0.0448647 -0.0211578 0.0618814 0.0449686 -0.0288422 0.0543065 0.04475 -0.0321177 0.0623053 0.05075 -0.00944926 -0.0297533 -0.011294 -0.0456672 -0.0308299 0.00550546 -0.0751666 -0.0307279 -0.00550687 -0.0751203 -0.0319293 -0.00550032 -0.044231 -0.0510384 0.00722534 -0.0623321 -0.0484662 -0.0055 -0.0748157 -0.0510039 -0.00678963 -0.0623318 -0.0509307 -0.00659261 -0.0753325 -0.0298351 0.0107695 -0.0456088 3.80935e-05 0.0117175 -0.055774 0.00922783 0.0149144 -0.0749281 0.00816343 0.0162626 -0.0749481 0.00909687 0.0156344 -0.0619423 -0.0510039 0.0154604 -0.0623318 -0.0485472 0.01675 -0.0623159 -0.0509548 -0.0167399 -0.0623315 -0.0640469 -0.01275 -0.0624164 -0.0622077 -0.0165491 -0.062391 -0.064174 -0.0135767 -0.0424159 -0.0641695 0.01525 -0.0434886 -0.0640441 0.0163915 -0.0624161 -0.0611879 0.0192473 -0.0623978 -0.0616712 0.0192275 -0.0425575 -0.0640175 0.0162519 -0.0421392 0.0200628 0.0192496 -0.0618713 0.0230935 -0.0165855 -0.0530229 0.023148 -0.0150206 -0.061851 -0.0590677 -0.0167454 -0.00408666 -0.0532577 -0.01275 -0.0216764 -0.0616351 -0.016732 -0.0419881 -0.0533717 -0.01275 -0.0234191 -0.0529461 0.0162647 -0.0226621 -0.022538 0.0202072 -0.0530823 -0.0423669 0.0202942 -0.0389794 -0.0279038 0.01925 -0.0518811 0.006552 0.019259 -0.0574268 -0.051949 0.0192472 -0.0281965 -0.00485306 0.0201295 -0.0574562 0.019318 0.0193191 -0.0543191 0.0230957 0.0169731 -0.0527491 0.0231669 0.0146238 -0.0618513 0.0168339 -0.0141456 -0.0520381 0.0148586 -0.00905532 -0.0619051 -0.0600018 0.00833021 -0.0623901 -0.0570121 0.00918679 -0.04643 -0.061814 0.0100467 -0.0473194 -0.0574451 -0.0134345 -0.047198 -0.0563546 -0.00974205 -0.0623665 -0.0592403 -0.0136798 -0.0623852 -0.061796 -0.0111949 -0.0463818 -0.0617167 -0.0100451 -0.0624013 -0.0209677 0.01675 -0.0692439 -0.0208261 0.01275 -0.0694462 0.000527122 0.00653465 -0.0749945 0.000270506 0.0113346 -0.0749954 -0.00195645 0.0127517 -0.0749773 -0.027704 0.0127478 -0.0751742 -0.0295784 0.010706 -0.0751931 -0.0278433 -0.0127446 -0.0751751 -0.0509507 0.00731904 -0.0749072 -0.0296124 -0.010478 -0.0751933 0.00927199 -0.00812375 -0.0749211 -0.0508771 -0.0159079 -0.0753357 -0.0209864 -0.00475 0.0502973 0.00467684 -0.00475 0.054299 0.00852151 -0.00474628 0.053811 -0.015254 -0.00475 0.0523217 -0.0177788 -0.00475 0.0498562 -0.00904722 -0.00475 0.0366865 0.00191671 -0.00475 0.0379266 -0.0053802 -0.00475 0.0542338 -0.00862368 -0.00875026 -0.0375124 -0.00142322 0.0123053 0.0575169 -0.00408161 0.0102964 0.0523547 -0.0116924 0.0148143 0.0515404 -0.00691471 0.022239 0.0520565 -0.00273592 0.0152284 0.0406471 -0.0140321 0.01825 -0.0457941 0.00411597 0.01075 -0.0412756 -0.0147462 -0.00875 -0.0469426 0.00982608 0.01825 -0.0520386 0.0123267 0.0182509 -0.0531631 0.0101464 -0.00875 -0.0526344 0.0142261 -0.0105521 -0.0526494 -0.0177225 0.01825 0.0497671 -0.0112028 0.01075 0.0399387 0.00500545 0.0182499 -0.0429481 0.0173419 0.010742 -0.0379119 0.0314305 0.0107434 -0.0273823 0.0349342 0.01825 -0.0255086 0.0432552 0.01825 0.000280319 -0.0122253 0.01825 0.0414791 -0.0176934 0.01075 -0.0375171 -0.0259803 0.01825 -0.0345849 -0.0357689 0.0182496 -0.0246836 -0.0276854 0.0107447 -0.0311422 -0.037755 0.0107446 -0.0176316 -0.0411178 0.01825 -0.0134319 -0.0429844 0.01825 -0.00484084 -0.0416505 0.0107438 -0.00123791 -0.0425012 0.0182497 0.00907386 -0.0364292 0.01075 0.019837 -0.0255946 0.01075 0.0326421 -0.0233997 0.0182495 0.0365226 0.00788671 0.01825 0.0523434 -0.0202886 0.01825 0.0506039 -0.0531134 0.0227449 -0.000679186 -0.0485068 0.0497497 -0.0222538 -0.0520953 0.0227469 -0.0103813 -0.0513927 0.0497499 -0.0264296 -0.0582559 0.0497492 0.0136064 -0.0508143 0.0497492 -0.0315719 -0.0550287 0.0497499 0.0176516 -0.049878 0.0497494 0.0185276 -0.0392473 0.0497473 0.0357669 -0.0452 0.04955 0.0278659 -0.0374461 0.0497501 -0.0377414 -0.0308294 0.0497493 0.0513214 -0.0264296 0.04975 0.0513927 -0.0221274 0.0497496 0.0483679 -0.00389967 0.0497508 0.0530425 0.00312486 0.0497623 -0.0530937 0.00913339 0.0497498 0.0527416 0.0175101 0.0497499 0.0561039 0.0320684 0.04975 -0.0478982 0.0418189 0.0497499 0.0328112 0.0182245 0.0497499 0.0502283 0.0317903 0.0497409 0.0427758 0.0392473 0.0497473 -0.0357669 0.0460392 0.0497499 0.0313914 0.0510343 0.0497498 0.0311007 0.0525343 0.0497497 -0.00872695 0.057565 0.0497498 -0.0161268 0.0510938 0.04955 0.014458 0.009074 0.00576181 -0.0619425 0.0043494 -0.00525491 -0.0619832 0.00434788 -0.000276003 -0.0556216 0.00401273 0.0054011 -0.0619749 -0.00989855 0.0464983 0.060717 0.0056113 0.048859 -0.0571203 0.0108629 0.0457589 -0.058228 0.0629979 0.0252605 0.000416678 0.06197 0.0252598 0.0113432 0.0590598 0.02575 0.0219305 0.0543551 0.0252542 0.0318508 0.0311225 0.0252593 0.054773 0.0211615 0.0252593 0.0593392 0.0105358 0.0252591 0.0621123 -0.00040991 0.0252633 0.0629982 -0.0113432 0.0252604 0.06197 -0.0219235 0.0252604 0.0590611 -0.048529 0.0252603 0.0401717 -0.0408029 0.0252604 0.048 -0.054763 0.0252603 0.0311441 -0.0593392 0.0252603 0.0211615 -0.0621123 0.0252603 0.0105358 -0.020945 -0.0167501 -0.0626368 -0.0211501 -0.0190005 -0.0635834 -0.0204985 0.019 -0.0644947 -0.0151508 -0.0164999 -0.314722 -0.00889506 -0.0165 -0.286879 0.0119761 -0.0169534 -0.286421 0.0180432 -0.0168264 -0.301285 -0.00550023 0.0168382 -0.317238 0.0201816 0.0164986 -0.292991 -0.0152247 0.017 -0.28864 -0.0111725 0.022 -0.299624 -0.0126034 0.024 -0.298669 0.0098456 0.0240263 -0.291024 0.0122967 0.022 -0.295019 0.000626061 -0.024 -0.286268 -0.006654 -0.022 -0.288525 -0.00737642 0.022 -0.307479 -0.0101245 0.017 -0.30279 0.0101243 0.017 -0.297223 -0.00278339 0.017 -0.289882 -0.00265195 -0.017 -0.310166 0.0101595 -0.017 -0.302658 0.00983825 -0.022 -0.304874 0.00265175 -0.017 -0.289847 -0.000613382 -0.022 -0.28924 -0.0598892 0.00662218 -0.0673897 -0.0601036 -0.00226164 -0.0623909 0.0147938 0.000216696 -0.0669055 0.0175782 0.00234322 -0.0618874 0.0189675 -0.00154114 -0.0618784 -0.061972 0.0092468 -0.0623405 -0.0574928 0.0156085 -0.067372 -0.0490716 0.019 -0.135321 -0.0177084 0.0190405 -0.185597 -0.0486595 0.019106 -0.199182 -0.0175348 0.0192628 -0.212388 -0.0173996 0.0200346 -0.233201 -0.0484047 0.0206675 -0.238599 -0.0485921 -0.0193006 -0.214812 -0.0486595 -0.0191061 -0.199203 -0.016747 -0.019008 -0.16742 -0.0490715 -0.019 -0.135321 0.00512259 -0.01675 -0.0769683 -0.0211658 0.01675 -0.064215 0.00512259 0.01675 -0.0769683 -0.0489304 0.01675 -0.0803186 -0.0494524 0.019 -0.0761705 0.00598915 -0.019 -0.0785821 0.0231893 0.0162491 -0.0668512 -0.0640356 -0.0172901 -0.0624358 -0.0494789 -0.01575 -0.262962 -0.0508329 -0.0156349 -0.0628308 -0.0510438 -0.01475 -0.062832 -0.0494886 0.01675 -0.0626056 0.0091603 -0.01475 -0.0624419 -0.0534415 0.015 -0.0778529 -0.0552375 0.0154093 -0.076073 -0.0536982 -0.011 -0.0775995 0.0120083 -0.0123237 -0.0781782 0.00957673 -0.016641 -0.0806039 0.0231492 -0.016083 -0.0619423 0.0150779 -0.0160759 -0.0749103 0.0218524 -0.018455 -0.0658801 -0.057216 -0.0160154 -0.067893 -0.050931 -0.018715 -0.076794 -0.0639996 -0.0171203 -0.0673583 -0.0624413 -0.0190002 -0.0629235 -0.0531248 0.0165619 -0.0777193 -0.0624383 0.0184391 -0.0666281 0.0219936 0.018334 -0.0658757 0.0145065 0.0159666 -0.0755389 0.0120086 0.0119703 -0.078178 -0.0145497 0.0164351 -0.155628 0.00361879 0.0163112 -0.0799783 0.00431592 0.0155229 -0.0799737 0.00423774 -0.0156937 -0.0799742 0.0036232 -0.0162795 -0.0799782 0.0038387 0.024 -0.313212 0.0131247 0.024 -0.301963 -0.00150072 0.024 -0.287421 -0.0256845 0.024 -0.296483 -0.00934208 0.0234346 -0.30947 0.0213066 -0.0165046 -0.301198 0.017521 0.0227326 -0.289049 -0.0524425 0.0161802 -0.232768 -0.0503746 -0.0164989 -0.272091 -0.0522474 0.0164989 -0.262947 -0.0485154 0.0165 -0.274895 -0.0521424 0.0179683 -0.0773034 -0.0508145 0.0187386 -0.0768544 -0.0494524 -0.019 -0.0761705 -0.0531693 -0.0164402 -0.0777827 -0.0524007 -0.0177353 -0.0773583 -0.0494305 0.0165 -0.0803221 -0.0143326 0.0165 -0.290563 0.0065234 0.0168182 -0.282899 0.00663685 0.0165 -0.276656 0.0130456 0.0168821 -0.312884 -0.00556459 0.0164976 -0.320657 -0.048247 0.0165 -0.26297 -0.052247 -0.0165 -0.262946 -0.0494305 -0.0165 -0.0803221 0.00649403 -0.0165005 -0.320362 -0.048247 -0.0165 -0.26297 0.0181189 -0.0165023 -0.288514 0.0168414 -0.0165006 -0.313149 0.00661776 -0.016505 -0.276446 -0.0498494 0.0164403 -0.0803247 -0.0490514 -0.016266 -0.262965 -0.0486507 -0.0164446 -0.262967 -0.0414776 0.0165 -0.28438 -0.046676 -0.024 -0.269737 -0.00925187 -0.024 -0.290874 0.0191103 -0.0235919 -0.291634 -0.000626033 -0.024 -0.313745 -0.0135333 -0.024 -0.302453 0.0132544 -0.024 -0.303674 0.0109625 -0.024 -0.293019 -0.0144015 0.0165001 -0.315593 0.00985298 0.0164999 -0.319515 0.0200852 0.0168544 -0.308381 -0.0414776 -0.0165 -0.28438 0.00441288 -0.01675 -0.0799729 -0.0486507 0.0164446 -0.262967 -0.0495648 0.015584 -0.262962 -0.0497471 0.01475 -0.262961 -0.0497471 -0.01475 -0.262961 0.00978405 0.016333 -0.0804956 -0.00253773 -0.015 -0.119591 -0.0125205 0.0165508 -0.165603 -0.0114369 -0.0151025 -0.158589 -0.0114369 0.0151025 -0.158589 0.00598915 0.019 -0.0785821 0.00115739 0.015 -0.106519 -0.00253773 0.015 -0.119591 -0.00729576 0.019 -0.123054 -0.0148266 0.0186271 -0.162379 -0.00205169 0.0172446 -0.114654 -0.0523929 0.0165415 -0.199225 -0.0526599 0.0151056 -0.199165 -0.0485197 0.0194517 -0.22084 -0.0484546 0.0199244 -0.230857 -0.0507615 0.019096 -0.230053 -0.0528735 0.0162425 -0.135345 -0.0515074 0.0179149 -0.199209 -0.0501443 0.0188203 -0.199194 -0.0519747 0.0217127 -0.267739 -0.0506683 0.0235173 -0.263965 -0.0440053 0.0201084 -0.281448 -0.01391 0.0232593 -0.313584 -0.044843 0.0230178 -0.278888 -0.0140781 0.0209276 -0.315888 0.0109163 0.0237851 -0.317589 -0.00321387 0.0235338 -0.320758 0.0208941 0.0224981 -0.297258 -0.0526075 -0.0152071 -0.207244 -0.0524076 -0.0165025 -0.199246 -0.0485511 -0.0195539 -0.223788 -0.0485087 -0.0201151 -0.233334 -0.0504482 -0.0186855 -0.207184 -0.0513735 -0.019058 -0.23507 -0.0503076 -0.0188042 -0.135329 -0.0515276 -0.0178942 -0.199231 -0.0518462 -0.0223283 -0.265173 -0.0483095 -0.0238242 -0.262662 -0.0461705 -0.0234403 -0.275704 -0.0482766 -0.0215865 -0.275599 -0.0147313 -0.0231534 -0.312784 -0.0416935 -0.0204573 -0.284112 -0.00773028 -0.023992 -0.317247 -0.014157 -0.0204448 -0.315859 -0.00558755 -0.016683 -0.320871 0.0107284 -0.0235156 -0.318508 0.0203394 -0.0234871 -0.304759 -0.00453547 -0.019 -0.111968 0.00784805 -0.018535 -0.0793404 0.00841977 -0.015 -0.0846612 -0.00975476 -0.0150006 -0.150386 0.00115739 -0.015 -0.106519 -0.00186102 -0.0172723 -0.114198 -0.050235 -0.016266 -0.0803273 0.00441288 -0.015 -0.0799729 0.00286895 -0.0165 -0.0799832 -0.0489304 -0.01675 -0.0803186 0.00441288 0.01675 -0.0799729 0.00482795 -0.022 -0.287646 -0.00983845 -0.022 -0.295139 -0.0100893 -0.022 -0.305074 -0.00482726 -0.022 -0.312367 0.000613208 -0.022 -0.310772 0.00665383 -0.022 -0.311487 0.00901701 -0.022 -0.294092 0.0126736 -0.022 -0.296074 0.010773 0.022 -0.30048 0.00499434 0.022 -0.309781 0.0115661 0.022 -0.306511 -0.00114104 0.022 -0.311067 -0.00837901 0.022 -0.292917 -0.00413904 0.022 -0.289769 0.00579659 0.022 -0.290913 0.00376816 0.022 -0.287283 -0.0110235 -0.016003 -0.229096 -0.000471456 0.0165 -0.257513 0.0066992 0.0215918 -0.276826 -0.0122707 -0.0156043 -0.222273 -0.0126225 0.0151085 -0.167953 -0.0126262 -0.0159894 -0.166482 -0.0484992 -0.0209012 -0.240377 -0.0128805 -0.0202806 -0.234923 -0.0176027 -0.0191292 -0.20191 0.00157528 -0.024 -0.274225 -0.0483554 -0.0234853 -0.258049 -0.00254143 -0.0238539 -0.26296 -0.048441 -0.0221553 -0.248307 -0.00404794 -0.0235753 -0.258758 -0.00962244 -0.021402 -0.243474 -0.00374114 0.0233425 -0.256363 -0.0173327 0.021402 -0.243524 -0.0483859 0.0230885 -0.254569 -0.00254104 0.023854 -0.262962 -0.0483158 0.0237953 -0.262135 -0.000202697 0.024 -0.269435 -0.0487828 0.0190256 -0.180077 -0.0141451 -0.0182066 -0.165451 -0.0130711 -0.0173473 -0.20614 -0.014831 -0.0188934 -0.206134 -0.0162204 -0.0193006 -0.214603 -0.00047172 -0.0164987 -0.257509 -0.0161443 -0.0196729 -0.226324 -0.0133794 -0.0186692 -0.226208 0.00637187 -0.0222352 -0.277303 -0.00493203 -0.0233338 -0.256287 -0.000759279 -0.0228695 -0.259737 -0.00975476 0.0150006 -0.150386 -0.0131431 0.0174585 -0.205071 -0.015565 0.0195917 -0.227278 -0.000316141 0.0222222 -0.259786 -0.00864006 0.0213765 -0.243472 -0.0118961 0.0176819 -0.22609 -0.0122708 0.0156368 -0.222274 0.0168119 0.017 -0.296549 0.0048517 0.017 -0.290376 0.00963027 0.017 -0.304858 -0.00963046 0.017 -0.295154 -0.014209 0.017 -0.309634 -0.0048519 0.017 -0.309637 0.0027832 0.017 -0.310131 -0.00281569 -0.0159531 -0.258383 -0.0151227 -0.0145 -0.167969 -0.0120893 -0.0145 -0.149838 -0.0537626 -0.0107916 -0.0673494 -0.0640143 0.0162482 -0.0674159 -0.0617725 -0.00913102 -0.0674018 -0.0578011 -0.00085656 -0.0673762 0.0119425 -0.0128467 -0.0669239 0.0165411 -0.00731575 -0.0668942 0.0156303 0.016157 -0.0668964 0.0196707 -0.000215693 -0.066874 0.0119412 0.0118475 -0.0669239 0.0231894 -0.0162489 -0.0668511 0.0187437 0.00766141 -0.0668799 0.00956661 -0.017 -0.29503 -0.0049764 -0.017 -0.29044 -0.0115628 -0.017 -0.28493 0.00497618 -0.017 -0.309573 0.00221262 -0.0169145 -0.319204 -0.0095668 -0.017 -0.304983 -0.0168119 -0.017 -0.303464 -0.0101597 -0.017 -0.297355 0.00853195 -0.0167489 -0.0768918 0.00856842 0.0166428 -0.0768501 -0.00281583 0.0156255 -0.258383 -0.00469003 0.0165 -0.259079 -0.0133639 0.0145 -0.229975 -0.0147705 0.0145 -0.222289 -0.0144034 0.0145 -0.226194 -0.0171224 0.0165 -0.167982 -0.0154994 0.0162741 -0.226209 -0.0151227 0.0145 -0.167969 -0.0151231 0.0152819 -0.165925 0.00286895 0.0165 -0.0799832 -0.0122709 0.015 -0.150607 -0.0153486 -0.0157371 -0.163068 -0.0161536 -0.016338 -0.163908 -0.0149347 -0.0145 -0.164918 -0.0171224 -0.0165 -0.167982 -0.0153272 -0.0161784 -0.226596 -0.0147705 -0.0145 -0.222289 -0.0167705 -0.0165 -0.222302 -0.0144034 -0.0145 -0.226194 -0.0133639 -0.0145 -0.229975 -0.0537729 0.0128369 -0.0673497 -0.0553629 0.0103572 -0.0623602 -0.056772 -0.00831935 -0.0623692 -0.0596897 -0.0146843 -0.0623882 0.0141541 -0.00954606 -0.0619096 0.0170499 -0.0157706 -0.0656327 0.0201717 -0.00888876 -0.0618705 0.015866 0.014512 -0.0618982 0.0198321 0.00872504 -0.0618727 -0.0507988 -0.016748 -0.0623809 -0.0609159 0.0137579 -0.0623961 0.014909 -0.000802118 -0.0619047 0.0150168 0.00863808 -0.0619039 0.00965218 0.0172475 -0.0619388 -0.0580396 0.00217822 -0.0623776 -0.0614086 -0.00886489 -0.0623993 0.0080363 -0.0167516 -0.0620116 -0.0510438 0.01475 -0.062832 0.00915678 0.0167469 -0.0624453 -0.0508899 0.0155197 -0.0628311 -0.0218667 0.0172141 -0.0621511 -0.0617128 0.0189967 -0.0627789 -0.0640426 0.0157484 -0.0629167 -0.021447 0.0186709 -0.0621641 0.0191857 0.0189757 -0.0619958 0.0231487 0.0161062 -0.0619033 -0.0201822 -0.0190007 -0.0626338 0.0191606 -0.019 -0.0623771 0.0210811 -0.0184981 -0.0618647 + + + + + + + + + + -0.0878771 0.890791 -0.445835 0.341027 0.925769 0.163256 0.0878764 0.890792 0.445832 -0.22644 0.901553 0.368682 0.733871 0.16925 0.657866 -0.617074 0.00309639 -0.786899 -0.648508 -0.0899851 -0.755871 -0.665117 0.038272 -0.745758 0.210207 -0.977657 0.000424046 0.335068 -0.941391 0.0388862 0.689632 -0.0579682 0.721836 -0.672121 0.0217454 -0.740122 0.502652 0.0389096 0.863613 0.790764 -0.38116 -0.478966 -0.608936 -0.013063 -0.793112 -0.652475 -0.131003 -0.746401 0.335068 -0.941391 0.0388867 0.302697 0.382456 0.872985 -0.534182 0.0986294 -0.839596 -0.537424 -0.660852 0.52388 -0.590256 0.00261051 -0.807212 -0.563583 0.0110595 -0.825985 -0.143529 -0.83735 0.527489 -0.0734119 0.764887 0.639968 -0.479386 0.0665086 -0.87508 -0.509084 0.0458077 -0.859497 -0.0734128 0.764884 0.639971 -0.288928 -0.932183 0.218074 0.430225 -0.230405 0.872823 -0.686065 -0.284281 -0.669701 -0.486944 0.0868329 -0.869106 -0.832818 -0.228902 0.504002 -0.0712539 -0.951049 0.300715 -0.553983 -0.797817 0.237887 -0.552843 -0.08075 -0.829364 -0.963615 0.249213 -0.0966414 -0.973609 -0.024425 -0.226912 -0.970365 -0.0229555 -0.240551 -0.980587 -0.0174086 -0.19531 -0.750753 0.581892 -0.312683 -0.996541 0.00703615 -0.0828074 0.0322502 -0.276243 -0.960547 0.230734 0.638905 -0.733868 -0.994872 0.0155291 -0.099946 0.993486 -0.110975 0.0258999 0.0293397 -0.964411 -0.262775 0.635154 -0.446142 -0.630505 -0.98915 -0.0529455 -0.137037 -0.996733 0.00637613 -0.0805121 -0.89382 -0.224495 -0.388185 0.635153 -0.446142 -0.630506 0.664358 0.128136 -0.736349 -0.993552 0.0296167 -0.109445 -0.996302 -0.0143025 -0.0847161 -0.989919 -0.00483113 -0.141551 -0.997074 0.00769074 -0.0760525 0.390873 -0.763655 0.513857 -0.968403 -0.0617902 -0.241616 0.457541 0.624892 0.632586 0.939114 0.0762024 0.33505 0.958046 0.0497938 0.282256 0.0585231 -0.893848 0.444534 0.136539 -0.98078 0.139385 -0.95997 -0.0148512 -0.27971 0.948345 0.0376995 0.314993 -0.974484 -0.0165049 -0.223848 -0.7427 0.0572393 0.667173 -0.757131 -0.0648934 0.650032 -0.764094 -0.00854283 0.645049 -0.800408 -0.00236478 0.59945 0.814126 -0.00786222 -0.580635 -0.450403 0.890446 -0.0651329 -0.0536692 -0.465668 -0.883331 -0.760372 -0.01353 0.649347 -0.775436 0.0125404 0.631301 0.661356 0.207292 -0.72086 -0.218923 0.932182 -0.288287 -0.181353 0.380839 -0.906682 -0.761322 0.0382081 0.647248 -0.797949 -0.236168 0.554529 0.0900075 -0.624893 -0.775504 -0.824612 -0.0122089 0.565567 -0.816443 -0.0133157 0.577272 0.637252 -0.765229 0.0912952 -0.815704 -0.146079 0.559721 0.204028 0.976377 0.071132 -0.832118 0.00155014 0.554597 0.835636 0.465666 0.29132 0.835636 0.465667 0.291319 -0.834862 0.00926099 0.550382 -0.822716 -0.0101903 0.568362 -0.836209 0.00763363 0.548358 -0.0922013 -0.000251223 0.99574 -0.0805442 0.00638423 0.996731 -0.105257 -0.0477117 0.9933 -0.189963 0.977315 -0.0936481 -0.0847838 0.0102598 0.996347 0.0751014 -0.0130551 -0.99709 -0.402662 -0.234523 0.884795 -0.662564 -0.465672 -0.58665 -0.630507 -0.446142 -0.635152 -0.0600511 -0.0789922 -0.995065 -0.0758309 0.00717075 0.997095 -0.737045 0.101603 -0.668163 -0.0812969 0.0241837 0.996397 -0.0898796 -0.176111 0.980258 0.235016 -0.0426196 -0.971057 -0.142326 -0.00830226 0.989785 -0.195692 0.00722211 0.980639 0.442371 -0.8906 -0.105542 -0.145176 -0.0135006 0.989314 -0.184005 -0.156451 0.970395 0.566498 -0.783558 0.25518 -0.12635 0.00124057 0.991985 0.0852127 -0.00646402 -0.996342 -0.0673196 0.0107412 0.997674 0.7791 0.446048 -0.440505 0.779098 0.44605 -0.440506 -0.19798 0.0114274 0.980139 -0.154207 -0.0176378 0.987881 -0.200623 0.00962361 0.979621 -0.18082 0.0139662 0.983417 0.563196 0.159451 0.810794 0.529056 0.0491715 0.847161 0.590915 -0.0181446 0.80653 0.544697 -0.227323 0.807236 0.661064 -0.0844738 0.74556 0.648738 -0.0127826 0.760905 -0.363567 -0.734608 0.572861 -0.883331 -0.465667 0.0536713 0.649365 -0.0135138 0.760357 0.631351 0.0125216 0.775396 -0.720868 0.207354 -0.661328 -0.288287 0.932182 0.218924 -0.639339 0.763655 -0.0898709 0.659098 0.108151 0.74424 0.0912957 -0.765227 -0.637254 0.525761 -0.00328653 0.850626 0.0711238 0.976383 -0.204004 0.555218 0.00641083 0.83168 0.608243 -0.00176002 0.793749 -0.511896 0.609448 0.605421 0.29132 0.465668 -0.835635 0.155908 -0.898518 -0.410314 -0.496954 -0.0722858 -0.864761 0.580368 -0.0144037 0.814227 0.552503 0.0109694 0.833439 0.218264 -0.944136 -0.246916 0.839459 -0.473685 -0.26633 0.506144 -0.800915 -0.319927 0.603971 -0.0695699 0.793964 0.937127 -0.252489 -0.240919 -0.937127 0.252489 0.240919 0.770318 0.391698 -0.503174 -0.770318 -0.391698 0.503174 -0.689359 -0.154454 0.707763 0.689359 0.154454 -0.707763 -0.661295 0.448451 0.601316 -0.541675 -0.0439773 0.839437 0.738593 0.0583426 -0.671622 0.501089 -0.38271 -0.776172 -0.656666 0.483678 -0.578658 0.656666 -0.483678 0.578658 -0.569594 -0.0245571 -0.82156 -0.634574 -0.559929 -0.532725 0.634574 0.559929 0.532725 0.569594 0.0245571 0.82156 -0.0134679 -0.283383 -0.958912 -0.309985 0.678468 -0.666026 0.388096 0.297855 0.872161 -0.410731 0.182119 -0.893383 -0.424259 0.635774 -0.644822 0.307272 -0.674519 0.671274 0.516967 -0.340771 0.785251 0.960787 0.19391 -0.198212 0.877513 -0.18609 -0.441975 0.868614 0.0868089 -0.487825 0.700441 -0.104582 -0.706007 0.689792 9.33486e-07 -0.724007 0.0441375 -0.0678546 0.996718 0.0684169 0.0934938 0.993266 0.383739 -0.112951 0.916508 0.408644 0.0735742 0.909724 0.65804 -0.0103983 0.752911 0.678067 0.154047 0.718676 0.780539 -0.185399 0.596981 0.851243 0.173415 0.495291 0.921311 -0.135436 0.364476 0.944639 0.169639 0.280857 0.980653 -0.0898524 0.173914 0.997305 0.0695658 0.02329 0.951673 -0.297442 -0.0764645 -0.147317 -0.152483 0.977265 -0.266999 0.357099 0.895093 -0.408911 -0.167847 0.897006 -0.578461 0.0385407 0.814799 -0.596621 0.271328 0.755265 -0.719061 -0.145108 0.679629 -0.738518 -0.0537285 -0.67209 -0.750557 0.0965758 -0.653711 -0.920072 -0.104023 -0.377687 -0.931803 0.0734961 -0.355447 -0.997873 0.0106544 -0.0643086 -0.997834 0.00456959 -0.0656238 -0.990527 -0.0107075 0.136901 -0.985166 0.0761026 0.153809 -0.898098 -0.105364 0.426988 -0.893202 0.0364536 0.448176 -0.793149 0.0923548 0.601985 -0.514728 -0.0361162 -0.856592 -0.0210995 0.135283 -0.990582 -0.298287 -0.141454 -0.943936 -0.384622 0.43146 -0.816032 0.167043 -0.158296 -0.973159 0.00321105 -0.0339057 -0.99942 0.305199 -0.0137646 -0.952189 0.323377 0.089565 -0.942022 -0.523691 0.802746 0.285214 -0.115958 0.709823 -0.69477 -0.959197 0.210663 0.188581 0.539187 0.140679 -0.830353 -0.539187 -0.140679 0.830353 -0.811927 -0.551004 0.192794 -0.12561 -0.987799 0.0920668 -0.0337527 -0.99935 -0.0126525 -0.0407852 -0.999024 -0.0169712 -0.0647881 -0.997161 -0.0383698 -0.032695 -0.987761 -0.152509 0.139075 -0.979963 -0.142587 0.0571555 -0.997299 -0.0461294 0.0417934 -0.998954 0.0185655 0.079643 -0.995823 0.0446455 0.0567749 -0.998102 0.0238573 0.0324924 -0.988502 0.147675 0.974503 0.127818 -0.184408 -0.989239 -0.0940218 0.112095 0.456454 0.880359 0.128912 -0.4462 0.854521 -0.265892 0.514761 0.758336 -0.399934 0.808257 0.239543 -0.537904 0.880017 0.36879 -0.299272 0.936028 0.182327 -0.301011 0.92487 0.375851 0.0578839 0.558084 0.82609 0.0782182 0.862474 -0.307485 0.401984 0.607912 0.672863 0.421543 0.58398 -0.474492 0.658654 0.503756 0.50279 0.702447 0.228936 -0.15532 0.96097 0.220711 -0.229236 0.948018 -0.136546 0.198355 0.970572 -0.168817 -0.198356 0.965482 -0.501789 0.229236 0.834062 -0.513159 -0.359869 0.779206 -0.80371 0.391987 0.447658 -0.8694 0.165072 0.46572 -0.924237 0.368787 0.0989066 -0.96488 -0.257398 0.0524579 -0.653987 0.734888 -0.179554 -0.652107 -0.692362 -0.308854 -0.603058 0.535886 -0.590887 -0.37737 0.874703 -0.304116 -0.428789 0.125849 -0.894596 -0.270356 0.636463 -0.722373 -0.127514 -0.636911 -0.760319 0.106997 0.488875 -0.865767 0.0559621 0.729687 -0.681487 0.421643 0.900113 -0.109611 -0.149716 0.723951 0.673409 -0.109974 -0.275471 0.954998 0.17958 0.233007 0.95575 0.174526 0.270166 0.946864 0.382092 -0.386827 0.839268 0.392637 0.725387 0.565376 0.515395 0.597075 0.61471 0.604486 -0.549029 0.577204 0.681052 0.649951 0.337243 0.624288 -0.767295 0.14671 0.866871 0.492523 0.0771772 0.952348 -0.0458214 -0.301553 0.421629 -0.888291 -0.182124 0.433486 0.781027 -0.449541 0.304861 -0.783764 -0.541086 0.24211 0.671966 -0.699889 -0.0221365 -0.713213 -0.700597 -0.134797 0.555883 -0.820258 -0.356323 -0.477566 -0.803097 -0.44481 0.560708 -0.698391 -0.575361 -0.617983 -0.535777 -0.685363 0.525963 -0.503627 -0.962344 -0.093238 -0.255344 -0.943106 -0.228901 -0.241156 -0.973003 0.205012 0.105997 -0.968963 -0.205011 0.138132 -0.875935 0.191676 0.442716 -0.823618 0.567097 0.00734784 0.147786 0.985119 -0.087746 -0.885286 -0.165907 0.434446 -0.956089 -0.031457 0.291383 -0.834202 -0.167177 -0.525508 -0.306348 -0.254851 -0.91717 -0.107526 -0.146736 -0.983314 0.525235 -0.162869 -0.835226 0.52386 -0.163995 -0.835869 0.993265 -0.0863872 0.0772096 -0.381304 -0.156906 0.911037 0.793275 0.485877 -0.366931 0.593012 0.804015 0.0435492 0.593012 0.804015 0.0435486 0.100223 0.993404 -0.055711 0.0461642 -0.989304 -0.138372 0.381112 -0.334992 -0.861704 -0.381112 0.334992 0.861704 0.567527 -0.465682 -0.679009 -0.998352 -0.0193664 -0.0540194 -0.995203 0.0459403 -0.0863743 -0.682528 -0.170997 -0.710574 -0.477233 0.0762943 -0.875459 0.0251437 -0.176066 -0.984057 0.532897 0.198044 -0.822678 0.880425 0.177613 0.439665 0.540076 -0.223671 0.81135 0.000295101 0.0269394 0.999637 0.0197052 0.00197723 0.999804 -0.718268 -0.0679504 0.692441 0.880736 -0.453293 0.13722 0.808901 0.184291 -0.558316 -0.621943 -0.759474 0.190752 0.42542 -0.899214 -0.10214 -0.167655 -0.94487 0.281269 0.715283 0.0129341 -0.698715 0.519049 0.0127458 -0.854649 0.429777 -0.0364841 -0.902198 0.290128 0.0255605 -0.956646 0.0431181 0.00699991 -0.999045 -0.0444818 -0.0420374 -0.998125 -0.206627 0.0255669 -0.978086 -0.443509 0.00704593 -0.896242 -0.474568 -0.0125418 -0.88013 -0.684051 0.0205479 -0.729145 -0.739113 -0.0267144 -0.673052 -0.920645 0.0308475 -0.38918 -0.96307 -0.0421335 -0.265935 -0.997058 0.043349 -0.0632123 -0.982937 -0.0348574 0.18061 -0.921199 0.0498371 0.385888 -0.892406 0.00303842 0.451223 -0.71464 -0.026714 0.698983 -0.654619 0.0312094 0.755314 -0.368569 0.00399204 0.929592 -0.329024 -0.0322598 0.94377 0.0823792 0.0376922 0.995888 0.168857 -0.0324401 0.985107 0.551956 0.0379736 0.833008 0.622903 -0.0323614 0.781629 0.884988 0.0379688 0.464064 0.922928 -0.0335166 0.383512 0.999231 0.0318161 0.0229373 0.996302 -0.0263291 -0.0817851 0.963249 0.0226821 -0.267652 0.908999 -0.018279 -0.416397 0.866545 0.0153363 -0.498863 0.747783 -0.0101993 -0.663865 -0.198426 -0.958961 -0.202536 0.321939 -0.74297 -0.586815 -0.0225241 -0.436554 0.899396 0.302704 -0.641173 -0.705172 -0.0876893 -0.648894 -0.755809 -0.74796 -0.655088 -0.106849 -0.679183 -0.681265 0.273109 -0.458084 -0.679338 0.573288 0.998771 -0.0213552 -0.0447176 0.998583 0.0365789 0.0386577 0.95381 -0.0372688 0.298089 0.848984 0.0614524 0.524832 0.742143 -0.0397414 0.669062 0.463264 0.0306781 0.885689 0.502354 -0.00825077 0.864623 0.122577 0.033211 0.991903 0.0469126 -0.0190513 0.998717 -0.267292 0.00223867 0.963613 -0.263415 -2.90841e-06 0.964683 -0.512851 0.00431596 0.858467 -0.505602 0 0.862767 -0.711679 0 0.702505 -0.711674 -3.37085e-06 0.70251 -0.873204 0.00413529 0.487337 -0.875985 0.00708768 0.482286 -0.967484 -0.00242036 0.25292 -0.968869 0.000107065 0.247576 -0.99988 0.00431486 -0.0149066 -0.999979 2.32138e-10 -0.00648067 -0.964569 9.45044e-09 -0.263831 -0.964228 0.000617616 -0.265073 -0.862099 0.00125831 -0.506738 -0.862767 0.000627485 -0.505602 -0.701545 0.00127844 -0.712624 -0.702509 0.000630757 -0.711674 -0.492181 0.00128795 -0.870492 -0.441735 0.0292613 -0.896668 -0.23922 -0.0282282 -0.970555 0.0099339 0.0248683 -0.999641 0.0300606 0.0387048 -0.998798 0.27811 -0.0282272 -0.960134 0.507438 0.0246272 -0.861336 0.476492 0.000543407 -0.879179 0.712639 0.00128506 -0.70153 0.711674 0.000627064 -0.702509 0.883819 0.00134453 -0.467827 0.88659 0.00541709 -0.462524 -0.5847 -0.768646 0.259439 -0.993692 -0.0983997 -0.0537952 -0.680379 -0.38006 -0.626609 0.164717 -0.610258 -0.774889 0.572065 0.804066 -0.161925 0.579952 -0.689284 -0.434215 0.836592 0.542976 0.0727419 0.225197 -0.854977 -0.467227 -0.880545 -0.194908 0.432033 -0.896637 -0.241081 -0.371378 -0.610364 0.0761548 -0.788452 -0.0889006 -0.222276 -0.970922 0.494136 -0.37812 -0.78285 0.905801 0.194952 -0.376189 0.585428 -0.167659 -0.793199 0.933373 -0.0136998 0.358647 0.438188 -0.0877743 0.894588 0.126566 0.0377934 0.991238 -0.899542 -0.168937 0.402845 -0.280443 -0.238385 0.929798 0.223233 -0.484259 -0.845967 0.794173 0.152244 -0.588313 0.554769 0.485231 -0.675856 0.11553 -0.0645871 -0.991202 0.148643 0.0912795 -0.984669 -0.122064 -0.178264 -0.976382 -0.283371 0.184162 -0.941161 -0.530315 -0.240877 -0.812862 -0.744583 0.218776 -0.630661 -0.824992 -0.101728 -0.555913 -0.972428 0.0524623 -0.227225 -0.967549 0.0834365 -0.23851 -0.98077 -0.158428 0.113974 -0.97602 0.0818944 0.201687 -0.803473 -0.0296209 0.594603 -0.823404 0.10725 0.557229 -0.569523 -0.136683 0.810531 -0.507407 0.0419552 0.860684 -0.22919 0.0210943 0.973153 0.141646 -0.0770241 0.986916 0.397062 0.0123545 0.917709 0.454133 -0.108037 0.884359 0.714933 0.0771831 0.69492 0.766282 -0.122155 0.630786 0.940653 0.0770764 0.330502 0.954317 -0.212881 0.20967 0.964301 0.236173 -0.11977 0.885742 -0.307171 -0.348005 -0.619382 -0.012589 -0.784989 -0.442714 -0.0468211 0.89544 -0.536038 0.0839751 0.840007 -0.59962 -0.0432743 0.799114 -0.512381 -0.0980712 0.85314 -0.849556 0.00665103 0.527457 -0.931456 0.0351186 0.362155 -0.879327 -0.0877256 0.468068 -0.982713 0.00551621 0.185055 -0.999364 0.0356395 0.00124466 -0.983021 0.0189181 -0.182518 -0.969344 -0.0585851 -0.23862 -0.930781 0.0675575 -0.359282 -0.850753 0.0157161 -0.52533 -0.739724 0.0169638 -0.672697 -0.805189 -0.0999399 -0.584537 -0.603564 0.0119667 -0.797225 -0.446765 0.0169785 -0.89449 -0.396107 -0.0480373 -0.916947 -0.274143 0.0709433 -0.959069 -0.0934819 0.00360139 -0.995614 0.0909638 0.0445505 -0.994857 -0.0460872 -0.0742757 -0.996172 0.274076 -0.0179923 -0.96154 0.272432 -0.0206011 -0.961955 0.44425 0.0422262 -0.894907 0.601401 0.0294125 -0.798406 0.544893 -0.0581093 -0.836489 0.737956 0.0249964 -0.674386 0.849063 0.0347063 -0.52715 0.763803 -0.027282 -0.644872 0.93191 0.0145754 -0.362397 0.909746 -0.0772285 -0.407919 0.999861 0.0166153 -0.0012011 0.996342 -0.0711541 0.047325 0.982598 0.0348811 0.182439 0.932588 0.0263447 0.359979 0.947329 -0.0317749 0.318683 0.850421 0.0320753 0.525125 0.739724 0.0169644 0.672697 0.796772 -0.0827284 0.598591 0.630434 -0.0100566 0.776178 0.603359 0.0286892 0.796953 0.446769 0.0163889 0.894499 0.398493 -0.0504745 0.915781 0.274143 0.0709437 0.959069 0.0934823 0.00360209 0.995614 -0.0909638 0.0445504 0.994857 0.046086 -0.0742775 0.996172 -0.22164 -0.0884406 0.97111 -0.264743 -0.0147322 0.964207 -0.767059 0.0285914 0.640939 -0.677841 -0.124847 0.724531 0.716103 -0.268595 -0.644246 0.834817 0.489925 -0.251106 0.981221 -0.147169 -0.124688 0.939252 0.342769 0.017752 0.803951 -0.52889 0.271915 0.90963 -0.00121488 0.415418 0.637468 0.494804 0.590595 0.56192 -0.261648 0.784721 0.450546 0.367056 0.813805 0.0150462 -0.101878 0.994683 -0.00666156 -0.252446 0.967588 -0.276757 0.565216 0.777134 -0.50695 -0.428238 0.748073 -0.655838 0.468978 0.591555 -0.879001 -0.115687 0.462573 -0.858149 0.365496 0.360547 -0.99461 -0.0794723 -0.0665954 -0.908809 -0.404589 -0.10185 -0.788072 0.453676 -0.416078 -0.690641 -0.429185 -0.582078 -0.578024 0.353682 -0.735389 -0.385563 -0.324457 -0.863753 -0.228123 0.355999 -0.906214 0.0266644 -0.351157 -0.935937 0.195573 0.87154 -0.449633 0.291998 0.65277 0.69902 -0.075584 0.709939 0.700195 -0.689975 0.681418 0.24414 -0.942352 0.0479849 -0.331166 -0.0522803 0.976771 -0.207812 -0.97004 -0.225155 -0.0912588 -0.878573 0.453809 -0.148887 -0.551748 0.638709 -0.536307 -0.808275 0.0717802 -0.584413 -0.312236 0.270771 -0.9106 -0.329283 0.193229 -0.924249 -0.138697 0.0296495 -0.989891 0.155432 0.755236 -0.636757 0.449748 -0.559958 -0.695826 0.435103 0.827656 -0.3545 0.897963 -0.395212 -0.193573 0.930571 -0.290835 0.222381 0.875736 0.482418 -0.018946 0.710348 -0.374552 0.595916 0.826808 0.399919 0.395541 0.568928 0.451193 0.687565 0.24782 -0.287638 0.925121 0.99271 -0.0866079 0.0838215 0.859876 -0.0879716 0.502866 -0.866441 0.0791822 0.492961 -0.318798 0.947606 0.0202427 -0.495206 0.867618 -0.0448297 -0.691547 0.709839 0.133756 -0.812062 0.0124717 -0.583438 0.314817 -0.0811314 -0.945679 0.365642 -0.870774 -0.328723 -0.794019 0.0478167 0.606009 -0.869258 -0.0927102 0.485588 -0.906689 0.0950073 0.410961 -0.995109 -0.0761873 0.0628727 -0.999278 -0.00667988 0.0374147 -0.958459 0.106246 -0.264705 -0.785587 0.100291 -0.61057 -0.495869 -0.0476823 -0.867087 -0.440811 0.0951431 -0.892543 -0.0932896 -0.0384583 -0.994896 -0.00641963 0.138218 -0.990381 0.406764 0.124322 -0.905035 0.63166 -0.0471524 -0.77381 0.754277 0.176082 -0.632504 0.827213 -0.0231147 -0.561412 0.9549 0.0202332 -0.296237 0.961294 0.13537 -0.239979 0.971924 0.137813 0.190714 0.803621 0.115934 0.58374 0.630571 -0.0509364 0.774458 0.466777 0.162811 0.869259 0.307096 -0.130658 0.942667 0.070668 0.138085 0.987896 -0.105327 -0.0596197 0.992649 -0.166906 0.0189974 0.98579 -0.966041 -0.155687 -0.206218 0.840534 0.417558 -0.345178 0.955575 0.294665 -0.00698083 0.852469 -0.0130632 0.522615 0.629075 0.186019 0.75476 -0.900059 -0.0507185 -0.432807 0.517668 0.495975 -0.697157 0.833211 -0.0311534 0.552077 0.439781 -0.294374 0.848491 0.406401 -0.307145 0.860523 -0.233095 -0.481416 0.84493 -0.279913 -0.490929 0.825007 -0.831848 -0.418219 0.364859 -0.848774 -0.411149 0.332474 0.272773 0.961663 -0.0282886 0.997122 -0.0619257 0.0437278 0.984458 0.114674 -0.133014 0.959293 -0.109353 -0.260381 0.927113 0.141328 -0.347115 0.86559 -0.152637 -0.476923 0.833386 0.0102163 -0.552596 0.702732 -0.0322777 -0.710722 0.696878 0 -0.717189 0.993763 -0.0631104 -0.0919387 0.994157 3.73435e-08 -0.107946 0.953665 8.0059e-08 -0.300869 0.905519 0.211928 -0.367589 0.869363 -0.148404 -0.471364 0.699857 0.0606289 -0.711706 0.709993 0 -0.704208 0.997534 0.0604293 0.0356871 0.989335 -0.11331 -0.091529 0.990995 0 -0.133897 0.953665 0 -0.300869 0.905519 0.211928 -0.367589 0.860404 -0.178748 -0.477236 0.702868 0.0442257 -0.709944 0.709993 0 -0.704208 0.997534 0.0604293 0.0356871 0.989335 -0.11331 -0.091529 0.990995 0 -0.133897 0.953665 0 -0.300869 0.905519 0.211928 -0.367589 0.860404 -0.178748 -0.477236 0.702868 0.0442257 -0.709944 0.709993 0 -0.704208 0.997534 0.060429 0.0356871 0.989335 -0.113309 -0.0915291 0.990995 0 -0.133897 0.953665 0 -0.300869 0.927102 0.141369 -0.347127 0.863482 -0.158154 -0.478944 0.824569 0.0320046 -0.564856 0.702519 -0.0542951 -0.709591 0.689818 0 -0.723983 -0.849574 -0.000142457 0.527469 -0.849725 -2.6867e-05 0.527226 -0.932031 -1.33286e-05 0.362378 -0.932018 -2.82224e-05 0.362413 -0.982748 -1.4009e-05 0.184948 -0.982742 -2.69777e-05 0.184979 -0.999999 -1.34553e-05 0.0012197 -0.999999 -1.86616e-05 0.00123258 -0.983196 -1.84373e-05 -0.182551 -0.984373 -0.00267964 -0.176077 -0.932912 0.00105913 -0.360104 -0.933834 -2.85227e-05 -0.357707 -0.850859 -1.4005e-05 -0.525395 -0.850875 -2.67249e-05 -0.525368 -0.73983 -1.34013e-05 -0.672794 -0.739847 -2.34387e-05 -0.672776 -0.603607 -1.57647e-05 -0.797282 -0.603709 -6.72495e-05 -0.797205 -0.44683 4.29992e-06 -0.894619 -0.446892 -2.36993e-05 -0.894588 -0.274835 -1.18196e-05 -0.961491 -0.274807 0 -0.961499 -0.0934824 0 -0.995621 -0.093803 -0.000132771 -0.995591 0.0910541 7.63424e-06 -0.995846 0.0909465 -3.60915e-05 -0.995856 0.27249 -9.74341e-06 -0.962159 0.272455 -2.41127e-05 -0.962168 0.444646 -1.19302e-05 -0.895706 0.44461 -2.84047e-05 -0.895724 0.601661 -1.41176e-05 -0.798752 0.601636 -2.66486e-05 -0.79877 0.738187 -1.32808e-05 -0.674596 0.738164 -2.69074e-05 -0.674621 0.849574 -1.51149e-05 -0.527469 0.849559 -2.67846e-05 -0.527493 0.932031 -1.33649e-05 -0.362378 0.932018 -2.84374e-05 -0.362413 0.982748 -1.41974e-05 -0.184948 0.982742 -2.71969e-05 -0.18498 0.999999 -1.34568e-05 -0.0012197 0.999999 -1.95705e-05 -0.00123482 0.983196 -1.96021e-05 0.182551 0.983196 -1.76282e-05 0.182556 0.932912 -8.78759e-06 0.360104 0.932904 0 0.360124 0.850859 0 0.525395 0.851015 -0.000122958 0.525141 0.73983 9.27392e-06 0.672794 0.739886 -2.48176e-05 0.672732 0.603607 -1.23578e-05 0.797282 0.603651 -3.46777e-05 0.797248 0.44683 -1.12974e-05 0.894619 0.446857 -2.36969e-05 0.894605 0.274835 -1.18196e-05 0.961491 0.274807 0 0.961499 0.0934824 0 0.995621 0.0938027 -0.000132616 0.995591 -0.0910541 7.78918e-06 0.995846 -0.090938 -3.93749e-05 0.995857 -0.27249 -7.60255e-06 0.962159 -0.27245 -2.40692e-05 0.96217 -0.445231 -1.19202e-05 0.895416 -0.444663 -0.000261732 0.895698 -0.601084 -0.00090086 0.799185 -0.601439 -0.000726002 0.798918 -0.735332 -0.00170294 0.677705 -0.738135 -2.26606e-05 0.674653 0.803701 -0.0278211 0.594383 0.817615 -0.0188069 0.575458 0.995114 -0.00805983 0.0984056 0.991274 -0.00179078 0.131805 0.855762 -0.021847 -0.516908 0.924825 -0.00616732 -0.380343 0.223828 -0.0632331 -0.972575 -0.17658 -0.0116177 -0.984218 -0.0429485 0.0186196 -0.998904 -0.695306 -0.00211471 -0.718711 -0.678887 -0.00682436 -0.734212 -0.97478 -0.00509298 -0.22311 -0.859775 -0.000149105 -0.510673 0.0860361 0.0143543 0.996189 0.104592 0.0229503 0.99425 -0.530311 -0.05272 0.846162 -0.77471 0.0510177 0.630256 -0.967791 -0.0447539 0.247745 -0.9492 0.031356 -0.313108 0.528122 -0.357914 -0.770055 -0.419981 0.31283 -0.851911 -0.455928 0.299597 -0.838076 0.864868 0.401015 -0.301978 0.904689 0.37699 -0.198535 -0.00457491 -0.999966 0.00692838 -0.00665464 -0.999939 0.00880575 0.00177341 -0.999979 0.00623508 0.0042802 -0.999983 0.00399128 -0.000456823 -1 0.000122718 -0.00425382 -0.999988 0.00248315 -0.00654939 -0.999978 -0.000553031 -0.00147409 -0.999997 -0.002147 -0.000386779 -1 0.000584 -0.00221355 -0.999973 -0.00704064 0.0133222 -0.999876 -0.00834817 0.000132747 -1 -0.000396747 0.00014895 -1 -0.000389594 0.000421549 -1 -0.00012987 0.00037011 -1 -0.000350983 0.00184318 -0.999998 -0.000287428 0.0218009 0.999696 -0.0115227 -0.00037561 -1 -0.000129704 0.000293495 -1 -0.000771413 -0.000140672 -1 -0.000526109 -0.000137952 -1 -0.000529944 0.00354046 -0.999989 -0.00323035 0.00237612 -0.999997 0.000867063 0.00293527 -0.999995 -0.00117768 0.0787879 0.996355 0.0326963 -0.000675334 -0.999993 -0.00364997 0.00357629 -0.999993 -0.00111558 0.00774032 -0.999927 0.00929001 -0.000430685 -1 0.000213745 -0.00802881 -0.999968 7.52771e-05 -0.00546847 -0.999985 0.000730711 -0.00377597 -0.99999 -0.00245493 -0.000136273 -0.999998 -0.00203034 -0.0118263 0.999139 -0.0397759 0.0166449 -0.999772 0.0133544 0.000170511 -1 0.000432395 0.000619452 -0.999999 0.00104556 8.58793e-05 -1 0.00051898 0.0125647 0.998966 0.0436993 -0.000385455 -0.999955 0.00947218 -0.00629124 -0.999973 0.00374807 -0.00443693 -0.999988 0.00195229 0.000141777 -1 8.76029e-05 0.684748 0.0486076 -0.727157 0.056588 0.992904 0.104596 -6.08395e-05 1 -5.7546e-05 0.0232493 0.999495 0.0216627 -0.0177995 0.999812 0.00762777 0 -1 0 0.0987432 -0.978 0.183755 0.365767 0.0890805 0.926434 0.310616 -0.138715 -0.94036 0.565479 -0.00562868 0.824743 0.478724 -0.0393568 0.877083 0.725471 -0.0531404 0.686198 0.731061 -0.0250082 0.681853 0.345111 0.0905604 0.934183 0.372578 -0.132198 0.918536 0.689564 -0.24968 0.679824 -1.76637e-05 1 -2.38409e-05 0 1 0 4.86503e-06 1 1.77648e-05 0.0139919 0.990252 0.138586 0.00590132 -0.995842 0.0909092 0 -1 0 -0.364218 -0.0605046 -0.929346 -0.385003 0.0776263 -0.919645 0.447482 -0.0753392 0.891114 -0.674384 -0.0484844 -0.736787 -0.778567 0.0574974 -0.624922 -0.365874 -0.06486 -0.928402 -0.38053 -0.254776 -0.888981 -0.733397 -0.162237 -0.660158 0.043374 0.999045 0.00522859 0.356837 0.933179 0.0429555 1.09503e-05 1 8.83397e-05 -0.000273249 1 2.71561e-05 3.03119e-05 -1 3.52884e-06 0.346164 -0.937308 0.0402996 0.957433 -0.0757259 0.278547 0.844003 -0.0426544 0.53464 0.988032 -0.0741507 -0.135255 0.935392 -0.186001 0.300742 -0.958316 0.0278651 -0.28435 0.945206 -0.305927 -0.113989 0.864409 -0.497603 -0.0720259 0.188844 0.975474 0.113088 -0.429947 0.898079 0.0927372 -0.313726 -0.826547 0.467329 -0.171665 -0.955131 0.241361 -0.85924 0.124105 0.496292 -0.190578 0.0102989 0.981618 8.185e-05 1 3.12827e-05 -0.000109166 1 4.45291e-05 0.00013011 1 -0.00015513 -0.224795 0.974373 0.0080736 -0.00853617 -0.999921 0.00919974 -0.917777 -0.186135 -0.35077 0.960828 0.0772754 -0.266154 -0.989884 -0.0848909 0.113677 -0.989543 0.0490221 0.135652 -0.9394 -0.200782 -0.277874 -0.933716 -0.339831 0.112645 0 1 0 1.71495e-05 1 9.34055e-05 8.00294e-05 1 -0.0004124 0.28301 0.915799 -0.284986 -7.4432e-06 1 -2.1812e-06 0.258718 -0.820378 -0.509945 8.54047e-05 1 7.14703e-05 -2.27722e-05 1 -9.65126e-05 1.25789e-06 1 5.33114e-06 0.267664 0.941803 0.203381 -0.269787 0.953266 -0.136013 6.91459e-05 1 -2.31216e-05 -0.000590619 -1 5.68387e-05 -7.15847e-06 1 2.00925e-06 3.63764e-05 1 3.88991e-05 0 1 0 3.65626e-05 1 1.88652e-05 0.0877916 0.971951 -0.218183 0 1 0 0.0796317 0.996459 -0.0270041 -0.531645 0.840126 -0.107433 0 1 0 -0.0117566 0.988031 -0.153805 0 1 0 0 1 0 0 1 0 0 1 0 0.186296 0.974379 0.126015 0.901521 0.198067 -0.384746 0 1 0 2.24056e-06 -1 -2.90305e-05 -0.172885 -0.983726 -0.0489304 0 -1 0 0.167135 -0.985933 0.000952291 -0.0978121 -0.973574 0.206366 0.00975815 -0.999909 0.0093371 -2.89501e-06 -1 -2.77009e-06 0.136098 -0.986605 -0.089928 -3.76366e-06 -1 4.58143e-08 -0.129217 -0.924161 0.359485 -0.852559 0.346254 0.391473 -0.00117819 -0.999999 1.43419e-05 0.0404327 -0.994726 -0.0942651 0 -1 0 0.144147 -0.979198 -0.142803 -1.50539e-06 -1 -5.25636e-06 0.0978918 -0.995197 8.12084e-05 -0.00281317 -0.999996 -2.33373e-06 -0.00398678 -0.999986 -0.00357144 -0.0260693 -0.915156 -0.402257 0.0542947 -0.998458 0.0115313 0.00433778 -0.999981 -0.00430243 -4.01592e-06 -1 1.81692e-06 0 -1 0 5.00777e-06 -1 -5.27418e-07 5.05311e-06 -1 -5.48671e-07 0 1 0 0.0253417 0.993644 -0.109678 0 1 0 -7.14219e-06 1 -4.80554e-06 -0.0592407 0.993728 -0.0948426 0 1 0 -1.15705e-06 1 4.48594e-06 0.18821 0.970458 0.150959 -0.0815291 0.995854 -0.0403406 1.94815e-06 1 9.63946e-07 -7.55386e-06 1 1.87141e-06 0 1 0 0 1 0 0.0268252 0.996505 0.0791056 -0.209492 0.957237 -0.199525 0 1 0 0.0796318 0.996459 -0.027004 -0.199525 0.957237 0.209492 0 1 0 -0.0551406 0.948899 -0.310725 -0.0492075 0.959525 -0.277291 0 1 0 0 1 0 0 1 0 0 1 0 0.0994178 0.994272 0.0392451 0.212544 0.972932 -0.0907137 0 1 0 0 -1 0 0.0472818 -0.996505 -0.0688601 -0.232465 -0.963177 0.135097 0 -1 0 0 -1 0 -0.0406584 -0.99357 -0.105663 -0.175342 -0.967621 0.181562 0.019709 -0.999537 0.0231807 0 -1 0 0 -1 0 -0.0693181 -0.996459 -0.0475965 0 -1 0 0.135203 -0.957237 0.255769 0.0168187 -0.995799 0.0900134 -3.99219e-07 -1 -2.13662e-06 -3.63961e-06 -1 4.22653e-06 -5.49827e-06 -1 1.10109e-05 -2.13661e-06 -1 3.99222e-07 0.0894162 -0.995854 -0.0167072 1.10109e-05 -1 5.49826e-06 4.22653e-06 -1 3.63962e-06 -0.00018357 -1 0.000144833 0 -1 0 0.11303 -0.993083 0.0317785 0 -1 0 0 -1 0 0.0663014 -0.997273 -0.0324255 0 1 0 0 1 0 -2.30459e-06 1 -1.20897e-05 -1.04955e-06 1 1.05176e-06 0.121658 0.985057 -0.121914 -2.35637e-06 1 -5.05548e-06 0.631432 0.54639 -0.550228 0 1 0 0 1 0 0 1 0 -9.97577e-06 1 1.39948e-06 -0.081529 0.995854 -0.0403406 1.94815e-06 1 9.63946e-07 -7.55386e-06 1 1.87141e-06 0 1 0 0 1 0 0.0268252 0.996505 0.0791046 -0.20949 0.957238 -0.199525 0 1 0 0.0796308 0.996459 -0.0270039 -0.199525 0.957237 0.209491 0 1 0 -0.0959367 0.992561 -0.074959 0 1 0 1.90878e-06 1 2.20548e-07 0 1 0 4.44726e-07 1 1.75556e-07 0.0994177 0.994272 0.0392451 0.212553 0.97293 -0.090712 -1.43093e-05 1 1.32383e-06 3.94764e-06 -1 1.15606e-05 -0.262962 -0.952626 0.15282 0 -1 0 -3.03004e-07 -1 -8.74758e-06 1.05934e-05 -1 5.03972e-06 -0.0807925 -0.974011 0.211601 0 -1 0 -6.41362e-06 -1 -5.97283e-06 0 -1 0 -0.0693172 -0.996459 -0.047596 0 -1 0 0.135203 -0.957237 0.255767 0.0168188 -0.995799 0.0900132 -3.99222e-07 -1 -2.13661e-06 -3.8507e-06 -1 6.76278e-06 -2.13661e-06 -1 3.99225e-07 0.089416 -0.995854 -0.0167073 6.76277e-06 -1 3.8507e-06 -0.0563693 -0.945706 -0.320098 -0.000457763 -0.999997 -0.00259945 0 -1 0 0.113029 -0.993083 0.0317782 0 -1 0 0 -1 0 0.0663 -0.997273 -0.0324248 0 1 0 0 1 0 9.56841e-05 -1 0.00021005 -3.40412e-05 -1 0.000146408 0.00182025 -0.999977 -0.00650314 0.112665 -0.980715 0.1597 -0.164282 -0.984797 0.0564515 0 -1 0 3.23187e-05 -1 3.86744e-05 0.00010218 -1 -4.74622e-06 -0.119197 -0.989857 -0.077298 6.0221e-05 -1 -2.91131e-06 0.32103 0.71244 0.623995 -0.00237817 -0.999994 0.00247264 -0.00822449 -0.999304 0.0363972 -0.00111052 -0.999995 0.00283593 0.357959 0.854428 0.376588 -0.00177338 -0.999998 0.000165 0.11476 -0.99337 0.00673514 0.000204672 -1 5.51367e-06 3.85711e-05 -1 2.19127e-05 6.77453e-05 -1 0.000174114 0.0593055 -0.992837 0.103721 0.00538744 -0.999847 -0.0166285 0.00882035 -0.999955 0.00346004 -4.28432e-05 -1 -2.51174e-05 -0.0301935 -0.991313 0.128008 0.184488 -0.980262 0.0710732 0.00608287 -0.999981 -0.000512644 -0.00242816 -0.999997 -0.000897415 -1.60003e-05 -1 1.68515e-06 0 1 0 0 1 0 -0.00929608 0.110195 -0.993867 -0.184843 -0.159895 -0.969674 -0.273033 0.144752 -0.951052 -0.418571 -0.13547 -0.898024 -0.738166 -0.180479 -0.650029 -0.85213 0.266843 -0.450188 -0.865898 0.124352 -0.484518 -0.967159 -0.0848087 0.239606 -0.960487 0.0880488 0.26403 -0.679601 0.19713 0.706599 -0.474755 -0.39309 0.787457 -0.360389 0.257404 0.896584 0.0224816 0.188038 0.981904 0.180552 -0.26511 0.947163 0.410309 0.238155 0.8803 0.374652 -0.0492937 0.925854 0.69703 0.132289 0.704733 0.831912 -0.237411 0.501556 0.865217 -0.0989324 0.49154 0.962113 0.115727 0.246873 0.296241 0.0615161 -0.95313 -0.0623223 -0.180479 -0.981602 -0.275361 0.247245 -0.929003 -0.267549 0.175892 -0.947354 -0.746356 -0.218247 -0.628745 -0.827593 0.317243 -0.463084 -0.916508 -0.132352 -0.377487 -0.967159 -0.0848105 0.239606 -0.960885 0.0848083 0.263643 -0.514458 -0.0848107 0.853311 -0.493024 0.0848084 0.865872 0.239605 -0.0848113 0.967159 0.263643 0.0848092 0.960885 0.853311 -0.08481 0.514458 0.865872 0.0848077 0.493024 0.303332 0.0649169 -0.950671 -0.276685 -0.0641344 0.958818 0.0229525 -0.115351 -0.99306 -0.251405 0.109943 -0.961617 -0.260162 0.182319 -0.948196 -0.701938 -0.108087 -0.703989 -0.755126 0.248063 -0.606835 -0.892503 -0.132844 -0.431034 -0.929735 0.0822913 -0.358916 -0.99306 -0.115351 -0.0229518 -0.955349 0.124117 0.268148 -0.960885 0.0848092 0.263643 -0.606544 0.0787207 0.791143 -0.633758 -0.238155 0.735957 -0.430761 0.26511 0.862648 -0.287789 -0.188665 0.938926 -0.0229522 -0.115351 0.99306 0.268148 0.124116 0.955349 0.263643 0.0848101 0.960885 0.776692 0.172029 0.605934 0.75776 0 0.652534 0.887779 0 0.460271 0.892473 0.0698981 0.445653 0.0983066 0.00416576 -0.995147 -0.0618601 -0.216494 -0.974322 -0.282719 0.337441 -0.897888 -0.263137 0.0900269 -0.960549 -0.705175 0.056132 -0.706808 -0.744713 -0.123848 -0.655793 -0.875665 0.0983092 -0.472806 -0.872592 0.191367 -0.449403 -0.987241 0.155434 0.0345682 -0.907724 -0.36233 0.211553 -0.583571 0.0800729 0.808105 -0.560907 -0.0675618 0.825117 -0.338714 -0.141968 0.930117 -0.27806 0.0774647 0.957435 0.0345682 0.155434 0.987241 0.211553 -0.36233 0.907724 0.83039 -0.223313 0.510475 0.874327 0.0802619 0.478654 0.303332 0.0649164 -0.950671 0.0675957 0.0565646 -0.996108 -5.80729e-05 1 7.38039e-05 1.3027e-07 1 -5.63801e-07 0 1 0 0.835559 0.546392 0.0574193 9.1679e-05 1 0.000199587 0.631433 0.546392 -0.550225 -3.06552e-07 1 -4.90781e-07 0 1 0 0.000317323 0.999996 0.00266019 0.00506431 0.999986 0.00173272 -0.0942423 0.995197 -0.0264816 -0.00113256 0.999999 0.000561505 -0.000628674 1 -0.000176654 0 1 0 0 1 0 0 1 0 0.016063 0.993655 0.111318 -0.173841 0.970755 -0.165571 0 1 0 0.0796313 0.996459 -0.0270039 -0.143231 0.970242 0.195232 -0.00489724 0.999987 -0.00161455 -0.0193418 0.915355 -0.402182 0.0127641 0.972181 -0.233884 -0.150152 0.988511 -0.0173491 0 1 0 0.00902871 0.999945 0.00529104 -0.0189257 0.987151 0.158668 0 1 0 0.0994178 0.994272 0.0392451 0 1 0 -0.143298 -0.837559 0.52722 3.92678e-06 -1 1.10479e-05 1.83925e-05 -1 0.000292936 -5.49181e-07 -1 -8.74677e-06 -0.00259938 -0.999988 -0.00412663 1.09728e-05 -1 5.38947e-06 0.353561 -0.840126 0.411319 0 -1 0 -6.50213e-06 -1 -5.60965e-06 0 -1 0 -0.0788819 -0.995769 -0.0471455 0 -1 0 0.532698 -0.845349 0.0402255 -0.00273498 -0.994413 0.105525 -9.38715e-06 -1 3.65455e-06 0 -1 0 0.902633 0.287971 0.319885 0.119119 -0.992846 0.00815682 0.000269928 -1 3.48248e-05 0.000225359 -1 0.000204955 -0.349367 -0.927427 -0.133496 0.0807471 -0.993585 -0.0791709 0.0107726 -0.999922 0.00631297 0.120179 -0.992259 0.0312862 2.64056e-05 -1 -1.19466e-05 0 -1 0 0.234254 -0.968086 -0.0890758 -0.000339354 1 3.57408e-05 -0.000229951 1 3.10696e-05 -0.0788347 -0.170608 -0.98218 0.0187339 0.12021 -0.992572 -0.24396 0.210376 -0.946692 -0.391014 -0.191971 -0.900142 -0.420301 -0.129581 -0.898084 -0.856619 0.0458372 -0.51391 -0.830971 -0.14357 -0.537471 -0.900874 0.0200168 -0.433619 -0.970824 -0.214435 0.107322 -0.969083 0.165948 0.182593 -0.939563 0.178118 0.292397 -0.631232 -0.238587 0.737986 -0.466076 0.31117 0.828219 -0.398176 -0.0908689 0.912797 0.313629 -0.109418 0.94322 0.182928 0.178406 0.966803 0.062407 -0.162069 0.984804 0.350826 -0.038129 0.935664 0.842684 -0.341193 0.416499 0.764173 0.0428276 0.643588 0.235708 0.0177779 -0.971661 0.0431827 0.902628 0.428251 -0.698004 0.495882 -0.516616 0.000728012 1 6.49162e-05 -0.415638 0.854778 0.310805 0 1 0 -0.124269 0.988399 -0.0873196 -0.23007 0.908054 -0.350009 -0.0516763 0.893836 -0.445407 0.0297244 0.999557 0.00168877 -0.409987 0.873743 -0.261697 -0.106426 0.89842 0.426047 0.0685737 -0.975395 0.209529 -0.0805032 0.968674 -0.234925 0.33843 0.864791 -0.370946 -2.03686e-05 1 -9.70064e-05 0 1 0 0.00010492 1 0.000466125 -0.000370915 1 0.000754465 1.08887e-05 1 6.23319e-05 0 1 0 0 1 0 0.0160583 0.998189 0.0579689 -0.129157 0.990047 0.0559146 -0.571461 0.818829 -0.0543262 -0.0415641 0.987806 -0.150042 -0.329474 0.861524 0.386294 9.54943e-05 1 -0.000845748 8.86228e-05 1 -0.000836328 0.000186897 1 -0.000573401 -0.626898 0.68056 0.379259 -0.192964 0.923676 0.331041 -9.32671e-05 1 -0.000108357 0 1 0 4.70957e-05 1 0.000467882 0.372246 0.879993 0.295033 0.349806 0.803663 0.481417 0.00044926 1 0.000425677 0.000784145 1 0.000285792 0 1 0 0 1 0 -8.05613e-06 1 3.39951e-06 0 1 0 0.293683 0.955902 -0.00110043 -0.056019 0.99843 0.000209902 -0.129459 0.984728 0.116409 0.180687 0.970028 -0.162473 0.412336 0.646533 -0.641853 0.373752 0.756125 0.537201 0.148687 0.988713 -0.01839 -0.0861946 0.992828 0.0828455 -0.301815 0.397106 0.866726 -0.439623 0.858222 0.264928 4.50885e-05 1 9.90373e-05 -2.58622e-05 1 -1.91414e-05 0.416374 0.891632 -0.177835 0.171848 0.879404 -0.443978 0.349596 0.927188 0.134556 0.19641 0.977574 0.0759697 0.0940882 0.934092 0.344413 -0.536302 0.843135 0.0387769 -0.631031 0.48794 0.603087 -0.179593 0.835912 0.51865 -0.0611892 0.99812 -0.00358484 -0.523246 0.34061 -0.781152 0.279925 0.863641 -0.419246 0.149 0.965474 -0.213679 0.059944 0.918877 -0.389963 0.1227 0.765378 0.631776 0.107429 -0.979381 -0.171092 3.11399e-05 1 8.07208e-06 0.20449 0.937146 0.282739 3.48136e-05 1 0.000296808 -0.0264294 0.969409 -0.244023 0.22022 -0.930987 0.291146 -0.00809697 -0.999705 -0.0228997 0.000359616 0.999999 0.00111579 -0.0903472 0.947843 -0.305666 -0.106566 0.972577 -0.206733 -0.20307 0.973822 -0.102144 0.0806432 0.996597 -0.0170705 -0.0910347 -0.938135 -0.33409 0.0444056 -0.998408 -0.0347777 0.0493219 0.998393 -0.0278982 -1.25956e-05 1 -1.27008e-05 -0.00374929 -0.999992 -0.00154255 -0.513399 0.857899 0.0207368 -0.176319 0.974227 0.140691 1.22802e-06 1 -2.13219e-06 0.0861389 0.97878 0.185928 -0.107114 0.979997 0.167727 -0.0346046 0.992899 0.113813 -0.0774515 0.994855 -0.0653037 -0.129412 -0.979915 0.151719 -0.0589141 -0.99336 0.0988172 0.0774515 -0.994855 0.0653037 -0.498909 0.0266134 0.866246 -0.511908 -0.0266131 0.858628 -0.451618 0.630197 0.63158 0 1 0 -0.223778 0.631878 -0.742061 -7.60079e-07 1 -2.52047e-06 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.164694 0.984999 -0.0515044 -6.98694e-07 1 -2.04079e-07 2.2235e-07 1 -1.79914e-06 0 1 0 0 1 0 -3.85546e-07 1 -3.19265e-07 -9.42278e-07 1 3.20446e-07 -6.60187e-07 1 5.1292e-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.234552 0.941268 -0.242899 -0.0461642 0.989304 0.138372 0.865526 -0.199329 -0.459492 -0.0432177 0.99905 -0.00557409 2.17133e-05 1 -2.49353e-06 -0.144564 0.988981 -0.0318886 0.00041614 1 -4.13568e-05 -2.94393e-05 -1 -3.55507e-06 0 -1 0 0.256484 0.937601 -0.234777 0.192427 0.980077 -0.0492037 0.0170772 0.998495 -0.0521109 0.0203827 0.996263 -0.083933 -0.00183532 0.99879 -0.0491459 -0.0415487 0.99168 -0.121838 -0.0285045 0.998364 -0.0495605 -0.0743756 0.994606 -0.0722947 -0.0241011 0.99971 3.53842e-05 -0.280923 0.949065 0.14268 -0.327747 0.920968 0.210711 -0.0274683 0.94655 0.321387 -0.0646874 0.993844 0.0899373 0.037745 0.990648 0.131114 0.0235665 0.994506 0.101989 0.10989 0.987308 0.11466 0.0614488 0.995344 0.0742659 0.056359 0.997877 0.0326391 0.0837704 0.995679 0.0400782 0.0650634 0.997868 0.00519256 0.110186 0.993908 -0.00239661 0.0548874 0.99834 -0.0174312 0.196635 0.957042 -0.213086 -0.503093 0.85319 0.137712 -0.401087 0.879378 0.256559 -0.00876415 0.999876 -0.0130816 -0.0132627 0.999769 -0.0169315 -0.00599363 0.999967 -0.00553256 -0.0196962 0.999751 -0.0104549 -0.00942883 0.999953 -0.00218882 -0.0204019 0.999791 -0.00143332 -0.0186804 0.999825 -0.000941854 0.477099 0.77315 -0.417871 0.054906 0.982251 -0.179355 0.00823357 0.999954 -0.00488261 0.00135303 0.999756 0.0220674 -0.0417581 0.998154 -0.0441124 0.0512161 0.998623 0.011369 0.00329702 -0.999994 -0.000778527 -3.19533e-06 -1 -1.2935e-06 2.73849e-05 -1 8.96843e-05 -3.37168e-06 -1 7.05055e-05 -2.63622e-05 -1 1.23332e-05 9.73675e-06 -1 8.83174e-06 -5.67561e-05 -1 -1.08559e-05 4.54842e-05 -1 1.64617e-05 0.000126131 -1 2.90071e-05 0.000126525 -1 2.92686e-05 1.76911e-05 -1 -1.30922e-05 0.000100754 -1 -4.83378e-05 -5.25095e-05 -1 -8.35956e-06 9.05272e-05 -1 -1.87067e-05 -0.00110828 -0.999999 0.000839691 -2.21998e-05 -1 0.000641348 1.17614e-05 -1 -1.18904e-05 -0.0019353 -0.999998 0.000799449 -3.57346e-05 -1 -3.94719e-05 0.00230696 -0.999994 0.00253322 9.60479e-07 -1 1.32377e-05 2.2616e-05 -1 -3.48141e-05 -0.00435597 0.999987 -0.0025522 0.659375 -0.46379 0.591713 0.656731 0.59318 0.465663 0.845878 -0.439568 0.30211 0.0275029 -0.32165 0.946459 0.313942 0.237033 0.919378 0.307362 0.394677 0.865886 -0.661285 -0.140257 0.736906 -0.62086 0.255495 0.741118 -0.342678 -0.256125 0.903865 -0.330945 0.0258925 0.943295 -0.720496 -0.664682 0.197692 -0.919434 0.219375 0.326368 -0.609953 0.606146 -0.510435 -0.507619 -0.810973 -0.290941 -0.927347 0.186245 -0.324561 -0.155031 -0.394706 -0.905634 -0.175438 -0.237033 -0.95553 -0.434011 0.308961 -0.846273 -0.13148 0.9564 0.260792 -2.31216e-05 1 -6.91458e-05 5.68387e-05 -1 0.000590617 2.00925e-06 1 7.15848e-06 -0.0902912 -0.976728 -0.194553 -3.74305e-06 -1 -1.09615e-05 1.24045e-08 -1 7.03216e-06 0.390998 -0.912275 0.121961 0.391446 0.346031 0.852662 1.87172e-06 -0.999999 0.00106109 0.792692 -0.128278 0.595973 0.801174 0.179685 0.570818 0.937915 -0.141873 0.316523 0.0501793 0.141871 0.988612 0.318794 -0.163653 0.933589 0.342306 0.321784 0.882769 -0.595973 -0.128277 0.792692 -0.570818 0.179685 0.801174 -0.316478 -0.14192 0.937923 -0.988612 0.141871 0.0501789 -0.925994 -0.179687 0.332035 -0.924656 0.128277 0.358548 -0.676981 0.439567 -0.590321 -0.728037 -0.591606 -0.346358 -0.927347 0.186244 -0.324561 -0.0611424 0.440002 -0.895913 -0.267315 -0.561885 -0.782833 -0.401019 0.392776 -0.827593 0.270628 -0.142685 -0.952051 -0.0403405 0.995854 0.0815292 9.63944e-07 1 -1.94816e-06 1.87141e-06 1 7.55387e-06 0 -1 0 -0.0475963 -0.996459 0.0693183 0 -1 0 0.262963 -0.952626 -0.15282 0.792692 -0.12828 0.595973 0.801174 0.179684 0.570818 0.937915 -0.141875 0.316523 0.132796 -0.321811 0.937445 0.17815 0.163653 0.970299 0.435455 -0.136731 0.889766 -0.595973 -0.128278 0.792692 -0.570818 0.179686 0.801174 -0.316478 -0.141921 0.937923 -0.988612 0.141875 0.0501787 -0.925995 -0.179685 0.332035 -0.924656 0.128278 0.358548 -0.734342 -0.0498866 -0.676945 -0.712412 0.37019 -0.596178 -0.728037 -0.591606 -0.346358 -0.927347 0.186246 -0.324561 -0.0387319 -0.302502 -0.952361 -0.313942 0.237033 -0.919378 -0.307361 0.394677 -0.865886 0.289145 -0.143197 -0.946515 0 1 0 -0.304075 0.952636 -0.00480708 0.154216 0.981284 0.115322 0 1 0 0 1 0 -5.02736e-06 -1 2.62292e-05 0 -1 0 0.020289 -0.999698 0.0139007 3.83963e-05 -0.999928 0.0119976 -0.0807961 -0.986232 0.144284 0 -1 0 7.65519e-05 -0.999984 -0.00557884 0.709013 0.387936 0.588903 0.861156 0.123681 0.493065 0.883736 0.0955041 0.458138 0.859046 -0.0218531 0.511432 0.857614 -0.374165 0.352844 0.894188 -0.30633 0.326481 0.931075 0.0915277 0.35316 0.667198 -0.0471909 0.743384 0.751516 0.059205 0.657053 0.317636 0.303488 0.898333 0.318909 0.273678 0.907413 0.225378 -0.513934 0.827693 0.291607 0.555082 0.779006 0.201521 0.0149192 0.979371 0.100909 -0.0568066 0.993273 -0.787421 -0.00189843 0.616413 -0.700242 0.11548 0.704503 -0.365618 -0.598961 0.712439 -0.277859 0.0153669 0.960499 -0.299153 -0.0086667 0.954166 -0.818932 -0.489943 0.298843 -0.557954 0.75029 0.354615 -0.893872 0.173263 0.413489 -0.903326 -0.0343042 0.42758 -0.905726 -0.0264045 0.42304 -0.773094 0.623116 0.118544 -0.904347 -0.404561 0.135965 -0.960359 0.261919 0.0954424 0.965011 -0.0450637 0.258308 -0.933387 -0.15375 -0.324269 -0.87577 0.457643 -0.153588 0.28513 -0.632479 -0.720189 -0.920221 -0.215193 -0.326933 -0.539761 -0.760203 -0.361594 -0.914949 0.0417355 -0.401407 -0.34525 0.243039 -0.906496 -0.333032 -0.0990282 -0.937701 -0.0926742 0.0642753 -0.99362 0.208652 0.926909 -0.311937 -0.311193 0.507686 -0.803376 -0.423516 -0.255933 -0.868984 -0.0446054 -0.786363 -0.616153 -0.114069 -0.53957 -0.834178 -0.0874261 -0.140692 -0.986186 0.36547 -0.222119 -0.903933 0.0235099 -0.208958 0.977642 0.285042 0.0199327 -0.958308 0.282334 0.0259995 -0.958964 0.892467 -0.447978 -0.0530922 0.715331 0.65138 -0.252995 0.873785 -0.283228 -0.395325 0.994683 -0.0832011 -0.0606985 0.845437 0.422421 -0.326797 0.873785 -0.283227 -0.395325 0.994683 -0.0832007 -0.0606985 0.845435 0.422425 -0.326796 0.873786 -0.283225 -0.395325 0.89768 -0.41907 -0.136201 0.960359 0.26192 -0.0954424 0.904132 -0.311396 -0.292537 0.424021 0.849597 -0.313673 0.837078 0.334664 -0.432782 0.865588 -0.0380507 -0.499309 0.905592 0.0540353 -0.420693 0.76558 0.63229 -0.118732 -0.862728 0.00042136 -0.505667 -0.862676 0.000264169 -0.505757 -0.862276 -0.00172079 -0.506436 -0.825756 0.010286 -0.563933 -0.846366 -0.0786886 -0.526757 -0.761558 0.256835 -0.595034 -0.863371 -5.43181e-05 -0.504569 -0.862291 -5.42925e-05 -0.506413 -0.738822 0.229553 -0.633599 -0.85229 0.00233376 -0.523065 -0.861921 0.0017531 -0.50704 -0.865492 -0.00773645 -0.500863 -0.863315 0.00359048 -0.504653 -0.860229 0.00397267 -0.509892 -0.866863 -0.00733448 -0.498492 -0.908255 -0.0809702 -0.410508 -0.88067 -0.0795813 -0.466999 0.867979 0.00615263 0.496563 0.862677 0 0.505756 0.862689 -4.48482e-05 0.505736 0.863082 -5.22098e-05 0.505064 0.862767 0 0.505602 0.862752 5.72779e-05 0.505628 0.862767 0 0.505602 0.862689 0.000289906 0.505735 0.863198 0.000326721 0.504865 0.863003 -0.000175971 0.505199 0.863121 8.39328e-05 0.504998 0.862673 -0.00067527 0.505761 0.857761 0 0.514049 0.862605 -0.0194006 0.505507 0.862767 0 0.505602 0.862767 4.81146e-07 0.505602 -0.862768 -1.07222e-06 -0.5056 0.862764 0 0.505606 0.863075 7.74277e-05 0.505076 0.861956 -0.0192394 0.506617 0.874772 0.0521144 0.481725 0.0612779 0.439565 0.896118 0.270016 -0.593177 0.758441 0.390619 0.463787 0.795184 -0.651641 -0.176269 0.737762 -0.464912 0.598384 0.652528 -0.301925 -0.439998 0.84572 -0.896117 0.439567 0.061278 -0.758439 -0.593179 0.270015 -0.795183 0.46379 0.390619 -0.734342 -0.049885 -0.676945 -0.712411 0.370194 -0.596177 -0.727228 -0.593178 -0.345369 -0.838488 0.46379 -0.28607 -0.0405863 -0.0498816 -0.99793 -0.0821903 0.370191 -0.925313 -0.269919 -0.591982 -0.759408 -0.39757 0.410803 -0.820475 -0.0264816 0.995197 0.0942425 0.000561505 0.999999 0.00113256 -0.000176654 1 0.000628674 -4.79767e-05 -1 -0.000134761 -0.0471716 -0.995811 0.0783333 -2.00658e-05 -1 0.000265729 0.0402253 -0.845348 -0.532699 0.737762 -0.176269 0.651641 0.652526 0.598389 0.464909 0.845879 -0.439566 0.30211 0.994683 -0.0832013 -0.0606985 0.845437 0.422422 -0.326797 0.873785 -0.283228 -0.395325 -0.170303 0.348161 0.921836 0.140984 -0.13417 0.980878 0.679593 -0.262469 0.685028 0.793375 -0.0499329 0.606681 -0.00734896 0.258553 -0.965969 -0.980094 -0.115173 -0.161714 -0.873578 0.0137626 0.48649 0.696748 -0.708659 -0.111108 -0.784267 -0.261198 0.562762 0.00480301 0.99998 -0.00415763 0.505531 -0.678308 0.533232 -0.00159923 0.999993 -0.00324624 -0.00530717 0.999985 0.0014285 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.00221991 0.99999 0.00378809 -0.00293423 0.999992 0.00289645 -0.0492296 0.998735 0.0102308 0.120535 0.99001 0.073151 0 1 0 -9.31386e-05 1 0.000244353 -0.000208478 1 5.90105e-05 -0.00116257 0.99999 0.00425758 -0.00427709 0.999989 -0.00211624 0 1 0 0 1 0 -0.00015932 1 -0.000282781 0.00339229 0.999994 0.0010272 0.000644913 0.99999 0.00437021 -0.00872395 0.999936 0.00727245 0.00441068 0.99999 0.000961096 0.00429132 0.99999 0.00160052 0.0048124 0.999988 0.00125046 0.00430959 0.999991 0.000110837 0.00408537 0.999992 0.000515306 0.00173521 0.999998 -0.00122706 0.00159283 0.999995 -0.0028662 -1.57029e-05 1 -5.52869e-05 0.000863035 0.999996 0.00273883 0.00885392 0.999907 0.0103815 -2.04701e-05 1 3.26647e-05 0.00113939 0.999999 -0.000288561 3.03568e-05 1 -1.01168e-05 -0.00990047 0.999889 0.0111694 -0.00474151 0.999956 0.0081293 0.00561411 0.999955 -0.00764718 -0.0126824 0.999919 0.000810297 -0.0142861 0.999898 0.000441286 -0.00604648 0.999861 0.0155241 -0.00346665 0.999991 -0.00258789 -0.00239757 0.999988 -0.00428963 -0.00231355 0.999997 -0.00123259 -0.000419456 0.999999 -0.00160281 0.00114682 0.999999 -0.000961056 0.000789403 0.999999 -0.00121756 0.00030806 0.999992 -0.00395572 -0.000470101 0.999991 -0.00425317 0.00131884 0.999998 -0.00154464 -0.00161266 0.999997 -0.00181862 -0.000671806 0.999999 -0.00136025 -0.000124988 1 -7.77892e-05 -0.000128345 1 -2.99125e-05 -0.0145531 0.999618 0.0234808 -9.00773e-05 1 1.69308e-05 0.00784842 0.999969 0.000441538 0.00447429 0.999986 -0.00268068 6.94176e-05 1 -1.08378e-05 -0.572653 0.156002 0.804818 -0.890165 0.121779 0.439063 0.426633 0.903916 -0.030331 6.90056e-05 1 -3.46245e-05 -0.000168394 1 0.000112392 2.93111e-06 1 0.000237932 5.19425e-07 1 1.87636e-08 -0.017108 0.999829 -0.00708056 -3.29765e-05 1 -1.19124e-06 -0.0195121 0.999409 0.0282988 0.0755929 0.994906 -0.0666907 -7.07697e-06 1 -0.00010344 -0.00167696 0.998985 0.0450079 -1.76384e-05 1 1.22926e-05 3.31773e-05 1 -1.99924e-05 0.00694644 0.99996 0.00564377 0.409297 0.139702 0.901643 0.737062 0.186797 0.649497 9.89342e-05 1 5.78533e-05 0.000988165 0.999999 0.00138875 -0.00132894 0.999994 0.0032025 -0.00500711 0.999973 -0.00530698 -0.00265714 0.999979 -0.00591533 0.00205032 0.999997 -0.000982876 0.00291357 0.999995 0.000892706 0.988162 -0.139627 0.0635613 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 4.36134e-06 1 -3.1126e-05 -0.000284784 1 -0.000429405 -0.000304988 1 -0.000398096 0 1 0 0 1 0 0 1 0 0 1 0 5.73151e-05 1 6.3623e-05 9.25781e-05 1 6.58891e-05 8.66977e-05 1 4.87628e-05 0.290088 0.912607 -0.288092 -0.638596 0.524904 -0.562736 -0.000918311 -0.999999 -0.000486121 -0.00373674 -0.999983 -0.00457922 -0.000945807 -1 -0.000341904 0.0106763 -0.999896 -0.00966937 -0.0173321 -0.99985 0.000257643 0.0903646 -0.98164 0.16798 6.74747e-05 -1 -2.65371e-05 1.353e-05 -1 2.25161e-05 -0.391534 -0.66996 -0.630757 -0.569885 -0.415306 0.70905 0.896111 -0.169958 0.409999 -0.000870965 -0.999998 0.00177085 0.000417825 -1 -0.000442725 0.429947 -0.808977 -0.400877 0.0594694 -0.420569 0.90531 -0.29144 -0.896562 -0.333525 0.081637 -0.837386 -0.540481 -0.686319 -0.676639 0.266694 0.472497 -0.769466 0.429731 0.39746 -0.917263 0.0255993 -0.000138029 -1 -9.83724e-05 -0.00103643 -0.999989 0.00457674 -0.000692964 -1 -0.000635432 0.000177334 -1 0.000277765 0.00130979 0.999971 -0.00744777 0 -1 0 0 -1 0 0.000635206 -0.999997 0.00222222 -0.0436377 -0.999014 0.00821238 -0.0445445 -0.999005 -0.0022456 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.00218045 -0.999988 -0.00436558 0.0868063 -0.995653 -0.0337507 0.0908502 -0.995758 -0.0145952 0.0436376 -0.999014 -0.00821235 0.0445449 -0.999005 0.00224562 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.0442958 -0.997304 -0.058509 0 -1 0 0 -1 0 0 -1 0 0.000180696 -1 -0.000595814 0.000300644 -1 -0.000669143 0 -1 0 0 -1 0 0 -1 0 2.51911e-05 -1 -0.000583678 -0.000119144 -1 -0.000673722 -0.000136978 -1 -0.000648399 -0.000287098 -1 -0.000580167 -0.00108888 -0.999999 -0.000715596 -0.00146823 -0.999998 -0.00154538 -0.00125101 -0.999999 -0.00012143 -0.00177494 -0.999998 -0.000764901 -0.00163444 -0.999999 -9.08668e-05 -0.00247331 -0.999997 0.000900596 -0.00235917 -0.999997 0.00098595 -0.00247983 -0.999996 0.00157718 0.00224076 -0.999997 0.000486768 0.00162841 -0.999998 0.000851498 0.0018719 -0.999998 5.57022e-05 0.00191023 -0.999998 -0.00027886 0.00179249 -0.999998 -0.000186576 0.000833766 -0.999999 -0.00128725 0.00173283 -0.999997 0.00170393 0.00120794 -0.999998 0.00182589 0.00139472 -0.999999 0.00101856 0.000113703 -0.999999 0.00137456 0.000209793 -0.999999 0.001179 -0.000226655 -1 0.000606195 -0.000538938 -1 0.000605642 -0.00260665 -0.999995 0.00150486 -0.0110092 -0.999939 -0.000441626 -0.0129477 -0.999914 0.00190953 -0.00193679 -0.999998 -0.00016573 -0.000882016 -0.999998 -0.00168471 -0.00166376 -0.999997 -0.00150437 0.00561198 -0.999978 -0.00361138 0.0117285 -0.999931 0.00030577 0.0044647 -0.999974 -0.00561032 -0.00376346 -0.999987 0.00338148 -0.00174899 -0.999997 0.00172953 0.00412262 -0.999991 -0.000408486 -0.0119845 -0.99992 -0.00402694 0.000477155 -0.999999 -0.00115015 -4.66053e-05 -0.999999 -0.00109813 -0.000212891 -0.999999 -0.00129132 0.00262904 -0.999993 0.00270217 -0.000545209 -0.999996 -0.00284273 -0.000875697 -0.999998 0.00159471 0.000333413 -1 0.000612298 0.00100942 -0.999999 0.000682553 0.00110044 -0.999999 0.00128618 0.000499715 -0.999999 0.000955331 -0.691427 -0.681698 -0.239201 -0.196616 -0.909711 0.365742 0.494976 -0.675966 0.545956 0.7892 -0.614118 -0.00477938 -0.49979 -0.81809 0.284498 -0.366552 -0.762227 -0.533525 -0.00392669 -0.999952 0.00892766 -0.00563151 -0.999759 0.0212393 0.382638 -0.859398 0.33915 0.671945 -0.734506 -0.0948167 -0.00238156 -0.999986 -0.0047782 -0.41167 -0.379892 -0.828378 -0.688017 -0.332566 -0.645006 0.43433 -0.453811 -0.778083 0.669784 0 -0.742556 -0.689977 0.623825 -0.367117 0.162475 -0.977767 -0.132566 0.672196 -0.0830046 -0.735706 0.672195 -0.0830159 -0.735705 0.686844 0.0180634 -0.726581 0.680277 -0.000360975 -0.732955 -0.756807 -0.0677001 0.650123 0.297229 -0.275017 -0.914341 -0.0892891 -0.994872 -0.0475126 0.878257 -0.151407 -0.453585 0.668433 0.206749 0.71446 0.823364 0.0240565 0.567003 -0.342349 0.618757 -0.707062 0.0193091 -0.802607 -0.596195 -0.342349 0.618757 -0.707062 0.0193091 -0.802607 -0.596195 -0.34235 0.618758 -0.70706 0.0193088 -0.802609 -0.596193 0.825185 -0.523878 -0.211239 0.928382 -0.210533 0.30624 0.687443 -0.149978 0.710583 0.458389 -0.28061 0.843289 0.0782647 -0.996458 -0.0307714 -0.810696 -0.126908 -0.571547 -0.441199 -0.695748 -0.566814 0.781271 -0.575863 0.240828 0.446403 -0.315131 0.837506 0.0413666 -0.543903 0.838128 0.916144 -0.320211 0.241132 0.867254 -0.241197 0.43554 0.867311 0.425916 -0.25762 0.710487 0.00272763 0.703705 -0.890422 0.335123 -0.307965 -0.972464 0.172754 -0.156426 -0.862802 -0.00432804 -0.505524 -0.936936 -0.248256 -0.246009 0.631578 0.312498 0.709545 -0.669857 0.196275 -0.716078 -0.987165 0.014953 -0.159005 0.0709539 0.816895 0.572406 0.641684 -0.0242296 0.766586 -0.0302805 0.0984086 -0.994685 -0.0646537 0.963127 -0.261164 0.885293 -0.00450895 -0.465011 -0.449453 -0.019994 -0.89308 -0.44815 -0.0173282 -0.893791 0.255703 0.0231961 0.966477 0.361766 -0.453625 -0.814463 0.782931 0.125935 -0.609229 0.327305 0.636746 -0.698159 0.382281 0.465668 0.798132 -0.00068381 0.999995 -0.00293717 0.000210206 1 0.00018515 0.000203504 1 0.000179247 0.000262043 1 0.00029555 -0.000651634 1 -0.000177091 -0.000872622 1 -0.000406714 -0.000867123 1 -0.000406155 0 1 0 0 1 0 0 1 0 -0.29467 0.931164 0.214717 -0.323299 0.921511 0.215162 -0.197973 0.976673 0.0831648 -0.228253 0.971282 0.0671743 -0.157691 0.969782 0.186161 -0.0431929 0.984997 0.167077 0.0269813 0.978113 0.206319 0.000655442 0.999999 -0.00135011 -0.000154515 1 -0.000921318 0.000115707 1 -9.34164e-05 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.00217244 0.999997 -0.00105027 0.00181913 0.999998 -0.000974471 0.00369044 0.999988 -0.00335205 0 1 0 0.000265684 0.999999 -0.0013195 0.000208799 0.999999 -0.00119414 -0.126712 0.807239 -0.576462 -0.276369 0.400632 -0.873564 0.32557 0.473509 -0.818409 0.840216 0.417767 -0.3457 -0.997581 0.00834859 -0.0690132 -0.987559 -0.0967136 -0.123991 0.882502 0.00144449 0.470307 0.784728 -0.211441 0.582662 0.485492 -0.00584962 0.874222 0.550216 0.10161 0.828817 -0.795235 0.356521 -0.490402 -0.088984 0.977987 0.188739 0.533738 0.779197 0.328598 -0.224452 0.00682253 0.974461 -0.257803 -0.0586642 0.964415 0.855796 0.187985 -0.481949 0.26222 -0.0970533 -0.960115 0.289707 0.944744 0.153389 0.522049 0.0929461 -0.847836 -0.512095 -0.00218266 0.858926 -0.631505 -0.35958 0.686952 -0.0191936 0.796962 -0.603724 -0.328655 0.0504566 -0.943101 -0.242805 0.925871 0.289496 -0.432962 -0.280784 -0.856565 0.88939 -0.406371 -0.209401 -0.0232379 0.75851 0.651247 -0.87213 0.00341373 0.489262 -0.807271 0.131572 0.575328 0.981903 0.0581226 0.180247 0.622215 0.663383 0.415657 0.984451 -0.058874 -0.165497 -0.99731 -0.00767361 0.0728955 -0.989976 -0.141227 -0.00184009 -0.0718966 0.0972411 -0.992661 0.288263 0.870763 -0.398342 -0.580922 0.8009 -0.145217 0.40898 0.909992 0.0681958 0.984331 0.164896 0.0624676 0.970792 0.0412498 0.236348 -0.978848 -0.016413 -0.20393 0.991279 -0.0247918 0.129428 0.0030411 0.988793 -0.149259 -0.440263 0.44614 -0.779184 0.979237 0.00831279 0.202546 0.99663 -0.0415736 0.0707082 0.981637 0.0023892 0.190745 -0.440262 0.446139 -0.779185 -0.440263 0.446141 -0.779184 0.980139 0.0114275 0.19798 0.987881 -0.0176382 0.154206 0.979621 0.0096245 0.200624 -0.0592075 0.988881 -0.136417 -0.1224 -0.972916 -0.196094 0.97251 0.023666 0.231654 -0.995029 -0.00385547 -0.099515 -0.311889 -0.325745 0.892533 -0.257434 -0.464313 0.847432 0.992765 0.0105915 0.119608 0.990041 -0.00798517 0.140553 -0.0397311 0.927437 0.371863 -0.0619622 0.90038 0.430671 0.994517 0.00151246 0.104564 -0.994831 -0.00206325 -0.101525 0.994537 0.001128 0.10438 -0.0619627 0.900377 0.430675 -0.368055 -0.256188 0.893814 0.00526393 0.961644 0.274249 0.995893 -0.0461548 0.0778961 0.992619 0.00301469 0.121237 0.152824 0.243942 -0.957673 -0.994757 -0.00140853 -0.102259 0.133226 -0.189508 -0.972799 0.0636589 0.00500782 -0.997959 0.236648 -0.018389 -0.971421 -0.196959 -0.962346 0.187343 0.222613 -0.339009 -0.914066 -0.14117 0.989402 -0.0339681 -0.268531 0.0900123 0.959056 -0.186569 -0.965339 0.182516 -0.140666 0.989479 -0.0338374 0.275172 -0.00926262 -0.96135 0.218594 -0.0176833 -0.975656 0.239569 -0.0228483 -0.970611 -0.92887 0.0998768 -0.356685 -0.94896 0.166278 -0.268005 -0.169094 -0.0599869 -0.983773 -0.0484214 -0.0326787 0.998292 0.0506492 0.0319849 -0.998204 0.484719 -0.624893 0.612011 0.137234 -0.167158 0.976333 0.047791 0.0212026 -0.998632 -0.0509746 -0.0203928 0.998492 0.251651 -0.95455 0.159705 0.178844 -0.973109 0.145167 0.383712 0.914606 -0.127519 0.103255 0.00150032 -0.994654 0.117696 0.00400822 -0.993042 0.0758313 0.00717072 -0.997095 -0.00111753 -0.999995 -0.0029304 0.501636 -0.189311 -0.844111 0.330766 0.4859 -0.809009 0.436814 0.499668 -0.748014 0.721411 0.0265368 -0.691998 0.437907 0.499989 -0.74716 0.65285 0.479506 -0.586396 0.148609 0.475197 -0.867239 0.630766 6.80284e-05 -0.775973 0.593217 -0.0821902 -0.800836 -0.57875 -0.507129 -0.638646 -0.86106 0.0038328 0.508489 -0.889229 -0.00189555 0.457459 -0.922046 0.00317168 0.387067 -0.930282 -0.000405637 0.366845 -0.682975 0 0.730442 -0.692823 0.00281619 0.721102 -0.84436 -0.000398371 0.535776 -0.78418 0.00352484 0.620523 -0.772326 -0.000144368 0.635227 -0.81066 0.000646567 0.585517 -0.833933 -0.00154446 0.551864 -0.703906 -0.0774278 0.706061 -0.816853 -0.00247939 0.576841 -0.99522 0.00186133 0.0976404 -0.991245 -3.75725e-09 0.132032 -0.913393 1.15843e-08 -0.40708 -0.91283 6.27801e-05 -0.408341 -0.592359 -0.000155402 -0.805674 0.583004 2.63209e-07 -0.812469 0.455957 -7.07841e-08 -0.890002 0.455957 7.36781e-08 -0.890002 0.318489 7.84734e-08 -0.947926 0.318489 0 -0.947927 0.174033 0 -0.98474 0.174151 2.49906e-05 -0.984719 0.570631 0.00511694 -0.821191 0.560923 -0.0213451 -0.827593 0.41413 0.0141221 -0.910108 0.404672 -0.0066267 -0.914438 0.244279 0.00588928 -0.969687 0.243624 0.00443166 -0.96986 0.0664773 0.00248333 -0.997785 0.0246274 -0.0927568 -0.995384 -0.112856 0.104408 -0.988111 -0.288895 -0.0771877 -0.954244 -0.27691 -0.0317138 -0.960373 -0.456543 0.0218321 -0.889433 -0.469114 -0.00674308 -0.883112 -0.608729 0.00744811 -0.793343 -0.609141 0.00637327 -0.793036 -0.741114 0.00161881 -0.671377 -0.740866 0.00244964 -0.671648 -0.849471 0.000203484 -0.527636 -0.930031 -0.0251097 -0.366622 -0.980944 0.00948109 -0.194062 -0.982602 -0.0100817 -0.185452 -0.999809 0.0124474 -0.015058 -0.999953 -0.00719736 -0.00653036 -0.987689 0.0122033 0.155951 0 1 0 0 1 0 7.98452e-08 1 1.46436e-07 -0.979608 0.00519361 0.200852 -0.969146 -0.0657985 0.237543 -0.924575 0.0617029 0.37597 -0.842282 -0.0488581 0.536819 -0.852643 -0.00516249 0.522468 0.00641744 0.00241613 -0.999977 0.00671907 0.000387653 -0.999977 0 1 0 0 1 0 0 1 0 -0.550664 0.00519358 0.834711 -0.548345 0 0.836252 -0.388663 0 0.92138 -0.388663 0 0.92138 -0.216254 0 0.976337 -0.213532 -0.00519415 0.976922 0 1 0 0 1 0 0.220848 0.0051619 0.975295 0.203339 0.0488578 0.977889 0.375971 -0.0617032 0.924575 0.506219 0.0657975 0.859891 0.539798 -0.00519388 0.841778 0 1 0 6.08889e-07 1 -1.44426e-06 0.977082 -0.00586223 0.212782 0.959571 0.0957332 0.264687 0.921311 -0.00013357 0.388827 0.85715 0.112598 0.502609 0.823483 -0.0132612 0.567185 0 1 0 0 1 0 0 1 0 0 1 0 0.387386 0.0809525 -0.918356 0.215809 -0.064134 -0.974327 0.237831 -0.0051546 -0.971293 0 1 0 0 1 0 1.60005e-07 1 4.70869e-08 -0.200928 0.00512671 -0.979593 -0.237571 -0.0657733 -0.969141 -0.375972 0.0617033 -0.924574 -0.536819 -0.0488593 -0.842282 -0.522468 -0.00516164 -0.852643 -0.83489 0.00491166 -0.550395 -0.853324 -0.0656987 -0.517225 -0.919624 0.0617025 -0.387922 -0.975171 -0.0488572 -0.215996 -0.97235 -0.00516185 -0.233469 0 1 0 -1.46436e-07 1 7.98453e-08 0 1 0 -0.45645 -0.000512175 0.889749 -0.449675 0 0.893192 -0.35908 -0.035385 0.932636 -0.380075 0 0.924955 -0.19554 0 0.980696 -0.195615 0.000131841 0.980681 -0.985315 -4.81123e-05 0.170749 -0.98535 -3.52961e-09 0.170545 4.94357e-07 1 -1.03632e-06 3.70923e-07 1 7.40156e-06 0.0638234 0.997927 -0.00831156 0 1 0 0.000350528 1 -0.000841094 0.000398999 0.999999 0.00165436 0 1 0 3.50981e-08 1 9.58956e-07 -3.31473e-08 1 1.16134e-06 2.13955e-07 1 5.53914e-07 -0.773998 0.632409 0.0314041 0.289139 0.757071 -0.585869 1.45756e-05 1 -7.8495e-06 0 1 0 0 1 0 0 1 0 0 1 0 1.88803e-07 1 5.88141e-07 0.242675 0.963183 0.115705 0.604694 0.629418 0.488035 0.198458 0.922371 -0.33143 -3.68844e-06 1 8.60832e-06 -0.193669 0.915738 -0.352017 0.298486 0.951954 -0.0684884 0.311171 0.9448 -0.102594 0.267152 0.949355 -0.165395 0.230898 0.957883 -0.170721 0.272645 0.945618 -0.1774 0.393378 0.914044 0.098878 0.375299 0.925811 0.0450058 0.330252 0.943455 -0.0287362 0.308304 0.949874 -0.0518453 0.386701 0.922204 -0.00136249 0.495174 0.854671 0.156011 0.476412 0.874785 0.0882165 0.624739 0.73116 0.274055 0.693484 0.556096 0.45808 0.646082 0.507963 0.569695 0.640525 0.565345 0.519724 0.549224 0.448794 0.704937 0.552389 0.60855 0.569678 0.418746 0.405233 0.812673 0.441502 0.657497 0.610552 0.36717 0.561917 0.741239 0.212365 0.604577 0.767717 0.213114 0.606409 0.766061 0.0917049 0.559129 0.823993 -0.20014 0.535168 0.820695 -0.0384357 0.583997 0.810845 -0.00964511 0.619087 0.785263 -0.234686 0.489758 0.839678 -0.341849 0.526825 0.778199 -0.410093 0.471349 0.780804 -0.729162 0.452125 0.513718 -0.569738 0.533715 0.624937 -0.622403 0.476393 0.621018 -0.514668 0.485926 0.706394 -0.488386 0.510205 0.707933 -0.696938 0.530149 0.482928 -0.616258 0.581029 0.531632 -0.721064 0.593041 0.358286 -0.764824 0.548823 0.337398 -0.802037 0.577546 0.152241 -0.772906 0.608062 0.181318 -0.773195 0.568702 0.280619 -0.752915 0.655227 0.0616144 -0.710931 0.703068 -0.0165087 -0.670964 0.741234 0.0195046 -0.677294 0.735709 -0.00245158 -0.664695 0.746915 -0.0173144 -0.674931 0.737554 -0.0219708 -0.68894 0.723829 -0.0378688 0.300105 0.906051 -0.298343 0.27806 0.927375 -0.250318 0.277604 0.92756 -0.250136 0.341139 0.870865 -0.353861 0.333022 0.891598 -0.306839 0.379366 0.859403 -0.342796 0.358834 0.875209 -0.324419 0.40688 0.801402 -0.43841 0.502443 0.787501 -0.356922 -5.97433e-07 1 1.55923e-07 -8.51766e-07 1 8.35662e-08 -0.0262008 0.999646 0.00453486 -0.00708403 0.999924 0.0100884 0.00767542 0.999905 0.0114806 5.06326e-07 1 7.57341e-07 0 1 0 0 1 0 8.14187e-08 1 7.1286e-07 -8.74908e-07 1 4.43808e-07 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.00381776 0.999993 0.000514268 0 1 0 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.73483e-07 1 5.3704e-07 2.85344e-07 1 -3.8437e-08 0 1 0 -1.67312e-06 1 -2.50784e-07 8.16177e-07 1 1.22337e-07 1.02235e-06 1 6.62427e-09 9.35028e-07 1 1.26066e-07 -1.77863e-06 1 1.85841e-07 0 1 0 0 1 0 0 1 0 0 1 0 0.00155666 0.999997 -0.00202115 -0.00548388 0.999983 -0.00184428 -0.00455511 0.999987 -0.00233642 2.22591e-07 1 1.70836e-06 -2.27515e-07 1 1.61617e-07 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.000345045 1 5.98922e-05 -0.000403702 1 -0.000220725 -7.84949e-05 1 -0.000250932 0 1 0 0 1 0 0 1 0 5.39122e-08 1 4.61034e-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.54624e-07 1 5.83628e-08 1.13088e-07 1 3.51263e-07 5.61405e-08 1 3.43253e-07 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 8.74133e-06 1 4.35131e-06 1.61695e-07 1 1.20478e-07 4.04228e-07 1 4.13047e-07 2.67097e-06 1 2.38511e-05 -0.384682 0 0.923049 -0.384682 0 0.923049 -0.210123 0 0.977675 -0.210123 0 0.977675 -0.0306058 0 0.999532 -0.0285305 -0.00360736 0.999586 0.110623 0.109257 0.987839 0.193433 -0.104258 0.975558 0.329448 0.10854 0.937914 0.495994 -0.0829952 0.864351 0.477516 0 0.878623 0.658226 0 0.752821 0.646994 0.0338444 0.761743 0.757961 0.0630801 0.649243 0.775361 0 0.631518 0.877417 0 0.479729 0.877417 0 0.479729 0.950118 0 0.311889 0.950118 -6.45488e-08 0.311889 0.991033 -2.76534e-08 0.133617 0.989518 0.023102 0.142552 0.998772 -0.00641537 -0.049127 0.998899 -0.000635222 -0.0469096 0.973136 0.00141497 -0.230227 0.972041 -0.0094024 -0.234622 0.914867 0.0112091 -0.4036 0.908746 -0.0213147 -0.416805 0.825983 0.0169954 -0.563439 0.822015 0.0025998 -0.56946 0.70964 0.00316276 -0.704558 0.709766 0.00357598 -0.704429 -0.161596 -3.94944e-05 -0.986857 -0.161409 0 -0.986888 -0.306457 0 -0.951885 -0.306456 7.8801e-08 -0.951885 -0.444815 7.41434e-08 -0.895622 -0.444816 0 -0.895622 -0.573116 0 -0.819474 -0.572976 3.60296e-05 -0.819572 -0.812079 -3.957e-05 -0.583548 -0.811968 2.41606e-08 -0.583701 -0.889781 1.88909e-08 -0.456388 -0.889781 1.88909e-08 -0.456388 -0.947833 1.31944e-08 -0.318766 -0.947833 6.5972e-09 -0.318766 -0.984713 3.60494e-09 -0.174185 -0.984682 3.66568e-05 -0.174357 0.570386 0.00326755 -0.82137 0.986857 -3.95082e-05 -0.161595 0.986888 3.34052e-09 -0.161409 0.951885 6.3424e-09 -0.306455 0.951885 1.26848e-08 -0.306455 0.895622 1.84119e-08 -0.444817 0.895621 0 -0.444817 0.819475 0 -0.573115 0.819573 3.59753e-05 -0.572975 0.812078 -0.000231368 0.583549 0.827472 -0.0380476 0.560217 0.887367 0.0342455 0.45979 0.936353 -0.0588905 0.346086 0.955476 0.000236801 0.295067 0.98468 3.95055e-05 0.174372 0.984713 -7.20995e-09 0.174186 0.955062 -1.22689e-08 0.296407 0.19233 -0.0418012 0.98044 0.299561 0.0815248 0.950588 0.427204 -0.0564709 0.90239 0.546663 0.0423863 0.836279 0.572974 0.000231007 0.819574 -0.0959345 -0.00152796 -0.995386 0.678729 -3.25544e-06 -0.734389 0.680397 0.00110278 -0.732843 0.692554 -0.000852402 -0.721365 0.694044 -0.000418907 -0.719932 0.708264 0.000542522 -0.705947 0.711844 -0.000714806 -0.702337 0.736863 -0.000436258 -0.676042 0.745258 0.00221879 -0.666773 0.768175 -0.00171894 -0.640238 0.805261 0.000660107 -0.59292 0.800429 -0.000809252 -0.599427 0.848005 0.00150778 -0.529986 0.947113 0.0029823 -0.320887 0.938588 -0.000823282 -0.345038 0.867513 -0.00394432 -0.497399 0.992883 0.00268791 0.119066 0.997143 -0.00169028 0.0755229 0.997536 0.00235997 -0.0701109 0.994553 -0.000921061 -0.104232 0.923794 -5.38625e-05 0.382889 0.965286 0.00104135 0.261194 0.96983 -0.00202838 0.243773 0.948148 0.00160724 0.317825 0.940965 -0.00139182 0.338501 0.918265 0.0034181 0.395951 0.899958 -0.0014651 0.435975 0.883291 0.00661577 0.468778 0.851512 -0.00233777 0.52433 0.837608 0.00364482 0.546259 0.782343 -0.00139842 0.622846 0.77512 0.000997957 0.631813 0.726397 -0.00263093 0.68727 0.674394 0.00428353 0.738359 0.693746 -0.00209554 0.720217 0.603649 -0.00148915 0.797249 0.586906 0.00321122 0.809649 0.109969 0.00402054 0.993927 0.123265 0.00151196 0.992373 0.203202 -0.000928675 0.979136 0.271403 0.00620731 0.962446 0.30632 -0.00140715 0.951928 0.448455 0.00130631 0.893804 0.464318 -0.00328347 0.885663 -0.150311 -0.00622199 0.988619 -0.0432076 0.00397119 0.999058 -0.00283156 -0.00275726 0.999992 -0.314285 -0.000913696 0.949328 -0.266913 0.0129227 0.963634 -0.5901 0.00117309 0.80733 -0.468941 0.0010694 0.883229 -0.46329 -0.000804583 0.886206 -0.669293 -0.000437965 0.742998 -0.667799 -6.59572e-06 0.744342 -0.594428 -2.53206e-05 0.804149 -0.824057 -0.00064872 0.566507 -0.818799 0.000843884 0.57408 -0.763108 -0.000161243 0.646271 -0.761562 -0.000681616 0.648092 -0.897899 0.00262546 0.440194 -0.887371 -0.00160894 0.461053 -0.946443 -0.00153474 0.322868 -0.944257 -0.000289316 0.329208 -0.980235 0.00220658 0.197822 -0.98234 -0.000846495 0.187104 -0.995915 -0.0015287 0.0902809 -0.997087 0.00186946 0.0762446 -0.999993 -1.31414e-05 -0.00361965 -0.999996 -0.000204303 -0.00294859 -0.999578 0.000184751 0.0290573 -0.999566 0.000100957 0.0294736 -0.998492 -7.71789e-05 0.054894 -0.998675 -0.000349068 -0.0514674 -0.99947 0.000479298 -0.0325354 -0.99952 -1.31764e-05 -0.0309896 -0.998493 0.000605631 -0.0548845 -0.997862 -0.000221769 -0.0653613 -0.99642 0.00207986 -0.0845155 -0.992476 -0.00143175 -0.12243 -0.949759 -0.000139027 -0.312982 -0.951235 -0.000634771 -0.308465 -0.83327 0.00202242 -0.552862 -0.799384 -0.00175422 -0.600818 -0.610399 -0.00105098 -0.792094 -0.590703 0.000786861 -0.806889 -0.355432 0.00271262 -0.934698 -0.311031 -0.00213032 -0.950397 -0.0970127 0.00942381 -0.995239 -0.145522 -0.0195392 -0.989162 -0.170621 -0.000950037 -0.985336 -0.128347 -0.00424731 -0.99172 -0.677902 0.732828 -0.058423 -0.688386 0.72351 -0.0515489 -0.672716 0.707908 -0.215221 -0.440759 0.772874 -0.456506 -0.564616 0.735126 -0.375232 -0.263507 0.697443 -0.666436 -0.39669 0.741317 -0.541374 -0.0677332 0.707442 -0.703519 -0.0677152 0.707261 -0.703702 0.563641 0.653233 -0.505565 0.431356 0.676528 -0.596859 0.234994 0.701616 -0.672691 0.193265 0.681984 -0.705369 0.0681194 0.650396 -0.756535 0.18511 -0.00103215 -0.982717 0.0901732 0.0474245 -0.994796 -0.0260769 0.104108 -0.994224 0.264251 0.0009797 -0.964453 0.191731 -0.0014609 -0.981446 0.129124 -0.0624595 -0.989659 0.559713 0.00334849 -0.82868 0.524807 -0.00113013 -0.85122 0.387829 0.000729532 -0.921731 0.36193 -0.00136551 -0.932204 0.65678 -0.00311359 -0.754076 -0.0298898 -0.0715377 -0.99699 0.476603 -0.689753 -0.54506 0.385158 -0.675725 -0.628529 0.256905 -0.713814 -0.651513 0.171498 -0.756061 -0.631633 0.0904566 -0.700402 -0.707994 -0.714321 -0.69851 0.0427678 -0.701143 -0.712973 0.00825969 -0.706496 -0.707708 0.00366912 -0.708006 -0.705536 -0.0307581 -0.688088 -0.725305 -0.0216373 -0.713555 -0.699232 -0.0437576 -0.702856 -0.70664 0.081565 -0.701163 -0.709322 0.0723396 -0.706654 -0.70493 0.0609467 -0.70334 -0.710102 0.0326633 -0.700196 -0.705711 0.108158 -0.690106 -0.713608 0.12049 -0.695255 -0.695718 0.180548 -0.644449 -0.719941 0.257624 -0.647157 -0.710754 0.27571 -0.615937 -0.694693 0.371515 -0.553097 -0.70869 0.437998 -0.534644 -0.716291 0.448423 -0.50836 -0.705474 0.493839 -0.466445 -0.712758 0.523836 -0.441141 -0.703941 0.556652 -0.410386 -0.707813 0.574964 -0.386221 -0.703786 0.596253 -0.342868 -0.712574 0.612111 -0.297215 -0.704695 0.644258 -0.27273 -0.710991 0.648159 -0.17779 -0.703714 0.687879 -0.191004 -0.711214 0.676529 -0.08829 -0.69947 0.709187 -0.0104416 -0.712834 0.701255 0.0178636 -0.706087 0.7079 0.0886024 -0.708034 0.700598 0.158917 -0.708629 0.687452 0.148519 -0.706943 0.691501 0.0961437 -0.706695 0.700955 0.246087 -0.712922 0.656646 0.216052 -0.705702 0.674764 0.318189 -0.705753 0.632984 0.330089 -0.709955 0.622097 0.409571 -0.706414 0.577262 0.407675 -0.705786 0.579368 0.45576 -0.707113 0.540624 0.457718 -0.706702 0.539506 0.49351 -0.706441 0.507335 0.505725 -0.71006 0.489957 0.533288 -0.705377 0.466955 0.559538 -0.717526 0.414818 0.579008 -0.707835 0.404622 0.607028 -0.70961 0.35773 0.61757 -0.704539 0.349617 0.628856 -0.7083 0.320704 0.634747 -0.705619 0.314958 0.647726 -0.706581 0.284947 0.649239 -0.713784 0.26268 0.670245 -0.705128 0.231443 0.691639 -0.714997 0.102052 0.681921 -0.729819 0.0484603 0.703758 -0.709969 -0.0258623 0.694511 -0.689676 -0.204941 0.639143 -0.702016 -0.314118 0.60667 -0.71926 -0.338551 0.594114 -0.706795 -0.384017 0.566787 -0.709737 -0.41836 0.545123 -0.720252 -0.429043 0.54412 -0.709245 -0.448223 0.526701 -0.704796 -0.475235 0.508557 -0.715585 -0.478861 0.507771 -0.703991 -0.496553 0.483844 -0.711407 -0.509701 0.484436 -0.709706 -0.511507 -0.10376 -0.695332 -0.711159 -0.217329 -0.708869 -0.671024 -0.323567 -0.75802 -0.566313 -0.425848 -0.72164 -0.545793 -0.588045 -0.676797 -0.442887 -0.721533 -0.648627 -0.242225 -0.729955 -0.678158 -0.0852466 -0.067836 -0.706934 -0.704019 -0.0678178 -0.7068 -0.704155 2.46139e-08 -1 -2.76424e-08 -4.83892e-05 -1 -2.04452e-05 0 -1 0 0 -1 0 1.45904e-08 -1 -2.60477e-08 1.9203e-08 -1 -2.6904e-08 1.97527e-05 -1 -1.26769e-06 4.54489e-05 -1 4.51261e-07 -3.126e-07 -1 1.74885e-07 1.05135e-08 -1 -2.49859e-08 -5.24622e-06 -1 1.74226e-06 -3.47767e-07 -1 2.73713e-07 -7.69883e-06 -1 -9.13358e-06 -6.08961e-06 -1 -7.39591e-06 -1.09875e-06 -1 5.16601e-06 0.00219438 -0.999997 0.00107191 0.00232449 -0.999997 0.000488973 3.40795e-05 -1 -2.35352e-05 0 -1 0 0 -1 0 4.44374e-06 -1 -2.51433e-06 -1.40757e-08 -1 -8.29503e-09 -1.55315e-07 -1 -6.28402e-08 1.16434e-07 -1 -3.67804e-07 5.33146e-08 -1 -1.68416e-07 2.43835e-06 -1 1.65204e-05 -6.24908e-06 -1 0.000168412 -6.31627e-09 -1 -1.68541e-08 -4.23039e-09 -1 -1.83e-08 -2.45472e-09 -1 -1.941e-08 -1.32558e-08 -1 -9.82727e-09 -1.19264e-08 -1 -1.15546e-08 -1.08043e-08 -1 -1.28161e-08 -9.76534e-09 -1 -1.3878e-08 -8.15693e-09 -1 -1.53728e-08 8.78438e-06 -1 -1.83391e-05 -9.8064e-06 -1 1.35222e-05 0.0446211 -0.837281 0.544949 0.0465991 -0.830856 0.554533 -0.68277 0.720565 0.12088 -0.422427 -0.825386 -0.374559 0.31382 -0.480473 -0.81894 -0.212154 -0.953461 -0.214249 0.540277 -0.84148 0.00351487 0.54306 -0.839685 0.00388543 8.31438e-06 -1 -5.29508e-08 -0.0971994 0.0111881 -0.995202 -0.0962519 0.00184057 -0.995355 0 1 0 0 1 0 3.15227e-08 1 3.18965e-08 2.33255e-08 1 3.63745e-08 1.71604e-08 1 4.22004e-08 0 1 0 0 1 0 -3.34518e-07 1 1.9018e-07 -3.06824e-07 1 2.88993e-07 -2.17051e-08 1 7.43829e-08 1.05422e-07 1 -3.61278e-07 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -5.59331e-07 1 2.01218e-07 -1.6867e-08 1 2.05497e-07 0 1 0 1.41803e-08 1 2.32797e-07 -1.49532e-09 1 2.32615e-07 -1.45076e-09 1 2.32419e-07 3.17662e-08 1 3.16098e-08 1.43465e-06 1 1.42758e-06 6.60943e-06 1 -6.51571e-06 2.49672e-07 1 4.41642e-08 7.27372e-08 1 1.46486e-07 0 1 0 0 1 0 -4.61954e-08 1 -4.85913e-10 -1.49151e-09 1 2.3241e-07 -1.75984e-07 1 1.37273e-07 -6.73272e-08 1 1.6276e-07 9.53666e-08 1 9.64676e-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 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 -1.30189e-09 1 1.23726e-07 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1.65601e-07 1 3.38111e-07 5.11061e-08 1 -2.33814e-07 -3.80391e-07 1 -7.97621e-07 -1.17748e-05 1 1.9486e-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.33769e-06 1 5.98397e-07 -3.29401e-07 1 3.9463e-07 1.55345e-07 1 2.09237e-07 2.36037e-07 1 2.10091e-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 -1.40258e-08 1 2.16072e-06 -6.30479e-07 1 -4.58021e-07 4.57284e-07 1 1.26339e-06 4.82836e-08 1 3.39605e-10 7.80132e-09 1 3.75178e-08 4.10709e-09 1 4.2134e-08 -4.46215e-08 1 4.42805e-08 -1.71842e-05 1 1.70529e-05 1.7439e-05 -1 -1.72039e-05 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -4.45547e-06 1 -1.09315e-05 0 1 0 -1.07914e-07 1 1.79312e-07 -7.78472e-10 1 1.35654e-07 3.91868e-08 1 9.6145e-08 0 1 0 -0.999986 9.98157e-05 -0.00529992 -0.999987 0.000158439 -0.00509806 0.869299 -6.5927e-06 -0.494287 0.869331 -4.36197e-05 -0.494231 0.999979 -7.45234e-06 0.00654119 0.999979 2.22967e-05 0.00649596 3.33072e-08 -1 -1.66926e-07 0.0159984 -0.996652 -0.0801794 8.52819e-08 -1 -8.40301e-08 1.06129e-08 -1 4.95283e-07 -5.28769e-09 -1 -5.46808e-08 -1.61533e-06 -1 1.45711e-07 8.98021e-06 -1 -1.30723e-05 0 -1 0 3.32861e-08 -1 -1.66941e-07 7.6824e-08 -1 -5.90259e-08 7.39545e-08 -1 -7.29409e-08 1.11831e-06 -1 6.06248e-07 -1.26555e-08 -1 -4.01592e-08 0 -1 0 0 -1 0 -2.1801e-08 -1 -3.3351e-08 -1.81051e-07 -1 -1.23109e-09 -3.26575e-10 -1 -4.08057e-08 -1.56111e-08 -1 -3.64037e-08 0.702927 7.93193e-05 0.711262 0.702927 7.92704e-05 0.711262 -0.711969 -7.29179e-05 0.702211 -0.711889 -2.62484e-05 0.702292 0.999977 -1.43002e-05 0.00679952 0.999975 -9.52028e-05 0.00703337 -0.941876 2.41958e-06 0.33596 -0.941869 1.35471e-05 0.33598 -0.64079 0.00721357 0.767682 0.0205483 0.282857 0.958942 0.99658 0.000414909 -0.0826301 0.982134 0.164564 0.0912758 -0.0480201 0.0462222 0.997776 0.00800292 -0.000326097 0.999968 0.587741 0.000118462 -0.809049 0.891662 -3.86369e-05 -0.452701 0.89208 1.34436e-08 -0.451877 0.999979 -1.92764e-10 0.00647934 0.999979 -1.84383e-10 0.00647934 0.886148 -1.31871e-08 0.463403 0.88572 3.85953e-05 0.46422 0.577203 -0.000118459 0.8166 -0.156563 0.000118537 -0.987668 0.310403 -3.85194e-05 -0.950605 0.311278 0 -0.950319 0.711673 0 -0.702511 0.711674 5.81568e-08 -0.70251 0.954278 2.47459e-08 -0.298921 0.954278 2.47459e-08 -0.298921 0.985569 -1.40133e-08 0.169275 0.985743 -7.3918e-05 0.16826 -0.809047 0.000118503 -0.587745 -0.452708 -3.86565e-05 -0.891659 -0.451885 0 -0.892076 0.00648915 0 -0.999979 0.00649113 8.27825e-08 -0.999979 0.463403 7.33591e-08 -0.886148 0.463461 2.82168e-06 -0.886117 0.815245 3.76448e-05 -0.579117 -0.987679 0.000118408 0.156496 -0.950606 -3.85456e-05 -0.3104 -0.95032 0 -0.311276 -0.702507 0 -0.711676 -0.702506 5.89157e-08 -0.711677 -0.298935 7.89988e-08 -0.954274 -0.298936 0 -0.954273 0.169283 0 -0.985567 0.168265 -7.41376e-05 -0.985742 -0.801884 0.000981816 -0.59748 0.807574 -0.000907594 -0.589765 -0.158897 -5.00007e-05 -0.987295 0.597483 0.000982459 -0.801881 0.587036 -0.000982304 0.80956 0.792592 0.0531726 0.60743 0.383134 -0.234492 0.893432 -0.792965 -0.00366281 0.609256 -0.574666 0.00259265 0.818384 -0.9895 0.000983035 0.144529 -0.596105 -0.00050673 -0.802906 0.883999 0 0.467489 0.883999 -3.91265e-08 0.467489 0.883588 0 0.468266 0.88362 -8.21147e-05 0.468204 -0.588336 0 0.808617 -0.615087 0.00779198 0.788421 -0.555367 -0.000680828 0.831605 -0.257617 -0.00061652 -0.966247 -0.253353 -0.000180302 -0.967374 -0.252553 2.00252e-08 -0.967583 0.769923 -0.00616099 0.638108 0.656927 0.00513737 0.753936 0.0562355 -0.00284169 0.998414 0.0623871 -0.00325555 0.998047 0.450646 0.00445527 0.892692 -0.347558 0.0056269 0.937642 -0.99232 0.00631937 0.123532 -0.765727 0.0019988 -0.643162 -0.958986 -0.000404941 -0.283454 -0.967019 -0.00196905 -0.254698 -0.444784 0.00407196 -0.895629 -0.688214 -0.00262893 -0.725503 0.450102 0.693787 0.5622 0.555212 0.48033 0.678986 0.890487 0.402946 0.211348 -0.239448 0.800047 0.550082 -0.31854 0.799042 0.509965 -0.325426 0.744336 0.583148 -0.362075 0.828616 0.426962 -0.54287 0.703116 0.45926 -0.517657 0.750507 0.410816 -0.533335 0.789279 0.304289 -0.589194 0.779523 0.212587 -0.622873 0.728871 0.284212 -0.631483 0.717599 0.293737 -0.861155 0.457926 -0.220718 -0.704798 0.628016 -0.329934 -0.210615 0.739669 -0.639164 -0.169916 0.697106 -0.696543 0.979608 0.00519363 -0.200851 0.969146 -0.0657989 -0.237543 0.924575 0.0617037 -0.37597 0.842109 -0.0490437 -0.537074 0.852408 -0.00569343 -0.522847 0 1 0 0 1 0 -4.7087e-08 1 1.60005e-07 -0.00624201 -0.000387563 0.99998 -0.00582822 0.00239521 0.99998 0.711848 0.000360839 -0.702334 0.712134 -0.00239506 -0.70204 -0.711506 -0.000387954 0.702679 -0.711214 0.00239494 0.702972 -0.99998 -0.000387559 -0.00624135 -0.99998 0.00239514 -0.00582758 0.999977 0.000393624 0.00671694 0.999972 -0.00239516 0.00713158 -0.702407 -0.000456075 -0.711775 -0.702481 0.000174698 -0.711703 0.70227 9.82437e-05 0.711911 0.701996 -0.00239527 0.712177 0.00624189 -0.000387941 -0.99998 0.005828 0.00239521 -0.99998 -0.00642816 -7.64714e-05 0.999979 -0.00635076 0.000389557 0.99998 -0.711842 0.000428674 0.70234 -0.712135 -0.00239534 0.702038 0.711742 -0.000389328 -0.702441 0.711484 0.00185399 -0.702699 -0.999978 0.000388394 -0.00658148 -0.999978 0.00152933 -0.00641194 0.99998 -0.000387639 0.00624113 0.99998 0.0024014 0.00582639 -0.702333 0.000387834 -0.711849 -0.70203 -0.00245436 -0.712143 0.702968 0.00427903 0.711209 0.702435 -0.000389812 0.711748 -0.911078 -0.0443152 0.409846 -0.826582 0.0401346 0.561384 0.687646 -0.489319 -0.536386 -0.429323 -0.889014 -0.159173 -0.744403 -0.0656381 0.664496 -0.657781 0.422163 -0.623781 0.196581 -0.237001 0.951413 0.218267 -0.208717 0.953308 0.463416 -0.252001 0.849553 0.481102 -0.229012 0.846223 0.661944 -0.228959 0.713728 0.678535 -0.204142 0.705632 0.852213 -0.25772 0.455317 0.879326 -0.19876 0.43276 0.957321 -0.254359 0.137253 0.965995 -0.228938 0.120169 -0.405281 -0.911749 -0.0667972 0.723879 -0.498931 0.476515 0.275611 -0.858796 -0.431866 -0.509363 -0.802481 0.310764 0.677995 -0.733413 -0.0492824 0.055385 -0.992477 0.109188 -0.966976 -0.222803 -0.123756 -0.217866 -0.0684592 -0.973575 0.759539 -0.644719 -0.0862418 -0.335957 -0.937673 0.0888903 -0.933037 -0.347084 -0.0947374 0.158208 -0.129002 -0.978943 0.787782 0.597303 0.150431 0.44896 -0.88642 -0.112667 -0.344319 -0.923084 0.171348 0.826487 -0.4917 0.274137 -0.00549974 -0.993552 -0.113243 -0.166774 0.920655 -0.352961 -0.634279 0.139434 -0.760426 0.0676972 0.959346 0.273992 0.760077 -0.649373 0.0244417 0.308684 0.715352 0.626886 -0.0275202 -0.999521 0.0141654 -0.462214 -0.731025 0.501957 -0.655046 0.71347 -0.248748 0.0937847 0.530643 -0.842391 -0.950236 0.191383 -0.245813 0.832392 0.332987 -0.442993 -0.941879 -0.0133804 -0.335685 -0.597529 0.80179 -0.00955095 -0.509044 0.844684 0.165476 -0.682899 0.689785 0.240512 -0.00735848 -0.7673 0.641246 -0.189795 -0.385432 0.903006 0.238721 0.970315 -0.0387534 -0.477582 0.787701 -0.389156 0.927542 0.0123803 -0.373513 -0.887304 0.00674296 -0.461136 0.0437916 -0.118814 -0.99195 0.43845 0.260304 -0.860234 -0.443205 0.853535 -0.273948 -0.975642 0.202144 -0.085211 -0.909381 0.404849 -0.0955205 -0.868766 0.202146 -0.452087 -0.66186 0.643204 -0.385007 -0.472385 -0.678315 -0.562797 -0.350084 0.678222 -0.646108 -0.200173 -0.678222 -0.707068 -0.0544379 0.678316 -0.732751 0.206356 -0.653528 -0.728229 0.326846 0.0715903 -0.942362 0.444824 0.740415 -0.503902 0.609571 -0.569045 -0.551915 0.882428 -0.152667 -0.444988 0.371903 0.921657 -0.110619 0.665031 0.742556 0.0796512 -0.0201382 0.839259 -0.543359 -0.98865 0.00712776 -0.150067 -0.775104 -0.0218499 0.631456 0.292163 0.101206 -0.950999 -0.998145 0.0230791 0.0563444 -0.255891 -0.012803 0.966621 -0.347011 0.0182178 0.937684 -0.514335 0.0376827 0.856761 -0.882239 0.0197507 -0.470388 -0.892242 0.00563123 -0.451523 -0.858009 -0.00623018 -0.513597 -0.793911 0.0215673 -0.607652 -0.776325 0.00571142 -0.630307 -0.296114 0.0513335 -0.953772 -0.35519 -0.00310537 -0.934789 -0.194861 0.00942794 -0.980785 -0.177348 0.017613 -0.983991 0.898029 0.00285449 -0.439926 0.965174 0.00971472 -0.26143 0.965357 0.0103259 -0.26073 0.996125 0.0140903 -0.0868074 0.997191 0.00445235 -0.0747646 -0.995655 4.97165e-05 -0.0931205 -0.960457 0.00868534 -0.278293 -0.946415 -0.000579488 -0.322953 -0.876808 0.0226405 -0.480307 -0.704791 -0.011083 -0.709329 -0.668876 0.00695967 -0.743341 -0.520897 0.00739266 -0.853588 -0.481474 -0.00901164 -0.876414 -0.364994 0.0181681 -0.930833 -0.213981 0.030283 -0.976368 -0.0230791 -0.00209713 -0.999731 0.00648029 0.00712752 -0.999954 0.164307 -0.000790623 -0.986409 0.190933 0.00761198 -0.981574 0.336513 -0.000479905 -0.941679 0.367418 -0.0187683 -0.929867 0.531889 0.0125067 -0.846722 0.537129 0.00769366 -0.843465 0.678471 -2.59103e-05 -0.734627 0.676348 0.00114247 -0.736581 0.798701 -0.00111133 -0.601727 0.801906 0.000787522 -0.59745 0.896093 -0.000829429 -0.443865 0.894107 0.00234483 -0.447847 0.997535 -5.34699e-05 -0.0701687 0.909048 -0.000109724 -0.416691 0.968507 -0.000141134 -0.248985 0.967592 0.00204398 -0.25251 0.996732 -0.0043602 -0.0806564 0.810501 0.000118726 -0.585737 0.817891 -0.00482273 -0.575353 0.822945 -0.00934837 -0.568044 0.908656 0.000415323 -0.417545 0.711719 -0.00395665 -0.702453 0.705181 -5.40129e-05 -0.709027 0.578891 -2.04056e-05 -0.815405 0.57859 0.000138297 -0.815618 0.434273 0.000210848 -0.900782 0.428415 -0.0024956 -0.903578 0.265098 2.17159e-05 -0.964221 0.265771 -0.00028868 -0.964036 0.0936357 0.000149415 -0.995607 0.093991 -1.13623e-05 -0.995573 -0.0806718 -2.27144e-05 -0.996741 -0.0809107 8.0545e-05 -0.996721 -0.252529 4.24361e-05 -0.967589 -0.252442 3.5247e-06 -0.967612 -0.416706 2.27158e-05 -0.909041 -0.41859 0.000914442 -0.908175 -0.568168 -0.00945526 -0.822858 -0.588711 0.000322325 -0.808344 -0.702456 -0.00391605 -0.711716 -0.708983 -5.41363e-05 -0.705225 -0.815421 -2.05877e-05 -0.578869 -0.815547 7.31935e-05 -0.578691 -0.902507 0.000114155 -0.430676 -0.903561 -0.000968692 -0.428458 -0.964236 9.57926e-05 -0.265044 -0.964197 2.81883e-05 -0.265188 -0.995607 1.5518e-05 -0.0936354 -0.995548 -0.000261533 -0.0942524 -0.999695 -0.00486584 -0.0242234 -0.992651 0.00652044 -0.12084 -0.987765 5.95986e-09 -0.155951 -0.954106 0.00447753 -0.299436 -0.955157 0.000198439 -0.296099 -0.955381 1.30995e-08 -0.295376 0.937386 0.102436 0.332889 -0.876579 0.0163297 -0.480981 -0.686109 0.0790874 -0.723187 -0.4847 0.0734407 -0.871592 -0.00102034 -0.0471014 -0.99889 -0.165333 0.12747 -0.977965 -0.239435 -0.0929325 -0.966455 0.156003 0.110901 -0.981511 0.236569 -0.0177823 -0.971452 0.394585 0.0206256 -0.918628 0.361155 0.0616095 -0.930468 0.669846 0.00343274 -0.742492 0.673674 0.00479904 -0.739013 0.994113 0.000196828 -0.108352 0.999081 0.0201386 -0.0378244 0.793091 0.00573059 -0.609076 0.807523 -1.77934e-05 -0.589836 0.890194 -4.81913e-06 -0.455582 0.890183 9.03744e-07 -0.455602 0.957916 -1.30479e-05 -0.287048 0.957901 8.29125e-09 -0.287099 0.990104 3.11178e-09 -0.140333 0.4306 0.00733459 -0.902513 0.524499 -0.00013331 -0.851411 0.524943 -0.000300319 -0.851137 -0.132077 0.881336 0.453655 0.103763 -0.606684 0.788142 0.459459 0.316735 0.829805 -0.22564 0.00449338 -0.9742 -0.177648 -0.000124734 -0.984094 0.00648067 -6.20762e-05 -0.999979 0.00631692 -0.000202199 -0.99998 0.190115 -0.000100609 -0.981762 0.189945 -0.00024725 -0.981795 0.332999 0.000309031 -0.942927 0.367029 0.0189213 -0.930017 0.420911 -0.000678198 -0.907101 -0.995193 -0.000229502 -0.0979359 -0.995118 -8.16445e-06 -0.0986915 -0.960032 -3.89993e-06 -0.27989 -0.960037 -8.76105e-06 -0.279874 -0.892256 -2.94252e-06 -0.45153 -0.892267 -1.0191e-05 -0.451508 -0.794095 -4.04085e-06 -0.607793 -0.793239 0.000401367 -0.608911 -0.668892 -0.00022663 -0.74336 -0.668317 -6.4621e-06 -0.743877 -0.520911 -7.54645e-06 -0.853611 -0.520889 0 -0.853624 -0.355192 0 -0.934794 -0.355229 -1.15829e-05 -0.934779 -0.209454 2.91254e-05 -0.977819 -0.125833 0.0443072 -0.991062 0.99631 -4.4599e-05 -0.0858275 0.996321 -4.14581e-06 -0.0856958 0.963575 -8.13551e-06 -0.267438 0.963579 -3.9744e-06 -0.267424 0.898033 -5.58542e-06 -0.439929 0.898033 -5.42148e-06 -0.439928 0.801737 -8.30171e-06 -0.597677 0.801906 7.33405e-05 -0.59745 0.678009 -0.000184094 -0.735054 0.67847 -2.38251e-06 -0.734628 0.531935 -4.94382e-06 -0.846785 0.531931 -6.26639e-06 -0.846788 0.415971 6.37072e-05 -0.909378 -0.89024 0.441343 -0.112648 -0.851318 -0.428946 -0.302098 -0.849172 0.118197 -0.514721 -0.711241 -0.395202 -0.581336 -0.528391 0.398057 -0.749902 -0.389874 -0.360066 -0.847556 -0.127891 0.454637 -0.881447 0.0170205 -0.489155 -0.872031 0.355823 0.521256 -0.775682 0.510611 -0.347804 -0.786326 0.693918 0.433328 -0.57507 0.837957 -0.22413 -0.497588 0.857957 0.444412 -0.257696 0.97033 -0.213208 -0.114028 0.440883 0.896347 -0.0467332 0.672095 0.698928 -0.244517 0.387609 0.890015 -0.240068 0.472841 0.758991 -0.44761 0.252271 0.875791 -0.41152 0.31743 0.576218 -0.753134 -0.153729 0.438072 -0.885698 -0.235485 0.894324 -0.380435 -0.592105 0.5775 -0.562055 -0.640906 0.346039 -0.685198 -0.81709 0.4558 -0.353001 -0.497628 0.864603 -0.0694799 -0.492414 0.86752 -0.0702677 0.09855 -0.17592 -0.979459 0.158722 -0.350528 -0.923005 -0.987087 -0.107998 -0.118303 -0.989751 -0.0223049 -0.141049 -0.895052 0.224659 -0.38524 -0.82808 0.0803501 -0.554822 -0.744126 -0.205961 -0.635497 -0.639806 0.123401 -0.758564 -0.36921 -0.0865172 -0.92531 -0.349238 -0.0139731 -0.93693 -0.101934 0.11458 -0.98817 0.291244 0.015656 -0.956521 0.719888 0.109048 -0.685471 0.655443 -0.0789342 -0.751108 0.530607 0.136188 -0.836606 0.861687 -0.0648589 -0.503277 0.903651 0.274091 -0.329072 0.971406 -0.21599 -0.0985864 0.853234 0.454211 -0.25629 0.433794 0.826298 -0.359242 0.408617 0.850872 -0.330225 0.262985 0.611858 -0.745968 0.112393 0.000666699 -0.993664 0.113505 -6.54951e-05 -0.993537 -0.216783 -0.769792 -0.600354 -0.360994 0.906733 -0.217987 -0.321607 0.928664 -0.184803 -0.991612 0.0307846 -0.125531 0.999928 -0.00497692 0.0109357 0.999945 -0.00231564 0.0102133 0.999834 -0.0182183 -0.000996681 0.00729834 -0.00235022 -0.999971 0.00683884 0.000995988 -0.999976 0.00740696 0.006102 -0.999954 0.0095991 0.0168467 -0.999812 0.00659995 0.000385036 -0.999978 0.00879997 0.000212429 -0.999961 0.00161721 -0.00553039 -0.999983 -0.000986485 0.0111678 -0.999937 0.0102238 -0.00678721 -0.999925 0.00724501 0.000667239 -0.999974 0.00693885 0.000197121 -0.999976 0.0076477 -0.0137194 -0.999877 0.00656335 -0.00264767 -0.999975 0.0072706 0.00255372 -0.99997 -0.213955 -0.0477709 -0.975675 0.00210256 -0.012124 -0.999924 0.00510996 -0.00631542 -0.999967 -0.999201 -0.0315879 0.0244842 -0.0741048 0.984929 0.156283 -0.130429 0.976779 -0.169974 0.173247 0.983283 0.0560417 -0.385607 -0.51882 0.762976 0.446516 0.893692 0.0440209 0.122668 0.967959 0.219109 0.405755 0.86745 0.287913 -0.816043 -0.491892 -0.303505 0.0385509 0.976763 -0.210826 0.444319 0.841638 -0.306963 0.409973 0.873122 -0.263781 -0.543915 0.0964217 -0.833582 0.000507041 1 -0.000412609 0.933905 0.329627 0.13845 -0.0361068 0.894908 -0.444787 -0.228829 0.959022 -0.167073 0.0219943 0.999723 0.00834238 -0.178848 0.979289 -0.0949032 0.000234862 1 0.000166653 -3.11556e-05 1 2.19155e-06 0.0677955 0.997656 0.00926264 0.0099708 0.999944 -0.0034464 0.031018 0.999485 -0.00816866 0.0247205 0.999622 -0.0120344 0.0579525 0.986922 -0.150422 -0.383425 0.914721 -0.127554 -0.206594 0.963312 0.171317 0.0255364 0.678918 0.73377 -0.461876 0.69294 0.553628 -0.475335 -0.56393 -0.675307 0.0196277 0.823326 0.567229 0.0399135 0.869857 0.491686 0.532506 -0.827176 0.179492 0.474868 0.827779 0.298801 0.360207 0.60756 0.7079 -0.593063 -0.352369 0.723957 -0.479088 0.743761 0.466148 -0.551477 0.818009 0.163505 -0.443237 0.889291 0.112708 0.00644066 -0.999978 0.0014841 0.00353912 -0.999992 0.00210194 0.00483727 -0.999982 0.00359957 0.0020939 -0.999988 0.0043921 0.000827669 -1 0.000461205 0.000789889 -0.999997 0.00218611 0.181996 -0.956372 -0.228538 0.000631854 -0.999999 -0.00164114 0.00130752 -0.999997 -0.00207112 0.00163465 -0.999998 -0.00141932 0.00105869 -0.999999 -0.00109889 0.00209794 -0.999997 -0.00143662 0.00307006 -0.999994 -0.00128659 0.00237304 -0.999997 -0.000177269 0.00339769 -0.999994 -3.79008e-05 -0.0657357 -0.994762 -0.0782782 -0.0490133 -0.970775 -0.234933 -0.0419481 -0.985801 0.162596 -0.0384315 -0.998935 0.0255257 -0.00452651 -0.999971 0.00618936 -0.00321599 -0.99999 0.00314461 -0.00659304 -0.999972 0.00364446 -0.00357903 -0.999993 0.000809424 -0.0026977 -0.999996 0.000872688 -0.00581315 -0.999982 -0.00113622 -0.00245032 -0.999996 -0.00155635 -0.00169155 -0.999998 -0.000894935 -0.00233659 -0.999995 -0.00203631 -0.000980572 -0.999996 -0.00269154 -0.0195622 -0.00121155 -0.999808 -0.0194222 -0.0011459 -0.999811 0.0375973 0.000306942 -0.999293 0.233835 -0.359498 -0.903373 -0.0152484 -0.00046277 -0.999884 -0.108208 7.57104e-05 -0.994128 -0.107974 0 -0.994154 0 -1 0 -0.202328 -0.46519 0.861778 -0.000209886 -1 -0.000289257 7.63351e-05 -1 4.05151e-05 2.59519e-05 -1 4.70056e-05 -5.24893e-05 -1 6.82069e-06 1.30492e-05 -1 -3.73484e-06 -1.70457e-05 -1 7.06091e-06 3.36705e-05 -1 -1.74432e-05 -1.01949e-05 -1 -3.18133e-05 1.33915e-07 -1 -1.02844e-07 2.91409e-05 -1 1.2781e-05 2.59214e-05 -1 -2.87325e-05 2.08784e-05 -1 -3.38916e-05 -6.13837e-05 -1 -3.11946e-05 -2.66004e-06 -1 -7.29563e-05 0.000307531 -1 -8.80187e-05 0 -1 0 -4.69238e-07 -1 1.82799e-05 7.29583e-06 -1 1.92012e-05 1.01242e-05 -1 1.65904e-05 1.61551e-05 -1 -1.2929e-05 0 -1 0 -3.77438e-06 -1 2.66041e-05 1.99674e-05 -1 1.50496e-05 2.10864e-05 -1 1.06709e-05 2.09496e-05 -1 1.03103e-05 2.40757e-05 -1 7.01908e-06 1.79963e-05 -1 -4.9542e-05 4.68655e-05 -1 -1.81628e-05 4.80832e-05 -1 2.25809e-05 2.22296e-05 -1 4.72736e-05 3.77248e-05 -1 -1.13046e-05 0.973291 0.194778 0.121519 0.941238 -0.156284 0.29941 0.860646 0.135396 0.490873 0.767664 -0.0608993 0.637952 0.744602 0.00174005 0.667506 0.559892 0.00381728 0.828557 0.539395 0.0598466 0.839924 0.218663 -0.046722 0.974681 0.21474 -0.033635 0.976092 -0.0537704 0.134329 0.989477 -0.168027 -0.105376 0.980134 -0.435695 0.0933675 0.895239 -0.432205 0.0792667 0.898285 -0.734723 -0.0480086 0.676666 -0.737334 -0.0373421 0.674496 -0.85783 0.0992776 0.504253 -0.942351 -0.104319 0.317951 -0.966408 0.0882906 0.241371 -0.0748518 0.992193 -0.0997527 -0.126822 0.963052 0.237587 0.14341 0.988441 -0.0491805 0.0416687 0.447695 0.893215 0.0452033 0.985966 0.160712 0.103537 0.989401 0.101809 -0.595716 0.77681 0.204178 -0.647203 0.725124 0.235209 -0.372115 0.84046 0.3939 -0.292978 0.919729 0.261271 -0.324869 0.662663 0.674787 -0.067898 0.905962 0.417879 -0.0288466 0.812993 0.581558 0.206228 0.773308 0.599554 0.0748824 0.923967 0.375069 0.624235 0.458898 0.632252 0.309178 0.869873 0.384357 0.688112 0.682716 0.245765 0.288221 0.942538 0.16897 0.688209 0.720728 0.0831795 0.0111464 -0.999716 -0.0210466 0.0232234 -0.99909 -0.0357634 0.028438 -0.999437 -0.0177917 0.0332206 -0.999253 -0.0197268 0.0374897 -0.999288 -0.00418606 0.0360858 -0.99934 -0.00424059 0.0413825 -0.999038 0.0145217 0.0327015 -0.999413 0.0101839 0.0374513 -0.998592 0.03758 0.0242203 -0.99948 0.0212763 0.0219208 -0.997477 0.0675248 0.0113113 -0.999577 0.0268013 -0.00523408 -0.999438 0.033115 -0.00525642 -0.999435 0.0331945 -0.029992 -0.998652 0.0423629 -0.016954 -0.99969 0.018213 -0.0482317 -0.998425 0.0286405 -0.0257035 -0.999629 0.00899604 -0.057607 -0.998316 0.00676959 -0.0347829 -0.999395 -0.000862934 -0.0129685 -0.999604 -0.0249722 -0.0168131 -0.999502 -0.026703 -0.0244171 -0.998292 -0.0530809 0.000890845 -0.999573 -0.0292248 0.000520602 -0.999644 -0.0266726 0.883564 0.459761 0.0890708 0.890733 -0.360067 0.277393 0.77314 0.401575 0.490909 0.730067 -0.236015 0.641326 0.526864 0.432253 0.731827 0.343844 -0.466919 0.814713 0.162025 0.466517 0.869546 -0.144863 -0.376999 0.914815 -0.248642 0.330941 0.910305 -0.38409 0.400764 0.831783 -0.539068 -0.360067 0.761418 -0.708641 0.363353 0.604816 -0.824725 -0.28283 0.489731 -0.825033 0.50943 0.244542 -0.971984 -0.205429 0.114222 0.112147 0.930516 0.348659 0.00343769 0.999824 0.0184492 0.00699225 0.999928 0.00971241 0.00359115 0.999991 0.00228022 0.0502348 0.992447 -0.111917 0.0364068 0.994517 -0.0980341 -0.0551537 0.923288 -0.380128 -0.0382321 0.9977 -0.0559708 -0.0050882 0.999978 0.00434264 -0.139553 0.844902 0.516398 0 -1 0 0 -1 0 0.00323733 -0.999989 0.00345075 -2.25125e-05 -1 -2.41166e-05 0 -1 0 0 -1 0 0 -1 0 7.39915e-06 -1 -3.4448e-05 -2.9774e-05 -1 -2.34854e-05 -3.28002e-05 -1 -1.75393e-05 -2.16084e-05 -1 2.63128e-05 0 -1 0 0 -1 0 -9.5886e-06 -1 1.47396e-05 -2.37386e-05 -1 3.77897e-05 -3.12913e-05 -1 2.69171e-05 -2.40017e-05 -1 2.59883e-05 -3.09784e-05 -1 2.28491e-05 -3.44965e-05 -1 1.07558e-05 -2.56955e-05 -1 1.25877e-05 -3.06617e-05 -1 8.50961e-06 -3.18069e-05 -1 -1.299e-05 2.25277e-05 -1 4.24094e-05 -4.35546e-07 -1 2.63274e-06 0 -1 0 0.66017 -0.00186837 0.751114 -0.278107 -0.0012077 0.960549 -0.167557 -0.0178423 0.985701 -0.314247 -0.0178433 0.949174 -0.342599 -0.0563501 0.93779 -0.404403 0.00460282 0.914569 -0.397061 -0.000979527 0.917792 -0.269162 -0.00140678 0.963094 -0.301961 0.00527165 0.953306 -0.402085 0.00293535 0.915598 -0.366864 0.120394 0.922451 0.545134 -0.0104597 0.838284 0.543029 0.00151021 0.839713 0.556062 -0.00562432 0.831122 0.274606 0.0754839 0.958589 0.341225 -0.0257088 0.93963 0.414723 0.0646742 0.907647 0.512977 -0.041524 0.857398 0.95705 0.017724 0.289381 0.953766 -0.0270678 0.299329 0.884197 0.0062363 0.467072 0.88723 0 0.461327 0.785144 0 0.619314 0.785144 0 0.619314 0.661912 0 0.749582 0.887536 -0.0178677 0.460393 0.892005 -0.00753291 0.451964 0.786266 4.5692e-05 0.617888 0.785142 -0.00170614 0.619313 0.662129 -0.0022413 0.749387 0.650614 -0.0154047 0.759252 0.614217 -0.0368211 0.788278 0.556326 0.00481 0.83095 0.562163 0.00259019 0.827022 0.514818 0.140135 0.845769 0.362371 -0.0391632 0.931211 0.172122 -0.0295306 0.984633 -0.15556 0.0548966 0.9863 -0.163805 0.029505 0.986051 -0.995797 0.00202246 0.0915667 -0.994648 -0.00148073 0.103307 0.994631 0.00345962 0.103428 0.99263 -0.00172993 0.121174 0.9642 0.000192763 0.265174 0.969535 0.00667499 0.244863 -0.404456 0.000868921 0.914557 -0.524498 -0.000730142 0.851411 -0.601972 0.0247813 0.798133 -0.66985 -0.000611766 0.742496 -0.793103 -0.00176567 0.609085 -0.832074 0.016823 0.55441 -0.890193 -0.0010498 0.455581 -0.901401 0.00225073 0.432981 -0.957913 -0.00243791 0.287048 -0.962194 0.00149472 0.272361 0.352164 0.93587 -0.0112801 0.013884 -0.999878 -0.00710552 -0.0176468 -0.999594 -0.022377 0.0270951 -0.999624 -0.00412315 -0.127717 -0.991317 0.031281 -0.243018 -0.967683 -0.0673233 0.0487147 -0.998645 0.0183308 -0.00706814 -0.999798 -0.0188366 -0.0152245 -0.999862 -0.00666485 -0.0103568 -0.999941 -0.00325038 -0.00901459 -0.999948 -0.0047619 -0.0211857 -0.999748 -0.0074411 -0.016262 -0.9998 -0.0116783 -0.0184938 -0.999752 -0.0123858 -0.130653 -0.891029 0.434739 0.00200278 -0.999996 -0.00210872 0.470674 -0.702687 0.533571 0.00188231 -0.999995 -0.00241476 0.0027141 -0.999991 -0.00320591 -0.00842681 -0.99971 -0.0225736 0.00642987 -0.999948 -0.00797472 0.0289319 -0.974718 0.221558 0.0705811 -0.829963 0.553336 -0.282119 -0.842817 0.458332 0.0167443 -0.999538 -0.0253525 -0.0219537 -0.996412 -0.0817444 -0.0211211 -0.996968 -0.0748948 0.46177 -0.748052 0.476641 -0.022845 -0.999564 0.0186841 0.0237272 -0.999717 0.00159946 0.00335579 -0.999957 -0.00864573 0.00356733 -0.99993 -0.0112587 0.00349099 -0.99993 -0.0112843 0.0145181 -0.998107 -0.059771 0.063208 -0.997069 -0.0431021 0.0140611 -0.999877 0.00694797 0.00996146 -0.999944 0.00361702 0.0154552 -0.999876 -0.00309414 0.0166825 -0.999856 -0.00299773 0.0133747 -0.999901 -0.00440146 0.0259909 -0.999651 -0.00470295 0.0193078 -0.999736 -0.0124373 -0.000861065 -1 -0.000294528 0.0650862 -0.986887 0.147708 0.000547262 0.999999 0.00160304 0.034391 -0.998797 0.0349565 0.0451942 -0.998553 0.0291459 -0.0676973 -0.959346 -0.273992 0.0654884 -0.992313 -0.105003 0.250296 -0.958514 -0.136393 0.00165788 -0.999762 -0.0217666 -0.00680742 -0.999954 0.00678312 0.0139179 -0.999565 -0.0259953 -0.000866157 -1 -6.73434e-05 -0.0169108 -0.999821 -0.00849091 0.0607906 0.998091 -0.0109401 -0.830925 0.471488 -0.295403 -0.0132768 -0.999907 0.00306649 -0.802303 0.397538 -0.445278 0.0130534 -0.999251 -0.0364302 0.00603784 -0.99995 0.00794603 0.00115361 -0.999999 0.000127807 -0.000399678 -1 -0.000292804 3.49077e-05 -1 2.55733e-05 -0.000161659 -1 0.000777638 0.000108486 -1 -0.000522396 -0.000116525 -1 0.000183994 0.000157304 -1 -0.000283168 -0.00647596 0.0359916 0.999331 -0.11019 0.00712547 0.993885 0.00695476 0.0137674 0.999881 0.0927706 -0.0279036 0.995296 -0.0447128 0.0108217 0.998941 0.648214 0.712837 -0.267735 -0.162861 -0.00833846 0.986614 -0.290374 0.233651 0.927949 -0.186484 -0.00126638 0.982457 -0.187168 0.0296614 0.98188 -0.105174 -0.0522197 0.993082 0.999843 -0.00459637 0.0171206 0.785144 -7.99878e-05 0.619314 0.738215 0.0196165 0.674281 0.659279 0.00393121 0.751888 0.660165 0.00419745 0.751109 -0.669846 0.00352191 0.742491 -0.668643 0.003098 0.743577 -0.994113 0.000196827 0.108352 -0.999081 0.0201342 0.0378401 -0.990104 -2.63027e-09 0.140333 -0.974349 -4.99016e-09 0.225042 -0.957906 0.00470094 0.287045 -0.949886 -1.17477e-08 0.312597 -0.890194 -2.02045e-08 0.455582 -0.890194 -1.65876e-08 0.455582 -0.80726 -2.61744e-08 0.590197 -0.793092 0.00562917 0.609076 -0.524491 0.00514268 0.8514 -0.505973 0 0.862549 -0.361843 0 0.932239 -0.361843 0 0.932239 -0.239831 3.29277e-08 0.970815 0.51342 -0.00019843 0.858138 0.514046 0 0.857763 0.34973 0 0.936851 0.34973 -3.31751e-08 0.936851 0.174503 7.40662e-08 0.984657 0.134316 -0.0101099 0.990887 -0.0705811 0.829963 -0.553336 0.992655 0.00586155 0.120841 0.988315 -2.81306e-09 0.152426 0.954115 -6.63987e-09 0.299439 0.954115 -1.65876e-08 0.299439 0.884214 -2.07144e-08 0.467081 0.884214 0 0.467081 0.80258 0 0.596545 0.988548 -0.14034 -0.0554745 -0.996741 0.000182311 0.0806719 -0.996744 0.000166401 0.0806367 -0.967589 1.21512e-05 0.252528 -0.96747 0.000223803 0.252987 -0.909038 9.26206e-05 0.416712 -0.909136 -1.13639e-05 0.4165 -0.822867 -2.27693e-05 0.568234 -0.822804 2.51835e-05 0.568326 -0.711734 -0.00388701 0.702439 -0.705129 -5.38977e-05 0.709079 -0.578891 -2.01481e-05 0.815405 -0.578665 9.90236e-05 0.815565 -0.433717 9.53896e-05 0.901049 -0.428415 -0.00245158 0.903579 -0.265099 5.87365e-05 0.964221 -0.264453 0.000367723 0.964399 -0.0936359 -0.000266278 0.995606 -0.0930642 -1.14716e-05 0.99566 0.0806727 -2.26787e-05 0.996741 0.0809115 8.04826e-05 0.996721 0.252529 4.22722e-05 0.967589 0.252743 0.000137672 0.967533 0.416706 7.10845e-05 0.909041 0.418473 0.000936625 0.908229 0.568167 -0.00946544 0.822859 0.588404 0.000165176 0.808567 0.702456 -0.00385961 0.711717 0.709135 -5.40942e-05 0.705073 0.815421 -2.03457e-05 0.578869 0.815546 7.31937e-05 0.578692 0.902571 0.000114189 0.430541 0.90356 -0.000902015 0.428461 0.964236 9.58197e-05 0.265044 0.964213 5.60013e-05 0.265129 0.995604 -6.12909e-05 0.0936631 0.995618 5.82421e-07 0.0935199 0.000115702 -1 -1.90788e-05 0.000252025 -1 -0.000153644 7.49987e-05 -1 -5.43778e-05 4.23379e-05 -1 -1.96233e-05 3.28821e-08 -1 -3.39778e-08 0.000383907 1 -0.000197131 3.45351e-05 1 -8.22829e-06 -2.76953e-08 1 3.15761e-08 -3.28821e-08 1 3.39778e-08 1.25074e-05 1 -2.03076e-06 -0.999971 -0.00494238 -0.00571195 -0.999963 -0.00574312 -0.00633691 0.883807 0.0192599 0.467455 0.892238 0.00636555 0.451521 0.855648 -0.00512457 0.517532 0.793911 0.0215576 0.607652 0.775133 0.00465101 0.631781 0.757515 -0.00237549 0.652813 0.296195 0.0554831 0.953515 0.355186 -0.00537309 0.93478 0.16753 0.0224494 0.985611 0.177347 0.0179738 0.983984 -0.898027 0.00368382 0.439925 -0.964483 0.00203261 0.264136 -0.963578 -0.00100532 0.267424 -0.996194 0.0153128 0.0858037 -0.997786 0.00146867 0.0664955 -0.998072 -1.92039e-05 0.0620683 0.95868 -0.0023238 0.284476 0.885684 0.0182716 0.463928 0.668868 0.00846289 0.743333 0.636807 -0.00325018 0.771017 0.520893 0.00846043 0.85358 0.456445 -0.012207 0.889668 0.0448953 0.0131355 0.998905 0.0809764 -0.0159752 0.996588 -0.0064802 0.00882674 0.99994 -0.157119 -0.00305166 0.987575 -0.190934 0.00761225 0.981573 -0.329295 -6.84573e-05 0.944227 -0.367414 -0.0193223 0.929857 -0.531891 0.0122166 0.846725 -0.536963 0.0075225 0.843572 -0.678471 -3.09776e-05 0.734627 -0.676334 0.00114255 0.736594 -0.798701 -0.0011116 0.601727 -0.801906 0.00078748 0.59745 -0.895526 -0.000818049 0.445008 -0.8941 0.00134012 0.447865 0.988946 -0.0688024 -0.131347 0.585682 0.061555 -0.8082 0.01621 -0.0474526 -0.998742 0.587468 -0.00336649 0.80924 0.620781 -0.0223985 0.783664 0.882234 0.0348665 -0.469519 0.781471 -0.0249272 -0.623443 -0.127576 -0.00510322 0.991816 -0.114554 -0.0110236 0.993356 0.952946 0.0302853 0.301624 0.993189 -0.0330979 0.111718 -0.799945 0.0158247 0.599864 0.433714 0.0783814 0.897635 0.942078 -0.0351883 0.333543 0.146875 0.0138299 -0.989058 -0.0580697 -0.0312482 -0.997823 -0.835543 0.0504421 -0.547105 -0.978401 -0.0430157 -0.202191 0.841453 -0.0119583 -0.540197 0.805589 -0.0334029 -0.591533 0.00597306 0.0533974 -0.998555 -0.374022 -0.0551701 -0.925777 -0.992468 0.0211247 -0.120673 0.239518 -0.0290542 -0.970457 -0.574624 0.0429766 -0.817288 -0.643008 0.019122 -0.765621 0.959531 0.0112565 0.281378 0.822496 0.0196121 -0.568433 0.777032 -0.00722151 -0.62942 0.981365 -0.0288621 0.189971 0.972391 -0.0180603 0.232658 -0.714904 0.0436295 0.69786 0.640359 -0.00852098 0.768029 -0.967731 0.0231922 -0.250917 -0.395405 -0.0209568 0.918268 -0.234208 0.0157491 0.972059 -0.605772 -0.0191158 -0.795409 -0.720448 0.0129947 0.693387 -0.317374 0.0962246 -0.943406 0.998895 0.0415032 0.022049 -0.287638 0.103087 0.952175 0.167655 0.00350154 -0.98584 0.150637 -0.00254988 -0.988586 2.57778e-05 1 0.000210906 0.000130258 1 0.000240562 0.00013147 1 0.000173684 0.000156357 1 0.000144691 0.000252779 1 0.000147043 0.000212135 1 4.5141e-05 0.000239163 1 2.51215e-05 9.67481e-05 1 -0.00012679 -6.39622e-06 1 1.98531e-06 0.000105492 1 4.38899e-05 9.4613e-05 1 -1.83101e-05 0.000152056 1 -0.00017225 7.49368e-06 1 -0.000253757 2.90683e-05 1 -8.38097e-05 -9.74305e-06 1 -0.000131144 -4.74092e-05 1 -9.7645e-05 -5.57217e-05 1 -0.000102839 -7.32363e-05 1 -4.74156e-05 -8.40364e-05 1 -4.88844e-05 -8.98722e-05 1 -9.08281e-05 -0.00025458 1 -2.66455e-05 -0.000255728 1 8.50059e-05 -0.000241302 1 7.1494e-05 -0.000207907 1 0.000189534 -0.000192415 1 0.000156174 -9.77167e-05 1 0.000225706 -5.43637e-05 1 0.000453067 -6.33405e-05 1 0.000170523 1.67358e-05 1 0.000225268 0.000197881 -0.999998 -0.00210583 0.000329102 -0.999998 -0.00177405 0.000519887 -0.999998 -0.00190247 0.000654632 -0.999998 -0.00168657 0.000845305 -0.999998 -0.00177889 0.000951897 -0.999998 -0.0015452 0.00113715 -0.999998 -0.00160351 0.00121704 -0.999998 -0.00134903 0.00139567 -0.999998 -0.0013775 0.00144525 -0.999998 -0.00110992 0.00158826 -0.999998 -0.0011111 0.0016062 -0.999998 -0.000822016 0.00175782 -0.999998 -0.000799768 0.00174492 -0.999998 -0.000523068 0.0018579 -0.999998 -0.000488358 0.00179443 -0.999998 -8.10267e-05 0.00170404 -0.999999 -0.000118168 -0.00163148 -0.999999 -8.44287e-05 -0.00171943 -0.999999 -0.000135303 -0.00177967 -0.999998 -0.000558717 -0.00140357 -0.999999 -0.000248417 -0.000905377 -1 -0.000314206 -0.00137653 -0.999998 -0.00157456 -0.00343152 -0.999994 -0.000880994 -0.00508734 -0.999974 -0.00513967 -0.00326109 -0.999947 -0.00974537 -0.000873801 -0.999999 -0.00124318 -0.000849153 -0.999998 -0.00184141 -0.000308208 -0.999998 -0.0020102 -0.000267357 -0.999997 -0.00255245 -0.000451988 -0.999998 -0.00208803 -0.00163393 -0.999999 0.000148069 -0.00179619 -0.999998 8.1376e-05 -0.00185967 -0.999998 0.000488155 -0.00174578 -0.999998 0.000523139 -0.00175904 -0.999998 0.000808975 -0.00162013 -0.999998 0.000829149 -0.00160193 -0.999998 0.00110436 -0.00143649 -0.999998 0.00110319 -0.00138654 -0.999998 0.00137604 -0.00121704 -0.999998 0.00134903 -0.00113721 -0.999998 0.0016033 -0.000951984 -0.999998 0.001545 -0.000845396 -0.999998 0.00177869 -0.000654514 -0.999998 0.00168627 -0.000519672 -0.999998 0.00190232 -0.000339508 -0.999998 0.00178105 5.29918e-05 -0.999997 0.00225695 -0.000179564 -0.999997 0.00246581 -1.24026e-05 -0.999998 0.0019139 0.000387003 -0.999999 0.00144254 0.000332592 -0.999998 0.0018767 0.000643199 -0.999999 0.00139253 0.000659577 -0.999998 0.00176686 0.000894711 -0.999999 0.00127287 0.000970119 -0.999998 0.00162112 0.00113019 -0.999999 0.00113011 0.00124481 -0.999998 0.00141629 0.00123355 -0.999998 0.00147327 0.00064418 -1 0.000508123 0.000656923 -1 0.000347016 0.00140375 -0.999999 0.000248395 0.00177964 -0.999998 0.000558521 0.00171444 -0.999999 0.000100261 0.00170155 -0.999999 9.28009e-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 1.22659e-07 1 1.33574e-07 0.0494474 0.998769 0.00405684 0.0456245 0.998946 0.0050021 0.0466386 0.998896 0.00567738 0.000211849 1 -0.000192807 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 8.61562e-08 1 -7.42681e-08 0.000445818 0.999996 -0.00290232 0.000378418 0.999999 0.00143144 0 1 0 0 1 0 8.48162e-10 1 2.82876e-07 -2.34294e-07 1 -8.1447e-08 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.0197464 0.999803 0.0022331 -0.0255814 0.99967 -0.00223424 0.0155554 0.999856 -0.00682813 0 1 0 1.28828e-07 1 5.78602e-08 -3.11853e-07 1 2.83821e-07 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.000740893 0.999993 0.00364964 -0.00094573 0.999998 0.00148515 0 1 0 0.697656 0.712675 0.0732812 0.902888 -0.340017 0.263022 0.552358 0.769195 0.321309 0.663173 -0.526385 0.53209 0.473804 0.173716 0.863327 0.460669 0.25484 0.8502 0.0768274 -0.254843 0.963926 0.0729624 -0.173709 0.982091 -0.286643 0.569046 0.770728 -0.351962 -0.569044 0.743177 -0.754304 0.173709 0.633128 -0.709803 0.405305 0.576114 -0.933985 0.202139 0.294638 -0.876712 0.404849 0.259755 -0.887981 0.248889 -0.386709 0.319296 -0.133617 0.938188 -0.0437916 0.118814 0.99195 0.887304 -0.00674296 0.461136 -0.275851 0.949043 0.152392 -0.927542 -0.0123803 0.373513 -0.658799 0.30777 0.686485 0.547733 0.218916 -0.807505 -0.544739 0.814583 -0.199284 -0.000299207 1 -0.000640478 0.148503 0.988765 -0.0170309 -0.0844653 0.977431 0.193633 0.148574 0.980014 -0.13228 0.1153 0.953318 -0.279089 -0.155419 0.987536 0.0248659 -0.203477 0.967564 0.149725 0.909274 0.17911 0.375686 -0.403837 0.0250467 0.914488 -0.506423 0.194258 0.840119 0.00123551 0.999997 -0.00202803 0.745281 -0.255523 -0.615845 -0.00548913 0.999982 -0.0023267 -0.810119 0.584843 0.0408191 -0.193355 0.655087 0.730393 -0.105977 0.949487 0.295369 0.252062 0.966814 0.0416662 -0.0691439 0.995378 0.0666482 0.158705 0.776511 0.60979 -0.693738 0.714911 -0.0873512 0.0150444 0.999878 0.00411568 0.782771 0.582845 0.218087 0.00448812 0.661071 -0.75031 0.380416 0.885859 0.26559 0.610225 -0.312686 -0.72791 0.309476 0.823754 -0.47503 -0.0364844 0.901776 -0.430662 -0.76034 -0.12828 -0.636732 -0.520463 0.790454 -0.322956 0.153937 -0.987839 -0.0218409 -0.242631 0.725957 0.643519 0.0481245 0.955741 0.290246 0.0882501 0.936904 0.338264 0.084809 0.933573 0.348209 0.0327934 0.979362 -0.199436 -0.000197437 1 0.000108216 0.000478199 0.999997 -0.00222074 0.00387838 0.99999 -0.00226694 -0.00416301 -0.999846 -0.017043 -0.000683095 0.999999 0.00135032 0.0234923 0.999683 -0.00900644 0.0123825 0.999923 -0.000449892 -0.132158 0.990808 0.0288627 0.00744561 0.999927 0.00955378 0.00353647 0.999948 -0.00951995 0.0185737 0.999715 -0.0150066 0.0260495 0.999563 -0.0139441 0.00578011 0.999983 -0.00106444 0.760042 0.550166 0.34591 -0.00107887 0.999999 0.000514709 -0.000872635 0.999999 0.000854837 0.0368292 0.999029 0.0241686 0.00530827 0.999986 -0.00054445 0.00326344 0.999951 -0.00936984 0.000149763 -1 -0.000411159 -1.08288e-05 1 0.00013065 8.55694e-05 1 0.000115984 1.20746e-05 1 -5.20883e-06 0.00517844 0.999967 0.00631915 -0.000284558 0.999999 0.00155888 -1.3765e-05 1 -0.000137807 -0.00507923 0.998978 -0.0449102 -0.00893593 0.999715 -0.0221526 0.00558012 0.999982 0.00197883 0.0103589 0.999879 -0.0115707 -0.00328662 0.999969 -0.00719376 -0.0599458 0.998194 -0.00382467 -5.8807e-05 0.999999 -0.00153594 -0.000426797 -1 -0.000123185 -0.0132841 0.999904 -0.00406801 0.00526831 0.999961 0.00705927 2.493e-05 0.999897 -0.0143393 0.000143198 0.999997 -0.00260767 4.58525e-05 1 -6.51722e-05 0.00291077 0.999995 0.00100527 -0.000901839 0.999997 -0.00246755 -0.00378284 0.999993 0.000501833 2.40006e-05 1 1.56962e-05 -0.000307902 1 0.00010608 0.00997711 0.99995 0.000972264 0.0111869 0.999933 0.00308964 0.00228202 0.999997 0.000434263 0.00456947 0.999954 0.00838078 0.00853749 0.999936 0.00738667 -0.00203457 0.999997 0.00128241 0.00205532 0.999997 -0.00094486 -0.00106483 0.999999 -0.000710836 -0.0144033 0.999517 0.0275288 0.000777399 0.999991 0.0040898 2.26096e-05 1 -0.000175624 -0.00806465 0.9997 -0.0231393 -0.00509173 0.999987 -0.000607052 -0.00640929 0.999961 0.006157 -0.000210257 1 5.619e-06 0.0521917 -0.953337 -0.297364 -0.000137092 1 2.03275e-05 -0.00641013 0.999963 0.00569661 0.00986842 0.999949 0.00216528 0.024376 0.998779 -0.0429689 -0.00363103 0.99999 -0.00275749 -0.000637515 0.999998 -0.00185306 -0.00411523 0.999991 -0.00100918 -0.00719097 0.999969 -0.00317258 -0.216576 0.975957 0.0245371 -0.00819743 0.999827 0.0167016 -0.0165751 0.999595 0.0231357 0.000702573 1 -0.000432027 0.0144636 0.999133 0.0390413 -0.00443138 0.999977 0.00511884 -0.00369804 0.999993 -0.000367017 0.00296536 0.999933 -0.0111965 -0.183046 0.945695 -0.268619 -0.283806 0.958292 -0.0336342 0.545932 0.370222 0.751595 0.683884 0.582127 0.439808 -0.22026 0.277017 0.935279 0.952015 0.125416 0.279174 0.643323 0.410026 -0.646541 -0.548447 0.767431 -0.332048 0.802303 -0.397538 0.445278 -0.802303 0.397538 -0.445278 -0.851334 -0.493022 0.179334 0.999968 -0.000637039 0.00798526 0.999981 -0.000113339 0.0061445 0.00647634 9.6411e-08 -0.999979 0.00638897 -1.63312e-05 -0.99998 0.00648053 -7.20197e-07 -0.999979 0.00647994 2.47005e-06 -0.999979 0.00648045 1.65137e-05 -0.999979 0.00647774 2.77153e-06 -0.999979 0.00595406 0.0011438 -0.999982 0.00648048 0 -0.999979 -0.978762 -0.0328184 -0.202357 0.00648245 -2.46651e-06 -0.999979 0.00640878 3.06346e-06 -0.999979 0.0064827 6.78496e-06 -0.999979 0.00647815 3.8861e-06 -0.999979 0.00648106 2.80081e-08 -0.999979 0.00648246 1.73663e-06 -0.999979 -0.989698 0.0050139 -0.143084 0.00648043 -3.9401e-08 -0.999979 0.00648053 -1.9509e-08 -0.999979 0.00648057 1.00431e-07 -0.999979 0.00647137 1.43458e-06 -0.999979 0.00648097 2.08425e-07 -0.999979 0.0064806 -7.78118e-08 -0.999979 0.00522446 -0.00340118 -0.999981 0.00374073 -0.00186667 -0.999991 0.00911909 -0.00227264 -0.999956 0.00647159 8.19994e-06 -0.999979 0.00643071 4.601e-06 -0.999979 0.008297 -0.000724794 -0.999965 0.00646877 3.1028e-06 -0.999979 0.00645323 8.20934e-05 -0.999979 0.00642673 -4.52964e-05 -0.999979 0.00647852 2.36695e-05 -0.999979 0.00647278 2.79802e-05 -0.999979 0.00652934 -0.000106038 -0.999979 0.0065381 -6.58678e-05 -0.999979 0.0065357 5.79774e-05 -0.999979 0.00632437 0.000984987 -0.99998 0.00660791 -1.27552e-05 -0.999978 0.00646179 4.79424e-06 -0.999979 -0.99997 0.00418358 -0.00654054 -0.999969 0.00356835 -0.00695118 -0.99998 -8.1827e-05 -0.00635957 -0.999978 9.59323e-05 -0.00662252 -0.869286 -2.65447e-05 0.49431 0 1 0 0 1 0 0 1 0 0 1 0 0.462214 0.731025 -0.501957 -0.525197 0.688903 -0.499581 -0.470674 0.702687 -0.533571 0.650107 0.31127 -0.693161 -0.298335 0.914652 0.27278 -0.46177 0.748052 -0.476641 0.94301 -0.015424 -0.332406 -0.0676973 -0.959346 -0.273992 0.63428 -0.139434 0.760426 -0.532262 -0.845164 0.0489431 -0.177172 -0.982901 0.0501506 -0.156106 -0.98489 0.0749842 -0.161035 -0.98342 0.0833892 -0.0730957 -0.993698 0.0849798 -0.25056 -0.421094 0.871722 0.360147 -0.26691 0.893898 0.266238 0.201566 0.942597 -0.299767 -0.947074 -0.114849 0.417364 0.892673 0.170126 0.0710106 -0.99741 0.0114608 0.999981 0.000847704 0.00619099 0.999979 0 0.0064055 0.999378 0.0348098 0.00573317 -0.997778 0.0666192 -0.000442528 -0.977568 0.208612 -0.0290031 0.000582726 1 0.000233858 -0.000332132 1 0.000230718 -0.000112346 0.999999 0.00105335 0.000331604 1 0.000157484 -0.000518289 1 0.000495143 0.99962 -0.0261537 0.0087287 -0.998497 -0.0533837 -0.0124257 -0.99879 -0.0479141 -0.0111224 0.000146964 -1 0.000203344 0.000916338 -0.999999 -0.000720488 0.00207212 -0.999998 -0.000342895 3.59058e-05 -1 -2.84512e-05 6.69066e-05 -1 -6.97758e-05 -4.39996e-08 -1 -2.95957e-08 -1.19352e-07 -1 1.97504e-08 -0.253423 -0.0519099 -0.965962 -0.282445 -0.0086618 -0.959244 0.371741 0.00317987 0.928331 0.326008 -0.0634868 0.943233 0.771676 0.00848343 -0.635959 0.757252 0.0304648 -0.652412 0.0631812 -0.994813 -0.0797258 0.0303503 -0.999533 -0.00348643 -0.0125726 -0.999898 -0.00678263 0.0419476 -0.998844 0.0234705 0.580834 -0.793609 0.181153 0.54038 0.679459 -0.496311 0.93116 0.219725 0.290969 0.555927 -0.00685799 -0.831203 0.996865 -0.00350671 -0.0790434 0.987892 -0.135363 -0.0758076 -0.107018 -0.992578 -0.0577672 -0.331029 -0.943599 0.00646905 -0.797615 -0.470061 -0.377959 -0.789729 0.482999 -0.378207 -0.356952 0.933688 -0.0285101 -0.990635 0.136443 0.00515995 0.570077 0.821584 -0.00348914 0.788066 0.615241 0.0207654 0.618598 -0.785444 0.0203744 0.972072 -0.234013 -0.017726 0.975556 0.219153 -0.0162265 0.601755 0.798343 0.0232356 -0.718396 -0.695559 -0.0101958 -0.407294 0.913224 0.0115434 0.787709 -0.615993 0.00815489 0.736521 -0.676255 0.0147091 -0.372624 -0.927914 -0.0112701 -0.536752 -0.843677 0.0103135 0.784804 0.619181 -0.0264178 0.329102 0.944039 0.0219799 0.415059 0.909791 0.00268982 -0.464753 0.885026 0.0271111 -0.325777 0.945444 -0.00211125 -0.317067 -0.946346 -0.0624379 -0.00240929 0.999953 -0.00944118 -0.00338123 0.999994 0.000917849 -8.89137e-05 1 2.84844e-05 -0.000200028 1 0.00038015 -1.37031e-05 0.999998 -0.00215891 -0.899759 -0.435741 -0.0237297 -0.780078 -0.62547 0.0162838 -0.728693 -0.527045 0.437298 -0.989143 0.146937 0.00230487 -0.784871 0.619637 0.00529125 -0.706924 0.707097 -0.0165127 -0.994051 0.00420377 0.108837 -0.693956 0.602605 0.394072 -0.869363 -0.000142616 0.494174 0.822935 0.551632 -0.135943 0.514181 0.856612 0.0428221 0.949512 0.000461182 0.313731 -0.9602 0.021349 -0.278495 -0.494489 0.868527 0.0338032 -0.746809 -0.0130396 -0.664911 0.470976 -0.822944 -0.317716 -0.474204 0.816415 0.329541 -0.665219 0.0104986 -0.746575 -0.27314 0.49926 -0.822274 -0.517454 -0.675412 -0.525413 -0.149963 -0.329233 -0.932265 -0.0724423 -0.958461 -0.27587 0.120736 -0.977573 -0.172551 -0.93865 0.325499 0.113956 0.173742 -0.865695 -0.469452 -0.601247 0.777735 0.183387 0.841888 0.518487 -0.149651 -0.924282 0.323561 -0.202512 -0.590579 0.804607 0.0618415 0.935749 0.352627 -0.00541574 -0.64528 0.759735 0.0801031 0.191414 0.977527 -0.0883213 0.979125 0.178394 0.0974124 -0.803838 0.58867 0.0855091 0.446646 0.892183 -0.0672 0.825502 0.562645 0.0444718 0.00452599 0.715695 -0.698399 0.00245826 0.518083 -0.855327 -0.0151111 0.455218 -0.890252 -0.00170749 -0.529017 -0.84861 0.000947817 -1 -0.000159816 -1.04485e-07 -1 2.95862e-07 -4.562e-08 -1 2.35583e-07 5.06655e-08 -1 -3.71256e-08 1.84528e-10 -1 -2.84731e-08 3.07433e-09 -1 -2.718e-08 0.0589886 0.00883038 0.99822 0.0936876 -0.0105146 0.995546 -0.882547 -0.0576918 -0.466672 -0.826157 0.516867 0.224307 -0.230467 0.94107 -0.247533 0.449887 0.821165 0.351125 0.861475 0.441762 -0.250414 -0.102681 0.000276809 0.994714 -0.102794 0.000609548 0.994703 -0.106953 -0.000293562 0.994264 -0.106882 -0.000850023 0.994271 0.405281 0.911749 0.0667971 -0.840672 -0.0225743 -0.541073 -0.829757 0 -0.558124 -0.832145 -0.00035572 -0.554559 -0.831062 -0.00106964 -0.556179 -0.838735 -0.000964849 0.54454 -0.837725 -0.00205182 0.546089 -0.839189 -0.000941264 0.54384 -0.904959 -0.13957 0.401958 0.874762 0.00330555 0.484541 0.883298 7.76248e-05 0.468813 0.88334 0.000137225 0.468733 0.883468 -0.00030563 0.468492 -0.99956 0.0258127 0.0146255 0.410069 -0.0152571 0.911927 0.0118901 0.0186152 0.999756 0.923359 0.000366863 -0.383938 0.923655 0.00103993 -0.383224 0.923873 0.000138598 -0.3827 -0.832569 0.000438411 -0.553921 -0.833456 3.48988e-05 -0.552586 -0.833359 -9.98098e-05 -0.552732 -0.833353 -8.36338e-05 -0.552741 0.239243 -0.238276 -0.941269 0.196162 -0.303195 -0.93252 0.417626 -0.155503 -0.895213 0.563462 -0.337937 -0.753862 0.699852 -0.152481 -0.697823 0.843901 -0.27961 -0.457875 0.844041 -0.265747 -0.465803 0.970021 -0.196209 -0.143396 0.965802 -0.22852 -0.122492 -0.323379 -0.307277 -0.89499 -0.349265 -0.23397 0.907344 -0.533721 -0.123112 -0.836651 -0.459693 -0.281864 -0.842161 -0.702108 -0.158883 -0.694119 -0.756943 -0.329784 -0.564163 -0.891179 -0.162232 -0.423653 -0.930185 -0.293078 -0.221047 -0.942089 -0.265654 -0.204686 -0.986702 -0.158891 0.0342543 -0.94412 -0.298633 0.139484 -0.905738 -0.188586 0.379572 -0.903472 -0.161869 0.396909 -0.792084 -0.280007 0.542401 -0.681361 -0.188585 0.707236 -0.676127 -0.172729 0.716252 -0.513927 -0.270768 0.81398 -0.398248 -0.187729 0.897862 0.897479 0.015272 -0.440794 0.443108 -0.0449082 -0.895343 -0.310034 -0.00292286 -0.950721 -0.136227 0.0173371 -0.990526 0.530776 0.784972 0.319524 0.686522 0.596557 0.4157 0.974374 0.0564763 -0.217731 0.98305 0.151538 0.103199 0.859799 0.105416 0.499633 0.179356 -0.977534 -0.110723 0.475407 0.00691475 0.879739 -0.456202 -0.0997221 0.884271 -0.990422 0.0514864 -0.128111 -0.179374 -0.977529 0.110733 -0.818381 -0.14385 -0.55638 -0.989869 -0.0167488 -0.140996 -0.184826 -0.981956 -0.0400176 0.378506 0.923601 -0.0607848 0.108803 0.978438 -0.175561 0.429322 -0.889015 0.159173 -0.681548 -0.230083 0.694661 0.896645 -0.255127 0.361853 0.912578 -0.228501 0.3391 -0.912578 0.2285 -0.3391 -0.896645 0.255127 -0.361853 0.0366771 0.998088 0.049751 0.102542 -0.994305 -0.0290419 0.158847 -0.986658 -0.0356947 -0.0150575 -0.96336 -0.267789 -0.0154463 -0.967134 -0.253796 0.486753 0.873538 -0.00133777 0.720356 -0.692729 0.0348496 0.0529198 -0.995243 0.0817941 -0.20216 -0.977881 0.0536683 -0.0746408 -0.994785 -0.069509 0.0667214 0.972775 -0.221938 -0.274419 0.787728 0.551525 -0.110673 0.841996 0.52801 0.239306 0.368037 0.898488 0.840113 0.492212 0.227897 0.705423 0.645018 -0.293819 0.632157 -0.459324 -0.624018 0.589026 0.154129 -0.79328 0.242952 0.586469 -0.772676 -0.228234 -0.651437 -0.72356 -0.563966 0.54346 -0.621766 -0.823265 -0.511793 -0.245566 -0.843083 0.535105 0.0535978 -0.588565 -0.646196 0.485821 0.751651 -0.551394 -0.361919 0.850639 -0.421291 -0.314527 0.495017 -0.868793 -0.0125015 0.68623 -0.532867 0.495117 0.498079 0.654048 0.569332 -0.0582764 -0.646485 0.760698 -0.371548 0.774405 0.512103 -0.55503 -0.787733 0.267244 -0.542445 -0.821711 0.17477 -0.869073 0.458003 -0.186937 -0.676121 -0.382983 -0.629432 -0.474647 0.496493 -0.726777 0.0582654 -0.646496 -0.760689 0.375649 0.458038 -0.80566 0.921523 -0.0589133 -0.383828 0.968108 0.242577 -0.0626413 0.896996 -0.0864413 0.433504 0.785006 0.135474 0.604494 0.495056 -0.121342 0.860346 -0.188311 0.396725 0.898414 0.0642602 -0.0979245 0.993117 -0.596561 0.209598 0.774715 -0.820453 -0.25885 0.509757 -0.983548 0.169067 0.0636397 -0.872269 -0.182395 -0.453739 -0.789519 0.0838596 -0.60797 -0.114004 -0.0848444 -0.989851 -0.0645659 0.00503111 -0.997901 0.586744 0.176931 -0.790207 0.598055 0.197813 -0.77666 0.782383 -0.209594 -0.58647 0.992201 0.0979246 0.0771224 0.994317 -0.103459 -0.0251112 0.598015 -0.0770349 0.797774 0.460879 0.195981 0.865553 -0.0763747 -0.169065 0.982641 -0.520349 0.258849 0.813778 -0.782383 -0.209595 0.58647 -0.992201 0.0979241 -0.0771217 -0.992609 0.0949235 -0.0756088 -0.597686 -0.0838588 -0.797332 -0.442396 0.182395 -0.878076 0.0763821 -0.169063 -0.982641 0.520348 0.258849 -0.813778 0.741047 -0.342767 -0.577374 -0.956671 -0.266891 0.116402 -0.868321 0.404526 -0.287015 0.854053 0.239288 0.461881 0.754493 -0.63948 -0.147665 -0.082585 -0.900309 0.427345 -0.919055 -0.329192 -0.216727 0.0834082 0.960216 0.266512 0.174583 0.965602 0.192699 -0.430232 -0.708455 -0.559457 0.83981 -0.224932 0.49409 0.865963 -0.197065 0.459646 -0.144688 0.852267 -0.502699 -0.799487 0.212095 0.561993 -0.626296 0.4781 -0.615771 -0.193019 -0.920324 0.340217 0.116455 -0.992207 0.0443148 0.955651 0.282111 -0.084522 0.817215 0.523712 0.240592 -0.809515 0.372446 -0.45384 -0.803829 0.0401798 0.593502 0.103451 -0.925427 -0.364531 0.872488 0.123064 0.472884 -0.905 -0.331139 0.267064 -0.81576 -0.559727 -0.145744 0.737822 -0.630064 -0.242153 0.811844 -0.116823 -0.572068 0.510345 0.831615 0.219009 -0.0163524 0.978761 -0.204353 -0.00799629 0.990592 0.136616 0.00583839 0.98983 0.142138 -7.20579e-05 1 0.000178691 -0.00139711 0.999999 0.00056365 -1.26655e-08 1 3.14082e-08 0 1 0 0.000471666 1 0.000106341 0.00054726 0.999999 0.00102897 0.00026974 0.999991 0.0042074 -0.00152124 0.999965 0.0082877 0.00174044 0.999871 0.0159737 -0.00400755 0.999306 0.0370332 1.14569e-05 0.998889 0.0471321 0.0036794 0.995416 0.0955684 -0.00262327 0.99134 0.131292 1.90547e-05 -1 -0.000264625 -7.17133e-06 -1 -1.96864e-05 0.000344187 -0.999922 0.0124616 -0.000434715 -0.999994 0.00352368 0.00141115 -0.999998 0.00167034 -8.55725e-05 -1 0.000163114 -2.52261e-08 -1 -3.16525e-08 -1.02222e-05 -1 -1.28264e-05 1.41448e-05 -1 -4.45905e-06 0.999979 0 0.00647929 0.999979 0 0.00647929 6.96906e-05 1 -0.000102084 4.47745e-05 1 0.000182746 -0.000321468 1 -0.000574583 -5.3805e-08 1 8.30185e-06 -4.93287e-06 1 1.16515e-06 0.0126996 -0.974624 0.223489 -0.031388 -0.999471 0.00850287 -9.24452e-05 -1 -0.000190559 0 -1 0 0 -1 0 -5.98967e-08 -1 1.03269e-07 -0.99998 -0.000303485 -0.00633286 -0.999973 -0.00045276 -0.0073381 1.14171e-05 -1 -9.39474e-06 0.999966 4.30475e-06 0.00819794 0.999966 4.2713e-06 0.00819816 0.754473 -0.64165 0.138044 0.243601 -0.969192 0.036401 0.0976098 -0.992057 -0.0793375 -0.735194 -0.677247 -0.0287479 -0.812028 0.57951 0.0691287 -0.129392 0.984521 -0.118221 0.10877 0.990419 -0.0850898 0.871544 0.489854 0.0212979 0.770063 0.637948 0.0049905 0.965865 0.25897 0.00625826 0.998513 0.0437464 0.0325431 0.79153 0.611109 0.00500354 0.97274 0.231809 0.00644773 0.685493 -0.728065 0.00448176 0.659784 -0.751455 -0.000302458 0.703368 -0.710812 0.00442872 0.980571 -0.19606 0.00642933 0.976932 -0.213456 0.00632995 -0.87421 0.484679 -0.0290315 -0.999167 -0.000107126 0.0408117 0.941132 -0.00599732 0.337985 -0.703905 2.71888e-05 -0.710295 -0.987043 -0.0659867 0.146259 -0.591471 -0.794926 -0.135111 -0.833292 0.552588 -0.0164769 0.719845 -0.0155134 -0.693961 0.724107 0.00285401 -0.689682 0.719319 -0.00224056 -0.694676 0.706264 -5.53724e-06 -0.707948 0.758519 0.650727 0.0346763 0.518109 0.844125 -0.137902 0.859653 -0.510301 0.0242881 0.677705 -0.403504 -0.614736 0.56069 -0.5938 -0.577086 0.465026 -0.744261 -0.479402 0.171964 -0.969766 -0.173153 -0.168276 0.979479 -0.110925 -0.925614 -0.00885829 -0.378365 -0.565842 -0.539969 -0.623102 -0.393813 -0.824636 -0.406061 -0.16409 -0.984566 -0.0608623 -0.290687 -0.913376 -0.285035 -0.532888 0.598439 -0.598248 -0.667166 0.196741 -0.718458 -0.820211 0.569109 0.0580514 -0.687124 0.350617 -0.636339 -0.57635 0.574473 -0.581208 -0.361645 0.848554 -0.386223 -0.129513 0.984485 -0.118389 0.560196 0.592264 -0.579141 0.68324 0.381228 -0.622774 0.369306 0.82809 -0.421759 0.757236 -0.647692 -0.0841975 0.848185 -0.529699 -0.00069994 -0.244151 -0.968058 0.0570512 -0.785094 -0.590288 0.187585 -0.737634 -0.651304 0.178041 0.970786 -0.0765597 -0.227404 -0.945327 0.238245 0.222703 -0.693896 0.701339 0.163195 -0.681633 0.71396 0.160119 -0.280378 0.957659 0.0653996 0.0200941 0.999661 -0.0165861 0.0257112 -0.999618 0.0101122 0 1 0 -0.00226701 0.999997 0.000163603 0 1 0 -0.00919683 0.998442 -0.0550433 0.0728603 0.996171 0.0483148 -0.0477027 0.998715 -0.0171184 -0.00496386 0.998359 -0.0570441 0.709562 -0.198353 0.676149 0.969451 0.0283362 0.243642 0.97921 -0.181666 0.090254 0.935655 0.0486686 -0.349545 0.790087 -0.267065 -0.551759 0.567189 0.127247 -0.813698 0.0444125 -0.230194 -0.972131 -0.536329 0.106316 -0.837286 0.148206 0.986463 0.0701821 0.741974 0.0857196 0.664926 -0.999979 -7.49807e-06 -0.00647196 -0.999979 -4.00034e-06 -0.00646766 -0.999979 -1.05781e-05 -0.00644298 -0.999979 -1.28791e-05 -0.00646614 -0.998889 0.0467507 -0.0059651 -0.979635 0.00926379 -0.200575 -0.81 0.00440466 -0.586414 -0.7936 0.0878801 -0.602059 -0.930975 -0.156456 -0.329859 -0.931407 -0.218692 -0.290955 -0.800644 -0.0781794 -0.594018 -0.849517 0.135992 -0.509732 -0.818847 0.573972 -0.00675197 -0.97995 0.199173 -0.00537744 -0.187913 0.982185 -0.00120986 -0.999953 -0.00866645 -0.00442205 -0.156425 -0.987689 -0.0010074 -0.189038 -0.98197 -0.000517046 -0.553432 -0.832881 -0.0046253 0 -1 0 0 -1 0 0 -1 0 1.37343e-10 -1 -2.11979e-08 0.0341539 -0.998089 -0.0514977 -0.0600738 -0.996955 -0.0497273 3.60883e-09 -1 -4.04012e-08 -2.58106e-08 -1 -3.07613e-08 -0.0586508 -0.994605 0.0855642 0.0108806 -0.999672 -0.0231765 0.0558415 -0.993625 0.0979346 -0.00720075 -0.995035 0.099262 -0.0125575 -0.997899 0.0635617 -5.75948e-07 -1 -2.52861e-06 0 -1 0 0 -1 0 0.000262573 -1 -5.91044e-06 6.94417e-07 1 0.000118277 2.61073e-06 1 4.297e-06 -1.37343e-10 1 2.11979e-08 -8.1257e-06 1 -2.5691e-06 0.00021557 1 6.81569e-05 0.0270453 0.999559 0.0122994 -0.000105731 1 -1.28655e-05 1.8927e-08 1 3.11519e-08 -0.0413372 0.998645 0.0316096 -0.069144 0.992661 0.0992088 -0.0252357 0.96729 0.252415 2.58106e-08 1 3.07613e-08 1.47485e-08 1 3.4386e-08 -0.0816327 0.996354 -0.0248049 -0.097456 0.994934 -0.0246751 -0.0990585 0.994381 0.037339 0.000103722 1 0.000322633 0.000433346 1 -0.000167474 0.14102 -0.990006 0.000913785 0.135887 -0.990724 0.000868515 0.407091 0.913384 0.00263823 0.135959 0.990714 0.000881048 -0.754914 0.0113982 -0.655724 -0.755383 0.00330052 -0.655275 0 -1 0 0 -1 0 0.0270053 -0.998942 -0.0372214 0.022502 -0.998598 -0.0479223 -0.000869273 -0.999999 -0.000880606 -0.000718518 -0.999999 -0.000821472 0 -1 0 0.0482639 -0.998781 0.0103815 0.0396445 -0.997368 0.0607035 0.0215799 -0.999766 -0.00170095 0.0654762 -0.996897 -0.0437059 0.0720192 -0.997403 -0.0012193 -0.431531 0.131389 -0.892479 -0.497089 -0.0215615 -0.867432 0.073832 -0.0389368 -0.99651 0.209651 0.221164 -0.952435 0.73325 0.0717134 -0.676167 0.992204 -0.124294 -0.00908858 0.915246 0.155595 0.371637 0.749731 -0.0942442 0.654997 0.76974 0.0118871 0.638247 0.94899 0 -0.315307 0.949197 0.000506489 -0.314681 0.97362 0 -0.228174 0.97362 5.66676e-08 -0.228174 -0.755424 -0.00324315 -0.655228 -0.755307 -0.00130847 -0.655369 -0.97322 0 0.229877 -0.97322 0 0.229877 -0.97322 0 0.229877 -0.968401 0.0977641 0.229436 -0.97322 0 0.229876 -0.97322 -2.03433e-06 0.229875 -0.00587096 0.0034776 -0.999977 -0.00571266 -0.00463348 -0.999973 -0.00564321 -3.13407e-05 -0.999984 -0.00577642 -0.000177956 -0.999983 -0.00585591 0.00011542 -0.999983 -0.00580942 -0.000519519 -0.999983 -0.00561618 4.79324e-05 -0.999984 -0.00566302 -1.90377e-05 -0.999984 -0.00590099 0 -0.999983 0.961103 -0.00513555 -0.276142 0.96229 0 -0.272025 0.96229 6.75581e-08 -0.272025 0.988823 0.000812849 -0.149093 0.988276 0 -0.152676 0.979618 0 -0.200868 0.979618 0 -0.200868 0.931063 0.179192 -0.317822 0.514237 0.843403 -0.155669 0.533264 0.830815 -0.159298 0.896575 0.363203 -0.253449 0.934862 0.279347 -0.219086 0.448599 0.88874 -0.0943376 -0.990422 0.137908 -0.00680496 -0.147155 0.989113 -0.000145569 -0.164636 0.986354 -0.000497306 -0.983184 0.182512 -0.00617594 -0.983161 0.182741 -0.000514927 -0.185425 0.978556 0.0896946 -0.39443 0.908615 0.137276 -0.19077 0.973464 0.126388 -0.188985 0.981976 0.00291025 -0.189045 0.981888 0.0125558 -0.213424 0.976856 0.0142174 -0.324492 0.944934 0.042478 -0.309009 0.946895 0.0888959 -0.840406 0.541945 -0.00378562 -0.840434 0.541915 0.000429779 -0.864665 0.502331 -0.00413262 -0.888021 0.45584 0.0602389 -0.86582 0.496457 0.0623444 -0.854536 0.51937 -0.00467902 -0.553346 0.832746 0.0185095 -0.553268 0.832997 -0.00324706 -0.501218 0.865318 -0.00216789 -0.0703918 0.995665 -0.0608034 -0.00372213 0.999987 0.00350656 -0.11492 0.990919 -0.0698137 -0.834831 0.208146 -0.509639 -0.503694 0.83419 -0.224544 -0.235379 0.950417 -0.203234 -0.71537 0.334118 -0.613686 -0.610929 0.578335 -0.540642 0.157001 0.986931 0.0363129 0.135048 0.990833 -0.00355303 -0.100503 0.98861 -0.112021 0.759389 0.556278 -0.337466 -0.435426 0.648471 -0.624412 -0.373674 -0.926058 0.0527736 -0.255324 -0.966619 0.021385 -0.985866 -0.167516 -0.00249255 -0.938133 -0.346268 -0.00237925 -0.996683 -0.0777374 0.0240965 -0.981969 -0.188947 -0.00606114 -0.214376 -0.97639 0.0265747 -0.397808 -0.911865 0.101249 -0.330243 -0.932681 0.145072 -0.999768 0.0183601 -0.0112887 -0.446586 -0.889215 0.0992866 -0.27431 -0.961581 0.0107977 -0.229505 -0.973308 0.000136829 -0.156423 -0.987689 -0.00132623 -0.592096 -0.805868 -0.000172723 -0.464686 -0.879483 0.102841 -0.509458 -0.860492 -0.00252839 -0.682382 -0.730277 0.0323969 -0.843291 -0.533948 -0.0613169 -0.845156 -0.534493 -0.00535842 -0.859225 -0.511572 -0.0051258 -0.643528 -0.715751 -0.271241 -0.337663 -0.937603 -0.0829754 -0.575769 -0.624215 -0.528059 -0.625407 -0.568332 -0.534664 -0.652273 -0.504216 -0.565956 -0.255281 -0.940627 -0.223726 -0.125669 -0.986692 -0.103181 -0.475113 -0.614394 -0.629911 -0.367304 -0.324504 -0.871656 -0.0503611 -0.431761 -0.900581 0.580059 -0.581311 0.570622 0.734769 -0.131139 0.66552 0.215899 -0.974041 -0.0680607 0.441628 -0.883704 -0.155022 0.649673 -0.731361 -0.207451 0.93143 -0.191481 -0.309473 0.940165 -0.122876 -0.317791 0.337517 -0.939157 -0.0637736 0.942446 -0.250632 -0.221311 0.905689 -0.337903 -0.256025 0.476511 -0.872899 -0.10481 0.944203 -0.243962 -0.221276 0.774422 -0.632627 0.00733633 -0.0075722 0 0.999971 -0.184587 0.982816 -0.000489978 -0.00655059 0.000169391 0.999979 0.446353 0.893654 0.0463953 -0.00647894 0.000746539 0.999979 -0.00648094 0.00116144 0.999978 -0.00667553 -4.03221e-05 0.999978 -0.00676748 -9.6728e-05 0.999977 0.140922 -0.989915 0.0144311 0.446988 -0.894429 0.0140859 -0.00647894 -0.000746494 0.999979 -0.00648094 -0.00116136 0.999978 -0.00660602 -0.000388904 0.999978 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0.233589 0.88354 0.405949 0.430359 0.87837 0.207986 0 1 0 0 1 0 0.96078 -0.197442 -0.194729 0.937444 7.04163e-05 0.348136 0.937459 0.000144851 0.348095 -0.937469 -3.11505e-05 -0.348068 0.939063 -0.00634241 0.343687 0.999979 5.72899e-06 0.00647338 0.99998 0.000182304 0.00637355 -0.00248788 -0.991629 0.129093 0.000331037 -0.993828 0.110934 -0.00151523 -0.997551 0.0699215 -0.000205493 -0.999496 0.0317397 -0.00146187 -0.999601 0.0282016 0.00092852 -0.998276 0.0586855 -8.739e-05 -0.999909 0.0134979 0.00124873 -0.999909 0.0134236 -0.000170865 -0.997314 0.0732492 -0.000841686 -0.999563 -0.0295562 -0.0174059 0.995616 0.091898 -0.000278243 -0.987726 0.156199 0.0023843 -0.990803 0.135293 -0.00097369 -0.997832 0.0657994 -0.000467126 -0.995273 0.0971116 -0.00256007 -0.988959 0.14817 0.00198062 0.988456 0.151496 0.0003961 0.988708 0.149857 0.000386274 0.988704 0.149884 0.000118255 0.997008 0.0772994 -0.00192765 0.995665 0.0929917 -0.000879477 0.999752 0.0222365 0.0185233 0.999744 -0.0130273 0.00262642 0.999844 0.0174746 0.903261 -0.38934 -0.180373 0.811135 -0.582093 -0.0568136 0.297123 -0.954831 -0.00401686 0.936713 -0.349992 0.00866323 0.659552 -0.750631 0.0393117 0.659989 -0.751273 0.00155405 0.827092 -0.561978 0.00996248 0.919471 -0.393144 0.00314534 0.107396 -0.994104 0.0149696 0.12565 -0.991705 0.0270793 0.243172 -0.96996 0.00675165 0.33986 -0.93993 0.032056 0.199543 -0.96021 0.195394 0.924019 -0.162721 0.345991 0.160866 -0.968839 0.188344 0.32798 -0.925405 0.189879 0.857635 -0.359396 0.367827 0.250782 -0.955832 0.153274 0.310154 -0.916747 0.251753 0.932515 -0.0922724 0.349144 0.301161 -0.945695 0.12232 0.25862 -0.948059 0.185205 0.915323 -0.169144 0.365478 0.418534 -0.897734 0.137491 0.948622 -0.247138 -0.197582 0.560381 0.81855 -0.126293 0.933944 0.357293 0.00952097 0.673982 0.73872 0.00635745 0.998919 -0.0433604 -0.0167566 0.639225 0.769009 0.00415778 0.0260649 0.999554 0.0145603 0.378348 0.88848 0.259724 0.429765 0.863472 0.26404 0.872199 0.345473 0.346292 0.453032 0.875774 0.166679 0.477454 0.863096 0.16463 0.29054 0.948484 0.126353 0.576759 0.745985 0.332951 0.969275 -0.0387619 -0.242907 0.78966 -0.034209 0.61259 0.995214 9.14111e-06 0.0977202 0.99558 -0.0736469 0.0582821 0.45215 0.891203 0.0362977 0.999112 -0.00211003 -0.0420834 0 -1 0 0 -1 0 0 -1 0 -0.0112479 -0.999699 -0.0217936 -0.00155038 -0.999712 -0.0239619 -0.00229352 -0.999734 -0.0229721 -0.00851855 -0.999903 0.0110625 -0.0113871 -0.999887 0.00984149 0 -1 0 0 -1 0 0 -1 0 5.83119e-06 -0.999773 0.0212888 0.00136998 -0.999775 0.0211724 -0.00409542 -0.999612 0.0275385 0.348097 7.82358e-05 -0.937459 0.349389 -0.000106886 -0.936978 0.348123 -2.85614e-06 -0.937449 -0.937462 -5.85883e-06 -0.348088 -0.93746 0 -0.348093 -0.964241 0 -0.265027 -0.964241 0 -0.265027 -0.995609 0 -0.0936052 -0.995609 0 -0.0936052 -0.999979 0 -0.00648323 -0.999979 0 -0.00648323 -0.999978 -0.00625044 0.00218363 -0.998109 0 0.0614722 -0.98266 5.55863e-05 0.185419 0.00659793 -9.42003e-06 -0.999978 -0.0133311 -0.00173413 -0.99991 -0.0813596 0.0172483 -0.996536 0.00675161 0.00017273 -0.999977 0.00636087 5.27865e-06 -0.99998 0.00646479 -7.14491e-06 -0.999979 0.00652841 -3.768e-05 -0.999979 0.00652913 1.08193e-05 -0.999979 0.00622078 0.000314297 -0.999981 0.00648166 -3.64068e-06 -0.999979 0.169257 -0.135472 -0.976217 0.00647587 -4.15098e-06 -0.999979 0.00645118 1.23893e-06 -0.999979 0.00646999 5.85125e-06 -0.999979 0.00646763 -6.06299e-06 -0.999979 0.00646863 -6.50096e-06 -0.999979 -0.203981 -0.156467 -0.96639 0.00646875 6.50801e-06 -0.999979 0.00644645 3.88403e-06 -0.999979 0.00596797 0.000251586 -0.999982 -0.0253116 0.9995 0.0189734 -0.0231124 0.999613 0.0155039 0 1 0 -0.00242053 0.999973 -0.00699808 -0.00334982 0.999984 -0.00446876 -0.0151164 0.999885 -0.00117497 -0.0219408 0.999759 -0.0004111 0 1 0 -0.000705508 0.999959 0.00907711 0.0118819 0.999804 0.0158509 0.00152461 0.999972 0.00727287 0 1 0 0 1 0 -0.0343056 -0.00121019 0.999411 -0.0224224 0 0.999749 -0.999062 0.0010371 0.0433004 -0.378861 -0.916152 -0.130884 -0.87835 -0.336539 -0.339473 -0.0356999 0.999351 -0.00487205 -0.827567 -0.513219 -0.227461 -0.847733 -0.524402 -0.0797021 -0.924588 -0.380968 -0.000498638 -0.999844 0.0164046 -0.00648235 -0.512028 -0.858899 -0.0109397 -0.701876 -0.702499 0.117755 -0.604806 -0.787002 0.121812 -0.267085 0.961761 0.0606756 -0.983108 -0.00128388 0.183024 -0.840372 0.518296 0.158571 -0.943651 0.252121 0.214376 -0.91832 0.391778 0.056558 -0.987894 0.155 -0.00640487 -0.947173 0.320714 -0.0025457 -0.594264 0.804249 -0.00578599 -0.21863 0.975808 -0.000397782 -0.160704 0.987002 -0.00104087 -0.729655 -0.618535 -0.291578 -0.864794 0.495501 -0.0813061 -0.828918 0.510869 -0.227833 -0.87732 0.335716 -0.342935 -0.193926 -0.976896 -0.0898111 0.0120673 -0.999718 0.0204536 0.0682422 0.996547 -0.0472911 -0.0976134 -0.995221 -0.00251887 0.999983 5.17376e-05 0.00584607 0.999982 -1.4646e-05 0.00598864 -0.99998 -0.000436159 -0.0062796 -0.00649383 -3.44627e-06 0.999979 -0.00635452 -4.46339e-05 0.99998 0.00360969 -0.00378806 0.999986 -0.155181 0.0484949 0.986695 0.00372887 0.00124944 0.999992 -0.00136897 -0.00236325 0.999996 -0.00648508 1.60645e-05 0.999979 -0.00649238 1.20502e-05 0.999979 -0.0102633 -0.00113096 0.999947 -0.00647361 2.14186e-05 0.999979 -0.00646667 4.46174e-06 0.999979 -0.0064958 6.97637e-06 0.999979 0.435491 0.602601 -0.668745 0.00081746 0.00121644 0.999999 0.021193 -0.00121067 0.999775 -0.513159 -0.220659 0.829444 -0.001702 0.010958 0.999939 -0.00653359 -1.68336e-05 0.999979 -0.00647645 -1.19561e-05 0.999979 -0.00616536 0.0380004 0.999259 -0.00457044 0.0581274 0.998299 -0.00674751 0.0108195 0.999919 -0.0166803 0.0136799 0.999767 -0.00364489 -0.0121683 0.999919 -0.0146595 0.0706506 0.997393 -0.00598108 0.000809751 0.999982 0.0195764 -0.0563139 -0.998221 -0.000234243 0.00425288 0.999991 0.0166416 0.0178922 0.999701 0.0668749 -0.025912 0.997425 -0.00150114 0.00176579 0.999997 -0.0118128 -0.00412449 0.999922 -0.00661857 -6.97872e-05 0.999978 -0.0149887 -0.00142752 0.999887 0.000108595 0.032355 0.999476 -0.00274306 -0.00122658 0.999996 0.0359911 0.00529605 0.999338 0.00327226 -0.00384285 0.999987 -0.0267924 0.00402436 0.999633 0.00816592 -0.296043 0.95514 -0.00928221 0.901687 0.43229 0.869398 0.207801 0.448292 -0.714902 -5.32575e-06 0.699224 -0.389093 0.0204635 -0.920971 0.87878 0 -0.477226 0.160243 -0.0128887 -0.986993 0.190349 -0.0369755 -0.98102 -0.00399884 -0.709274 0.704922 -0.0126663 -0.976468 0.21529 -0.125353 0.0478933 0.990956 -0.226622 0.0141285 0.97388 0.559525 0.781628 0.275662 -0.0104544 -0.28326 0.958986 -0.00461121 -0.705678 0.708518 -0.0185763 -0.00497225 0.999815 0.0329574 0.384967 -0.922342 0.00327779 -0.978646 0.205525 + + + + + + + + + + + + + + +

269 0 268 0 314 0 279 1 311 1 315 1 286 2 2 2 3 2 291 3 290 3 305 3 614 4 335 4 4 4 504 5 411 5 4 5 6 6 553 6 554 6 466 7 467 7 4 7 4 8 467 8 761 8 5 9 466 9 481 9 481 10 466 10 4 10 481 11 4 11 480 11 480 12 4 12 411 12 480 13 411 13 390 13 504 14 6 14 503 14 503 15 6 15 554 15 503 16 554 16 537 16 4 17 334 17 330 17 4 18 452 18 465 18 4 19 490 19 358 19 504 20 4 20 6 20 6 21 4 21 502 21 518 22 535 22 502 22 357 23 501 23 358 23 358 24 501 24 4 24 4 25 501 25 502 25 389 26 490 26 388 26 465 27 424 27 479 27 465 28 479 28 4 28 4 29 479 29 388 29 4 30 388 30 490 30 332 31 765 31 766 31 332 32 766 32 452 32 764 33 328 33 330 33 4 34 330 34 452 34 656 35 607 35 7 35 506 36 839 36 9 36 468 37 427 37 9 37 392 38 491 38 9 38 9 39 861 39 540 39 429 40 454 40 7 40 352 41 757 41 654 41 352 42 654 42 656 42 656 43 7 43 351 43 351 44 7 44 454 44 351 45 454 45 568 45 483 46 725 46 429 46 483 47 429 47 7 47 483 48 7 48 395 48 395 49 7 49 493 49 395 50 493 50 394 50 540 51 523 51 524 51 540 52 524 52 9 52 9 53 524 53 8 53 9 54 8 54 7 54 7 55 8 55 493 55 522 56 538 56 506 56 9 57 491 57 506 57 573 58 442 58 427 58 427 59 442 59 9 59 9 60 442 60 392 60 350 61 569 61 468 61 7 62 564 62 349 62 7 63 349 63 9 63 9 64 349 64 350 64 9 65 350 65 468 65 10 66 21 66 542 66 10 67 377 67 413 67 10 68 432 68 469 68 343 69 10 69 622 69 622 70 10 70 469 70 622 71 469 71 754 71 444 72 722 72 432 72 444 73 432 73 10 73 444 74 10 74 485 74 485 75 10 75 413 75 485 76 413 76 415 76 689 77 366 77 377 77 377 78 10 78 507 78 507 79 10 79 542 79 507 80 542 80 546 80 343 81 455 81 428 81 343 82 412 82 362 82 563 83 539 83 525 83 10 84 525 84 840 84 362 85 363 85 10 85 362 86 10 86 343 86 484 87 396 87 412 87 428 88 728 88 443 88 428 89 443 89 343 89 343 90 443 90 484 90 343 91 484 91 412 91 36 92 628 92 13 92 715 93 743 93 13 93 35 94 13 94 628 94 745 95 746 95 36 95 745 96 36 96 13 96 745 97 13 97 471 97 471 98 13 98 743 98 471 99 743 99 742 99 717 100 704 100 715 100 717 101 715 101 13 101 717 102 13 102 699 102 558 103 796 103 798 103 558 104 798 104 559 104 13 105 595 105 987 105 13 106 456 106 430 106 509 107 508 107 559 107 13 108 494 108 509 108 508 109 543 109 544 109 508 110 544 110 559 110 559 111 544 111 556 111 509 112 581 112 582 112 13 113 509 113 559 113 13 114 559 114 699 114 699 115 559 115 798 115 397 116 416 116 494 116 430 117 574 117 486 117 430 118 486 118 13 118 13 119 486 119 397 119 13 120 397 120 494 120 13 121 987 121 456 121 598 122 597 122 17 122 598 123 747 123 737 123 598 124 718 124 495 124 14 125 560 125 528 125 14 126 496 126 417 126 14 127 434 127 16 127 598 128 324 128 565 128 445 129 719 129 434 129 445 130 434 130 14 130 445 131 14 131 399 131 399 132 14 132 417 132 399 133 417 133 418 133 382 134 368 134 496 134 496 135 14 135 528 135 799 136 789 136 510 136 14 137 510 137 845 137 495 138 688 138 14 138 495 139 14 139 598 139 598 140 14 140 16 140 319 141 16 141 571 141 487 142 714 142 718 142 737 143 575 143 744 143 737 144 744 144 598 144 598 145 744 145 487 145 598 146 487 146 718 146 610 147 751 147 748 147 610 148 748 148 747 148 749 149 750 149 17 149 598 150 17 150 747 150 870 151 18 151 23 151 870 152 23 152 18 152 868 153 19 153 843 153 868 154 843 154 19 154 861 155 838 155 860 155 860 156 838 156 861 156 1012 157 855 157 28 157 28 158 855 158 27 158 28 159 27 159 1012 159 1012 160 27 160 855 160 20 161 1005 161 34 161 20 162 34 162 1005 162 864 163 241 163 22 163 22 164 241 164 851 164 22 165 851 165 241 165 22 166 241 166 864 166 32 167 841 167 21 167 32 168 21 168 859 168 859 169 841 169 32 169 306 170 850 170 849 170 306 171 849 171 24 171 24 172 849 172 850 172 24 173 850 173 306 173 25 174 865 174 853 174 853 175 865 175 22 175 853 176 22 176 851 176 851 177 22 177 863 177 851 178 863 178 788 178 843 179 868 179 869 179 843 180 869 180 844 180 844 181 869 181 870 181 844 182 870 182 23 182 23 183 870 183 866 183 23 184 866 184 848 184 848 185 866 185 867 185 848 186 867 186 847 186 847 187 867 187 858 187 847 188 858 188 849 188 849 189 858 189 24 189 849 190 24 190 25 190 25 191 24 191 865 191 843 192 1011 192 868 192 843 193 26 193 1011 193 1011 194 26 194 1584 194 1584 195 26 195 871 195 871 196 26 196 837 196 871 197 837 197 32 197 27 198 28 198 873 198 27 199 873 199 854 199 854 200 873 200 860 200 854 201 860 201 838 201 838 202 860 202 872 202 838 203 872 203 29 203 29 204 872 204 30 204 29 205 30 205 31 205 31 206 30 206 32 206 31 207 32 207 841 207 841 208 32 208 837 208 27 209 33 209 28 209 34 210 874 210 856 210 856 211 874 211 33 211 856 212 33 212 27 212 875 213 20 213 34 213 34 214 20 214 874 214 779 215 878 215 34 215 34 216 878 216 875 216 35 217 628 217 611 217 38 218 589 218 590 218 42 219 347 219 353 219 41 220 40 220 321 220 41 221 321 221 40 221 343 222 622 222 45 222 229 223 178 223 46 223 46 224 55 224 677 224 677 225 55 225 47 225 677 226 47 226 48 226 677 227 162 227 54 227 53 228 167 228 169 228 53 229 169 229 49 229 49 230 56 230 51 230 51 231 56 231 174 231 51 232 174 232 50 232 51 233 52 233 177 233 49 234 895 234 170 234 55 235 46 235 156 235 57 236 566 236 1004 236 977 237 602 237 603 237 75 238 641 238 59 238 75 239 59 239 58 239 58 240 59 240 61 240 58 241 61 241 60 241 60 242 61 242 956 242 956 243 61 243 647 243 956 244 647 244 954 244 954 245 647 245 646 245 954 246 646 246 62 246 62 247 646 247 63 247 62 248 63 248 645 248 62 249 645 249 972 249 972 250 645 250 643 250 972 251 643 251 971 251 971 252 643 252 64 252 971 253 64 253 65 253 65 254 64 254 635 254 65 255 635 255 969 255 969 256 635 256 634 256 969 257 634 257 965 257 965 258 634 258 632 258 965 259 632 259 964 259 964 260 632 260 66 260 964 261 66 261 963 261 963 262 66 262 960 262 960 263 66 263 638 263 960 264 638 264 959 264 959 265 638 265 639 265 959 266 639 266 951 266 75 267 631 267 641 267 951 268 586 268 961 268 961 269 586 269 587 269 961 270 587 270 962 270 962 271 587 271 67 271 962 272 67 272 591 272 962 273 591 273 963 273 963 274 591 274 966 274 966 275 591 275 592 275 966 276 592 276 967 276 967 277 592 277 593 277 967 278 593 278 968 278 968 279 593 279 68 279 68 280 593 280 606 280 68 281 606 281 970 281 970 282 606 282 594 282 970 283 594 283 69 283 69 284 594 284 596 284 69 285 596 285 952 285 952 286 596 286 70 286 952 287 70 287 953 287 953 288 70 288 71 288 953 289 71 289 955 289 955 290 71 290 72 290 72 291 71 291 600 291 72 292 600 292 74 292 74 293 600 293 73 293 74 294 73 294 957 294 75 295 604 295 304 295 78 296 76 296 655 296 944 297 1013 297 140 297 140 298 1013 298 940 298 140 299 940 299 942 299 141 300 942 300 941 300 141 301 941 301 938 301 141 302 938 302 943 302 943 303 938 303 299 303 943 304 299 304 79 304 944 305 296 305 1013 305 370 306 384 306 932 306 403 307 421 307 933 307 438 308 449 308 934 308 776 309 460 309 648 309 650 310 651 310 949 310 91 311 928 311 813 311 91 312 813 312 928 312 82 313 808 313 930 313 810 314 85 314 87 314 87 315 85 315 928 315 87 316 928 316 812 316 812 317 928 317 84 317 812 318 84 318 88 318 88 319 84 319 89 319 90 320 83 320 809 320 809 321 83 321 820 321 820 322 83 322 823 322 83 323 82 323 823 323 823 324 82 324 85 324 91 325 928 325 923 325 923 326 929 326 930 326 107 327 106 327 105 327 922 328 94 328 110 328 96 329 108 329 107 329 97 330 113 330 93 330 97 331 93 331 98 331 93 332 99 332 98 332 98 333 99 333 908 333 908 334 99 334 909 334 99 335 100 335 909 335 909 336 100 336 910 336 910 337 100 337 101 337 100 338 92 338 101 338 101 339 92 339 103 339 92 340 102 340 103 340 103 341 102 341 104 341 102 342 105 342 104 342 104 343 105 343 912 343 105 344 106 344 912 344 912 345 106 345 913 345 106 346 107 346 913 346 107 347 108 347 913 347 913 348 108 348 920 348 920 349 108 349 919 349 108 350 96 350 919 350 919 351 96 351 109 351 96 352 926 352 109 352 109 353 926 353 918 353 926 354 95 354 918 354 918 355 95 355 914 355 95 356 110 356 914 356 914 357 110 357 111 357 110 358 94 358 111 358 111 359 94 359 112 359 112 360 94 360 922 360 112 361 922 361 113 361 113 362 922 362 93 362 911 363 114 363 144 363 86 364 143 364 916 364 151 365 150 365 149 365 137 366 138 366 135 366 134 367 135 367 132 367 117 368 833 368 127 368 126 369 127 369 118 369 119 370 118 370 125 370 121 371 826 371 829 371 829 372 826 372 821 372 829 373 821 373 827 373 827 374 821 374 818 374 827 375 818 375 120 375 120 376 818 376 123 376 123 377 818 377 122 377 123 378 122 378 124 378 123 379 124 379 832 379 832 380 124 380 125 380 125 381 124 381 822 381 125 382 822 382 119 382 119 383 822 383 819 383 119 384 819 384 118 384 118 385 819 385 824 385 118 386 824 386 126 386 126 387 824 387 815 387 126 388 815 388 127 388 127 389 815 389 128 389 127 390 128 390 117 390 117 391 128 391 814 391 117 392 814 392 833 392 833 393 814 393 129 393 833 394 129 394 116 394 116 395 129 395 130 395 116 396 130 396 131 396 131 397 130 397 133 397 131 398 133 398 132 398 132 399 133 399 816 399 132 400 816 400 134 400 134 401 816 401 135 401 135 402 816 402 136 402 135 403 136 403 137 403 137 404 136 404 138 404 138 405 136 405 825 405 138 406 825 406 830 406 830 407 825 407 817 407 830 408 817 408 121 408 121 409 817 409 826 409 813 410 823 410 810 410 813 411 810 411 87 411 813 412 87 412 812 412 811 413 812 413 88 413 811 414 88 414 80 414 80 415 88 415 89 415 80 416 89 416 809 416 924 417 90 417 139 417 140 418 232 418 944 418 140 419 228 419 232 419 141 420 228 420 140 420 141 421 978 421 228 421 943 422 980 422 141 422 141 423 980 423 226 423 141 424 226 424 978 424 943 425 227 425 980 425 227 426 231 426 230 426 944 427 231 427 227 427 232 428 142 428 944 428 944 429 142 429 231 429 976 430 684 430 916 430 916 431 684 431 680 431 976 432 916 432 143 432 674 433 945 433 143 433 143 434 86 434 674 434 674 435 86 435 144 435 674 436 144 436 145 436 145 437 144 437 114 437 145 438 114 438 146 438 146 439 114 439 911 439 146 440 911 440 678 440 911 441 147 441 678 441 678 442 147 442 148 442 678 443 148 443 679 443 679 444 148 444 682 444 148 445 115 445 682 445 682 446 115 446 149 446 682 447 149 447 681 447 681 448 149 448 150 448 683 449 150 449 151 449 683 450 151 450 675 450 675 451 151 451 152 451 675 452 152 452 676 452 676 453 152 453 915 453 676 454 915 454 154 454 154 455 915 455 153 455 154 456 153 456 680 456 680 457 153 457 916 457 677 458 48 458 159 458 979 459 289 459 905 459 981 460 289 460 979 460 907 461 229 461 905 461 905 462 229 462 979 462 906 463 155 463 178 463 880 464 46 464 155 464 155 465 46 465 178 465 156 466 46 466 880 466 55 467 156 467 881 467 55 468 881 468 157 468 55 469 157 469 47 469 158 470 47 470 157 470 883 471 47 471 158 471 159 472 48 472 883 472 883 473 48 473 47 473 677 474 159 474 160 474 677 475 160 475 161 475 677 476 161 476 162 476 887 477 162 477 161 477 163 478 162 478 887 478 164 479 54 479 163 479 163 480 54 480 162 480 54 481 164 481 53 481 53 482 164 482 891 482 53 483 891 483 165 483 166 484 167 484 165 484 165 485 167 485 53 485 893 486 167 486 166 486 168 487 169 487 893 487 893 488 169 488 167 488 895 489 49 489 168 489 168 490 49 490 169 490 49 491 170 491 171 491 49 492 171 492 56 492 56 493 171 493 898 493 900 494 174 494 898 494 898 495 174 495 56 495 173 496 174 496 900 496 172 497 50 497 173 497 173 498 50 498 174 498 50 499 172 499 51 499 51 500 172 500 175 500 51 501 175 501 902 501 51 502 902 502 52 502 903 503 52 503 902 503 176 504 52 504 903 504 904 505 177 505 176 505 176 506 177 506 52 506 289 507 981 507 904 507 904 508 981 508 177 508 906 509 178 509 907 509 907 510 178 510 229 510 190 511 179 511 640 511 640 512 179 512 665 512 640 513 665 513 180 513 180 514 665 514 185 514 180 515 185 515 181 515 181 516 185 516 673 516 181 517 673 517 194 517 181 518 194 518 644 518 644 519 194 519 186 519 644 520 186 520 671 520 644 521 671 521 182 521 182 522 671 522 187 522 182 523 187 523 642 523 642 524 187 524 670 524 642 525 670 525 633 525 633 526 670 526 669 526 633 527 669 527 188 527 633 528 188 528 183 528 183 529 188 529 189 529 183 530 189 530 636 530 636 531 189 531 667 531 636 532 667 532 637 532 637 533 667 533 666 533 637 534 666 534 184 534 184 535 666 535 197 535 663 536 666 536 192 536 666 537 663 537 197 537 661 538 665 538 193 538 198 539 660 539 195 539 195 540 673 540 198 540 198 541 673 541 661 541 661 542 673 542 665 542 660 543 659 543 194 543 194 544 195 544 660 544 196 545 672 545 659 545 672 546 194 546 659 546 672 547 196 547 671 547 671 548 196 548 658 548 671 549 658 549 199 549 199 550 200 550 670 550 191 551 670 551 200 551 668 552 191 552 664 552 664 553 191 553 200 553 192 554 668 554 201 554 201 555 668 555 664 555 202 556 192 556 201 556 202 557 663 557 192 557 203 558 219 558 220 558 220 559 221 559 222 559 975 560 210 560 661 560 210 561 212 561 661 561 661 562 212 562 198 562 212 563 213 563 198 563 198 564 213 564 205 564 215 565 206 565 207 565 207 566 216 566 217 566 975 567 976 567 208 567 975 568 208 568 210 568 210 569 208 569 209 569 210 570 209 570 212 570 212 571 209 571 211 571 212 572 211 572 213 572 205 573 213 573 836 573 205 574 836 574 214 574 214 575 836 575 835 575 214 576 835 576 215 576 215 577 835 577 206 577 207 578 206 578 834 578 207 579 834 579 216 579 216 580 834 580 218 580 216 581 218 581 217 581 217 582 218 582 203 582 203 583 218 583 219 583 220 584 219 584 221 584 222 585 221 585 831 585 222 586 831 586 223 586 223 587 831 587 828 587 223 588 828 588 662 588 662 589 828 589 224 589 662 590 224 590 204 590 204 591 224 591 974 591 228 592 641 592 631 592 979 593 226 593 980 593 227 594 981 594 980 594 981 595 227 595 629 595 981 596 629 596 184 596 631 597 232 597 228 597 226 598 979 598 978 598 227 599 230 599 629 599 629 600 230 600 630 600 230 601 231 601 630 601 630 602 231 602 142 602 630 603 142 603 225 603 225 604 142 604 232 604 225 605 232 605 631 605 619 606 621 606 617 606 1001 607 238 607 236 607 236 608 238 608 237 608 237 609 238 609 240 609 237 610 240 610 239 610 239 611 240 611 241 611 239 612 241 612 549 612 549 613 241 613 852 613 549 614 852 614 786 614 242 615 243 615 244 615 242 616 244 616 245 616 245 617 244 617 531 617 245 618 531 618 384 618 384 619 531 619 549 619 384 620 549 620 246 620 384 621 246 621 383 621 1000 622 369 622 248 622 248 623 369 623 247 623 248 624 247 624 249 624 249 625 247 625 250 625 249 626 250 626 421 626 421 627 250 627 370 627 421 628 370 628 371 628 421 629 371 629 251 629 999 630 252 630 451 630 451 631 252 631 406 631 451 632 406 632 450 632 450 633 406 633 253 633 450 634 253 634 449 634 449 635 253 635 403 635 449 636 403 636 404 636 449 637 404 637 448 637 998 638 254 638 255 638 255 639 254 639 439 639 255 640 439 640 256 640 256 641 439 641 437 641 256 642 437 642 257 642 257 643 437 643 438 643 257 644 438 644 648 644 648 645 438 645 783 645 648 646 783 646 459 646 292 647 864 647 258 647 258 648 864 648 259 648 258 649 259 649 260 649 260 650 259 650 313 650 260 651 313 651 882 651 882 652 313 652 317 652 882 653 317 653 261 653 261 654 317 654 0 654 261 655 0 655 262 655 262 656 0 656 306 656 262 657 306 657 263 657 263 658 306 658 307 658 263 659 307 659 264 659 264 660 307 660 265 660 264 661 265 661 884 661 884 662 265 662 266 662 884 663 266 663 885 663 885 664 266 664 267 664 885 665 267 665 886 665 886 666 267 666 268 666 886 667 268 667 888 667 888 668 268 668 269 668 888 669 269 669 889 669 889 670 269 670 314 670 889 671 314 671 890 671 890 672 314 672 271 672 890 673 271 673 270 673 270 674 271 674 308 674 270 675 308 675 272 675 272 676 308 676 309 676 272 677 309 677 892 677 892 678 309 678 312 678 892 679 312 679 273 679 273 680 312 680 274 680 273 681 274 681 894 681 894 682 274 682 275 682 894 683 275 683 276 683 276 684 275 684 310 684 276 685 310 685 896 685 896 686 310 686 1 686 896 687 1 687 897 687 897 688 1 688 277 688 897 689 277 689 899 689 899 690 277 690 311 690 899 691 311 691 278 691 278 692 311 692 279 692 278 693 279 693 280 693 280 694 279 694 315 694 280 695 315 695 281 695 281 696 315 696 316 696 281 697 316 697 901 697 901 698 316 698 282 698 901 699 282 699 283 699 283 700 282 700 2 700 283 701 2 701 284 701 284 702 2 702 286 702 284 703 286 703 285 703 285 704 286 704 3 704 285 705 3 705 287 705 287 706 3 706 288 706 287 707 288 707 289 707 289 708 288 708 290 708 289 709 290 709 905 709 905 710 290 710 291 710 905 711 291 711 907 711 907 712 291 712 305 712 907 713 305 713 292 713 292 714 305 714 864 714 862 715 298 715 940 715 940 716 298 716 941 716 301 717 862 717 940 717 293 718 301 718 940 718 1013 719 1015 719 293 719 1015 720 301 720 293 720 296 721 1014 721 1013 721 295 722 294 722 296 722 296 723 294 723 1014 723 294 724 295 724 297 724 294 725 297 725 300 725 877 726 876 726 297 726 300 727 297 727 876 727 941 728 298 728 879 728 941 729 879 729 938 729 938 730 879 730 299 730 299 731 879 731 877 731 299 732 877 732 939 732 939 733 877 733 297 733 958 734 304 734 1016 734 768 735 1017 735 300 735 300 736 1017 736 294 736 302 737 862 737 303 737 303 738 862 738 301 738 875 739 22 739 305 739 875 740 305 740 290 740 875 741 290 741 288 741 288 742 3 742 20 742 22 743 865 743 313 743 22 744 864 744 305 744 307 745 866 745 265 745 265 746 866 746 266 746 878 747 22 747 875 747 308 748 271 748 1011 748 308 749 1011 749 309 749 309 750 1011 750 1584 750 309 751 1584 751 871 751 310 752 30 752 872 752 32 753 30 753 310 753 32 754 310 754 274 754 274 755 310 755 275 755 867 756 866 756 307 756 307 757 306 757 867 757 870 758 869 758 314 758 314 759 869 759 868 759 310 760 872 760 1 760 1 761 872 761 277 761 860 762 315 762 277 762 277 763 315 763 311 763 309 764 871 764 312 764 312 765 871 765 274 765 316 766 315 766 1012 766 313 767 865 767 24 767 22 768 313 768 259 768 22 769 259 769 864 769 314 770 868 770 271 770 870 771 314 771 267 771 267 772 314 772 268 772 860 773 1012 773 315 773 874 774 20 774 3 774 1012 775 874 775 282 775 282 776 874 776 3 776 282 777 3 777 2 777 1012 778 282 778 316 778 313 779 24 779 317 779 317 780 24 780 0 780 873 781 1012 781 860 781 38 782 590 782 318 782 319 783 571 783 320 783 991 784 319 784 320 784 598 785 565 785 322 785 322 786 565 786 321 786 323 787 324 787 992 787 565 788 324 788 323 788 994 789 610 789 17 789 17 790 610 790 747 790 598 791 16 791 319 791 598 792 319 792 324 792 324 793 319 793 991 793 324 794 991 794 992 794 35 795 325 795 597 795 597 796 325 796 17 796 40 797 598 797 322 797 326 798 765 798 332 798 326 799 332 799 993 799 333 800 327 800 764 800 333 801 764 801 330 801 330 802 328 802 331 802 331 803 328 803 329 803 331 804 993 804 332 804 331 805 332 805 330 805 330 806 332 806 452 806 614 807 4 807 613 807 614 808 613 808 988 808 589 809 333 809 334 809 334 810 333 810 330 810 335 811 614 811 989 811 462 812 777 812 336 812 777 813 340 813 336 813 775 814 950 814 337 814 775 815 337 815 996 815 339 816 338 816 774 816 340 817 338 817 339 817 620 818 616 818 995 818 337 819 336 819 339 819 339 820 336 820 340 820 599 821 618 821 617 821 599 822 617 822 620 822 341 823 337 823 950 823 341 824 950 824 584 824 76 825 11 825 343 825 946 826 11 826 76 826 342 827 343 827 946 827 946 828 343 828 11 828 343 829 342 829 455 829 344 830 456 830 987 830 350 831 345 831 759 831 569 832 350 832 759 832 346 833 7 833 347 833 564 834 7 834 346 834 349 835 564 835 348 835 349 836 345 836 350 836 656 837 351 837 352 837 352 838 351 838 948 838 352 839 948 839 947 839 353 840 347 840 7 840 607 841 656 841 655 841 358 842 356 842 355 842 1010 843 354 843 355 843 1010 844 355 844 356 844 374 845 354 845 1010 845 357 846 358 846 355 846 504 847 693 847 692 847 359 848 504 848 692 848 360 849 504 849 359 849 360 850 359 850 695 850 360 851 695 851 491 851 8 852 690 852 361 852 361 853 363 853 8 853 8 854 363 854 492 854 363 855 362 855 492 855 509 856 365 856 364 856 364 857 365 857 366 857 581 858 509 858 364 858 377 859 366 859 365 859 368 860 685 860 367 860 367 861 685 861 686 861 496 862 368 862 497 862 497 863 368 863 367 863 500 864 696 864 579 864 370 865 250 865 372 865 372 866 250 866 247 866 370 867 931 867 371 867 372 868 369 868 373 868 369 869 769 869 373 869 370 870 932 870 931 870 247 871 369 871 372 871 374 872 375 872 580 872 357 873 580 873 501 873 501 874 580 874 375 874 693 875 504 875 505 875 491 876 695 876 694 876 491 877 694 877 505 877 505 878 694 878 693 878 690 879 8 879 376 879 690 880 376 880 691 880 10 881 363 881 691 881 525 882 10 882 376 882 376 883 10 883 691 883 379 884 689 884 377 884 582 885 378 885 379 885 582 886 379 886 509 886 378 887 689 887 379 887 381 888 380 888 686 888 380 889 381 889 496 889 496 890 381 890 382 890 696 891 512 891 1002 891 696 892 1002 892 579 892 932 893 384 893 383 893 769 894 770 894 385 894 245 895 384 895 770 895 245 896 770 896 769 896 245 897 769 897 242 897 388 898 478 898 386 898 233 899 386 899 387 899 387 900 386 900 478 900 389 901 388 901 386 901 391 902 480 902 390 902 482 903 480 903 391 903 482 904 391 904 577 904 482 905 577 905 392 905 393 906 395 906 394 906 393 907 396 907 395 907 396 908 484 908 395 908 707 909 397 909 398 909 398 910 397 910 485 910 416 911 397 911 707 911 485 912 415 912 398 912 400 913 701 913 401 913 401 914 701 914 703 914 399 915 418 915 400 915 399 916 400 916 401 916 402 917 782 917 781 917 402 918 781 918 420 918 403 919 253 919 407 919 407 920 253 920 406 920 403 921 785 921 404 921 407 922 252 922 405 922 405 923 252 923 578 923 403 924 933 924 785 924 406 925 252 925 407 925 711 926 489 926 408 926 233 927 489 927 711 927 389 928 408 928 490 928 490 929 408 929 489 929 409 930 710 930 411 930 411 931 710 931 390 931 392 932 577 932 409 932 392 933 409 933 410 933 410 934 409 934 411 934 709 935 708 935 493 935 493 936 708 936 394 936 709 937 493 937 412 937 412 938 396 938 709 938 416 939 706 939 494 939 706 940 415 940 494 940 415 941 413 941 414 941 415 942 414 942 494 942 702 943 418 943 499 943 702 944 499 944 703 944 499 945 418 945 498 945 498 946 418 946 417 946 420 947 712 947 419 947 784 948 421 948 251 948 1000 949 423 949 578 949 1000 950 422 950 423 950 249 951 421 951 422 951 784 952 933 952 421 952 249 953 422 953 1000 953 249 954 1000 954 248 954 464 955 463 955 424 955 732 956 424 956 463 956 441 957 732 957 463 957 465 958 464 958 424 958 466 959 5 959 572 959 426 960 466 960 572 960 425 961 466 961 426 961 425 962 426 962 427 962 427 963 426 963 573 963 727 964 429 964 725 964 727 965 728 965 429 965 728 966 428 966 429 966 723 967 430 967 431 967 431 968 430 968 432 968 574 969 430 969 723 969 432 970 722 970 431 970 435 971 433 971 474 971 474 972 433 972 721 972 434 973 719 973 435 973 434 974 435 974 474 974 436 975 735 975 736 975 438 976 437 976 440 976 440 977 437 977 439 977 438 978 935 978 783 978 440 979 254 979 771 979 771 980 254 980 576 980 438 981 934 981 935 981 439 982 254 982 440 982 733 983 441 983 734 983 424 984 734 984 479 984 479 985 734 985 477 985 477 986 734 986 441 986 731 987 730 987 5 987 442 988 573 988 731 988 442 989 731 989 481 989 481 990 731 990 5 990 729 991 726 991 483 991 483 992 726 992 725 992 729 993 483 993 443 993 443 994 728 994 729 994 574 995 724 995 486 995 724 996 722 996 486 996 722 997 444 997 486 997 720 998 719 998 488 998 720 999 488 999 721 999 488 1000 719 1000 445 1000 446 1001 782 1001 447 1001 446 1002 447 1002 736 1002 936 1003 449 1003 448 1003 999 1004 772 1004 576 1004 999 1005 773 1005 772 1005 450 1006 449 1006 773 1006 936 1007 934 1007 449 1007 450 1008 773 1008 999 1008 450 1009 999 1009 451 1009 452 1010 766 1010 767 1010 452 1011 767 1011 453 1011 453 1012 767 1012 234 1012 453 1013 234 1013 1006 1013 468 1014 569 1014 762 1014 468 1015 762 1015 467 1015 467 1016 762 1016 761 1016 755 1017 756 1017 454 1017 454 1018 756 1018 568 1018 755 1019 454 1019 455 1019 455 1020 342 1020 755 1020 470 1021 754 1021 469 1021 456 1022 984 1022 982 1022 456 1023 982 1023 470 1023 456 1024 344 1024 984 1024 982 1025 754 1025 470 1025 458 1026 995 1026 457 1026 475 1027 995 1027 458 1027 475 1028 458 1028 473 1028 473 1029 458 1029 16 1029 571 1030 16 1030 458 1030 768 1031 476 1031 1003 1031 768 1032 1003 1032 567 1032 937 1033 461 1033 459 1033 459 1034 461 1034 648 1034 998 1035 778 1035 462 1035 998 1036 460 1036 776 1036 998 1037 776 1037 778 1037 256 1038 257 1038 460 1038 256 1039 460 1039 998 1039 256 1040 998 1040 255 1040 1006 1041 463 1041 453 1041 453 1042 463 1042 464 1042 453 1043 464 1043 452 1043 452 1044 464 1044 465 1044 467 1045 466 1045 425 1045 467 1046 425 1046 427 1046 467 1047 427 1047 468 1047 454 1048 429 1048 428 1048 454 1049 428 1049 455 1049 469 1050 432 1050 470 1050 470 1051 432 1051 430 1051 470 1052 430 1052 456 1052 745 1053 471 1053 472 1053 472 1054 471 1054 740 1054 472 1055 740 1055 737 1055 472 1056 737 1056 747 1056 16 1057 434 1057 473 1057 473 1058 434 1058 474 1058 473 1059 474 1059 475 1059 475 1060 474 1060 995 1060 476 1061 436 1061 1003 1061 477 1062 387 1062 478 1062 477 1063 478 1063 388 1063 477 1064 388 1064 479 1064 481 1065 480 1065 482 1065 481 1066 482 1066 442 1066 442 1067 482 1067 392 1067 483 1068 395 1068 484 1068 483 1069 484 1069 443 1069 444 1070 485 1070 397 1070 444 1071 397 1071 486 1071 743 1072 715 1072 487 1072 743 1073 487 1073 744 1073 445 1074 399 1074 401 1074 445 1075 401 1075 488 1075 782 1076 402 1076 447 1076 447 1077 402 1077 419 1077 489 1078 1010 1078 356 1078 489 1079 356 1079 358 1079 489 1080 358 1080 490 1080 411 1081 504 1081 360 1081 411 1082 360 1082 410 1082 410 1083 360 1083 491 1083 410 1084 491 1084 392 1084 493 1085 8 1085 492 1085 493 1086 492 1086 362 1086 493 1087 362 1087 412 1087 413 1088 377 1088 365 1088 413 1089 365 1089 414 1089 414 1090 365 1090 494 1090 494 1091 365 1091 509 1091 717 1092 699 1092 698 1092 717 1093 698 1093 495 1093 717 1094 495 1094 718 1094 417 1095 496 1095 497 1095 417 1096 497 1096 498 1096 498 1097 497 1097 367 1097 498 1098 367 1098 499 1098 1010 1099 517 1099 375 1099 375 1100 517 1100 514 1100 375 1101 514 1101 502 1101 375 1102 502 1102 501 1102 504 1103 503 1103 505 1103 505 1104 503 1104 519 1104 505 1105 519 1105 506 1105 505 1106 506 1106 491 1106 8 1107 524 1107 376 1107 376 1108 524 1108 525 1108 377 1109 507 1109 379 1109 379 1110 507 1110 526 1110 379 1111 526 1111 508 1111 379 1112 508 1112 509 1112 699 1113 798 1113 511 1113 511 1114 798 1114 510 1114 496 1115 528 1115 529 1115 496 1116 529 1116 380 1116 512 1117 513 1117 1002 1117 1002 1118 513 1118 1009 1118 502 1119 514 1119 516 1119 515 1120 516 1120 517 1120 517 1121 516 1121 514 1121 1008 1122 515 1122 517 1122 518 1123 502 1123 516 1123 503 1124 537 1124 521 1124 520 1125 503 1125 521 1125 519 1126 503 1126 520 1126 519 1127 520 1127 506 1127 506 1128 520 1128 522 1128 793 1129 524 1129 523 1129 793 1130 563 1130 525 1130 793 1131 525 1131 524 1131 791 1132 508 1132 790 1132 508 1133 526 1133 790 1133 790 1134 526 1134 507 1134 543 1135 508 1135 791 1135 507 1136 546 1136 790 1136 530 1137 527 1137 529 1137 529 1138 527 1138 801 1138 528 1139 15 1139 530 1139 528 1140 530 1140 529 1140 513 1141 512 1141 548 1141 513 1142 548 1142 795 1142 549 1143 531 1143 534 1143 534 1144 531 1144 244 1144 550 1145 533 1145 246 1145 550 1146 246 1146 549 1146 534 1147 243 1147 802 1147 802 1148 243 1148 532 1148 244 1149 243 1149 534 1149 502 1150 535 1150 552 1150 794 1151 1008 1151 535 1151 552 1152 535 1152 551 1152 551 1153 535 1153 1008 1153 551 1154 1008 1154 1009 1154 538 1155 536 1155 537 1155 538 1156 555 1156 506 1156 555 1157 538 1157 554 1157 554 1158 538 1158 537 1158 539 1159 792 1159 540 1159 540 1160 792 1160 523 1160 539 1161 540 1161 541 1161 525 1162 539 1162 541 1162 543 1163 545 1163 544 1163 545 1164 546 1164 542 1164 545 1165 542 1165 544 1165 850 1166 1001 1166 561 1166 547 1167 1001 1167 801 1167 561 1168 1001 1168 547 1168 561 1169 547 1169 15 1169 561 1170 15 1170 528 1170 548 1171 562 1171 795 1171 787 1172 549 1172 786 1172 1001 1173 803 1173 532 1173 1001 1174 804 1174 803 1174 237 1175 239 1175 804 1175 787 1176 550 1176 549 1176 237 1177 804 1177 1001 1177 237 1178 1001 1178 236 1178 857 1179 551 1179 1005 1179 1005 1180 551 1180 1009 1180 857 1181 552 1181 551 1181 552 1182 857 1182 6 1182 552 1183 6 1183 502 1183 554 1184 553 1184 839 1184 554 1185 839 1185 555 1185 555 1186 839 1186 506 1186 840 1187 540 1187 861 1187 840 1188 541 1188 540 1188 541 1189 840 1189 525 1189 542 1190 21 1190 842 1190 542 1191 842 1191 544 1191 544 1192 842 1192 556 1192 845 1193 557 1193 846 1193 846 1194 557 1194 558 1194 846 1195 558 1195 559 1195 557 1196 845 1196 510 1196 850 1197 561 1197 560 1197 560 1198 561 1198 528 1198 562 1199 780 1199 1009 1199 570 1200 755 1200 342 1200 334 1201 4 1201 591 1201 71 1202 599 1202 600 1202 957 1203 604 1203 75 1203 353 1204 592 1204 335 1204 353 1205 335 1205 42 1205 77 1206 73 1206 584 1206 588 1207 585 1207 958 1207 958 1208 585 1208 586 1208 586 1209 585 1209 588 1209 566 1210 57 1210 958 1210 586 1211 588 1211 958 1211 586 1212 958 1212 57 1212 57 1213 1004 1213 586 1213 586 1214 1004 1214 587 1214 587 1215 1004 1215 1007 1215 587 1216 1007 1216 590 1216 587 1217 590 1217 589 1217 587 1218 589 1218 67 1218 335 1219 592 1219 591 1219 592 1220 353 1220 593 1220 593 1221 607 1221 655 1221 593 1222 655 1222 606 1222 353 1223 7 1223 593 1223 593 1224 7 1224 607 1224 606 1225 624 1225 595 1225 595 1226 13 1226 594 1226 594 1227 13 1227 35 1227 606 1228 595 1228 594 1228 44 1229 986 1229 595 1229 37 1230 35 1230 611 1230 594 1231 35 1231 596 1231 596 1232 35 1232 597 1232 596 1233 597 1233 70 1233 70 1234 597 1234 598 1234 70 1235 598 1235 40 1235 70 1236 40 1236 71 1236 40 1237 599 1237 71 1237 341 1238 73 1238 600 1238 341 1239 600 1239 997 1239 997 1240 600 1240 599 1240 341 1241 584 1241 73 1241 77 1242 601 1242 73 1242 73 1243 601 1243 957 1243 957 1244 601 1244 604 1244 604 1245 601 1245 602 1245 604 1246 602 1246 977 1246 604 1247 977 1247 605 1247 604 1248 605 1248 304 1248 304 1249 605 1249 603 1249 603 1250 605 1250 977 1250 43 1251 45 1251 983 1251 67 1252 589 1252 591 1252 591 1253 589 1253 334 1253 77 1254 651 1254 601 1254 651 1255 77 1255 584 1255 40 1256 321 1256 599 1256 606 1257 43 1257 624 1257 43 1258 983 1258 624 1258 343 1259 43 1259 606 1259 606 1260 76 1260 343 1260 946 1261 76 1261 78 1261 606 1262 655 1262 76 1262 4 1263 335 1263 591 1263 1006 1264 39 1264 318 1264 234 1265 39 1265 1006 1265 608 1266 38 1266 235 1266 38 1267 318 1267 235 1267 608 1268 235 1268 318 1268 610 1269 609 1269 751 1269 994 1270 609 1270 610 1270 325 1271 611 1271 749 1271 325 1272 749 1272 17 1272 612 1273 994 1273 17 1273 612 1274 17 1274 750 1274 613 1275 4 1275 760 1275 613 1276 760 1276 988 1276 4 1277 761 1277 760 1277 989 1278 758 1278 763 1278 614 1279 758 1279 989 1279 614 1280 988 1280 763 1280 758 1281 614 1281 763 1281 615 1282 457 1282 616 1282 617 1283 618 1283 619 1283 620 1284 621 1284 990 1284 45 1285 43 1285 343 1285 985 1286 982 1286 753 1286 623 1287 985 1287 753 1287 746 1288 752 1288 36 1288 44 1289 624 1289 625 1289 625 1290 624 1290 983 1290 611 1291 628 1291 12 1291 626 1292 625 1292 983 1292 627 1293 625 1293 626 1293 628 1294 611 1294 12 1294 985 1295 623 1295 626 1295 626 1296 623 1296 627 1296 595 1297 624 1297 44 1297 66 1298 632 1298 636 1298 629 1299 630 1299 639 1299 629 1300 639 1300 184 1300 636 1301 632 1301 183 1301 183 1302 632 1302 634 1302 183 1303 634 1303 633 1303 633 1304 634 1304 635 1304 633 1305 635 1305 642 1305 66 1306 636 1306 638 1306 638 1307 636 1307 637 1307 641 1308 190 1308 640 1308 637 1309 184 1309 638 1309 638 1310 184 1310 639 1310 181 1311 647 1311 180 1311 180 1312 647 1312 61 1312 180 1313 61 1313 640 1313 640 1314 61 1314 59 1314 640 1315 59 1315 641 1315 635 1316 64 1316 642 1316 642 1317 64 1317 182 1317 182 1318 64 1318 643 1318 182 1319 643 1319 645 1319 182 1320 645 1320 644 1320 644 1321 645 1321 63 1321 644 1322 63 1322 181 1322 181 1323 63 1323 646 1323 181 1324 646 1324 647 1324 649 1325 776 1325 648 1325 650 1326 949 1326 651 1326 601 1327 949 1327 602 1327 568 1328 652 1328 351 1328 948 1329 351 1329 652 1329 653 1330 655 1330 656 1330 653 1331 656 1331 654 1331 657 1332 757 1332 352 1332 657 1333 352 1333 947 1333 217 1334 199 1334 207 1334 207 1335 199 1335 658 1335 207 1336 658 1336 215 1336 215 1337 658 1337 196 1337 215 1338 196 1338 214 1338 214 1339 196 1339 659 1339 214 1340 659 1340 205 1340 205 1341 659 1341 660 1341 205 1342 660 1342 198 1342 975 1343 661 1343 193 1343 975 1344 193 1344 190 1344 204 1345 197 1345 662 1345 662 1346 197 1346 663 1346 662 1347 663 1347 223 1347 223 1348 663 1348 202 1348 223 1349 202 1349 222 1349 222 1350 202 1350 201 1350 222 1351 201 1351 220 1351 220 1352 201 1352 664 1352 220 1353 664 1353 203 1353 203 1354 664 1354 200 1354 203 1355 200 1355 217 1355 217 1356 200 1356 199 1356 193 1357 665 1357 179 1357 193 1358 179 1358 190 1358 192 1359 666 1359 667 1359 192 1360 667 1360 189 1360 192 1361 189 1361 668 1361 668 1362 189 1362 188 1362 668 1363 188 1363 191 1363 191 1364 188 1364 669 1364 191 1365 669 1365 670 1365 199 1366 670 1366 187 1366 199 1367 187 1367 671 1367 672 1368 671 1368 186 1368 672 1369 186 1369 194 1369 195 1370 194 1370 673 1370 673 1371 185 1371 665 1371 981 1372 945 1372 177 1372 146 1373 51 1373 145 1373 145 1374 177 1374 674 1374 674 1375 177 1375 945 1375 145 1376 51 1376 177 1376 676 1377 677 1377 675 1377 154 1378 46 1378 677 1378 154 1379 677 1379 676 1379 678 1380 49 1380 146 1380 146 1381 49 1381 51 1381 682 1382 53 1382 679 1382 679 1383 53 1383 49 1383 680 1384 46 1384 154 1384 679 1385 49 1385 678 1385 684 1386 229 1386 680 1386 680 1387 229 1387 46 1387 681 1388 53 1388 682 1388 150 1389 54 1389 681 1389 681 1390 54 1390 53 1390 683 1391 54 1391 150 1391 675 1392 677 1392 683 1392 683 1393 677 1393 54 1393 684 1394 973 1394 229 1394 368 1395 382 1395 381 1395 368 1396 381 1396 685 1396 685 1397 381 1397 686 1397 697 1398 583 1398 687 1398 697 1399 687 1399 700 1399 697 1400 700 1400 688 1400 366 1401 689 1401 378 1401 366 1402 378 1402 364 1402 364 1403 378 1403 582 1403 364 1404 582 1404 581 1404 361 1405 690 1405 691 1405 361 1406 691 1406 363 1406 692 1407 693 1407 359 1407 359 1408 693 1408 694 1408 359 1409 694 1409 695 1409 354 1410 374 1410 580 1410 354 1411 580 1411 355 1411 355 1412 580 1412 357 1412 699 1413 583 1413 697 1413 697 1414 688 1414 699 1414 699 1415 688 1415 698 1415 688 1416 495 1416 698 1416 583 1417 699 1417 511 1417 700 1418 687 1418 583 1418 583 1419 511 1419 700 1419 14 1420 688 1420 700 1420 510 1421 14 1421 511 1421 511 1422 14 1422 700 1422 400 1423 418 1423 702 1423 400 1424 702 1424 701 1424 701 1425 702 1425 703 1425 704 1426 716 1426 713 1426 713 1427 716 1427 705 1427 713 1428 705 1428 714 1428 398 1429 415 1429 706 1429 398 1430 706 1430 707 1430 707 1431 706 1431 416 1431 394 1432 708 1432 393 1432 393 1433 708 1433 709 1433 393 1434 709 1434 396 1434 390 1435 710 1435 391 1435 391 1436 710 1436 409 1436 391 1437 409 1437 577 1437 233 1438 711 1438 386 1438 386 1439 711 1439 408 1439 386 1440 408 1440 389 1440 781 1441 712 1441 420 1441 713 1442 715 1442 704 1442 713 1443 714 1443 715 1443 714 1444 487 1444 715 1444 705 1445 716 1445 717 1445 717 1446 716 1446 704 1446 705 1447 717 1447 718 1447 718 1448 714 1448 705 1448 435 1449 719 1449 720 1449 435 1450 720 1450 433 1450 433 1451 720 1451 721 1451 738 1452 742 1452 741 1452 738 1453 741 1453 739 1453 739 1454 741 1454 575 1454 431 1455 722 1455 724 1455 431 1456 724 1456 723 1456 723 1457 724 1457 574 1457 725 1458 726 1458 727 1458 727 1459 726 1459 729 1459 727 1460 729 1460 728 1460 572 1461 5 1461 730 1461 572 1462 730 1462 426 1462 426 1463 730 1463 731 1463 426 1464 731 1464 573 1464 732 1465 441 1465 733 1465 732 1466 733 1466 734 1466 732 1467 734 1467 424 1467 735 1468 446 1468 736 1468 471 1469 738 1469 739 1469 471 1470 742 1470 738 1470 575 1471 737 1471 739 1471 739 1472 737 1472 740 1472 739 1473 740 1473 471 1473 743 1474 741 1474 742 1474 741 1475 743 1475 744 1475 741 1476 744 1476 575 1476 745 1477 748 1477 752 1477 745 1478 752 1478 746 1478 745 1479 472 1479 748 1479 747 1480 748 1480 472 1480 323 1481 321 1481 565 1481 458 1482 615 1482 990 1482 458 1483 990 1483 321 1483 321 1484 990 1484 619 1484 990 1485 621 1485 619 1485 615 1486 458 1486 457 1486 321 1487 323 1487 458 1487 458 1488 323 1488 320 1488 458 1489 320 1489 571 1489 611 1490 612 1490 750 1490 611 1491 750 1491 749 1491 752 1492 748 1492 609 1492 609 1493 748 1493 751 1493 612 1494 611 1494 609 1494 609 1495 611 1495 752 1495 983 1496 45 1496 982 1496 982 1497 45 1497 754 1497 984 1498 753 1498 982 1498 986 1499 625 1499 984 1499 984 1500 625 1500 753 1500 756 1501 755 1501 652 1501 78 1502 653 1502 946 1502 946 1503 653 1503 657 1503 946 1504 657 1504 652 1504 946 1505 652 1505 755 1505 756 1506 652 1506 568 1506 657 1507 653 1507 757 1507 757 1508 653 1508 654 1508 762 1509 759 1509 348 1509 759 1510 762 1510 569 1510 42 1511 763 1511 762 1511 42 1512 762 1512 348 1512 346 1513 348 1513 564 1513 760 1514 761 1514 762 1514 760 1515 762 1515 763 1515 328 1516 764 1516 327 1516 328 1517 327 1517 329 1517 39 1518 329 1518 608 1518 327 1519 38 1519 608 1519 326 1520 767 1520 765 1520 765 1521 767 1521 766 1521 326 1522 39 1522 767 1522 767 1523 39 1523 234 1523 329 1524 327 1524 608 1524 1016 1525 1017 1525 958 1525 958 1526 1017 1526 768 1526 958 1527 768 1527 567 1527 958 1528 567 1528 566 1528 373 1529 769 1529 385 1529 373 1530 385 1530 372 1530 372 1531 385 1531 770 1531 578 1532 423 1532 405 1532 405 1533 423 1533 407 1533 407 1534 423 1534 422 1534 576 1535 772 1535 771 1535 771 1536 772 1536 440 1536 440 1537 772 1537 773 1537 338 1538 775 1538 774 1538 774 1539 775 1539 996 1539 778 1540 776 1540 777 1540 584 1541 775 1541 651 1541 651 1542 775 1542 338 1542 651 1543 338 1543 777 1543 651 1544 777 1544 776 1544 778 1545 777 1545 462 1545 876 1546 878 1546 300 1546 300 1547 878 1547 779 1547 548 1548 300 1548 779 1548 548 1549 779 1549 562 1549 562 1550 779 1550 780 1550 735 1551 436 1551 476 1551 548 1552 512 1552 696 1552 548 1553 696 1553 300 1553 500 1554 419 1554 696 1554 696 1555 419 1555 712 1555 696 1556 712 1556 300 1556 300 1557 712 1557 781 1557 781 1558 782 1558 446 1558 781 1559 446 1559 300 1559 300 1560 446 1560 735 1560 300 1561 735 1561 768 1561 768 1562 735 1562 476 1562 862 1563 302 1563 937 1563 459 1564 783 1564 937 1564 937 1565 783 1565 935 1565 937 1566 935 1566 862 1566 448 1567 404 1567 936 1567 936 1568 404 1568 785 1568 784 1569 251 1569 371 1569 371 1570 931 1570 784 1570 784 1571 931 1571 862 1571 784 1572 862 1572 785 1572 785 1573 862 1573 936 1573 936 1574 862 1574 935 1574 383 1575 246 1575 932 1575 932 1576 246 1576 533 1576 787 1577 786 1577 852 1577 852 1578 788 1578 787 1578 787 1579 788 1579 863 1579 787 1580 863 1580 533 1580 533 1581 863 1581 862 1581 533 1582 862 1582 932 1582 932 1583 862 1583 931 1583 796 1584 800 1584 797 1584 797 1585 800 1585 789 1585 797 1586 789 1586 799 1586 790 1587 546 1587 545 1587 790 1588 545 1588 791 1588 791 1589 545 1589 543 1589 523 1590 792 1590 793 1590 793 1591 792 1591 539 1591 793 1592 539 1592 563 1592 521 1593 537 1593 536 1593 521 1594 536 1594 520 1594 520 1595 536 1595 538 1595 520 1596 538 1596 522 1596 515 1597 1008 1597 794 1597 515 1598 794 1598 516 1598 516 1599 794 1599 535 1599 516 1600 535 1600 518 1600 797 1601 798 1601 796 1601 797 1602 799 1602 510 1602 797 1603 510 1603 798 1603 789 1604 800 1604 558 1604 558 1605 800 1605 796 1605 789 1606 558 1606 557 1606 510 1607 789 1607 557 1607 530 1608 15 1608 547 1608 530 1609 547 1609 527 1609 527 1610 547 1610 801 1610 532 1611 803 1611 802 1611 802 1612 803 1612 534 1612 534 1613 803 1613 804 1613 81 1614 806 1614 927 1614 806 1615 805 1615 927 1615 928 1616 91 1616 927 1616 928 1617 927 1617 805 1617 930 1618 808 1618 807 1618 925 1619 924 1619 139 1619 925 1620 139 1620 81 1620 89 1621 90 1621 809 1621 823 1622 85 1622 810 1622 812 1623 811 1623 816 1623 80 1624 809 1624 820 1624 812 1625 816 1625 133 1625 812 1626 133 1626 813 1626 129 1627 813 1627 130 1627 130 1628 813 1628 133 1628 813 1629 129 1629 815 1629 128 1630 815 1630 814 1630 814 1631 815 1631 129 1631 825 1632 136 1632 811 1632 811 1633 136 1633 816 1633 122 1634 818 1634 80 1634 80 1635 818 1635 821 1635 822 1636 823 1636 819 1636 819 1637 823 1637 824 1637 820 1638 823 1638 124 1638 820 1639 124 1639 80 1639 80 1640 124 1640 122 1640 821 1641 826 1641 80 1641 80 1642 826 1642 811 1642 822 1643 124 1643 823 1643 823 1644 813 1644 824 1644 824 1645 813 1645 815 1645 825 1646 811 1646 817 1646 817 1647 811 1647 826 1647 831 1648 827 1648 120 1648 831 1649 120 1649 123 1649 208 1650 976 1650 143 1650 831 1651 221 1651 827 1651 827 1652 221 1652 829 1652 829 1653 221 1653 219 1653 829 1654 219 1654 121 1654 121 1655 219 1655 218 1655 121 1656 218 1656 830 1656 830 1657 218 1657 138 1657 828 1658 831 1658 224 1658 224 1659 831 1659 123 1659 224 1660 123 1660 832 1660 974 1661 224 1661 208 1661 208 1662 213 1662 211 1662 208 1663 211 1663 209 1663 125 1664 224 1664 832 1664 208 1665 224 1665 125 1665 208 1666 143 1666 974 1666 127 1667 213 1667 208 1667 127 1668 208 1668 118 1668 118 1669 208 1669 125 1669 127 1670 833 1670 213 1670 213 1671 833 1671 116 1671 213 1672 116 1672 836 1672 836 1673 116 1673 131 1673 218 1674 834 1674 138 1674 138 1675 834 1675 135 1675 135 1676 834 1676 206 1676 135 1677 206 1677 132 1677 132 1678 206 1678 835 1678 132 1679 835 1679 131 1679 131 1680 835 1680 836 1680 34 1681 780 1681 779 1681 839 1682 838 1682 9 1682 9 1683 838 1683 861 1683 838 1684 839 1684 854 1684 861 1685 838 1685 29 1685 861 1686 29 1686 840 1686 840 1687 29 1687 31 1687 859 1688 21 1688 10 1688 859 1689 10 1689 840 1689 859 1690 840 1690 841 1690 841 1691 840 1691 31 1691 21 1692 837 1692 26 1692 21 1693 841 1693 837 1693 21 1694 26 1694 842 1694 19 1695 843 1695 559 1695 842 1696 26 1696 843 1696 842 1697 843 1697 556 1697 556 1698 843 1698 19 1698 559 1699 843 1699 846 1699 556 1700 19 1700 559 1700 844 1701 845 1701 846 1701 844 1702 846 1702 843 1702 845 1703 844 1703 18 1703 845 1704 18 1704 14 1704 14 1705 18 1705 560 1705 560 1706 848 1706 847 1706 560 1707 847 1707 850 1707 848 1708 560 1708 18 1708 848 1709 18 1709 23 1709 23 1710 18 1710 844 1710 238 1711 850 1711 849 1711 847 1712 849 1712 850 1712 850 1713 238 1713 1001 1713 241 1714 851 1714 788 1714 241 1715 788 1715 852 1715 853 1716 851 1716 241 1716 241 1717 240 1717 853 1717 853 1718 240 1718 238 1718 853 1719 238 1719 25 1719 25 1720 238 1720 849 1720 855 1721 27 1721 854 1721 27 1722 855 1722 856 1722 553 1723 855 1723 854 1723 553 1724 854 1724 839 1724 855 1725 553 1725 6 1725 855 1726 6 1726 856 1726 6 1727 857 1727 856 1727 856 1728 857 1728 34 1728 34 1729 857 1729 1005 1729 780 1730 34 1730 1009 1730 1009 1731 34 1731 1005 1731 858 1732 867 1732 306 1732 24 1733 306 1733 0 1733 858 1734 306 1734 24 1734 32 1735 859 1735 871 1735 859 1736 274 1736 871 1736 859 1737 32 1737 274 1737 1012 1738 873 1738 28 1738 28 1739 33 1739 1012 1739 861 1740 277 1740 872 1740 861 1741 860 1741 277 1741 862 1742 863 1742 298 1742 863 1743 878 1743 298 1743 878 1744 863 1744 22 1744 18 1745 870 1745 267 1745 267 1746 866 1746 18 1746 18 1747 866 1747 870 1747 19 1748 868 1748 1011 1748 868 1749 19 1749 271 1749 271 1750 19 1750 1011 1750 860 1751 861 1751 872 1751 33 1752 874 1752 1012 1752 20 1753 875 1753 288 1753 876 1754 877 1754 878 1754 878 1755 877 1755 879 1755 878 1756 879 1756 298 1756 155 1757 258 1757 880 1757 880 1758 258 1758 260 1758 880 1759 260 1759 156 1759 156 1760 260 1760 882 1760 156 1761 882 1761 881 1761 881 1762 882 1762 261 1762 881 1763 261 1763 157 1763 157 1764 261 1764 262 1764 157 1765 262 1765 158 1765 158 1766 262 1766 263 1766 158 1767 263 1767 883 1767 883 1768 263 1768 264 1768 883 1769 264 1769 159 1769 159 1770 264 1770 884 1770 159 1771 884 1771 160 1771 160 1772 884 1772 885 1772 160 1773 885 1773 161 1773 161 1774 885 1774 886 1774 161 1775 886 1775 887 1775 887 1776 886 1776 888 1776 887 1777 888 1777 163 1777 163 1778 888 1778 889 1778 163 1779 889 1779 164 1779 164 1780 889 1780 890 1780 164 1781 890 1781 891 1781 891 1782 890 1782 270 1782 891 1783 270 1783 165 1783 165 1784 270 1784 272 1784 165 1785 272 1785 166 1785 166 1786 272 1786 892 1786 166 1787 892 1787 893 1787 893 1788 892 1788 273 1788 893 1789 273 1789 168 1789 168 1790 273 1790 894 1790 168 1791 894 1791 895 1791 895 1792 894 1792 276 1792 895 1793 276 1793 170 1793 170 1794 276 1794 896 1794 170 1795 896 1795 171 1795 171 1796 896 1796 897 1796 171 1797 897 1797 898 1797 898 1798 897 1798 899 1798 898 1799 899 1799 900 1799 900 1800 899 1800 278 1800 900 1801 278 1801 173 1801 173 1802 278 1802 280 1802 173 1803 280 1803 172 1803 172 1804 280 1804 281 1804 172 1805 281 1805 175 1805 175 1806 281 1806 901 1806 175 1807 901 1807 902 1807 902 1808 901 1808 283 1808 902 1809 283 1809 903 1809 903 1810 283 1810 284 1810 903 1811 284 1811 176 1811 176 1812 284 1812 285 1812 176 1813 285 1813 904 1813 904 1814 285 1814 287 1814 904 1815 287 1815 289 1815 906 1816 907 1816 292 1816 906 1817 292 1817 155 1817 155 1818 292 1818 258 1818 112 1819 917 1819 111 1819 86 1820 98 1820 908 1820 98 1821 86 1821 917 1821 98 1822 917 1822 97 1822 97 1823 917 1823 113 1823 113 1824 917 1824 112 1824 908 1825 909 1825 86 1825 86 1826 909 1826 144 1826 909 1827 910 1827 144 1827 144 1828 910 1828 101 1828 144 1829 101 1829 911 1829 911 1830 101 1830 103 1830 911 1831 103 1831 147 1831 147 1832 103 1832 104 1832 147 1833 104 1833 912 1833 147 1834 912 1834 148 1834 148 1835 912 1835 913 1835 148 1836 913 1836 115 1836 914 1837 153 1837 915 1837 914 1838 915 1838 918 1838 914 1839 111 1839 153 1839 153 1840 111 1840 917 1840 153 1841 917 1841 916 1841 916 1842 917 1842 86 1842 915 1843 152 1843 918 1843 918 1844 152 1844 109 1844 109 1845 152 1845 151 1845 109 1846 151 1846 919 1846 919 1847 151 1847 149 1847 919 1848 149 1848 920 1848 920 1849 149 1849 913 1849 913 1850 149 1850 115 1850 105 1851 921 1851 107 1851 921 1852 105 1852 102 1852 924 1853 921 1853 102 1853 924 1854 102 1854 92 1854 924 1855 92 1855 100 1855 110 1856 923 1856 922 1856 922 1857 923 1857 93 1857 930 1858 807 1858 100 1858 81 1859 96 1859 921 1859 921 1860 96 1860 107 1860 95 1861 923 1861 110 1861 807 1862 924 1862 100 1862 930 1863 100 1863 99 1863 930 1864 99 1864 93 1864 930 1865 93 1865 923 1865 924 1866 925 1866 921 1866 921 1867 925 1867 81 1867 91 1868 923 1868 95 1868 91 1869 95 1869 926 1869 91 1870 926 1870 927 1870 96 1871 81 1871 927 1871 96 1872 927 1872 926 1872 924 1873 83 1873 90 1873 85 1874 82 1874 929 1874 85 1875 929 1875 923 1875 85 1876 923 1876 928 1876 81 1877 89 1877 84 1877 81 1878 84 1878 806 1878 928 1879 805 1879 84 1879 84 1880 805 1880 806 1880 89 1881 81 1881 139 1881 89 1882 139 1882 90 1882 808 1883 82 1883 83 1883 808 1884 83 1884 807 1884 807 1885 83 1885 924 1885 929 1886 82 1886 930 1886 550 1887 787 1887 533 1887 534 1888 804 1888 239 1888 534 1889 239 1889 549 1889 785 1890 933 1890 784 1890 935 1891 934 1891 936 1891 937 1892 304 1892 461 1892 461 1893 304 1893 603 1893 937 1894 302 1894 304 1894 304 1895 302 1895 303 1895 648 1896 460 1896 257 1896 949 1897 648 1897 602 1897 602 1898 648 1898 603 1898 603 1899 648 1899 461 1899 440 1900 773 1900 449 1900 440 1901 449 1901 438 1901 407 1902 422 1902 421 1902 407 1903 421 1903 403 1903 372 1904 770 1904 384 1904 372 1905 384 1905 370 1905 299 1906 939 1906 79 1906 79 1907 939 1907 297 1907 79 1908 297 1908 295 1908 79 1909 295 1909 296 1909 940 1910 1013 1910 293 1910 942 1911 940 1911 941 1911 140 1912 942 1912 141 1912 227 1913 943 1913 79 1913 227 1914 79 1914 296 1914 227 1915 296 1915 944 1915 184 1916 197 1916 945 1916 945 1917 197 1917 204 1917 945 1918 204 1918 143 1918 143 1919 204 1919 974 1919 684 1920 976 1920 975 1920 684 1921 975 1921 190 1921 684 1922 190 1922 973 1922 973 1923 190 1923 641 1923 184 1924 945 1924 981 1924 641 1925 228 1925 229 1925 973 1926 641 1926 229 1926 950 1927 775 1927 584 1927 340 1928 777 1928 338 1928 649 1929 651 1929 776 1929 655 1930 653 1930 78 1930 946 1931 755 1931 570 1931 947 1932 948 1932 657 1932 657 1933 948 1933 652 1933 570 1934 342 1934 946 1934 651 1935 649 1935 949 1935 949 1936 649 1936 648 1936 601 1937 651 1937 949 1937 951 1938 958 1938 586 1938 972 1939 69 1939 62 1939 62 1940 69 1940 952 1940 62 1941 952 1941 953 1941 62 1942 953 1942 954 1942 954 1943 953 1943 955 1943 954 1944 955 1944 956 1944 956 1945 955 1945 72 1945 956 1946 72 1946 60 1946 60 1947 72 1947 74 1947 60 1948 74 1948 58 1948 58 1949 74 1949 957 1949 58 1950 957 1950 75 1950 631 1951 75 1951 304 1951 631 1952 304 1952 225 1952 225 1953 304 1953 958 1953 225 1954 958 1954 630 1954 630 1955 958 1955 951 1955 959 1956 951 1956 961 1956 959 1957 961 1957 960 1957 960 1958 961 1958 962 1958 960 1959 962 1959 963 1959 964 1960 963 1960 966 1960 964 1961 966 1961 965 1961 965 1962 966 1962 967 1962 965 1963 967 1963 968 1963 965 1964 968 1964 969 1964 969 1965 968 1965 68 1965 969 1966 68 1966 65 1966 65 1967 68 1967 970 1967 65 1968 970 1968 971 1968 971 1969 970 1969 69 1969 971 1970 69 1970 972 1970 951 1971 639 1971 630 1971 978 1972 229 1972 228 1972 978 1973 979 1973 229 1973 979 1974 980 1974 981 1974 623 1975 753 1975 627 1975 627 1976 753 1976 625 1976 984 1977 344 1977 986 1977 986 1978 344 1978 987 1978 626 1979 983 1979 985 1979 985 1980 983 1980 982 1980 622 1981 754 1981 45 1981 44 1982 625 1982 986 1982 986 1983 987 1983 595 1983 991 1984 320 1984 992 1984 992 1985 320 1985 323 1985 616 1986 990 1986 615 1986 618 1987 599 1987 619 1987 599 1988 321 1988 619 1988 763 1989 988 1989 760 1989 759 1990 345 1990 348 1990 348 1991 345 1991 349 1991 42 1992 989 1992 763 1992 42 1993 348 1993 346 1993 347 1994 42 1994 346 1994 335 1995 989 1995 42 1995 990 1996 616 1996 620 1996 40 1997 322 1997 321 1997 36 1998 752 1998 628 1998 628 1999 752 1999 611 1999 994 2000 612 2000 609 2000 325 2001 37 2001 611 2001 608 2002 318 2002 39 2002 326 2003 993 2003 329 2003 329 2004 993 2004 331 2004 329 2005 39 2005 326 2005 589 2006 38 2006 327 2006 589 2007 327 2007 333 2007 37 2008 325 2008 35 2008 337 2009 341 2009 997 2009 997 2010 599 2010 620 2010 997 2011 995 2011 474 2011 997 2012 499 2012 367 2012 529 2013 801 2013 1001 2013 367 2014 686 2014 380 2014 367 2015 380 2015 997 2015 997 2016 380 2016 529 2016 997 2017 529 2017 1001 2017 401 2018 703 2018 499 2018 474 2019 721 2019 488 2019 474 2020 488 2020 997 2020 997 2021 488 2021 401 2021 997 2022 401 2022 499 2022 616 2023 457 2023 995 2023 617 2024 621 2024 620 2024 997 2025 620 2025 995 2025 254 2026 998 2026 997 2026 339 2027 774 2027 996 2027 339 2028 996 2028 337 2028 337 2029 997 2029 336 2029 336 2030 997 2030 998 2030 336 2031 998 2031 462 2031 999 2032 576 2032 254 2032 999 2033 254 2033 997 2033 999 2034 997 2034 252 2034 252 2035 997 2035 1000 2035 252 2036 1000 2036 578 2036 369 2037 242 2037 769 2037 1001 2038 532 2038 243 2038 1001 2039 243 2039 242 2039 1001 2040 242 2040 997 2040 997 2041 242 2041 369 2041 997 2042 369 2042 1000 2042 318 2043 590 2043 1007 2043 1003 2044 1009 2044 1007 2044 419 2045 500 2045 1009 2045 513 2046 795 2046 562 2046 513 2047 562 2047 1009 2047 500 2048 579 2048 1002 2048 500 2049 1002 2049 1009 2049 402 2050 420 2050 419 2050 436 2051 736 2051 447 2051 436 2052 447 2052 1003 2052 1003 2053 447 2053 1009 2053 1009 2054 447 2054 419 2054 566 2055 567 2055 1003 2055 566 2056 1003 2056 1004 2056 1004 2057 1003 2057 1007 2057 463 2058 1006 2058 1007 2058 318 2059 1007 2059 1006 2059 441 2060 463 2060 477 2060 477 2061 463 2061 1007 2061 477 2062 1007 2062 387 2062 387 2063 1007 2063 489 2063 387 2064 489 2064 233 2064 1010 2065 375 2065 374 2065 1008 2066 517 2066 1009 2066 1009 2067 517 2067 1010 2067 1009 2068 1010 2068 1007 2068 1007 2069 1010 2069 489 2069 266 2070 866 2070 267 2070 1016 2071 304 2071 303 2071 1014 2072 294 2072 1016 2072 1016 2073 303 2073 1015 2073 1015 2074 1013 2074 1014 2074 1015 2075 1014 2075 1016 2075 301 2076 1015 2076 303 2076 1017 2077 1016 2077 294 2077 1055 2078 1315 2078 1054 2078 1054 2079 1315 2079 1053 2079 1432 2080 1018 2080 1302 2080 1327 2081 1329 2081 1021 2081 1021 2082 1329 2082 1019 2082 1019 2083 1329 2083 1020 2083 1019 2084 1020 2084 1423 2084 1412 2085 1343 2085 1023 2085 1023 2086 1343 2086 1022 2086 1021 2087 1422 2087 1327 2087 1327 2088 1422 2088 1022 2088 1022 2089 1422 2089 1023 2089 1324 2090 1410 2090 1352 2090 1324 2091 1352 2091 1323 2091 1360 2092 1357 2092 1398 2092 1399 2093 1333 2093 1109 2093 1109 2094 1333 2094 1024 2094 1024 2095 1333 2095 1332 2095 1024 2096 1332 2096 1025 2096 1025 2097 1332 2097 1334 2097 1025 2098 1334 2098 1405 2098 1316 2099 1128 2099 1026 2099 1026 2100 1128 2100 1027 2100 1027 2101 1128 2101 1029 2101 1027 2102 1029 2102 1028 2102 1028 2103 1029 2103 1134 2103 1028 2104 1134 2104 1386 2104 1386 2105 1134 2105 1376 2105 1030 2106 1093 2106 1031 2106 1031 2107 1093 2107 1088 2107 1031 2108 1088 2108 1135 2108 1135 2109 1088 2109 1087 2109 1135 2110 1087 2110 1133 2110 1133 2111 1087 2111 1074 2111 1133 2112 1074 2112 1111 2112 1111 2113 1074 2113 1085 2113 1111 2114 1085 2114 1139 2114 1139 2115 1085 2115 1032 2115 1032 2116 1085 2116 1072 2116 1032 2117 1072 2117 1118 2117 1118 2118 1072 2118 1083 2118 1118 2119 1083 2119 1033 2119 1033 2120 1083 2120 1081 2120 1033 2121 1081 2121 1116 2121 1116 2122 1081 2122 1073 2122 1116 2123 1073 2123 1035 2123 1034 2124 1035 2124 1071 2124 1034 2125 1071 2125 1121 2125 1121 2126 1071 2126 1077 2126 1121 2127 1077 2127 1036 2127 1036 2128 1077 2128 1070 2128 1036 2129 1070 2129 1110 2129 1448 2130 1039 2130 1452 2130 1038 2131 1452 2131 1039 2131 1038 2132 1037 2132 1452 2132 1448 2133 1449 2133 1039 2133 1039 2134 1449 2134 1040 2134 1039 2135 1040 2135 1038 2135 1038 2136 1040 2136 1037 2136 1037 2137 1040 2137 1041 2137 1450 2138 1449 2138 1452 2138 1452 2139 1449 2139 1448 2139 1453 2140 1043 2140 1045 2140 1045 2141 1042 2141 1453 2141 1455 2142 1043 2142 1453 2142 1455 2143 1342 2143 1043 2143 1043 2144 1342 2144 1044 2144 1043 2145 1044 2145 1045 2145 1045 2146 1044 2146 1322 2146 1045 2147 1322 2147 1042 2147 1042 2148 1322 2148 1454 2148 1046 2149 1434 2149 1432 2149 1435 2150 1046 2150 1432 2150 1435 2151 1298 2151 1046 2151 1046 2152 1298 2152 1301 2152 1046 2153 1301 2153 1300 2153 1046 2154 1300 2154 1434 2154 1434 2155 1300 2155 1433 2155 1048 2156 1047 2156 1431 2156 1437 2157 1048 2157 1431 2157 1430 2158 1047 2158 1304 2158 1304 2159 1047 2159 1048 2159 1304 2160 1048 2160 1303 2160 1303 2161 1048 2161 1437 2161 1303 2162 1437 2162 1308 2162 1050 2163 1446 2163 1052 2163 1447 2164 1051 2164 1049 2164 1049 2165 1051 2165 1050 2165 1050 2166 1051 2166 1446 2166 1054 2167 1053 2167 1056 2167 1056 2168 1053 2168 1457 2168 1457 2169 1053 2169 1456 2169 1055 2170 1054 2170 1428 2170 1428 2171 1054 2171 1056 2171 1457 2172 1428 2172 1056 2172 1441 2173 1442 2173 1057 2173 1057 2174 1442 2174 1311 2174 1057 2175 1311 2175 1060 2175 1060 2176 1311 2176 1061 2176 1061 2177 1311 2177 1440 2177 1427 2178 1314 2178 1058 2178 1058 2179 1314 2179 1309 2179 1058 2180 1309 2180 1426 2180 1426 2181 1309 2181 1439 2181 1439 2182 1309 2182 1320 2182 1441 2183 1057 2183 1059 2183 1059 2184 1060 2184 1061 2184 1060 2185 1059 2185 1057 2185 1324 2186 1062 2186 1410 2186 1410 2187 1062 2187 1115 2187 1410 2188 1115 2188 1351 2188 1351 2189 1115 2189 1114 2189 1351 2190 1114 2190 1397 2190 1397 2191 1114 2191 1398 2191 1401 2192 1400 2192 1328 2192 1328 2193 1400 2193 1413 2193 1065 2194 1107 2194 1223 2194 1065 2195 1223 2195 1063 2195 1067 2196 1066 2196 1099 2196 1099 2197 1066 2197 1153 2197 1146 2198 1420 2198 1064 2198 1064 2199 1420 2199 1107 2199 1064 2200 1107 2200 1148 2200 1148 2201 1107 2201 1065 2201 1148 2202 1065 2202 1149 2202 1149 2203 1065 2203 1151 2203 1067 2204 1207 2204 1155 2204 1063 2205 1223 2205 1224 2205 1065 2206 1219 2206 1152 2206 1152 2207 1101 2207 1068 2207 1068 2208 1101 2208 1069 2208 1069 2209 1101 2209 1153 2209 1153 2210 1101 2210 1099 2210 1151 2211 1065 2211 1152 2211 1080 2212 1079 2212 1035 2212 1035 2213 1079 2213 1071 2213 1080 2214 1035 2214 1073 2214 1152 2215 1219 2215 1101 2215 1425 2216 1110 2216 1070 2216 1075 2217 1425 2217 1183 2217 1075 2218 1183 2218 1178 2218 1075 2219 1178 2219 1076 2219 1075 2220 1076 2220 1103 2220 1075 2221 1103 2221 1104 2221 1185 2222 1180 2222 1070 2222 1070 2223 1180 2223 1181 2223 1070 2224 1181 2224 1183 2224 1070 2225 1183 2225 1425 2225 1185 2226 1070 2226 1077 2226 1185 2227 1077 2227 1078 2227 1078 2228 1077 2228 1071 2228 1071 2229 1079 2229 1078 2229 1080 2230 1073 2230 1082 2230 1081 2231 1082 2231 1073 2231 1081 2232 1190 2232 1082 2232 1190 2233 1081 2233 1083 2233 1190 2234 1083 2234 1084 2234 1084 2235 1083 2235 1072 2235 1084 2236 1072 2236 1189 2236 1072 2237 1195 2237 1189 2237 1072 2238 1085 2238 1195 2238 1085 2239 1086 2239 1195 2239 1085 2240 1192 2240 1086 2240 1087 2241 1198 2241 1074 2241 1074 2242 1198 2242 1192 2242 1074 2243 1192 2243 1085 2243 1087 2244 1089 2244 1198 2244 1088 2245 1089 2245 1087 2245 1088 2246 1200 2246 1089 2246 1090 2247 1091 2247 1158 2247 1158 2248 1091 2248 1092 2248 1158 2249 1092 2249 1093 2249 1093 2250 1092 2250 1200 2250 1093 2251 1200 2251 1088 2251 1090 2252 1203 2252 1094 2252 1090 2253 1094 2253 1091 2253 1096 2254 1095 2254 1203 2254 1096 2255 1203 2255 1090 2255 1207 2256 1097 2256 1155 2256 1155 2257 1097 2257 1096 2257 1096 2258 1097 2258 1095 2258 1098 2259 1207 2259 1067 2259 1098 2260 1067 2260 1099 2260 1098 2261 1099 2261 1100 2261 1100 2262 1099 2262 1208 2262 1208 2263 1099 2263 1101 2263 1208 2264 1101 2264 1209 2264 1209 2265 1101 2265 1211 2265 1175 2266 1106 2266 1102 2266 1102 2267 1106 2267 1104 2267 1102 2268 1104 2268 1103 2268 1105 2269 1418 2269 1175 2269 1175 2270 1418 2270 1106 2270 1418 2271 1108 2271 1107 2271 1105 2272 1108 2272 1418 2272 1105 2273 1222 2273 1108 2273 1107 2274 1108 2274 1223 2274 1121 2275 1036 2275 1024 2275 1024 2276 1036 2276 1109 2276 1413 2277 1400 2277 1110 2277 1110 2278 1400 2278 1399 2278 1110 2279 1399 2279 1036 2279 1036 2280 1399 2280 1109 2280 1120 2281 1360 2281 1398 2281 1127 2282 1133 2282 1111 2282 1139 2283 1373 2283 1111 2283 1111 2284 1373 2284 1112 2284 1111 2285 1112 2285 1127 2285 1030 2286 1366 2286 1368 2286 1030 2287 1368 2287 1113 2287 1120 2288 1398 2288 1147 2288 1147 2289 1398 2289 1114 2289 1147 2290 1114 2290 1411 2290 1411 2291 1114 2291 1115 2291 1116 2292 1035 2292 1117 2292 1116 2293 1377 2293 1379 2293 1116 2294 1379 2294 1033 2294 1033 2295 1379 2295 1381 2295 1033 2296 1381 2296 1118 2296 1118 2297 1381 2297 1383 2297 1393 2298 1169 2298 1141 2298 1142 2299 1119 2299 1125 2299 1024 2300 1025 2300 1121 2300 1121 2301 1025 2301 1405 2301 1402 2302 1377 2302 1116 2302 1402 2303 1116 2303 1117 2303 1389 2304 1122 2304 1123 2304 1156 2305 1124 2305 1362 2305 1156 2306 1362 2306 1154 2306 1154 2307 1362 2307 1363 2307 1154 2308 1363 2308 1141 2308 1141 2309 1363 2309 1364 2309 1141 2310 1364 2310 1393 2310 1125 2311 1361 2311 1142 2311 1121 2312 1405 2312 1034 2312 1034 2313 1405 2313 1126 2313 1034 2314 1126 2314 1035 2314 1035 2315 1126 2315 1163 2315 1035 2316 1163 2316 1117 2316 1127 2317 1375 2317 1133 2317 1133 2318 1375 2318 1376 2318 1135 2319 1029 2319 1031 2319 1031 2320 1029 2320 1128 2320 1031 2321 1128 2321 1030 2321 1368 2322 1129 2322 1113 2322 1113 2323 1129 2323 1130 2323 1113 2324 1130 2324 1123 2324 1141 2325 1169 2325 1131 2325 1131 2326 1169 2326 1168 2326 1131 2327 1168 2327 1136 2327 1136 2328 1168 2328 1137 2328 1125 2329 1119 2329 1132 2329 1132 2330 1119 2330 1145 2330 1132 2331 1145 2331 1150 2331 1133 2332 1376 2332 1135 2332 1135 2333 1376 2333 1134 2333 1135 2334 1134 2334 1029 2334 1123 2335 1122 2335 1157 2335 1361 2336 1136 2336 1137 2336 1383 2337 1403 2337 1118 2337 1118 2338 1403 2338 1138 2338 1118 2339 1138 2339 1032 2339 1032 2340 1138 2340 1160 2340 1032 2341 1160 2341 1139 2341 1139 2342 1160 2342 1140 2342 1139 2343 1140 2343 1384 2343 1387 2344 1366 2344 1030 2344 1387 2345 1030 2345 1128 2345 1389 2346 1123 2346 1130 2346 1122 2347 1143 2347 1157 2347 1157 2348 1143 2348 1144 2348 1157 2349 1144 2349 1156 2349 1156 2350 1144 2350 1391 2350 1150 2351 1145 2351 1396 2351 1139 2352 1384 2352 1373 2352 1156 2353 1391 2353 1124 2353 1150 2354 1396 2354 1360 2354 1411 2355 1146 2355 1147 2355 1147 2356 1146 2356 1064 2356 1147 2357 1064 2357 1120 2357 1120 2358 1064 2358 1148 2358 1120 2359 1148 2359 1360 2359 1360 2360 1148 2360 1149 2360 1360 2361 1149 2361 1150 2361 1150 2362 1149 2362 1151 2362 1150 2363 1151 2363 1132 2363 1132 2364 1151 2364 1125 2364 1125 2365 1151 2365 1152 2365 1125 2366 1152 2366 1361 2366 1361 2367 1152 2367 1068 2367 1361 2368 1068 2368 1136 2368 1136 2369 1068 2369 1069 2369 1136 2370 1069 2370 1131 2370 1131 2371 1069 2371 1153 2371 1131 2372 1153 2372 1141 2372 1141 2373 1153 2373 1066 2373 1141 2374 1066 2374 1154 2374 1154 2375 1066 2375 1067 2375 1154 2376 1067 2376 1156 2376 1156 2377 1067 2377 1155 2377 1156 2378 1155 2378 1157 2378 1157 2379 1155 2379 1096 2379 1157 2380 1096 2380 1123 2380 1123 2381 1096 2381 1090 2381 1123 2382 1090 2382 1113 2382 1113 2383 1090 2383 1158 2383 1113 2384 1158 2384 1030 2384 1030 2385 1158 2385 1093 2385 1371 2386 1384 2386 1312 2386 1312 2387 1384 2387 1140 2387 1312 2388 1140 2388 1159 2388 1159 2389 1140 2389 1160 2389 1159 2390 1160 2390 1338 2390 1338 2391 1160 2391 1138 2391 1338 2392 1138 2392 1336 2392 1336 2393 1138 2393 1403 2393 1335 2394 1402 2394 1161 2394 1161 2395 1402 2395 1117 2395 1161 2396 1117 2396 1162 2396 1162 2397 1117 2397 1163 2397 1162 2398 1163 2398 1164 2398 1164 2399 1163 2399 1126 2399 1164 2400 1126 2400 1404 2400 1404 2401 1126 2401 1405 2401 1316 2402 1387 2402 1128 2402 1390 2403 1391 2403 1165 2403 1165 2404 1391 2404 1144 2404 1165 2405 1144 2405 1166 2405 1166 2406 1144 2406 1143 2406 1166 2407 1143 2407 1167 2407 1167 2408 1143 2408 1122 2408 1167 2409 1122 2409 1388 2409 1388 2410 1122 2410 1389 2410 1394 2411 1137 2411 1356 2411 1356 2412 1137 2412 1168 2412 1356 2413 1168 2413 1347 2413 1347 2414 1168 2414 1169 2414 1347 2415 1169 2415 1406 2415 1393 2416 1392 2416 1169 2416 1169 2417 1392 2417 1170 2417 1169 2418 1170 2418 1406 2418 1171 2419 1396 2419 1145 2419 1171 2420 1145 2420 1172 2420 1172 2421 1145 2421 1119 2421 1172 2422 1119 2422 1395 2422 1395 2423 1119 2423 1142 2423 1266 2424 1340 2424 1173 2424 1231 2425 1222 2425 1174 2425 1174 2426 1222 2426 1105 2426 1174 2427 1105 2427 1264 2427 1264 2428 1105 2428 1175 2428 1175 2429 1102 2429 1264 2429 1264 2430 1102 2430 1176 2430 1176 2431 1102 2431 1263 2431 1102 2432 1103 2432 1263 2432 1263 2433 1103 2433 1177 2433 1177 2434 1103 2434 1179 2434 1179 2435 1103 2435 1076 2435 1179 2436 1076 2436 1178 2436 1183 2437 1184 2437 1178 2437 1178 2438 1184 2438 1261 2438 1178 2439 1261 2439 1179 2439 1180 2440 1260 2440 1181 2440 1181 2441 1260 2441 1182 2441 1181 2442 1182 2442 1183 2442 1183 2443 1182 2443 1184 2443 1187 2444 1186 2444 1078 2444 1260 2445 1180 2445 1258 2445 1258 2446 1180 2446 1185 2446 1258 2447 1185 2447 1078 2447 1258 2448 1078 2448 1186 2448 1187 2449 1078 2449 1079 2449 1187 2450 1079 2450 1188 2450 1188 2451 1079 2451 1080 2451 1188 2452 1080 2452 1257 2452 1257 2453 1080 2453 1082 2453 1257 2454 1082 2454 1256 2454 1256 2455 1082 2455 1190 2455 1256 2456 1190 2456 1254 2456 1254 2457 1190 2457 1253 2457 1253 2458 1190 2458 1084 2458 1253 2459 1084 2459 1191 2459 1191 2460 1084 2460 1189 2460 1192 2461 1248 2461 1086 2461 1086 2462 1248 2462 1193 2462 1086 2463 1193 2463 1251 2463 1086 2464 1251 2464 1195 2464 1195 2465 1251 2465 1194 2465 1195 2466 1194 2466 1189 2466 1189 2467 1194 2467 1191 2467 1198 2468 1196 2468 1197 2468 1198 2469 1197 2469 1192 2469 1192 2470 1197 2470 1248 2470 1089 2471 1201 2471 1196 2471 1089 2472 1196 2472 1198 2472 1092 2473 1199 2473 1200 2473 1200 2474 1199 2474 1089 2474 1089 2475 1199 2475 1201 2475 1091 2476 1205 2476 1202 2476 1091 2477 1202 2477 1092 2477 1092 2478 1202 2478 1199 2478 1203 2479 1243 2479 1204 2479 1203 2480 1204 2480 1094 2480 1094 2481 1204 2481 1091 2481 1091 2482 1204 2482 1205 2482 1095 2483 1242 2483 1203 2483 1203 2484 1242 2484 1243 2484 1097 2485 1206 2485 1242 2485 1097 2486 1242 2486 1095 2486 1206 2487 1097 2487 1207 2487 1206 2488 1207 2488 1240 2488 1240 2489 1207 2489 1235 2489 1235 2490 1207 2490 1098 2490 1208 2491 1239 2491 1100 2491 1100 2492 1239 2492 1237 2492 1100 2493 1237 2493 1098 2493 1098 2494 1237 2494 1236 2494 1098 2495 1236 2495 1235 2495 1210 2496 1234 2496 1209 2496 1209 2497 1234 2497 1208 2497 1208 2498 1234 2498 1239 2498 1209 2499 1211 2499 1210 2499 1210 2500 1211 2500 1270 2500 1270 2501 1211 2501 1220 2501 1270 2502 1220 2502 1212 2502 1212 2503 1220 2503 1269 2503 1220 2504 1213 2504 1269 2504 1269 2505 1213 2505 1214 2505 1269 2506 1214 2506 1268 2506 1268 2507 1214 2507 1216 2507 1216 2508 1214 2508 1215 2508 1216 2509 1215 2509 1221 2509 1216 2510 1221 2510 1267 2510 1340 2511 1266 2511 1217 2511 1266 2512 1267 2512 1217 2512 1217 2513 1267 2513 1218 2513 1218 2514 1267 2514 1221 2514 1211 2515 1101 2515 1220 2515 1220 2516 1101 2516 1219 2516 1220 2517 1219 2517 1213 2517 1065 2518 1214 2518 1219 2518 1219 2519 1214 2519 1213 2519 1065 2520 1221 2520 1215 2520 1065 2521 1215 2521 1214 2521 1065 2522 1063 2522 1221 2522 1221 2523 1063 2523 1225 2523 1108 2524 1222 2524 1223 2524 1223 2525 1222 2525 1224 2525 1224 2526 1229 2526 1063 2526 1063 2527 1229 2527 1226 2527 1226 2528 1225 2528 1063 2528 1227 2529 1232 2529 1226 2529 1226 2530 1232 2530 1225 2530 1173 2531 1340 2531 1227 2531 1229 2532 1230 2532 1226 2532 1226 2533 1230 2533 1227 2533 1227 2534 1230 2534 1173 2534 1222 2535 1233 2535 1224 2535 1224 2536 1233 2536 1228 2536 1224 2537 1228 2537 1229 2537 1229 2538 1228 2538 1230 2538 1222 2539 1231 2539 1233 2539 1225 2540 1232 2540 1355 2540 1231 2541 1277 2541 1233 2541 1233 2542 1277 2542 1228 2542 1228 2543 1277 2543 1230 2543 1230 2544 1277 2544 1271 2544 1230 2545 1271 2545 1173 2545 1238 2546 1239 2546 1273 2546 1273 2547 1239 2547 1279 2547 1279 2548 1239 2548 1234 2548 1279 2549 1234 2549 1278 2549 1278 2550 1234 2550 1210 2550 1278 2551 1210 2551 1270 2551 1272 2552 1235 2552 1236 2552 1272 2553 1236 2553 1238 2553 1238 2554 1236 2554 1237 2554 1238 2555 1237 2555 1239 2555 1235 2556 1272 2556 1240 2556 1240 2557 1272 2557 1241 2557 1240 2558 1241 2558 1206 2558 1206 2559 1241 2559 1275 2559 1206 2560 1275 2560 1242 2560 1242 2561 1275 2561 1243 2561 1243 2562 1275 2562 1204 2562 1204 2563 1275 2563 1274 2563 1204 2564 1274 2564 1205 2564 1205 2565 1274 2565 1244 2565 1205 2566 1244 2566 1202 2566 1202 2567 1244 2567 1245 2567 1202 2568 1245 2568 1199 2568 1199 2569 1245 2569 1246 2569 1199 2570 1246 2570 1201 2570 1201 2571 1246 2571 1247 2571 1201 2572 1247 2572 1280 2572 1201 2573 1280 2573 1196 2573 1196 2574 1280 2574 1197 2574 1197 2575 1280 2575 1249 2575 1197 2576 1249 2576 1248 2576 1286 2577 1248 2577 1249 2577 1250 2578 1251 2578 1286 2578 1286 2579 1251 2579 1193 2579 1286 2580 1193 2580 1248 2580 1284 2581 1194 2581 1250 2581 1250 2582 1194 2582 1251 2582 1284 2583 1191 2583 1194 2583 1191 2584 1284 2584 1289 2584 1191 2585 1289 2585 1253 2585 1253 2586 1289 2586 1252 2586 1253 2587 1252 2587 1255 2587 1253 2588 1255 2588 1254 2588 1254 2589 1255 2589 1256 2589 1256 2590 1255 2590 1288 2590 1256 2591 1288 2591 1257 2591 1257 2592 1288 2592 1287 2592 1257 2593 1287 2593 1188 2593 1188 2594 1287 2594 1281 2594 1188 2595 1281 2595 1187 2595 1187 2596 1281 2596 1259 2596 1187 2597 1259 2597 1186 2597 1186 2598 1259 2598 1258 2598 1258 2599 1259 2599 1292 2599 1258 2600 1292 2600 1260 2600 1260 2601 1292 2601 1182 2601 1182 2602 1292 2602 1262 2602 1182 2603 1262 2603 1184 2603 1184 2604 1262 2604 1261 2604 1261 2605 1262 2605 1179 2605 1179 2606 1262 2606 1290 2606 1179 2607 1290 2607 1177 2607 1177 2608 1290 2608 1263 2608 1263 2609 1290 2609 1276 2609 1263 2610 1276 2610 1176 2610 1176 2611 1276 2611 1264 2611 1264 2612 1276 2612 1265 2612 1264 2613 1265 2613 1174 2613 1174 2614 1265 2614 1277 2614 1174 2615 1277 2615 1231 2615 1266 2616 1283 2616 1267 2616 1267 2617 1283 2617 1216 2617 1216 2618 1283 2618 1278 2618 1216 2619 1278 2619 1268 2619 1268 2620 1278 2620 1269 2620 1269 2621 1278 2621 1212 2621 1278 2622 1270 2622 1212 2622 1283 2623 1266 2623 1271 2623 1271 2624 1266 2624 1173 2624 1244 2625 1274 2625 1285 2625 1285 2626 1241 2626 1272 2626 1285 2627 1272 2627 1238 2627 1285 2628 1238 2628 1273 2628 1285 2629 1246 2629 1245 2629 1285 2630 1245 2630 1244 2630 1274 2631 1275 2631 1285 2631 1285 2632 1275 2632 1241 2632 1291 2633 1265 2633 1276 2633 1246 2634 1285 2634 1247 2634 1247 2635 1285 2635 1280 2635 1291 2636 1276 2636 1290 2636 1282 2637 1271 2637 1291 2637 1291 2638 1271 2638 1277 2638 1291 2639 1277 2639 1265 2639 1278 2640 1283 2640 1295 2640 1278 2641 1295 2641 1279 2641 1279 2642 1295 2642 1293 2642 1279 2643 1293 2643 1273 2643 1273 2644 1293 2644 1285 2644 1249 2645 1280 2645 1285 2645 1281 2646 1287 2646 1285 2646 1291 2647 1292 2647 1259 2647 1291 2648 1259 2648 1285 2648 1285 2649 1259 2649 1281 2649 1271 2650 1282 2650 1283 2650 1283 2651 1282 2651 1295 2651 1285 2652 1284 2652 1250 2652 1285 2653 1250 2653 1286 2653 1285 2654 1286 2654 1249 2654 1287 2655 1288 2655 1285 2655 1285 2656 1288 2656 1255 2656 1255 2657 1252 2657 1285 2657 1285 2658 1252 2658 1289 2658 1285 2659 1289 2659 1284 2659 1290 2660 1262 2660 1291 2660 1291 2661 1262 2661 1292 2661 1296 2662 1294 2662 1282 2662 1282 2663 1294 2663 1295 2663 1291 2664 1296 2664 1282 2664 1285 2665 1296 2665 1291 2665 1297 2666 1285 2666 1293 2666 1285 2667 1297 2667 1296 2667 1297 2668 1293 2668 1294 2668 1294 2669 1293 2669 1295 2669 1297 2670 1294 2670 1296 2670 1221 2671 1225 2671 1218 2671 1218 2672 1225 2672 1355 2672 1161 2673 1162 2673 1314 2673 1369 2674 1367 2674 1319 2674 1349 2675 1433 2675 1299 2675 1299 2676 1433 2676 1300 2676 1299 2677 1300 2677 1301 2677 1302 2678 1325 2678 1298 2678 1298 2679 1325 2679 1454 2679 1303 2680 1348 2680 1406 2680 1303 2681 1406 2681 1304 2681 1349 2682 1348 2682 1308 2682 1308 2683 1348 2683 1303 2683 1304 2684 1406 2684 1170 2684 1304 2685 1170 2685 1430 2685 1305 2686 1306 2686 1365 2686 1365 2687 1306 2687 1307 2687 1365 2688 1307 2688 1390 2688 1365 2689 1390 2689 1392 2689 1392 2690 1390 2690 1430 2690 1392 2691 1430 2691 1170 2691 1390 2692 1444 2692 1430 2692 1430 2693 1444 2693 1319 2693 1430 2694 1319 2694 1436 2694 1349 2695 1308 2695 1433 2695 1433 2696 1308 2696 1018 2696 1018 2697 1308 2697 1436 2697 1404 2698 1320 2698 1164 2698 1164 2699 1320 2699 1309 2699 1164 2700 1309 2700 1162 2700 1162 2701 1309 2701 1314 2701 1310 2702 1320 2702 1449 2702 1449 2703 1450 2703 1310 2703 1310 2704 1450 2704 1451 2704 1310 2705 1451 2705 1325 2705 1313 2706 1310 2706 1325 2706 1314 2707 1310 2707 1313 2707 1440 2708 1311 2708 1338 2708 1442 2709 1371 2709 1311 2709 1311 2710 1371 2710 1312 2710 1311 2711 1312 2711 1159 2711 1311 2712 1159 2712 1338 2712 1313 2713 1440 2713 1314 2713 1314 2714 1440 2714 1336 2714 1313 2715 1443 2715 1442 2715 1442 2716 1443 2716 1456 2716 1315 2717 1367 2717 1316 2717 1315 2718 1316 2718 1053 2718 1053 2719 1316 2719 1026 2719 1442 2720 1456 2720 1386 2720 1386 2721 1456 2721 1028 2721 1028 2722 1456 2722 1053 2722 1028 2723 1053 2723 1027 2723 1027 2724 1053 2724 1026 2724 1367 2725 1315 2725 1319 2725 1317 2726 1429 2726 1388 2726 1388 2727 1429 2727 1167 2727 1167 2728 1429 2728 1318 2728 1167 2729 1318 2729 1166 2729 1166 2730 1318 2730 1165 2730 1165 2731 1318 2731 1390 2731 1390 2732 1318 2732 1444 2732 1370 2733 1429 2733 1317 2733 1370 2734 1369 2734 1429 2734 1429 2735 1369 2735 1319 2735 1429 2736 1319 2736 1445 2736 1342 2737 1041 2737 1328 2737 1328 2738 1041 2738 1040 2738 1298 2739 1454 2739 1409 2739 1345 2740 1321 2740 1342 2740 1342 2741 1321 2741 1062 2741 1342 2742 1062 2742 1044 2742 1044 2743 1062 2743 1324 2743 1044 2744 1324 2744 1322 2744 1323 2745 1409 2745 1454 2745 1323 2746 1454 2746 1322 2746 1323 2747 1322 2747 1324 2747 1325 2748 1302 2748 1018 2748 1451 2749 1342 2749 1325 2749 1320 2750 1401 2750 1449 2750 1449 2751 1401 2751 1040 2751 1040 2752 1401 2752 1328 2752 1328 2753 1326 2753 1415 2753 1328 2754 1415 2754 1330 2754 1327 2755 1342 2755 1329 2755 1329 2756 1342 2756 1328 2756 1329 2757 1328 2757 1020 2757 1020 2758 1328 2758 1330 2758 1020 2759 1330 2759 1331 2759 1332 2760 1333 2760 1334 2760 1334 2761 1333 2761 1401 2761 1334 2762 1401 2762 1404 2762 1404 2763 1401 2763 1320 2763 1336 2764 1378 2764 1335 2764 1336 2765 1335 2765 1314 2765 1314 2766 1335 2766 1161 2766 1337 2767 1378 2767 1380 2767 1380 2768 1378 2768 1336 2768 1380 2769 1336 2769 1382 2769 1440 2770 1338 2770 1336 2770 1442 2771 1386 2771 1371 2771 1371 2772 1386 2772 1385 2772 1374 2773 1372 2773 1339 2773 1339 2774 1372 2774 1371 2774 1339 2775 1371 2775 1385 2775 1299 2776 1301 2776 1217 2776 1217 2777 1301 2777 1298 2777 1217 2778 1298 2778 1340 2778 1340 2779 1298 2779 1409 2779 1340 2780 1409 2780 1227 2780 1227 2781 1409 2781 1341 2781 1327 2782 1022 2782 1342 2782 1342 2783 1022 2783 1343 2783 1342 2784 1343 2784 1344 2784 1342 2785 1344 2785 1414 2785 1342 2786 1414 2786 1345 2786 1345 2787 1414 2787 1346 2787 1018 2788 1436 2788 1325 2788 1315 2789 1443 2789 1319 2789 1319 2790 1443 2790 1436 2790 1436 2791 1443 2791 1313 2791 1436 2792 1313 2792 1325 2792 1451 2793 1041 2793 1342 2793 1352 2794 1353 2794 1323 2794 1323 2795 1353 2795 1409 2795 1350 2796 1347 2796 1348 2796 1348 2797 1347 2797 1406 2797 1349 2798 1354 2798 1350 2798 1349 2799 1350 2799 1348 2799 1353 2800 1352 2800 1351 2800 1351 2801 1352 2801 1410 2801 1358 2802 1354 2802 1407 2802 1232 2803 1357 2803 1359 2803 1359 2804 1218 2804 1355 2804 1359 2805 1355 2805 1232 2805 1356 2806 1347 2806 1350 2806 1356 2807 1350 2807 1394 2807 1397 2808 1353 2808 1351 2808 1353 2809 1397 2809 1357 2809 1353 2810 1357 2810 1408 2810 1408 2811 1357 2811 1232 2811 1171 2812 1172 2812 1218 2812 1354 2813 1358 2813 1350 2813 1350 2814 1358 2814 1394 2814 1218 2815 1172 2815 1395 2815 1358 2816 1407 2816 1218 2816 1358 2817 1218 2817 1395 2817 1171 2818 1218 2818 1359 2818 1407 2819 1354 2819 1299 2819 1299 2820 1354 2820 1349 2820 1353 2821 1408 2821 1409 2821 1409 2822 1408 2822 1341 2822 1218 2823 1407 2823 1217 2823 1217 2824 1407 2824 1299 2824 1227 2825 1341 2825 1232 2825 1232 2826 1341 2826 1408 2826 1399 2827 1401 2827 1333 2827 1360 2828 1359 2828 1357 2828 1137 2829 1394 2829 1361 2829 1361 2830 1394 2830 1358 2830 1361 2831 1358 2831 1142 2831 1142 2832 1358 2832 1395 2832 1124 2833 1390 2833 1307 2833 1124 2834 1307 2834 1362 2834 1362 2835 1307 2835 1306 2835 1362 2836 1306 2836 1363 2836 1363 2837 1306 2837 1305 2837 1363 2838 1305 2838 1364 2838 1364 2839 1305 2839 1365 2839 1364 2840 1365 2840 1393 2840 1366 2841 1316 2841 1367 2841 1366 2842 1367 2842 1368 2842 1368 2843 1367 2843 1369 2843 1368 2844 1369 2844 1129 2844 1129 2845 1369 2845 1370 2845 1129 2846 1370 2846 1130 2846 1130 2847 1370 2847 1317 2847 1130 2848 1317 2848 1389 2848 1389 2849 1317 2849 1388 2849 1373 2850 1371 2850 1372 2850 1373 2851 1372 2851 1112 2851 1112 2852 1372 2852 1374 2852 1112 2853 1374 2853 1127 2853 1127 2854 1374 2854 1339 2854 1127 2855 1339 2855 1375 2855 1375 2856 1339 2856 1385 2856 1375 2857 1385 2857 1376 2857 1377 2858 1335 2858 1378 2858 1377 2859 1378 2859 1379 2859 1379 2860 1378 2860 1337 2860 1379 2861 1337 2861 1381 2861 1381 2862 1337 2862 1380 2862 1381 2863 1380 2863 1383 2863 1383 2864 1380 2864 1382 2864 1383 2865 1382 2865 1403 2865 1403 2866 1382 2866 1336 2866 1371 2867 1373 2867 1384 2867 1385 2868 1386 2868 1376 2868 1316 2869 1366 2869 1387 2869 1390 2870 1124 2870 1391 2870 1393 2871 1365 2871 1392 2871 1359 2872 1360 2872 1396 2872 1359 2873 1396 2873 1171 2873 1398 2874 1357 2874 1397 2874 1399 2875 1400 2875 1401 2875 1335 2876 1377 2876 1402 2876 1405 2877 1334 2877 1404 2877 1115 2878 1062 2878 1411 2878 1411 2879 1062 2879 1321 2879 1420 2880 1146 2880 1411 2880 1420 2881 1411 2881 1321 2881 1343 2882 1412 2882 1344 2882 1344 2883 1412 2883 1421 2883 1344 2884 1421 2884 1417 2884 1110 2885 1424 2885 1326 2885 1110 2886 1326 2886 1413 2886 1413 2887 1326 2887 1328 2887 1345 2888 1419 2888 1321 2888 1419 2889 1420 2889 1321 2889 1414 2890 1417 2890 1346 2890 1417 2891 1419 2891 1346 2891 1346 2892 1419 2892 1345 2892 1344 2893 1417 2893 1414 2893 1423 2894 1020 2894 1331 2894 1415 2895 1416 2895 1330 2895 1330 2896 1416 2896 1331 2896 1331 2897 1416 2897 1423 2897 1326 2898 1424 2898 1415 2898 1415 2899 1424 2899 1416 2899 1418 2900 1419 2900 1417 2900 1419 2901 1418 2901 1107 2901 1419 2902 1107 2902 1420 2902 1418 2903 1417 2903 1421 2903 1412 2904 1106 2904 1421 2904 1421 2905 1106 2905 1418 2905 1023 2906 1106 2906 1412 2906 1106 2907 1023 2907 1104 2907 1023 2908 1422 2908 1104 2908 1104 2909 1422 2909 1021 2909 1019 2910 1423 2910 1075 2910 1104 2911 1021 2911 1075 2911 1075 2912 1021 2912 1019 2912 1425 2913 1075 2913 1423 2913 1425 2914 1423 2914 1416 2914 1425 2915 1416 2915 1424 2915 1110 2916 1425 2916 1424 2916 1052 2917 1444 2917 1050 2917 1050 2918 1444 2918 1318 2918 1050 2919 1318 2919 1049 2919 1049 2920 1318 2920 1447 2920 1447 2921 1318 2921 1429 2921 1058 2922 1426 2922 1438 2922 1427 2923 1058 2923 1438 2923 1426 2924 1439 2924 1438 2924 1320 2925 1310 2925 1439 2925 1439 2926 1310 2926 1438 2926 1427 2927 1438 2927 1314 2927 1314 2928 1438 2928 1310 2928 1440 2929 1313 2929 1061 2929 1061 2930 1313 2930 1059 2930 1456 2931 1443 2931 1457 2931 1457 2932 1443 2932 1428 2932 1441 2933 1059 2933 1442 2933 1442 2934 1059 2934 1313 2934 1429 2935 1445 2935 1447 2935 1447 2936 1445 2936 1051 2936 1055 2937 1428 2937 1315 2937 1315 2938 1428 2938 1443 2938 1430 2939 1436 2939 1047 2939 1047 2940 1436 2940 1431 2940 1319 2941 1444 2941 1446 2941 1446 2942 1444 2942 1052 2942 1437 2943 1431 2943 1308 2943 1308 2944 1431 2944 1436 2944 1433 2945 1018 2945 1434 2945 1434 2946 1018 2946 1432 2946 1435 2947 1432 2947 1298 2947 1298 2948 1432 2948 1302 2948 1454 2949 1325 2949 1042 2949 1042 2950 1325 2950 1453 2950 1455 2951 1453 2951 1342 2951 1342 2952 1453 2952 1325 2952 1452 2953 1037 2953 1451 2953 1451 2954 1037 2954 1041 2954 1051 2955 1445 2955 1319 2955 1051 2956 1319 2956 1446 2956 1450 2957 1452 2957 1451 2957 1459 2958 1537 2958 1460 2958 1463 2959 2097 2959 1464 2959 1465 2960 2111 2960 1903 2960 1466 2961 1607 2961 1467 2961 1466 2962 1467 2962 1617 2962 1617 2963 1467 2963 1610 2963 1617 2964 1610 2964 1624 2964 1624 2965 1610 2965 1468 2965 1624 2966 1468 2966 1628 2966 1628 2967 1468 2967 1609 2967 1628 2968 1609 2968 1630 2968 1630 2969 1609 2969 1469 2969 1630 2970 1469 2970 2063 2970 2049 2971 1470 2971 1635 2971 1741 2972 2047 2972 2048 2972 2048 2973 1471 2973 1741 2973 1471 2974 2048 2974 1472 2974 2022 2975 2023 2975 1473 2975 1473 2976 2023 2976 2020 2976 1473 2977 2020 2977 2019 2977 2022 2978 1473 2978 2019 2978 2018 2979 1918 2979 1475 2979 1475 2980 1918 2980 1474 2980 1475 2981 1474 2981 2017 2981 2018 2982 1475 2982 2017 2982 2014 2983 2015 2983 2056 2983 2015 2984 1693 2984 2056 2984 1926 2985 1693 2985 2015 2985 1692 2986 1921 2986 1922 2986 1922 2987 1476 2987 1692 2987 1479 2988 1480 2988 1559 2988 1705 2989 1704 2989 1728 2989 1935 2990 1953 2990 1945 2990 1489 2991 1954 2991 1934 2991 1545 2992 1954 2992 1489 2992 1722 2993 1564 2993 1751 2993 1930 2994 1722 2994 1751 2994 1492 2995 1516 2995 1915 2995 1782 2996 1882 2996 1493 2996 1493 2997 1882 2997 1463 2997 1913 2998 1873 2998 1874 2998 1913 2999 1874 2999 1871 2999 1904 3000 1593 3000 1972 3000 1904 3001 1972 3001 1498 3001 1498 3002 1972 3002 1596 3002 1498 3003 1596 3003 1501 3003 1499 3004 1465 3004 1903 3004 1902 3005 1500 3005 1586 3005 1505 3006 1504 3006 1760 3006 1870 3007 1578 3007 1869 3007 1867 3008 1591 3008 1892 3008 1866 3009 1590 3009 1865 3009 1502 3010 1911 3010 1503 3010 1579 3011 1504 3011 1505 3011 1864 3012 1805 3012 1848 3012 1848 3013 1805 3013 1506 3013 1848 3014 1506 3014 1847 3014 1847 3015 1506 3015 1803 3015 1847 3016 1803 3016 1507 3016 1507 3017 1803 3017 1802 3017 1507 3018 1802 3018 1845 3018 1845 3019 1802 3019 1508 3019 1845 3020 1508 3020 1843 3020 1843 3021 1508 3021 1801 3021 1843 3022 1801 3022 1509 3022 1843 3023 1509 3023 1842 3023 1842 3024 1509 3024 1841 3024 1841 3025 1509 3025 1800 3025 1841 3026 1800 3026 1854 3026 1635 3027 1660 3027 1649 3027 1889 3028 1890 3028 2099 3028 1462 3029 1510 3029 1887 3029 1784 3030 1882 3030 1782 3030 1789 3031 2105 3031 1884 3031 1884 3032 2105 3032 1496 3032 1496 3033 2105 3033 1907 3033 1463 3034 1464 3034 1512 3034 1510 3035 1520 3035 1494 3035 1494 3036 1520 3036 1513 3036 1494 3037 1513 3037 1886 3037 1886 3038 1513 3038 1514 3038 1886 3039 1514 3039 2098 3039 1889 3040 1522 3040 1888 3040 1888 3041 1522 3041 1846 3041 1888 3042 1846 3042 1523 3042 1523 3043 1846 3043 1524 3043 1872 3044 1517 3044 1518 3044 1872 3045 1518 3045 1871 3045 1871 3046 1518 3046 1841 3046 1871 3047 1841 3047 2079 3047 1871 3048 2079 3048 1796 3048 1772 3049 1519 3049 1849 3049 2106 3050 1849 3050 1520 3050 2106 3051 1520 3051 1462 3051 1462 3052 1520 3052 1510 3052 2098 3053 1514 3053 2100 3053 2100 3054 1514 3054 1521 3054 2100 3055 1521 3055 1522 3055 2100 3056 1522 3056 2099 3056 2099 3057 1522 3057 1889 3057 2095 3058 1523 3058 1524 3058 2095 3059 1524 3059 2093 3059 2093 3060 1524 3060 1525 3060 2093 3061 1525 3061 1526 3061 1526 3062 1525 3062 1527 3062 2092 3063 1526 3063 1527 3063 1516 3064 1527 3064 1844 3064 1516 3065 1844 3065 1528 3065 1516 3066 1528 3066 1515 3066 1515 3067 1528 3067 1529 3067 1515 3068 1529 3068 2087 3068 2087 3069 1529 3069 2088 3069 2088 3070 1529 3070 1517 3070 2088 3071 1517 3071 1872 3071 2088 3072 1872 3072 2086 3072 1972 3073 1764 3073 2114 3073 1820 3074 1969 3074 1821 3074 1821 3075 1969 3075 1966 3075 1821 3076 1966 3076 1530 3076 1530 3077 1966 3077 2114 3077 1909 3078 1596 3078 1531 3078 1531 3079 1596 3079 1971 3079 1531 3080 1971 3080 1820 3080 1820 3081 1971 3081 1969 3081 1909 3082 1531 3082 1817 3082 1909 3083 1817 3083 1532 3083 1532 3084 1817 3084 1815 3084 1532 3085 1815 3085 1908 3085 1908 3086 1815 3086 1893 3086 1893 3087 1815 3087 1461 3087 1893 3088 1461 3088 1814 3088 1893 3089 1814 3089 1533 3089 1533 3090 1814 3090 1827 3090 1533 3091 1827 3091 1534 3091 1534 3092 1827 3092 1826 3092 1534 3093 1826 3093 1599 3093 1599 3094 1826 3094 1825 3094 1599 3095 1825 3095 1894 3095 1894 3096 1825 3096 1535 3096 1894 3097 1535 3097 1600 3097 1600 3098 1535 3098 1824 3098 1600 3099 1824 3099 1910 3099 1910 3100 1824 3100 1536 3100 1910 3101 1536 3101 1581 3101 1581 3102 1536 3102 1460 3102 1581 3103 1460 3103 1580 3103 1580 3104 1460 3104 1905 3104 1905 3105 1460 3105 1537 3105 1905 3106 1537 3106 1459 3106 1905 3107 1459 3107 1912 3107 1912 3108 1459 3108 1458 3108 1912 3109 1458 3109 1760 3109 1538 3110 1734 3110 1746 3110 1734 3111 1538 3111 1823 3111 1734 3112 1823 3112 1732 3112 1823 3113 1539 3113 2004 3113 1823 3114 2004 3114 2001 3114 1823 3115 2001 3115 1732 3115 1732 3116 2001 3116 2000 3116 1539 3117 1541 3117 2004 3117 1540 3118 2006 3118 1541 3118 1542 3119 2005 3119 1540 3119 1813 3120 2008 3120 2010 3120 1813 3121 2010 3121 1542 3121 1542 3122 2010 3122 2005 3122 2008 3123 1813 3123 1544 3123 2008 3124 1544 3124 2011 3124 2012 3125 2011 3125 1543 3125 1543 3126 2011 3126 1544 3126 1818 3127 1935 3127 1816 3127 1549 3128 1816 3128 1935 3128 1838 3129 1545 3129 1822 3129 1822 3130 1545 3130 1934 3130 1935 3131 1818 3131 1819 3131 1935 3132 1819 3132 1546 3132 1546 3133 1819 3133 1547 3133 1546 3134 1547 3134 1729 3134 1729 3135 1547 3135 1822 3135 1729 3136 1822 3136 1548 3136 1548 3137 1822 3137 1934 3137 2012 3138 1543 3138 1998 3138 1998 3139 1543 3139 1816 3139 1998 3140 1816 3140 1549 3140 1555 3141 1554 3141 1666 3141 1672 3142 1557 3142 1555 3142 1672 3143 1601 3143 1557 3143 2038 3144 1621 3144 1560 3144 1479 3145 1721 3145 2037 3145 2037 3146 1721 3146 2043 3146 2043 3147 1721 3147 1719 3147 2043 3148 1719 3148 2039 3148 2039 3149 1719 3149 1723 3149 2039 3150 1723 3150 2036 3150 2036 3151 1723 3151 1724 3151 2036 3152 1724 3152 2078 3152 1706 3153 1941 3153 1629 3153 1629 3154 1941 3154 1715 3154 1629 3155 1715 3155 1627 3155 1627 3156 1715 3156 1482 3156 1627 3157 1482 3157 1626 3157 1626 3158 1482 3158 1481 3158 1626 3159 1481 3159 1625 3159 1625 3160 1481 3160 1558 3160 1625 3161 1558 3161 1623 3161 1623 3162 1558 3162 1559 3162 1623 3163 1559 3163 1622 3163 1622 3164 1559 3164 1480 3164 1622 3165 1480 3165 1560 3165 1560 3166 1480 3166 1479 3166 1560 3167 1479 3167 2038 3167 2038 3168 1479 3168 2037 3168 1952 3169 1708 3169 1561 3169 1561 3170 1708 3170 1562 3170 1561 3171 1562 3171 1477 3171 1477 3172 1562 3172 1687 3172 1477 3173 1687 3173 1478 3173 1478 3174 1687 3174 1686 3174 1478 3175 1686 3175 1564 3175 1564 3176 1686 3176 1563 3176 1564 3177 1563 3177 1565 3177 1565 3178 1563 3178 1566 3178 1565 3179 1566 3179 1724 3179 1724 3180 1566 3180 1688 3180 1724 3181 1688 3181 2078 3181 1656 3182 1679 3182 1677 3182 1656 3183 1677 3183 1657 3183 1657 3184 1677 3184 1575 3184 1657 3185 1575 3185 1659 3185 1659 3186 1575 3186 1676 3186 1659 3187 1676 3187 1661 3187 1661 3188 1676 3188 1675 3188 1661 3189 1675 3189 1567 3189 1567 3190 1675 3190 1568 3190 1567 3191 1568 3191 1650 3191 1650 3192 1568 3192 1573 3192 1650 3193 1573 3193 1569 3193 1569 3194 1573 3194 1674 3194 1569 3195 1674 3195 1653 3195 1808 3196 1640 3196 1652 3196 1652 3197 1640 3197 1641 3197 1652 3198 1641 3198 1651 3198 1651 3199 1641 3199 1642 3199 1651 3200 1642 3200 1649 3200 1649 3201 1642 3201 1635 3201 1660 3202 1635 3202 1645 3202 1660 3203 1645 3203 1658 3203 1658 3204 1645 3204 1646 3204 1658 3205 1646 3205 1657 3205 1657 3206 1646 3206 1647 3206 1657 3207 1647 3207 1812 3207 1812 3208 1647 3208 1648 3208 1635 3209 1485 3209 2049 3209 1635 3210 1486 3210 1485 3210 1483 3211 1804 3211 1648 3211 1483 3212 1648 3212 1647 3212 1483 3213 1647 3213 1646 3213 1483 3214 1646 3214 1570 3214 1483 3215 1570 3215 1484 3215 1484 3216 1570 3216 1645 3216 1484 3217 1645 3217 1485 3217 1485 3218 1645 3218 1571 3218 1485 3219 1571 3219 2049 3219 1635 3220 1572 3220 1486 3220 1642 3221 1641 3221 1487 3221 1487 3222 1486 3222 1642 3222 1642 3223 1486 3223 1572 3223 1641 3224 1488 3224 1487 3224 1641 3225 1640 3225 1488 3225 1488 3226 1640 3226 1798 3226 1714 3227 1674 3227 1573 3227 1568 3228 1604 3228 1573 3228 1573 3229 1604 3229 1714 3229 1568 3230 1574 3230 1604 3230 2042 3231 2041 3231 1550 3231 1550 3232 2041 3232 1574 3232 1551 3233 1550 3233 1575 3233 1551 3234 1575 3234 1677 3234 1677 3235 1552 3235 1551 3235 1679 3236 1552 3236 1677 3236 1925 3237 2034 3237 1923 3237 1985 3238 2107 3238 1983 3238 1983 3239 2107 3239 1576 3239 2033 3240 2031 3240 2035 3240 2035 3241 2031 3241 1737 3241 1737 3242 2031 3242 1958 3242 1975 3243 2033 3243 1980 3243 1980 3244 2033 3244 2035 3244 1737 3245 1957 3245 2034 3245 1957 3246 1737 3246 1958 3246 2027 3247 2028 3247 1984 3247 1984 3248 1983 3248 2027 3248 2027 3249 1983 3249 1576 3249 2027 3250 1576 3250 2026 3250 1984 3251 2028 3251 2029 3251 1984 3252 2029 3252 1577 3252 1577 3253 2029 3253 2030 3253 1919 3254 2032 3254 1577 3254 1919 3255 1577 3255 1974 3255 1974 3256 1577 3256 2030 3256 2110 3257 2108 3257 2109 3257 1910 3258 1578 3258 1870 3258 1910 3259 1870 3259 1600 3259 1870 3260 1578 3260 1600 3260 1912 3261 1579 3261 1505 3261 1760 3262 1504 3262 1912 3262 1912 3263 1504 3263 1579 3263 1581 3264 1580 3264 1910 3264 1503 3265 1586 3265 1500 3265 1503 3266 1911 3266 1586 3266 1586 3267 1911 3267 1582 3267 1582 3268 1911 3268 1891 3268 2111 3269 1896 3269 1903 3269 1585 3270 1584 3270 1586 3270 1896 3271 2111 3271 1499 3271 1588 3272 1587 3272 1896 3272 1589 3273 1865 3273 1761 3273 1590 3274 1761 3274 1865 3274 1593 3275 1892 3275 1591 3275 1592 3276 1762 3276 1589 3276 1593 3277 1764 3277 1972 3277 1594 3278 1968 3278 1972 3278 1595 3279 1596 3279 1972 3279 1595 3280 1972 3280 1968 3280 1595 3281 1759 3281 1596 3281 1597 3282 1596 3282 1909 3282 1597 3283 1909 3283 1868 3283 1597 3284 1501 3284 1596 3284 1533 3285 1598 3285 2113 3285 1909 3286 1532 3286 1908 3286 2112 3287 1533 3287 2113 3287 1598 3288 1533 3288 1534 3288 1598 3289 1534 3289 1599 3289 1674 3290 1556 3290 1673 3290 1673 3291 1556 3291 1601 3291 1673 3292 1601 3292 1672 3292 1666 3293 1554 3293 1678 3293 1678 3294 1554 3294 1553 3294 1678 3295 1553 3295 1679 3295 1679 3296 1553 3296 1552 3296 1556 3297 2072 3297 2069 3297 1556 3298 2069 3298 1601 3298 1601 3299 2069 3299 2068 3299 1601 3300 2068 3300 1557 3300 1557 3301 2068 3301 2065 3301 1557 3302 2065 3302 1602 3302 1604 3303 1574 3303 2058 3303 1604 3304 2058 3304 1603 3304 1604 3305 1603 3305 2075 3305 1604 3306 2075 3306 1714 3306 1714 3307 2075 3307 1605 3307 1714 3308 1605 3308 2074 3308 1714 3309 2074 3309 1606 3309 1714 3310 1606 3310 1556 3310 1556 3311 1606 3311 2072 3311 1551 3312 1467 3312 1550 3312 1550 3313 1467 3313 1607 3313 1555 3314 2051 3314 2060 3314 1555 3315 2060 3315 1554 3315 1554 3316 2060 3316 2061 3316 1554 3317 2061 3317 1553 3317 1553 3318 2061 3318 1608 3318 1553 3319 1608 3319 1552 3319 1552 3320 1608 3320 1469 3320 1552 3321 1469 3321 1609 3321 1552 3322 1609 3322 1551 3322 1551 3323 1609 3323 1468 3323 1551 3324 1468 3324 1610 3324 1551 3325 1610 3325 1467 3325 1963 3326 1982 3326 1612 3326 1963 3327 1612 3327 1611 3327 1611 3328 1612 3328 2109 3328 1614 3329 1611 3329 1704 3329 1611 3330 1614 3330 1963 3330 1963 3331 1614 3331 1613 3331 1963 3332 1613 3332 1962 3332 2052 3333 1613 3333 1614 3333 1704 3334 2056 3334 2055 3334 1614 3335 1704 3335 2052 3335 1704 3336 2055 3336 1615 3336 1704 3337 1615 3337 2044 3337 1704 3338 2044 3338 2052 3338 2059 3339 2053 3339 1616 3339 2077 3340 1466 3340 1617 3340 1713 3341 1631 3341 1618 3341 1618 3342 1631 3342 2062 3342 1618 3343 2062 3343 1712 3343 1712 3344 2062 3344 1620 3344 1712 3345 1620 3345 1619 3345 1619 3346 1620 3346 1690 3346 1690 3347 1620 3347 2054 3347 2054 3348 1620 3348 1616 3348 2054 3349 1616 3349 2053 3349 1621 3350 2077 3350 1560 3350 1560 3351 2077 3351 1617 3351 1560 3352 1617 3352 1622 3352 1622 3353 1617 3353 1623 3353 1623 3354 1617 3354 1624 3354 1623 3355 1624 3355 1625 3355 1625 3356 1624 3356 1628 3356 1625 3357 1628 3357 1626 3357 1626 3358 1628 3358 1627 3358 1627 3359 1628 3359 1630 3359 1627 3360 1630 3360 1629 3360 1629 3361 1630 3361 1706 3361 1706 3362 1630 3362 2063 3362 1706 3363 2063 3363 1631 3363 1706 3364 1631 3364 1707 3364 1707 3365 1631 3365 1713 3365 1798 3366 1640 3366 1639 3366 1798 3367 1639 3367 1797 3367 1797 3368 1639 3368 1638 3368 1797 3369 1638 3369 1940 3369 1940 3370 1638 3370 1637 3370 1940 3371 1637 3371 1939 3371 1939 3372 1637 3372 1636 3372 1939 3373 1636 3373 1938 3373 1938 3374 1636 3374 1632 3374 1938 3375 1632 3375 1633 3375 1938 3376 1633 3376 1937 3376 1937 3377 1633 3377 1807 3377 1807 3378 1633 3378 1644 3378 1807 3379 1644 3379 1936 3379 1936 3380 1644 3380 1643 3380 1936 3381 1643 3381 1634 3381 1936 3382 1634 3382 1804 3382 1804 3383 1634 3383 1648 3383 1636 3384 1637 3384 1638 3384 1642 3385 1572 3385 1635 3385 1643 3386 1648 3386 1634 3386 1571 3387 1635 3387 2049 3387 1645 3388 1635 3388 1571 3388 1646 3389 1645 3389 1570 3389 1812 3390 1648 3390 1811 3390 1811 3391 1648 3391 1643 3391 1811 3392 1643 3392 1655 3392 1655 3393 1643 3393 1644 3393 1655 3394 1644 3394 1633 3394 1655 3395 1633 3395 1810 3395 1810 3396 1633 3396 1632 3396 1810 3397 1632 3397 1809 3397 1809 3398 1632 3398 1636 3398 1809 3399 1636 3399 1654 3399 1654 3400 1636 3400 1638 3400 1654 3401 1638 3401 1808 3401 1808 3402 1638 3402 1639 3402 1808 3403 1639 3403 1640 3403 1649 3404 1567 3404 1651 3404 1651 3405 1567 3405 1650 3405 1651 3406 1650 3406 1652 3406 1652 3407 1650 3407 1569 3407 1652 3408 1569 3408 1808 3408 1808 3409 1569 3409 1653 3409 1808 3410 1653 3410 1654 3410 1654 3411 1653 3411 1662 3411 1654 3412 1662 3412 1809 3412 1809 3413 1662 3413 1664 3413 1809 3414 1664 3414 1810 3414 1810 3415 1664 3415 1665 3415 1810 3416 1665 3416 1655 3416 1655 3417 1665 3417 1667 3417 1655 3418 1667 3418 1668 3418 1655 3419 1668 3419 1811 3419 1811 3420 1668 3420 1669 3420 1811 3421 1669 3421 1812 3421 1812 3422 1669 3422 1656 3422 1812 3423 1656 3423 1657 3423 1658 3424 1657 3424 1659 3424 1658 3425 1659 3425 1660 3425 1660 3426 1659 3426 1661 3426 1660 3427 1661 3427 1649 3427 1649 3428 1661 3428 1567 3428 1653 3429 1674 3429 1663 3429 1653 3430 1663 3430 1662 3430 1662 3431 1663 3431 1673 3431 1662 3432 1673 3432 1664 3432 1664 3433 1673 3433 1671 3433 1664 3434 1671 3434 1665 3434 1665 3435 1671 3435 1670 3435 1665 3436 1670 3436 1667 3436 1667 3437 1670 3437 1666 3437 1667 3438 1666 3438 1680 3438 1667 3439 1680 3439 1668 3439 1668 3440 1680 3440 1678 3440 1668 3441 1678 3441 1669 3441 1669 3442 1678 3442 1679 3442 1669 3443 1679 3443 1656 3443 1555 3444 1670 3444 1672 3444 1672 3445 1670 3445 1671 3445 1672 3446 1671 3446 1673 3446 1673 3447 1663 3447 1674 3447 1574 3448 1568 3448 1675 3448 1574 3449 1675 3449 1550 3449 1550 3450 1675 3450 1676 3450 1550 3451 1676 3451 1575 3451 1678 3452 1680 3452 1666 3452 1555 3453 1666 3453 1670 3453 1694 3454 1698 3454 1682 3454 1682 3455 1698 3455 1696 3455 2050 3456 1681 3456 2066 3456 1708 3457 2071 3457 2073 3457 1682 3458 2050 3458 1694 3458 1694 3459 2050 3459 2066 3459 1694 3460 2066 3460 1683 3460 1683 3461 2066 3461 2067 3461 1683 3462 2067 3462 1699 3462 1699 3463 2067 3463 1684 3463 1684 3464 2067 3464 2070 3464 1684 3465 2070 3465 1710 3465 1710 3466 2070 3466 2071 3466 1710 3467 2071 3467 1708 3467 2076 3468 1688 3468 1566 3468 2076 3469 1566 3469 1685 3469 1685 3470 1566 3470 1563 3470 1685 3471 1563 3471 1686 3471 1685 3472 1686 3472 2073 3472 2073 3473 1686 3473 1687 3473 2073 3474 1687 3474 1562 3474 2073 3475 1562 3475 1708 3475 2076 3476 2064 3476 1688 3476 1688 3477 2064 3477 2057 3477 1688 3478 2057 3478 2078 3478 1689 3479 1694 3479 1683 3479 2056 3480 1692 3480 2054 3480 1947 3481 2014 3481 1705 3481 2054 3482 1692 3482 1476 3482 2054 3483 1476 3483 1690 3483 1690 3484 1476 3484 1691 3484 1690 3485 1691 3485 1693 3485 1692 3486 2056 3486 1691 3486 1691 3487 2056 3487 1693 3487 1946 3488 1693 3488 2014 3488 1946 3489 2014 3489 1947 3489 1981 3490 1697 3490 1694 3490 1981 3491 1689 3491 1695 3491 1981 3492 1694 3492 1689 3492 1964 3493 1696 3493 1961 3493 1961 3494 1696 3494 1698 3494 1961 3495 1698 3495 1697 3495 1697 3496 1698 3496 1694 3496 1956 3497 1709 3497 1951 3497 1710 3498 1711 3498 1684 3498 1684 3499 1711 3499 1699 3499 1699 3500 1711 3500 1700 3500 1699 3501 1700 3501 1683 3501 1683 3502 1700 3502 1765 3502 1683 3503 1765 3503 1689 3503 1956 3504 1951 3504 1727 3504 1956 3505 1727 3505 1766 3505 1766 3506 1727 3506 1950 3506 1766 3507 1950 3507 1701 3507 1725 3508 1976 3508 1701 3508 1725 3509 1701 3509 1950 3509 1973 3510 1725 3510 1703 3510 1725 3511 1702 3511 1976 3511 1702 3512 1725 3512 1973 3512 1703 3513 1725 3513 1949 3513 1703 3514 1949 3514 1960 3514 1960 3515 1948 3515 1705 3515 2014 3516 2056 3516 1704 3516 2014 3517 1704 3517 1705 3517 1941 3518 1706 3518 1942 3518 1942 3519 1706 3519 1707 3519 1952 3520 1709 3520 1708 3520 1708 3521 1709 3521 1710 3521 1710 3522 1709 3522 1956 3522 1710 3523 1956 3523 1711 3523 1693 3524 1946 3524 1690 3524 1690 3525 1946 3525 1619 3525 1619 3526 1946 3526 1945 3526 1619 3527 1945 3527 1712 3527 1712 3528 1945 3528 1618 3528 1618 3529 1945 3529 1944 3529 1618 3530 1944 3530 1713 3530 1713 3531 1944 3531 1943 3531 1713 3532 1943 3532 1707 3532 1707 3533 1943 3533 1942 3533 1714 3534 1556 3534 1674 3534 1478 3535 1749 3535 1748 3535 1559 3536 1718 3536 1479 3536 1729 3537 1548 3537 1934 3537 1729 3538 1934 3538 1941 3538 1941 3539 1934 3539 1715 3539 1934 3540 1954 3540 1715 3540 1715 3541 1954 3541 1716 3541 1715 3542 1716 3542 1482 3542 1482 3543 1716 3543 1717 3543 1482 3544 1717 3544 1757 3544 1482 3545 1757 3545 1481 3545 1481 3546 1757 3546 1931 3546 1481 3547 1931 3547 1558 3547 1558 3548 1931 3548 1933 3548 1559 3549 1558 3549 1932 3549 1932 3550 1933 3550 1755 3550 1932 3551 1755 3551 1559 3551 1559 3552 1755 3552 1718 3552 1720 3553 1718 3553 1756 3553 1723 3554 1719 3554 1754 3554 1490 3555 1754 3555 1719 3555 1756 3556 1490 3556 1720 3556 1490 3557 1719 3557 1720 3557 1720 3558 1719 3558 1721 3558 1720 3559 1721 3559 1718 3559 1718 3560 1721 3560 1479 3560 1930 3561 1722 3561 1564 3561 1478 3562 1564 3562 1722 3562 1478 3563 1722 3563 1749 3563 1723 3564 1754 3564 1753 3564 1723 3565 1753 3565 1724 3565 1724 3566 1753 3566 1751 3566 1724 3567 1751 3567 1565 3567 1565 3568 1751 3568 1564 3568 1726 3569 1709 3569 2000 3569 2000 3570 1709 3570 1952 3570 2000 3571 1952 3571 1730 3571 1730 3572 1952 3572 1561 3572 1730 3573 1561 3573 1748 3573 1748 3574 1561 3574 1477 3574 1748 3575 1477 3575 1478 3575 2000 3576 2002 3576 1726 3576 1725 3577 1726 3577 1949 3577 1949 3578 1726 3578 1948 3578 1725 3579 1950 3579 1726 3579 1727 3580 1726 3580 1950 3580 1953 3581 1935 3581 1945 3581 1945 3582 1935 3582 1546 3582 1945 3583 1549 3583 1953 3583 1946 3584 1998 3584 1549 3584 1946 3585 1549 3585 1945 3585 1947 3586 1998 3586 1946 3586 2002 3587 1988 3587 1726 3587 1988 3588 2002 3588 1990 3588 1730 3589 1731 3589 2000 3589 2000 3590 1734 3590 1732 3590 1730 3591 1733 3591 1731 3591 1491 3592 1734 3592 2000 3592 1947 3593 1728 3593 1998 3593 1728 3594 1925 3594 1998 3594 1728 3595 1737 3595 1925 3595 1988 3596 1736 3596 1726 3596 1726 3597 1736 3597 1948 3597 1988 3598 1735 3598 1736 3598 1737 3599 1736 3599 1735 3599 1736 3600 1728 3600 1948 3600 1728 3601 1736 3601 1737 3601 1738 3602 1471 3602 1830 3602 1955 3603 2045 3603 1739 3603 1830 3604 1471 3604 2045 3604 2045 3605 1955 3605 1830 3605 1830 3606 1955 3606 1720 3606 1955 3607 1490 3607 1720 3607 1739 3608 1741 3608 1754 3608 1490 3609 1955 3609 1754 3609 1754 3610 1955 3610 1739 3610 1740 3611 1741 3611 1738 3611 1738 3612 1741 3612 1471 3612 1838 3613 1954 3613 1545 3613 1742 3614 1932 3614 1835 3614 1835 3615 1932 3615 1931 3615 1755 3616 1932 3616 1743 3616 1743 3617 1932 3617 1742 3617 1744 3618 1722 3618 1745 3618 1745 3619 1722 3619 1751 3619 1538 3620 1746 3620 1747 3620 1747 3621 1746 3621 1731 3621 1731 3622 1733 3622 1747 3622 1747 3623 1733 3623 1730 3623 1747 3624 1730 3624 1828 3624 1730 3625 1748 3625 1828 3625 1828 3626 1748 3626 1749 3626 1828 3627 1749 3627 1750 3627 1750 3628 1749 3628 1722 3628 1750 3629 1722 3629 1744 3629 1745 3630 1751 3630 1752 3630 1751 3631 1753 3631 1752 3631 1752 3632 1753 3632 1754 3632 1752 3633 1754 3633 1740 3633 1740 3634 1754 3634 1741 3634 1755 3635 1743 3635 1832 3635 1755 3636 1832 3636 1718 3636 1718 3637 1832 3637 1831 3637 1718 3638 1831 3638 1756 3638 1756 3639 1831 3639 1830 3639 1756 3640 1830 3640 1720 3640 1756 3641 1720 3641 1490 3641 1954 3642 1838 3642 1837 3642 1954 3643 1837 3643 1716 3643 1716 3644 1837 3644 1836 3644 1716 3645 1836 3645 1717 3645 1717 3646 1836 3646 1835 3646 1717 3647 1835 3647 1757 3647 1757 3648 1835 3648 1931 3648 1970 3649 1758 3649 1759 3649 1760 3650 1458 3650 2128 3650 1760 3651 2128 3651 1583 3651 1583 3652 2128 3652 2127 3652 1583 3653 2127 3653 1891 3653 1891 3654 2127 3654 2126 3654 1891 3655 2126 3655 1582 3655 1582 3656 2126 3656 2124 3656 1582 3657 2124 3657 1586 3657 1586 3658 2124 3658 2125 3658 1586 3659 2125 3659 1585 3659 1585 3660 2125 3660 1829 3660 1585 3661 1829 3661 1584 3661 1584 3662 1829 3662 1901 3662 1901 3663 1829 3663 2123 3663 1901 3664 2123 3664 2122 3664 1901 3665 2122 3665 1896 3665 1896 3666 2122 3666 2121 3666 1896 3667 2121 3667 1588 3667 1588 3668 2121 3668 2120 3668 1588 3669 2120 3669 1587 3669 1587 3670 2120 3670 2119 3670 1587 3671 2119 3671 1898 3671 1898 3672 2119 3672 2118 3672 1898 3673 2118 3673 1761 3673 1761 3674 2118 3674 1833 3674 1761 3675 1833 3675 1589 3675 1589 3676 1833 3676 1834 3676 1589 3677 1834 3677 1592 3677 1592 3678 1834 3678 2117 3678 1592 3679 2117 3679 1762 3679 1762 3680 2117 3680 1763 3680 1763 3681 2117 3681 2116 3681 1763 3682 2116 3682 2115 3682 1763 3683 2115 3683 1593 3683 1593 3684 2115 3684 2114 3684 1593 3685 2114 3685 1764 3685 1711 3686 1920 3686 1700 3686 1919 3687 1974 3687 1689 3687 1919 3688 1689 3688 1920 3688 1920 3689 1689 3689 1765 3689 1920 3690 1765 3690 1700 3690 1975 3691 1978 3691 1976 3691 1976 3692 1978 3692 1701 3692 1701 3693 1978 3693 1917 3693 1701 3694 1917 3694 1766 3694 1766 3695 1917 3695 1956 3695 1979 3696 1980 3696 1988 3696 1988 3697 1980 3697 2035 3697 1876 3698 1773 3698 1877 3698 1877 3699 1773 3699 1767 3699 1877 3700 1767 3700 1878 3700 1878 3701 1767 3701 1774 3701 1878 3702 1774 3702 1792 3702 1792 3703 1774 3703 2089 3703 1776 3704 1768 3704 1495 3704 1495 3705 1768 3705 1839 3705 1495 3706 1839 3706 1794 3706 1794 3707 1839 3707 1778 3707 1769 3708 1851 3708 1770 3708 1769 3709 1770 3709 1883 3709 1883 3710 1770 3710 1771 3710 1883 3711 1771 3711 1519 3711 1883 3712 1519 3712 2104 3712 2104 3713 1519 3713 1772 3713 2081 3714 1773 3714 2080 3714 2080 3715 1773 3715 1876 3715 2089 3716 1774 3716 1840 3716 2089 3717 1840 3717 1775 3717 1775 3718 1840 3718 1768 3718 1775 3719 1768 3719 1776 3719 1777 3720 1794 3720 2094 3720 2094 3721 1794 3721 1778 3721 2094 3722 1778 3722 1779 3722 2094 3723 1779 3723 1780 3723 1780 3724 1779 3724 1781 3724 1881 3725 1780 3725 1781 3725 1782 3726 1781 3726 1853 3726 1782 3727 1853 3727 1783 3727 1782 3728 1783 3728 1784 3728 1784 3729 1783 3729 1852 3729 1784 3730 1852 3730 2101 3730 2101 3731 1852 3731 1785 3731 1785 3732 1852 3732 1851 3732 1785 3733 1851 3733 1769 3733 1785 3734 1769 3734 1795 3734 1787 3735 1786 3735 2090 3735 1787 3736 2090 3736 1492 3736 1492 3737 2090 3737 2091 3737 1871 3738 1796 3738 1873 3738 1873 3739 1796 3739 2083 3739 1873 3740 2083 3740 1874 3740 1874 3741 2083 3741 2085 3741 1878 3742 1792 3742 1879 3742 1879 3743 1792 3743 2084 3743 1879 3744 2084 3744 1875 3744 1875 3745 2084 3745 2082 3745 1794 3746 1895 3746 1880 3746 1880 3747 1899 3747 1788 3747 1788 3748 1899 3748 1793 3748 1886 3749 2102 3749 1885 3749 1885 3750 2102 3750 2103 3750 1885 3751 2103 3751 1887 3751 1887 3752 2103 3752 1511 3752 1523 3753 2095 3753 1790 3753 1790 3754 2095 3754 1897 3754 1790 3755 1897 3755 1890 3755 1890 3756 1897 3756 2096 3756 1890 3757 2096 3757 2099 3757 2092 3758 1527 3758 1791 3758 2092 3759 1791 3759 2091 3759 1492 3760 2091 3760 1791 3760 1916 3761 1786 3761 1787 3761 2080 3762 1876 3762 2082 3762 2082 3763 1876 3763 1875 3763 1906 3764 1776 3764 1793 3764 1793 3765 1776 3765 1788 3765 1895 3766 1794 3766 1777 3766 1512 3767 1464 3767 1881 3767 1882 3768 2097 3768 1463 3768 1795 3769 1769 3769 1496 3769 1795 3770 1496 3770 1907 3770 2104 3771 1789 3771 1883 3771 1511 3772 1462 3772 1887 3772 2102 3773 1886 3773 2098 3773 1786 3774 1916 3774 1515 3774 1515 3775 1916 3775 1516 3775 2086 3776 1872 3776 2085 3776 2085 3777 1872 3777 1874 3777 1938 3778 1859 3778 1939 3778 1939 3779 1859 3779 1856 3779 1939 3780 1856 3780 1940 3780 1940 3781 1856 3781 1797 3781 1797 3782 1856 3782 1799 3782 1797 3783 1799 3783 1798 3783 1798 3784 1799 3784 1800 3784 1798 3785 1800 3785 1488 3785 1488 3786 1800 3786 1509 3786 1488 3787 1509 3787 1487 3787 1487 3788 1509 3788 1486 3788 1486 3789 1509 3789 1801 3789 1486 3790 1801 3790 1485 3790 1801 3791 1508 3791 1485 3791 1485 3792 1508 3792 1802 3792 1485 3793 1802 3793 1484 3793 1484 3794 1802 3794 1803 3794 1484 3795 1803 3795 1483 3795 1483 3796 1803 3796 1506 3796 1483 3797 1506 3797 1804 3797 1804 3798 1506 3798 1805 3798 1804 3799 1805 3799 1936 3799 1936 3800 1805 3800 1863 3800 1936 3801 1863 3801 1807 3801 1807 3802 1863 3802 1806 3802 1807 3803 1806 3803 1937 3803 1937 3804 1806 3804 1938 3804 1938 3805 1806 3805 1861 3805 1938 3806 1861 3806 1859 3806 1813 3807 1827 3807 1814 3807 1813 3808 1814 3808 1544 3808 1544 3809 1814 3809 1461 3809 1544 3810 1461 3810 1543 3810 1543 3811 1461 3811 1815 3811 1543 3812 1815 3812 1816 3812 1816 3813 1815 3813 1817 3813 1816 3814 1817 3814 1818 3814 1818 3815 1817 3815 1531 3815 1818 3816 1531 3816 1819 3816 1819 3817 1531 3817 1820 3817 1819 3818 1820 3818 1547 3818 1547 3819 1820 3819 1821 3819 1547 3820 1821 3820 1822 3820 1822 3821 1821 3821 1530 3821 1822 3822 1530 3822 1838 3822 1838 3823 1530 3823 2114 3823 1538 3824 1458 3824 1823 3824 1823 3825 1458 3825 1459 3825 1823 3826 1459 3826 1539 3826 1539 3827 1459 3827 1460 3827 1539 3828 1460 3828 1541 3828 1541 3829 1460 3829 1536 3829 1541 3830 1536 3830 1540 3830 1540 3831 1536 3831 1824 3831 1540 3832 1824 3832 1542 3832 1542 3833 1824 3833 1535 3833 1542 3834 1535 3834 1825 3834 1542 3835 1825 3835 1813 3835 1813 3836 1825 3836 1826 3836 1813 3837 1826 3837 1827 3837 1458 3838 1538 3838 2128 3838 2128 3839 1538 3839 1747 3839 2128 3840 1747 3840 2127 3840 2127 3841 1747 3841 1828 3841 2127 3842 1828 3842 2126 3842 2126 3843 1828 3843 1750 3843 2126 3844 1750 3844 2124 3844 2124 3845 1750 3845 1744 3845 2124 3846 1744 3846 2125 3846 2125 3847 1744 3847 1745 3847 2125 3848 1745 3848 1829 3848 1829 3849 1745 3849 1752 3849 1829 3850 1752 3850 2123 3850 2123 3851 1752 3851 1740 3851 2123 3852 1740 3852 2122 3852 2122 3853 1740 3853 1738 3853 2122 3854 1738 3854 2121 3854 2121 3855 1738 3855 2120 3855 2120 3856 1738 3856 1830 3856 2120 3857 1830 3857 2119 3857 2119 3858 1830 3858 1831 3858 2119 3859 1831 3859 2118 3859 2118 3860 1831 3860 1832 3860 2118 3861 1832 3861 1833 3861 1833 3862 1832 3862 1743 3862 1833 3863 1743 3863 1834 3863 1834 3864 1743 3864 1742 3864 1834 3865 1742 3865 2117 3865 2117 3866 1742 3866 1835 3866 2117 3867 1835 3867 1836 3867 2117 3868 1836 3868 2115 3868 2115 3869 1836 3869 1837 3869 2115 3870 1837 3870 2114 3870 2114 3871 1837 3871 1838 3871 1860 3872 1778 3872 1858 3872 1858 3873 1778 3873 1839 3873 1858 3874 1839 3874 1768 3874 1858 3875 1768 3875 1857 3875 1857 3876 1768 3876 1840 3876 1857 3877 1840 3877 1774 3877 1857 3878 1774 3878 1855 3878 1855 3879 1774 3879 1767 3879 1855 3880 1767 3880 1773 3880 1855 3881 1773 3881 1854 3881 1854 3882 1773 3882 2081 3882 1854 3883 2081 3883 2079 3883 1854 3884 2079 3884 1841 3884 1842 3885 1841 3885 1518 3885 1842 3886 1518 3886 1517 3886 1842 3887 1517 3887 1843 3887 1843 3888 1517 3888 1529 3888 1843 3889 1529 3889 1528 3889 1843 3890 1528 3890 1844 3890 1843 3891 1844 3891 1845 3891 1845 3892 1844 3892 1527 3892 1527 3893 1525 3893 1845 3893 1845 3894 1525 3894 1524 3894 1845 3895 1524 3895 1846 3895 1845 3896 1846 3896 1507 3896 1507 3897 1846 3897 1522 3897 1507 3898 1522 3898 1521 3898 1507 3899 1521 3899 1847 3899 1847 3900 1521 3900 1514 3900 1847 3901 1514 3901 1513 3901 1847 3902 1513 3902 1848 3902 1848 3903 1513 3903 1520 3903 1848 3904 1520 3904 1849 3904 1848 3905 1849 3905 1864 3905 1864 3906 1849 3906 1519 3906 1864 3907 1519 3907 1771 3907 1864 3908 1771 3908 1850 3908 1850 3909 1771 3909 1770 3909 1850 3910 1770 3910 1851 3910 1850 3911 1851 3911 1862 3911 1862 3912 1851 3912 1852 3912 1862 3913 1852 3913 1783 3913 1862 3914 1783 3914 1860 3914 1860 3915 1783 3915 1853 3915 1860 3916 1853 3916 1781 3916 1860 3917 1781 3917 1779 3917 1860 3918 1779 3918 1778 3918 1854 3919 1800 3919 1799 3919 1854 3920 1799 3920 1855 3920 1855 3921 1799 3921 1856 3921 1855 3922 1856 3922 1857 3922 1857 3923 1856 3923 1858 3923 1858 3924 1856 3924 1859 3924 1858 3925 1859 3925 1860 3925 1860 3926 1859 3926 1861 3926 1860 3927 1861 3927 1806 3927 1860 3928 1806 3928 1862 3928 1862 3929 1806 3929 1850 3929 1850 3930 1806 3930 1863 3930 1850 3931 1863 3931 1864 3931 1864 3932 1863 3932 1805 3932 1503 3933 1500 3933 1502 3933 1502 3934 1500 3934 1911 3934 1865 3935 1590 3935 1866 3935 1867 3936 1892 3936 1591 3936 1597 3937 1868 3937 1501 3937 1869 3938 1578 3938 1870 3938 1746 3939 1491 3939 1731 3939 1516 3940 1791 3940 1527 3940 1492 3941 1791 3941 1516 3941 1872 3942 1871 3942 1874 3942 1879 3943 1875 3943 1877 3943 1877 3944 1878 3944 1879 3944 1877 3945 1875 3945 1876 3945 1776 3946 1495 3946 1788 3946 1495 3947 1794 3947 1788 3947 1788 3948 1794 3948 1880 3948 1512 3949 1881 3949 1782 3949 1781 3950 1782 3950 1881 3950 1493 3951 1463 3951 1512 3951 1883 3952 1496 3952 1769 3952 1789 3953 1497 3953 1496 3953 1789 3954 1496 3954 1883 3954 1497 3955 1789 3955 1884 3955 1497 3956 1884 3956 1496 3956 1885 3957 1887 3957 1494 3957 1494 3958 1886 3958 1885 3958 1494 3959 1887 3959 1510 3959 1889 3960 1888 3960 1914 3960 1889 3961 1914 3961 1890 3961 1523 3962 1790 3962 1888 3962 1888 3963 1790 3963 1914 3963 1914 3964 1790 3964 1890 3964 1910 3965 1580 3965 1905 3965 1902 3966 1586 3966 1584 3966 1902 3967 1584 3967 1901 3967 1896 3968 1587 3968 1898 3968 1900 3969 1589 3969 1762 3969 1900 3970 1762 3970 1763 3970 1501 3971 1868 3971 1909 3971 1533 3972 1908 3972 1893 3972 1598 3973 1599 3973 1899 3973 1899 3974 1599 3974 1894 3974 1899 3975 1894 3975 1600 3975 2094 3976 1780 3976 2112 3976 1526 3977 2092 3977 1499 3977 2086 3978 2085 3978 1911 3978 2086 3979 1911 3979 2087 3979 2087 3980 1911 3980 1500 3980 1899 3981 1895 3981 1598 3981 1911 3982 2085 3982 1891 3982 1881 3983 1533 3983 1780 3983 1780 3984 1533 3984 2112 3984 1583 3985 2083 3985 1796 3985 1901 3986 2091 3986 1902 3986 2085 3987 2083 3987 1891 3987 1891 3988 2083 3988 1583 3988 1796 3989 1760 3989 1583 3989 2094 3990 2112 3990 1598 3990 2094 3991 1598 3991 1777 3991 1777 3992 1598 3992 1895 3992 1905 3993 2084 3993 1910 3993 1796 3994 1505 3994 1760 3994 2091 3995 1901 3995 1499 3995 2091 3996 2090 3996 1902 3996 1902 3997 2090 3997 1786 3997 2095 3998 2093 3998 1499 3998 1499 3999 2093 3999 1526 3999 2089 4000 1775 4000 1578 4000 1910 4001 2084 4001 1792 4001 2091 4002 1499 4002 2092 4002 1896 4003 1898 4003 1897 4003 1897 4004 1898 4004 2096 4004 1793 4005 1899 4005 1600 4005 2087 4006 1500 4006 1515 4006 2099 4007 1761 4007 2100 4007 2100 4008 1761 4008 1590 4008 2103 4009 2102 4009 1865 4009 2103 4010 1900 4010 1511 4010 1511 4011 1900 4011 1763 4011 1578 4012 1793 4012 1600 4012 1903 4013 1896 4013 1897 4013 1903 4014 1897 4014 1499 4014 1499 4015 1897 4015 2095 4015 1865 4016 1900 4016 2103 4016 1772 4017 1591 4017 1892 4017 1772 4018 1892 4018 2104 4018 1907 4019 2105 4019 1498 4019 1498 4020 2105 4020 1904 4020 2084 4021 1905 4021 2082 4021 2082 4022 1905 4022 1912 4022 1906 4023 1793 4023 1578 4023 1906 4024 1578 4024 1775 4024 2089 4025 1578 4025 1792 4025 1792 4026 1578 4026 1910 4026 1892 4027 1904 4027 2105 4027 1892 4028 2105 4028 2104 4028 1533 4029 1464 4029 1908 4029 1500 4030 1902 4030 1515 4030 1515 4031 1902 4031 1786 4031 2096 4032 1898 4032 1761 4032 2096 4033 1761 4033 2099 4033 1511 4034 1763 4034 1462 4034 1795 4035 1498 4035 2101 4035 2101 4036 1498 4036 1501 4036 1795 4037 1907 4037 1498 4037 1464 4038 2097 4038 1909 4038 1505 4039 2082 4039 1912 4039 2100 4040 1590 4040 1865 4040 2100 4041 1865 4041 2098 4041 2098 4042 1865 4042 2102 4042 1772 4043 1462 4043 1591 4043 1591 4044 1462 4044 1763 4044 1591 4045 1763 4045 1593 4045 1464 4046 1533 4046 1881 4046 1909 4047 1908 4047 1464 4047 2080 4048 2082 4048 1505 4048 2101 4049 1501 4049 1909 4049 2101 4050 1909 4050 1784 4050 1784 4051 1909 4051 2097 4051 1901 4052 1896 4052 1499 4052 1865 4053 1589 4053 1900 4053 1904 4054 1892 4054 1593 4054 1913 4055 1871 4055 1873 4055 1493 4056 1512 4056 1782 4056 1516 4057 1916 4057 1915 4057 1915 4058 1916 4058 1787 4058 1915 4059 1787 4059 1492 4059 1746 4060 1734 4060 1491 4060 1734 4061 1491 4061 2000 4061 1734 4062 2000 4062 1491 4062 1491 4063 2000 4063 1731 4063 2013 4064 2012 4064 1999 4064 1999 4065 2012 4065 1998 4065 2107 4066 1985 4066 1921 4066 1993 4067 1918 4067 2016 4067 1997 4068 1985 4068 1929 4068 1997 4069 1929 4069 1994 4069 1994 4070 1929 4070 1987 4070 1994 4071 1987 4071 1986 4071 2107 4072 1921 4072 2108 4072 2020 4073 1920 4073 1917 4073 1978 4074 1979 4074 1917 4074 1917 4075 1979 4075 2020 4075 1918 4076 1993 4076 1994 4076 1918 4077 1994 4077 1474 4077 1474 4078 1994 4078 1986 4078 1474 4079 1986 4079 1977 4079 1474 4080 1977 4080 1920 4080 1920 4081 1977 4081 1919 4081 2023 4082 2016 4082 2020 4082 2020 4083 2016 4083 1920 4083 1920 4084 2016 4084 1474 4084 2013 4085 2015 4085 1923 4085 2020 4086 1979 4086 1988 4086 2020 4087 1988 4087 2021 4087 2021 4088 1988 4088 1990 4088 2021 4089 1990 4089 2023 4089 2023 4090 1990 4090 1989 4090 2023 4091 1989 4091 1993 4091 2023 4092 1993 4092 2016 4092 2108 4093 1921 4093 1923 4093 2013 4094 1923 4094 1921 4094 1997 4095 1922 4095 1985 4095 1985 4096 1922 4096 1921 4096 1923 4097 2015 4097 1925 4097 1925 4098 2015 4098 1924 4098 1925 4099 1924 4099 1999 4099 1999 4100 1924 4100 1926 4100 2013 4101 1922 4101 1997 4101 2110 4102 2107 4102 2108 4102 1999 4103 1926 4103 2013 4103 2013 4104 1926 4104 2015 4104 1986 4105 1577 4105 1977 4105 1977 4106 1577 4106 2032 4106 1991 4107 1992 4107 1989 4107 1989 4108 1992 4108 1993 4108 1991 4109 2003 4109 1996 4109 2024 4110 1929 4110 1927 4110 1928 4111 2024 4111 1927 4111 1929 4112 2024 4112 1987 4112 1987 4113 2024 4113 1928 4113 1722 4114 1930 4114 1751 4114 1933 4115 1931 4115 1932 4115 1755 4116 1933 4116 1932 4116 1545 4117 1489 4117 1934 4117 1935 4118 1953 4118 1549 4118 1722 4119 1930 4119 1564 4119 1933 4120 1932 4120 1558 4120 1953 4121 1935 4121 1945 4121 1728 4122 1704 4122 1705 4122 1941 4123 1942 4123 1729 4123 1729 4124 1942 4124 1943 4124 1729 4125 1943 4125 1944 4125 1729 4126 1944 4126 1546 4126 1546 4127 1944 4127 1945 4127 1728 4128 1947 4128 1705 4128 1728 4129 1705 4129 1948 4129 1948 4130 1960 4130 1949 4130 1727 4131 1951 4131 1726 4131 1726 4132 1951 4132 1709 4132 1576 4133 2107 4133 2110 4133 1956 4134 1917 4134 1711 4134 1711 4135 1917 4135 1920 4135 1973 4136 2033 4136 1702 4136 1704 4137 1957 4137 1958 4137 1958 4138 1705 4138 1704 4138 1959 4139 2031 4139 1703 4139 1959 4140 1705 4140 1958 4140 2031 4141 1959 4141 1958 4141 1959 4142 1703 4142 1960 4142 1959 4143 1960 4143 1705 4143 1695 4144 2030 4144 1981 4144 2026 4145 1612 4145 2027 4145 2027 4146 1612 4146 1982 4146 2028 4147 2025 4147 2029 4147 2029 4148 2025 4148 1697 4148 1697 4149 2025 4149 1961 4149 1962 4150 2025 4150 1963 4150 1963 4151 2025 4151 2028 4151 2025 4152 1962 4152 1964 4152 2025 4153 1964 4153 1961 4153 1758 4154 1971 4154 1759 4154 1759 4155 1971 4155 1596 4155 1594 4156 1972 4156 1967 4156 1967 4157 1972 4157 1966 4157 1968 4158 1594 4158 1965 4158 1594 4159 1967 4159 1965 4159 1758 4160 1970 4160 1971 4160 1971 4161 1970 4161 1969 4161 1966 4162 1969 4162 1965 4162 1967 4163 1966 4163 1965 4163 1970 4164 1968 4164 1969 4164 1970 4165 1595 4165 1968 4165 1970 4166 1759 4166 1595 4166 1965 4167 1969 4167 1968 4167 1972 4168 2114 4168 1966 4168 1925 4169 1737 4169 2034 4169 1576 4170 2110 4170 2026 4170 1612 4171 2026 4171 2110 4171 1612 4172 2110 4172 2109 4172 1611 4173 2109 4173 2108 4173 2108 4174 1957 4174 1611 4174 1611 4175 1957 4175 1704 4175 1703 4176 2031 4176 1973 4176 1973 4177 2031 4177 2033 4177 1689 4178 1974 4178 1695 4178 1695 4179 1974 4179 2030 4179 1702 4180 2033 4180 1975 4180 1702 4181 1975 4181 1976 4181 1919 4182 1977 4182 2032 4182 1978 4183 1980 4183 1979 4183 1981 4184 2030 4184 1697 4184 1697 4185 2030 4185 2029 4185 1963 4186 2028 4186 1982 4186 1982 4187 2028 4187 2027 4187 1985 4188 1983 4188 1984 4188 1985 4189 1984 4189 1927 4189 1985 4190 1927 4190 1929 4190 1577 4191 1986 4191 1987 4191 1577 4192 1987 4192 1928 4192 1735 4193 1988 4193 2035 4193 2008 4194 2011 4194 1997 4194 1995 4195 2009 4195 1994 4195 1994 4196 2009 4196 2007 4196 2007 4197 2008 4197 1994 4197 1994 4198 2008 4198 1997 4198 1991 4199 1989 4199 1990 4199 1991 4200 1990 4200 2002 4200 2003 4201 1991 4201 2002 4201 1992 4202 1996 4202 1993 4202 1993 4203 1996 4203 1995 4203 1993 4204 1995 4204 1994 4204 1991 4205 1996 4205 1992 4205 2004 4206 1995 4206 1996 4206 2004 4207 1996 4207 2003 4207 2012 4208 2013 4208 1997 4208 2012 4209 1997 4209 2011 4209 2000 4210 2001 4210 2004 4210 2004 4211 2003 4211 2000 4211 2000 4212 2003 4212 2002 4212 1541 4213 2006 4213 2009 4213 2009 4214 1995 4214 1541 4214 1541 4215 1995 4215 2004 4215 2006 4216 1540 4216 2007 4216 2007 4217 1540 4217 2005 4217 2009 4218 2006 4218 2007 4218 2007 4219 2005 4219 2008 4219 2008 4220 2005 4220 2010 4220 1999 4221 1998 4221 1925 4221 1691 4222 1476 4222 1922 4222 1691 4223 1922 4223 2013 4223 1691 4224 2013 4224 1921 4224 1691 4225 1921 4225 1692 4225 2014 4226 1693 4226 1926 4226 2014 4227 1926 4227 1924 4227 2014 4228 1924 4228 2015 4228 2017 4229 1474 4229 2016 4229 2017 4230 2016 4230 2018 4230 2018 4231 2016 4231 1918 4231 2019 4232 2020 4232 2021 4232 2019 4233 2021 4233 2022 4233 2022 4234 2021 4234 2023 4234 1927 4235 1984 4235 1928 4235 1928 4236 1984 4236 1577 4236 1980 4237 1978 4237 1975 4237 1737 4238 1735 4238 2035 4238 2042 4239 2038 4239 2037 4239 2036 4240 2040 4240 2039 4240 2039 4241 2040 4241 2043 4241 2043 4242 2040 4242 2041 4242 2042 4243 2037 4243 2043 4243 2042 4244 2043 4244 2041 4244 1615 4245 1555 4245 2044 4245 2044 4246 1555 4246 1557 4246 1471 4247 1472 4247 2045 4247 2046 4248 2045 4248 1472 4248 2045 4249 2046 4249 1739 4249 1739 4250 2046 4250 2047 4250 1741 4251 1739 4251 2047 4251 1470 4252 2046 4252 1472 4252 1472 4253 2048 4253 1470 4253 1470 4254 2048 4254 2047 4254 1470 4255 2047 4255 2046 4255 1635 4256 1470 4256 2049 4256 1682 4257 1696 4257 1964 4257 1962 4258 1613 4258 1964 4258 1964 4259 1613 4259 2052 4259 1964 4260 2052 4260 1682 4260 2044 4261 1557 4261 2052 4261 2052 4262 1557 4262 1602 4262 2052 4263 1602 4263 2050 4263 2050 4264 1602 4264 1681 4264 1555 4265 1615 4265 2051 4265 2051 4266 1615 4266 2055 4266 2051 4267 2055 4267 2053 4267 2051 4268 2053 4268 2059 4268 1682 4269 2052 4269 2050 4269 2053 4270 2055 4270 2054 4270 2054 4271 2055 4271 2056 4271 2042 4272 1607 4272 2038 4272 2038 4273 1607 4273 2077 4273 2077 4274 1607 4274 1466 4274 1574 4275 2041 4275 2058 4275 2058 4276 2041 4276 2040 4276 2058 4277 2040 4277 2057 4277 2058 4278 2057 4278 2064 4278 2060 4279 2051 4279 2059 4279 2059 4280 1616 4280 2060 4280 2060 4281 1616 4281 1620 4281 2060 4282 1620 4282 2061 4282 2061 4283 1620 4283 2062 4283 2061 4284 2062 4284 1631 4284 2061 4285 1631 4285 1608 4285 1608 4286 1631 4286 2063 4286 1608 4287 2063 4287 1469 4287 1681 4288 1602 4288 2065 4288 1603 4289 2058 4289 2064 4289 1681 4290 2065 4290 2068 4290 1681 4291 2068 4291 2066 4291 2066 4292 2068 4292 2067 4292 2067 4293 2068 4293 2069 4293 2067 4294 2069 4294 2070 4294 2070 4295 2069 4295 2072 4295 2070 4296 2072 4296 2071 4296 2071 4297 2072 4297 2073 4297 2073 4298 2072 4298 1606 4298 2073 4299 1606 4299 2074 4299 2073 4300 2074 4300 1685 4300 1685 4301 2074 4301 1605 4301 1685 4302 1605 4302 2075 4302 1685 4303 2075 4303 2076 4303 2076 4304 2075 4304 1603 4304 2076 4305 1603 4305 2064 4305 2042 4306 1550 4306 1607 4306 1621 4307 2038 4307 2077 4307 2057 4308 2040 4308 2078 4308 2078 4309 2040 4309 2036 4309 2113 4310 1598 4310 2112 4310 2111 4311 1465 4311 1499 4311 1505 4312 1796 4312 2079 4312 1505 4313 2079 4313 2081 4313 1505 4314 2081 4314 2080 4314 2088 4315 2086 4315 2087 4315 1776 4316 1906 4316 1775 4316 1880 4317 1895 4317 1899 4317 2097 4318 1882 4318 1784 4318 1785 4319 1795 4319 2101 4319 1789 4320 2104 4320 2105 4320 1772 4321 1849 4321 2106 4321 1772 4322 2106 4322 1462 4322 1923 4323 2034 4323 2108 4323 2108 4324 2034 4324 1957 4324 2115 4325 2116 4325 2117 4325 2129 4326 2130 4326 2446 4326 2443 4327 2440 4327 2172 4327 2443 4328 2172 4328 2131 4328 2131 4329 2172 4329 2443 4329 2443 4330 2172 4330 2440 4330 2394 4331 2132 4331 2396 4331 2396 4332 2132 4332 2392 4332 2392 4333 2132 4333 2133 4333 2392 4334 2133 4334 2134 4334 2134 4335 2133 4335 2233 4335 2138 4336 2223 4336 2247 4336 2138 4337 2247 4337 2373 4337 2373 4338 2247 4338 2136 4338 2369 4339 2226 4339 2137 4339 2369 4340 2137 4340 2224 4340 2138 4341 2224 4341 2223 4341 2324 4342 2206 4342 2323 4342 2323 4343 2206 4343 2325 4343 2325 4344 2206 4344 2210 4344 2139 4345 2210 4345 2140 4345 2139 4346 2140 4346 2326 4346 2326 4347 2140 4347 2208 4347 2326 4348 2208 4348 2327 4348 2327 4349 2208 4349 2329 4349 2329 4350 2208 4350 2141 4350 2329 4351 2141 4351 2142 4351 2142 4352 2141 4352 2207 4352 2142 4353 2207 4353 2324 4353 2324 4354 2207 4354 2206 4354 2144 4355 2241 4355 2315 4355 2315 4356 2241 4356 2244 4356 2315 4357 2244 4357 2316 4357 2316 4358 2244 4358 2317 4358 2317 4359 2244 4359 2243 4359 2317 4360 2243 4360 2319 4360 2319 4361 2243 4361 2245 4361 2319 4362 2245 4362 2151 4362 2151 4363 2245 4363 2321 4363 2321 4364 2245 4364 2246 4364 2321 4365 2246 4365 2314 4365 2314 4366 2246 4366 2143 4366 2314 4367 2143 4367 2144 4367 2144 4368 2143 4368 2241 4368 2326 4369 2372 4369 2139 4369 2139 4370 2372 4370 2146 4370 2139 4371 2146 4371 2145 4371 2145 4372 2146 4372 2374 4372 2145 4373 2374 4373 2325 4373 2325 4374 2374 4374 2323 4374 2323 4375 2374 4375 2375 4375 2323 4376 2375 4376 2371 4376 2323 4377 2371 4377 2322 4377 2322 4378 2371 4378 2147 4378 2322 4379 2147 4379 2328 4379 2328 4380 2147 4380 2370 4380 2328 4381 2370 4381 2327 4381 2327 4382 2370 4382 2148 4382 2327 4383 2148 4383 2326 4383 2326 4384 2148 4384 2372 4384 2391 4385 2315 4385 2397 4385 2397 4386 2315 4386 2395 4386 2395 4387 2315 4387 2316 4387 2395 4388 2316 4388 2149 4388 2149 4389 2316 4389 2318 4389 2149 4390 2318 4390 2393 4390 2393 4391 2318 4391 2151 4391 2393 4392 2151 4392 2150 4392 2150 4393 2151 4393 2390 4393 2390 4394 2151 4394 2320 4394 2390 4395 2320 4395 2152 4395 2152 4396 2320 4396 2153 4396 2152 4397 2153 4397 2391 4397 2391 4398 2153 4398 2315 4398 2155 4399 2154 4399 2434 4399 2434 4400 2154 4400 2382 4400 2434 4401 2382 4401 2155 4401 2155 4402 2382 4402 2154 4402 2431 4403 2156 4403 2157 4403 2157 4404 2156 4404 2386 4404 2157 4405 2386 4405 2158 4405 2158 4406 2386 4406 2156 4406 2158 4407 2156 4407 2431 4407 2160 4408 2421 4408 2430 4408 2160 4409 2430 4409 2154 4409 2154 4410 2430 4410 2159 4410 2154 4411 2159 4411 2421 4411 2154 4412 2421 4412 2160 4412 2192 4413 2422 4413 2379 4413 2379 4414 2422 4414 2381 4414 2381 4415 2422 4415 2435 4415 2381 4416 2435 4416 2423 4416 2381 4417 2423 4417 2192 4417 2192 4418 2423 4418 2422 4418 2425 4419 2426 4419 2384 4419 2384 4420 2426 4420 2424 4420 2384 4421 2424 4421 2425 4421 2389 4422 2428 4422 2385 4422 2385 4423 2428 4423 2427 4423 2385 4424 2427 4424 2387 4424 2387 4425 2427 4425 2432 4425 2387 4426 2432 4426 2389 4426 2389 4427 2432 4427 2428 4427 2131 4428 2443 4428 2444 4428 2441 4429 2443 4429 2131 4429 2441 4430 2131 4430 2175 4430 2351 4431 2161 4431 2131 4431 2131 4432 2161 4432 2175 4432 2261 4433 2264 4433 2131 4433 2131 4434 2264 4434 2351 4434 2261 4435 2131 4435 2444 4435 2351 4436 2162 4436 2163 4436 2163 4437 2162 4437 2164 4437 2163 4438 2164 4438 2269 4438 2269 4439 2164 4439 2165 4439 2269 4440 2165 4440 2270 4440 2270 4441 2165 4441 2166 4441 2166 4442 2165 4442 2346 4442 2447 4443 2446 4443 2130 4443 2219 4444 2130 4444 2195 4444 2167 4445 2338 4445 2168 4445 2168 4446 2338 4446 2169 4446 2168 4447 2169 4447 2170 4447 2170 4448 2169 4448 2303 4448 2170 4449 2303 4449 2219 4449 2219 4450 2303 4450 2130 4450 2130 4451 2303 4451 2176 4451 2181 4452 2255 4452 2437 4452 2437 4453 2255 4453 2254 4453 2129 4454 2312 4454 2429 4454 2436 4455 2398 4455 2129 4455 2129 4456 2398 4456 2171 4456 2312 4457 2129 4457 2251 4457 2251 4458 2129 4458 2171 4458 2172 4459 2440 4459 2182 4459 2399 4460 2438 4460 2173 4460 2173 4461 2438 4461 2172 4461 2173 4462 2172 4462 2313 4462 2172 4463 2174 4463 2313 4463 2174 4464 2172 4464 2182 4464 2442 4465 2380 4465 2178 4465 2178 4466 2380 4466 2194 4466 2176 4467 2447 4467 2130 4467 2189 4468 2388 4468 2445 4468 2445 4469 2388 4469 2177 4469 2191 4470 2189 4470 2448 4470 2191 4471 2448 4471 2447 4471 2191 4472 2447 4472 2176 4472 2195 4473 2178 4473 2194 4473 2197 4474 2442 4474 2441 4474 2197 4475 2441 4475 2175 4475 2261 4476 2444 4476 2198 4476 2445 4477 2177 4477 2198 4477 2309 4478 2237 4478 2179 4478 2255 4479 2181 4479 2179 4479 2429 4480 2309 4480 2180 4480 2180 4481 2309 4481 2179 4481 2180 4482 2179 4482 2181 4482 2253 4483 2252 4483 2236 4483 2236 4484 2182 4484 2439 4484 2236 4485 2439 4485 2253 4485 2253 4486 2439 4486 2437 4486 2253 4487 2437 4487 2254 4487 2183 4488 2398 4488 2436 4488 2183 4489 2438 4489 2399 4489 2192 4490 2186 4490 2184 4490 2184 4491 2186 4491 2185 4491 2186 4492 2420 4492 2185 4492 2185 4493 2420 4493 2160 4493 2192 4494 2379 4494 2186 4494 2187 4495 2190 4495 2188 4495 2199 4496 2200 4496 2256 4496 2256 4497 2200 4497 2188 4497 2188 4498 2200 4498 2187 4498 2187 4499 2383 4499 2190 4499 2190 4500 2383 4500 2425 4500 2191 4501 2388 4501 2189 4501 2191 4502 2188 4502 2190 4502 2191 4503 2190 4503 2388 4503 2188 4504 2191 4504 2304 4504 2191 4505 2176 4505 2304 4505 2220 4506 2194 4506 2192 4506 2220 4507 2192 4507 2184 4507 2194 4508 2220 4508 2221 4508 2194 4509 2221 4509 2193 4509 2194 4510 2193 4510 2219 4510 2194 4511 2219 4511 2195 4511 2185 4512 2380 4512 2197 4512 2184 4513 2185 4513 2196 4513 2197 4514 2380 4514 2442 4514 2185 4515 2197 4515 2196 4515 2196 4516 2197 4516 2217 4516 2217 4517 2197 4517 2218 4517 2197 4518 2175 4518 2218 4518 2177 4519 2199 4519 2198 4519 2198 4520 2199 4520 2256 4520 2198 4521 2256 4521 2261 4521 2199 4522 2385 4522 2387 4522 2199 4523 2387 4523 2200 4523 2409 4524 2201 4524 2202 4524 2202 4525 2201 4525 2410 4525 2202 4526 2410 4526 2203 4526 2203 4527 2410 4527 2313 4527 2310 4528 2411 4528 2204 4528 2204 4529 2411 4529 2412 4529 2204 4530 2412 4530 2205 4530 2311 4531 2205 4531 2412 4531 2207 4532 2281 4532 2206 4532 2207 4533 2141 4533 2281 4533 2208 4534 2209 4534 2350 4534 2208 4535 2350 4535 2141 4535 2208 4536 2140 4536 2209 4536 2209 4537 2140 4537 2210 4537 2209 4538 2210 4538 2282 4538 2282 4539 2210 4539 2206 4539 2281 4540 2282 4540 2206 4540 2235 4541 2242 4541 2233 4541 2233 4542 2242 4542 2211 4542 2211 4543 2242 4543 2302 4543 2211 4544 2302 4544 2234 4544 2234 4545 2302 4545 2301 4545 2234 4546 2301 4546 2231 4546 2231 4547 2301 4547 2300 4547 2300 4548 2299 4548 2132 4548 2141 4549 2350 4549 2212 4549 2212 4550 2350 4550 2332 4550 2229 4551 2284 4551 2213 4551 2213 4552 2284 4552 2268 4552 2268 4553 2284 4553 2184 4553 2229 4554 2213 4554 2215 4554 2215 4555 2213 4555 2275 4555 2292 4556 2229 4556 2214 4556 2214 4557 2250 4557 2297 4557 2297 4558 2295 4558 2214 4558 2214 4559 2295 4559 2292 4559 2215 4560 2275 4560 2216 4560 2277 4561 2239 4561 2216 4561 2277 4562 2216 4562 2275 4562 2217 4563 2272 4563 2196 4563 2196 4564 2272 4564 2184 4564 2161 4565 2218 4565 2175 4565 2184 4566 2284 4566 2220 4566 2170 4567 2219 4567 2290 4567 2290 4568 2219 4568 2193 4568 2290 4569 2193 4569 2221 4569 2225 4570 2331 4570 2223 4570 2223 4571 2331 4571 2401 4571 2401 4572 2228 4572 2223 4572 2222 4573 2405 4573 2409 4573 2223 4574 2224 4574 2225 4574 2225 4575 2224 4575 2137 4575 2401 4576 2405 4576 2228 4576 2228 4577 2405 4577 2222 4577 2226 4578 2248 4578 2249 4578 2226 4579 2249 4579 2137 4579 2227 4580 2136 4580 2247 4580 2136 4581 2227 4581 2248 4581 2136 4582 2248 4582 2226 4582 2239 4583 2247 4583 2223 4583 2239 4584 2223 4584 2216 4584 2216 4585 2223 4585 2228 4585 2216 4586 2228 4586 2215 4586 2214 4587 2229 4587 2232 4587 2133 4588 2132 4588 2232 4588 2414 4589 2230 4589 2311 4589 2132 4590 2250 4590 2232 4590 2232 4591 2250 4591 2214 4591 2394 4592 2300 4592 2132 4592 2356 4593 2133 4593 2417 4593 2417 4594 2133 4594 2232 4594 2135 4595 2234 4595 2394 4595 2394 4596 2234 4596 2231 4596 2394 4597 2231 4597 2300 4597 2230 4598 2414 4598 2232 4598 2232 4599 2414 4599 2417 4599 2134 4600 2233 4600 2135 4600 2135 4601 2233 4601 2211 4601 2135 4602 2211 4602 2234 4602 2235 4603 2233 4603 2133 4603 2235 4604 2133 4604 2356 4604 2228 4605 2222 4605 2236 4605 2228 4606 2236 4606 2252 4606 2237 4607 2309 4607 2238 4607 2238 4608 2230 4608 2232 4608 2280 4609 2247 4609 2277 4609 2277 4610 2247 4610 2239 4610 2240 4611 2241 4611 2339 4611 2339 4612 2241 4612 2143 4612 2243 4613 2301 4613 2245 4613 2243 4614 2298 4614 2301 4614 2240 4615 2298 4615 2244 4615 2244 4616 2298 4616 2243 4616 2240 4617 2244 4617 2241 4617 2245 4618 2242 4618 2246 4618 2246 4619 2242 4619 2143 4619 2143 4620 2242 4620 2339 4620 2301 4621 2302 4621 2245 4621 2245 4622 2302 4622 2242 4622 2282 4623 2227 4623 2280 4623 2280 4624 2227 4624 2247 4624 2227 4625 2282 4625 2248 4625 2248 4626 2282 4626 2281 4626 2248 4627 2281 4627 2249 4627 2249 4628 2283 4628 2137 4628 2137 4629 2283 4629 2212 4629 2137 4630 2212 4630 2332 4630 2137 4631 2332 4631 2225 4631 2307 4632 2262 4632 2305 4632 2305 4633 2262 4633 2256 4633 2306 4634 2362 4634 2257 4634 2257 4635 2362 4635 2263 4635 2297 4636 2250 4636 2299 4636 2299 4637 2250 4637 2132 4637 2173 4638 2313 4638 2171 4638 2171 4639 2313 4639 2310 4639 2171 4640 2310 4640 2251 4640 2411 4641 2310 4641 2378 4641 2313 4642 2410 4642 2310 4642 2310 4643 2410 4643 2378 4643 2238 4644 2232 4644 2229 4644 2228 4645 2252 4645 2215 4645 2215 4646 2252 4646 2253 4646 2255 4647 2179 4647 2229 4647 2229 4648 2179 4648 2237 4648 2229 4649 2237 4649 2238 4649 2215 4650 2253 4650 2254 4650 2215 4651 2254 4651 2229 4651 2229 4652 2254 4652 2255 4652 2188 4653 2305 4653 2256 4653 2262 4654 2307 4654 2263 4654 2263 4655 2307 4655 2257 4655 2335 4656 2258 4656 2259 4656 2259 4657 2258 4657 2260 4657 2306 4658 2259 4658 2362 4658 2362 4659 2259 4659 2260 4659 2256 4660 2262 4660 2266 4660 2256 4661 2266 4661 2261 4661 2264 4662 2261 4662 2266 4662 2262 4663 2263 4663 2266 4663 2263 4664 2362 4664 2266 4664 2266 4665 2265 4665 2264 4665 2184 4666 2272 4666 2267 4666 2274 4667 2218 4667 2351 4667 2351 4668 2218 4668 2161 4668 2184 4669 2267 4669 2268 4669 2268 4670 2267 4670 2213 4670 2349 4671 2276 4671 2347 4671 2347 4672 2276 4672 2166 4672 2166 4673 2276 4673 2271 4673 2351 4674 2163 4674 2274 4674 2274 4675 2163 4675 2271 4675 2271 4676 2163 4676 2269 4676 2271 4677 2269 4677 2270 4677 2271 4678 2270 4678 2166 4678 2272 4679 2273 4679 2267 4679 2267 4680 2273 4680 2271 4680 2267 4681 2271 4681 2213 4681 2213 4682 2271 4682 2275 4682 2275 4683 2271 4683 2276 4683 2273 4684 2272 4684 2217 4684 2271 4685 2273 4685 2274 4685 2274 4686 2273 4686 2217 4686 2274 4687 2217 4687 2218 4687 2276 4688 2349 4688 2279 4688 2350 4689 2209 4689 2349 4689 2349 4690 2209 4690 2279 4690 2279 4691 2277 4691 2275 4691 2276 4692 2279 4692 2275 4692 2209 4693 2278 4693 2279 4693 2280 4694 2277 4694 2279 4694 2280 4695 2279 4695 2278 4695 2283 4696 2141 4696 2212 4696 2283 4697 2281 4697 2141 4697 2278 4698 2209 4698 2282 4698 2249 4699 2281 4699 2283 4699 2280 4700 2278 4700 2282 4700 2287 4701 2286 4701 2289 4701 2289 4702 2286 4702 2288 4702 2285 4703 2284 4703 2229 4703 2285 4704 2229 4704 2289 4704 2289 4705 2229 4705 2292 4705 2284 4706 2285 4706 2220 4706 2286 4707 2167 4707 2288 4707 2287 4708 2289 4708 2336 4708 2336 4709 2289 4709 2342 4709 2340 4710 2342 4710 2293 4710 2293 4711 2342 4711 2292 4711 2167 4712 2168 4712 2288 4712 2288 4713 2168 4713 2170 4713 2288 4714 2170 4714 2290 4714 2290 4715 2291 4715 2288 4715 2342 4716 2289 4716 2292 4716 2291 4717 2290 4717 2221 4717 2289 4718 2288 4718 2285 4718 2285 4719 2288 4719 2291 4719 2285 4720 2291 4720 2221 4720 2285 4721 2221 4721 2220 4721 2292 4722 2295 4722 2294 4722 2292 4723 2294 4723 2293 4723 2294 4724 2295 4724 2297 4724 2297 4725 2296 4725 2294 4725 2297 4726 2299 4726 2296 4726 2294 4727 2296 4727 2298 4727 2294 4728 2298 4728 2240 4728 2296 4729 2299 4729 2298 4729 2298 4730 2299 4730 2300 4730 2298 4731 2300 4731 2301 4731 2242 4732 2359 4732 2339 4732 2242 4733 2235 4733 2359 4733 2304 4734 2176 4734 2303 4734 2304 4735 2303 4735 2308 4735 2304 4736 2308 4736 2188 4736 2307 4737 2305 4737 2308 4737 2308 4738 2305 4738 2188 4738 2352 4739 2308 4739 2169 4739 2308 4740 2352 4740 2306 4740 2257 4741 2307 4741 2308 4741 2303 4742 2169 4742 2308 4742 2308 4743 2306 4743 2257 4743 2238 4744 2309 4744 2429 4744 2251 4745 2310 4745 2204 4745 2238 4746 2429 4746 2230 4746 2204 4747 2205 4747 2251 4747 2230 4748 2429 4748 2312 4748 2230 4749 2312 4749 2311 4749 2311 4750 2312 4750 2251 4750 2311 4751 2251 4751 2205 4751 2313 4752 2202 4752 2203 4752 2182 4753 2236 4753 2222 4753 2182 4754 2222 4754 2174 4754 2174 4755 2222 4755 2409 4755 2174 4756 2409 4756 2313 4756 2313 4757 2409 4757 2202 4757 2320 4758 2314 4758 2153 4758 2153 4759 2314 4759 2144 4759 2153 4760 2144 4760 2315 4760 2316 4761 2317 4761 2318 4761 2318 4762 2317 4762 2319 4762 2318 4763 2319 4763 2151 4763 2320 4764 2151 4764 2321 4764 2320 4765 2321 4765 2314 4765 2328 4766 2142 4766 2322 4766 2322 4767 2142 4767 2324 4767 2322 4768 2324 4768 2323 4768 2325 4769 2210 4769 2145 4769 2145 4770 2210 4770 2139 4770 2328 4771 2327 4771 2329 4771 2328 4772 2329 4772 2142 4772 2258 4773 2266 4773 2362 4773 2330 4774 2356 4774 2332 4774 2331 4775 2225 4775 2332 4775 2331 4776 2332 4776 2356 4776 2332 4777 2367 4777 2330 4777 2333 4778 2368 4778 2334 4778 2333 4779 2334 4779 2335 4779 2336 4780 2344 4780 2337 4780 2336 4781 2337 4781 2287 4781 2287 4782 2337 4782 2357 4782 2355 4783 2167 4783 2357 4783 2357 4784 2167 4784 2286 4784 2357 4785 2286 4785 2287 4785 2355 4786 2338 4786 2167 4786 2339 4787 2341 4787 2240 4787 2340 4788 2293 4788 2341 4788 2341 4789 2293 4789 2294 4789 2341 4790 2294 4790 2240 4790 2336 4791 2342 4791 2344 4791 2344 4792 2342 4792 2340 4792 2341 4793 2343 4793 2340 4793 2340 4794 2343 4794 2360 4794 2340 4795 2360 4795 2344 4795 2366 4796 2345 4796 2346 4796 2346 4797 2345 4797 2347 4797 2346 4798 2347 4798 2166 4798 2348 4799 2349 4799 2345 4799 2345 4800 2349 4800 2347 4800 2348 4801 2350 4801 2349 4801 2264 4802 2265 4802 2351 4802 2162 4803 2351 4803 2265 4803 2306 4804 2352 4804 2259 4804 2259 4805 2352 4805 2335 4805 2352 4806 2169 4806 2338 4806 2333 4807 2353 4807 2358 4807 2358 4808 2353 4808 2354 4808 2352 4809 2354 4809 2353 4809 2352 4810 2353 4810 2335 4810 2335 4811 2353 4811 2333 4811 2352 4812 2338 4812 2354 4812 2354 4813 2338 4813 2355 4813 2354 4814 2355 4814 2358 4814 2358 4815 2355 4815 2357 4815 2344 4816 2361 4816 2358 4816 2361 4817 2356 4817 2330 4817 2337 4818 2344 4818 2358 4818 2337 4819 2358 4819 2357 4819 2358 4820 2361 4820 2330 4820 2343 4821 2341 4821 2361 4821 2344 4822 2360 4822 2361 4822 2359 4823 2235 4823 2356 4823 2361 4824 2341 4824 2339 4824 2360 4825 2343 4825 2361 4825 2361 4826 2359 4826 2356 4826 2361 4827 2339 4827 2359 4827 2362 4828 2260 4828 2258 4828 2258 4829 2265 4829 2266 4829 2334 4830 2368 4830 2363 4830 2258 4831 2363 4831 2265 4831 2363 4832 2258 4832 2334 4832 2363 4833 2364 4833 2265 4833 2265 4834 2364 4834 2162 4834 2366 4835 2364 4835 2367 4835 2366 4836 2367 4836 2365 4836 2365 4837 2367 4837 2332 4837 2350 4838 2345 4838 2365 4838 2350 4839 2365 4839 2332 4839 2350 4840 2348 4840 2345 4840 2365 4841 2345 4841 2366 4841 2367 4842 2333 4842 2358 4842 2367 4843 2358 4843 2330 4843 2333 4844 2367 4844 2368 4844 2367 4845 2363 4845 2368 4845 2367 4846 2364 4846 2363 4846 2335 4847 2334 4847 2258 4847 2148 4848 2138 4848 2372 4848 2371 4849 2369 4849 2147 4849 2147 4850 2369 4850 2370 4850 2370 4851 2369 4851 2224 4851 2370 4852 2224 4852 2148 4852 2148 4853 2224 4853 2138 4853 2375 4854 2226 4854 2371 4854 2371 4855 2226 4855 2369 4855 2372 4856 2138 4856 2146 4856 2146 4857 2138 4857 2373 4857 2146 4858 2373 4858 2374 4858 2374 4859 2373 4859 2136 4859 2374 4860 2136 4860 2375 4860 2375 4861 2136 4861 2226 4861 2331 4862 2400 4862 2401 4862 2356 4863 2376 4863 2331 4863 2331 4864 2376 4864 2400 4864 2400 4865 2376 4865 2402 4865 2402 4866 2376 4866 2419 4866 2402 4867 2419 4867 2418 4867 2402 4868 2418 4868 2404 4868 2404 4869 2418 4869 2416 4869 2404 4870 2416 4870 2403 4870 2403 4871 2416 4871 2407 4871 2407 4872 2416 4872 2377 4872 2408 4873 2407 4873 2413 4873 2413 4874 2407 4874 2377 4874 2408 4875 2413 4875 2378 4875 2382 4876 2420 4876 2379 4876 2380 4877 2381 4877 2194 4877 2194 4878 2381 4878 2192 4878 2160 4879 2154 4879 2380 4879 2380 4880 2154 4880 2381 4880 2381 4881 2154 4881 2382 4881 2381 4882 2382 4882 2379 4882 2382 4883 2154 4883 2420 4883 2420 4884 2154 4884 2160 4884 2386 4885 2177 4885 2388 4885 2383 4886 2384 4886 2425 4886 2384 4887 2383 4887 2156 4887 2156 4888 2383 4888 2387 4888 2156 4889 2387 4889 2389 4889 2384 4890 2156 4890 2386 4890 2384 4891 2386 4891 2388 4891 2388 4892 2425 4892 2384 4892 2156 4893 2389 4893 2386 4893 2386 4894 2389 4894 2177 4894 2177 4895 2389 4895 2385 4895 2150 4896 2135 4896 2393 4896 2393 4897 2135 4897 2394 4897 2391 4898 2392 4898 2152 4898 2152 4899 2392 4899 2134 4899 2152 4900 2134 4900 2390 4900 2390 4901 2134 4901 2150 4901 2150 4902 2134 4902 2135 4902 2397 4903 2392 4903 2391 4903 2393 4904 2394 4904 2149 4904 2149 4905 2394 4905 2395 4905 2395 4906 2394 4906 2396 4906 2395 4907 2396 4907 2397 4907 2397 4908 2396 4908 2392 4908 2399 4909 2173 4909 2398 4909 2398 4910 2173 4910 2171 4910 2399 4911 2398 4911 2183 4911 2400 4912 2406 4912 2401 4912 2406 4913 2400 4913 2402 4913 2401 4914 2406 4914 2405 4914 2404 4915 2406 4915 2402 4915 2406 4916 2404 4916 2403 4916 2408 4917 2406 4917 2403 4917 2408 4918 2403 4918 2407 4918 2405 4919 2406 4919 2408 4919 2408 4920 2410 4920 2201 4920 2408 4921 2201 4921 2405 4921 2405 4922 2201 4922 2409 4922 2378 4923 2410 4923 2408 4923 2378 4924 2413 4924 2411 4924 2311 4925 2412 4925 2414 4925 2413 4926 2377 4926 2411 4926 2377 4927 2416 4927 2411 4927 2411 4928 2416 4928 2415 4928 2411 4929 2415 4929 2412 4929 2412 4930 2415 4930 2417 4930 2412 4931 2417 4931 2414 4931 2417 4932 2415 4932 2376 4932 2418 4933 2415 4933 2416 4933 2418 4934 2419 4934 2415 4934 2419 4935 2376 4935 2415 4935 2376 4936 2356 4936 2417 4936 2385 4937 2199 4937 2177 4937 2425 4938 2388 4938 2190 4938 2160 4939 2380 4939 2185 4939 2383 4940 2187 4940 2387 4940 2387 4941 2187 4941 2200 4941 2420 4942 2186 4942 2379 4942 2433 4943 2431 4943 2157 4943 2434 4944 2421 4944 2155 4944 2155 4945 2421 4945 2159 4945 2430 4946 2441 4946 2159 4946 2434 4947 2422 4947 2429 4947 2429 4948 2422 4948 2423 4948 2422 4949 2434 4949 2155 4949 2422 4950 2155 4950 2435 4950 2178 4951 2423 4951 2435 4951 2158 4952 2431 4952 2426 4952 2433 4953 2424 4953 2431 4953 2431 4954 2424 4954 2426 4954 2425 4955 2424 4955 2189 4955 2158 4956 2426 4956 2445 4956 2445 4957 2426 4957 2189 4957 2189 4958 2426 4958 2425 4958 2433 4959 2427 4959 2445 4959 2432 4960 2427 4960 2433 4960 2428 4961 2432 4961 2157 4961 2448 4962 2436 4962 2178 4962 2433 4963 2444 4963 2443 4963 2433 4964 2443 4964 2440 4964 2440 4965 2443 4965 2182 4965 2178 4966 2429 4966 2423 4966 2441 4967 2430 4967 2443 4967 2443 4968 2430 4968 2421 4968 2443 4969 2421 4969 2182 4969 2445 4970 2427 4970 2428 4970 2424 4971 2448 4971 2189 4971 2445 4972 2428 4972 2157 4972 2445 4973 2157 4973 2158 4973 2448 4974 2424 4974 2436 4974 2157 4975 2432 4975 2433 4975 2424 4976 2433 4976 2436 4976 2445 4977 2444 4977 2433 4977 2434 4978 2429 4978 2421 4978 2421 4979 2429 4979 2182 4979 2159 4980 2178 4980 2155 4980 2155 4981 2178 4981 2435 4981 2129 4982 2429 4982 2178 4982 2129 4983 2178 4983 2436 4983 2181 4984 2429 4984 2180 4984 2433 4985 2438 4985 2183 4985 2433 4986 2183 4986 2436 4986 2437 4987 2429 4987 2181 4987 2429 4988 2437 4988 2182 4988 2182 4989 2437 4989 2439 4989 2433 4990 2440 4990 2438 4990 2438 4991 2440 4991 2172 4991 2441 4992 2442 4992 2159 4992 2178 4993 2159 4993 2442 4993 2445 4994 2198 4994 2444 4994 2178 4995 2195 4995 2448 4995 2447 4996 2448 4996 2446 4996 2446 4997 2448 4997 2129 4997 2130 4998 2129 4998 2448 4998 2448 4999 2195 4999 2130 4999

+
+
+
+
+ + + + + + + + + + + + + + +
diff --git a/descriptions/deep_robotics/x30_description/meshes/shank.dae b/descriptions/deep_robotics/x30_description/meshes/shank.dae new file mode 100755 index 0000000..aa29a35 --- /dev/null +++ b/descriptions/deep_robotics/x30_description/meshes/shank.dae @@ -0,0 +1,63 @@ + + + + + VCGLab + VCGLib | MeshLab + + Y_UP + 周四 11月 23 02:06:49 2023 + 周四 11月 23 02:06:49 2023 + + + + + + + + + 0.00614916 0.0115023 0.0366854 0.00255077 0.0115023 0.0456913 0.00866415 0.0110023 0.0384586 0.00996286 0.0115023 0.0394215 0.00988642 0.0115023 0.0440075 0.009982 0.0110023 0.0416404 0.00901778 0.0115023 0.0451761 0.00721238 0.0115023 0.0463317 0.00866425 0.0110023 0.0448225 0.00548174 0.0110023 0.0461406 0.00100549 0.0115023 0.0438682 0.00120022 0.0110144 0.0431572 0.00107468 0.0115023 0.0392797 0.00113546 0.0110023 0.040476 0.0019467 0.0115023 0.038105 0.00230023 0.0110023 0.0384585 0.00844611 -0.0110023 0.0488015 0.0133621 -0.0115023 0.0440838 0.00251158 -0.0110023 0.0487986 0.00347624 -0.0110023 0.0491267 0.00547779 -0.0115023 0.0498908 0.00547813 -0.0110023 0.0493908 0.0034762 -0.0110023 0.0341548 0.00157908 -0.0115023 0.0343724 0.00251795 -0.0110023 0.0344798 2.12268e-06 -0.0110023 0.0361605 0.00911157 -0.0115023 0.0342321 0.0074879 -0.0110023 0.0341548 0.00548289 -0.0115023 0.0333906 0.00548272 -0.0110023 0.0338908 2.15064e-06 -0.0110023 0.0471207 -0.00200388 -0.0110023 0.0436466 -0.00226789 -0.0110023 0.0416414 -0.00200389 -0.0110023 0.0396349 -0.0023967 -0.0115023 0.0391942 -0.00167852 -0.0110023 0.0386763 0.0109623 -0.0110023 0.0361604 0.012968 -0.0110023 0.0396348 0.0137321 -0.0115023 0.0416364 0.012968 -0.0110023 0.0436465 -0.0207822 0.00850219 -0.307494 0.000951691 0.00899992 -0.329153 -0.00457056 0.00899525 -0.328641 -0.00970301 0.00899998 -0.326541 -0.022572 0.00587674 -0.313876 -0.0228349 0.005 -0.307247 -0.016825 0.005 -0.32568 -0.0205202 0.00587674 -0.32017 -0.0206072 0.005 -0.320213 -0.0207821 0.005 -0.319853 -0.0116369 0.005 -0.329838 -0.00545346 0.00587674 -0.332243 -0.00547647 0.005 -0.332337 -0.00511317 0.005 -0.332423 0.0076639 0.005 -0.331684 0.0135461 0.005 -0.328587 0.00763145 0.00587674 -0.331593 -0.0205978 0.00837875 -0.305048 -0.019471 0.00888787 -0.305698 -0.0188919 0.00900313 -0.313237 -0.0206302 0.00850219 -0.313543 -0.0171978 0.00899525 -0.318524 -0.00498436 0.00850219 -0.330329 0.0123527 0.0085062 -0.326892 0.0126208 0.00900001 -0.324201 0.0155874 0.00729563 -0.325912 0.0130054 0.00754962 -0.327845 0.00697559 0.00850545 -0.329728 0.007358 0.00754962 -0.330819 0.00103859 0.00850219 -0.330905 -0.0105907 0.00850219 -0.328054 -0.0111724 0.00754962 -0.329046 -0.0153045 0.00850584 -0.324269 -0.0197849 0.00754962 -0.319806 -0.018755 0.00850219 -0.319295 -0.0217634 0.00754962 -0.313737 0.0134886 0.00587674 -0.328508 0.00109557 0.00754962 -0.332053 -0.00525798 0.00754962 -0.331446 0.00113636 0.00587674 -0.332873 -0.0115875 0.00587674 -0.329754 -0.0167539 0.00587674 -0.325614 -0.0161534 0.00754962 -0.325055 -0.0219234 0.00754962 -0.307357 -0.0227382 0.00587674 -0.307258 0.0129955 -0.00647238 -0.328634 0.0149695 -0.00804853 -0.325556 0.00914773 -0.00647238 -0.330795 0.0098048 -0.00499999 -0.330804 0.00483096 -0.00499999 -0.332485 -0.012119 -0.00499999 -0.329547 -0.00897044 -0.00647238 -0.330872 -0.00908138 -0.00499999 -0.33113 -0.0158984 -0.00693254 -0.325923 -0.0162467 -0.00519487 -0.326272 0.00878906 -0.00782843 -0.329979 0.0124859 -0.00782843 -0.327904 -0.0152251 -0.00808212 -0.325249 -0.0128426 -0.00647238 -0.32874 -0.00861868 -0.00782843 -0.330053 -0.00439852 -0.00782843 -0.331379 -0.0045779 -0.00647238 -0.332252 9.60988e-05 -0.00782843 -0.331827 -0.0115726 -0.00871916 -0.326886 -0.0123392 -0.00782843 -0.328005 -0.00808342 -0.00871916 -0.328807 -0.00511317 -0.00499999 -0.332423 0.000101322 -0.00499999 -0.332998 0.000100143 -0.00647238 -0.332718 0.00477187 -0.00647238 -0.332211 0.00458508 -0.00782843 -0.33134 0.0117102 -0.00871916 -0.326791 0.0138055 -0.0088216 -0.324884 0.00824318 -0.00871916 -0.328738 0.0043 -0.00871916 -0.330014 9.00331e-05 -0.00871916 -0.330471 -0.00412516 -0.00871916 -0.330051 -0.0142772 -0.00883956 -0.324346 0.0237157 0.00999999 0.0477566 0.0196998 0.0110607 0.0535511 0.0215706 0.01075 0.0530434 0.0212637 0.011299 0.0525882 0.0223264 0.0114906 0.0509964 0.0234728 0.0110759 0.0496202 0.0229918 0.011299 0.0479525 0.022268 0.0115 0.0481485 0.0115912 -0.013 0.00310567 0.0115911 0.013 -0.00310585 0.0115912 0.013 0.00310567 0.0115912 -0.00499999 0.00310567 0.00869644 -0.00499999 0.00826866 0.00848537 -0.013 0.00848513 0.00310592 0.013 0.011591 0.00310592 -0.013 0.011591 -0.00310593 0.013 0.0115913 -0.00310593 -0.013 0.0115913 -0.00848523 0.013 0.00848526 -0.00848523 -0.013 0.00848526 -0.0115913 0.013 0.00310598 -0.0115913 -0.013 0.00310598 -0.0115911 0.013 -0.00310588 0.00310578 0.013 -0.0115912 0.00310578 -0.013 -0.0115912 0.026 0.0147065 -0.0673193 0.0294143 0.0141586 -0.0659051 0.0292208 0.00325001 -0.0657351 0.0297843 0.00325001 -0.0664159 0.0261899 0.0145505 -0.0664679 0.0267428 0.00325001 -0.0657639 0.0259998 0.00325001 -0.0940014 0.0261522 0.00325001 -0.0947668 0.0262297 0.0182401 -0.0949321 0.0265857 0.018261 -0.0954156 0.0274047 0.0182627 -0.0959109 0.028 0.00325001 -0.0960014 0.044186 0.0013943 -0.100001 0.0449676 0.00183204 -0.100161 0.0447883 0.0177568 -0.100094 0.0456003 0.0177592 -0.100587 0.0460446 0.00325001 -0.101263 0.0458751 0.00290086 -0.100922 -0.00080883 0.0135 0.0176816 -0.00105579 0.0132999 0.0175246 -0.00876237 0.0135 0.0153791 -0.0146309 0.0133 0.00960098 -0.0147982 0.0135 0.00971082 -0.0173969 0.0133 0.00189604 -0.0165426 0.0135 -0.00629529 -0.00473144 0.0132975 -0.0168909 0.00340031 0.0133025 -0.0172266 0.00314732 -0.013 -0.0172148 -0.0117351 -0.0133 -0.0129821 -0.016381 -0.013 -0.0061573 -0.0163559 -0.0133 -0.00622397 -0.0173969 -0.0133 0.00189604 -0.0146309 -0.0133 0.00960098 0.00664973 -0.0133 0.0161875 0.0210001 0.00151795 -0.0836354 0.0193661 0.00140225 -0.0840643 0.019161 0.00152564 -0.0842033 0.0188286 0.00183578 -0.0844278 0.0185592 0.00226321 -0.0846102 0.0188115 0.00325001 -0.085244 0.0205862 0.00325001 -0.0855476 0.0213085 0.00223901 -0.0848567 0.0217319 0.00225 -0.0836353 0.0195709 0.00235857 -0.0853975 0.0203663 0.00163614 -0.0848358 0.00578052 -0.0047508 -0.0359099 0.00466018 -0.00444716 -0.0354793 0.00523978 -0.00401841 -0.0364028 0.00373471 -0.00390224 -0.037077 0.0045001 -0.00374999 -0.037077 0.00351361 -0.00401018 -0.037077 0.00380192 -0.0040276 -0.0362703 0.00324396 -0.00419353 -0.0370769 0.0046298 -0.00529818 -0.0350842 0.00308565 -0.00433579 -0.0370767 0.0026006 -0.00518656 -0.0364573 0.00250006 -0.00575 -0.0370769 0.00464147 -0.011912 -0.0350819 0.00381419 -0.011964 -0.0351708 0.00307312 -0.00516057 -0.035673 0.00275522 -0.012118 -0.036072 0.00597819 -0.00575 -0.0357298 0.00377771 -0.00575 -0.035212 0.00539731 -0.00570567 -0.0352799 0.00505644 -0.0118971 -0.0351558 0.0188115 -0.00575 -0.085244 0.0217696 -0.0175226 -0.0845673 0.0218857 -0.00575 -0.0843014 0.0189659 -0.00575 -0.0853473 0.0194421 -0.0177641 -0.0855561 0.0196627 -0.00575 -0.0856066 0.0197993 -0.00575 -0.0856252 0.0196631 -0.0177565 -0.0856069 0.0205862 -0.00575 -0.0855476 0.000602357 0.0012352 -0.312972 0.000776566 -0.002 -0.312897 0.00212147 -0.002 -0.31212 0.000776566 0.00200001 -0.312897 0.00211195 0.00199985 -0.312126 -0.000776377 0.00200001 -0.312896 -0.00289788 0.00200001 -0.310775 -0.00212137 -0.002 -0.31212 -0.000776615 -0.002 -0.307101 -0.00212119 -0.002 -0.307877 -0.00262493 -0.00123179 -0.30855 0.00289783 -0.002 -0.309222 0.00198822 0.00200001 -0.307752 0.00343752 -0.009 -0.32282 0.00209254 0.00900001 -0.322043 0.00209254 -0.009 -0.322043 0.000539593 0.00900001 -0.322043 -0.00158175 0.00900001 -0.324164 -0.00158175 -0.009 -0.324164 -0.000805157 0.00900001 -0.327062 -0.000805157 -0.009 -0.327062 0.000539494 -0.009 -0.327838 0.00209244 -0.009 -0.327839 0.00343734 0.00900001 -0.327062 0.00421378 0.00900001 -0.325717 0.00343734 -0.009 -0.327062 0.0042137 -0.009 -0.324164 0.00343752 0.00900001 -0.32282 -0.00671632 0.00900001 -0.320095 -0.00826926 0.00900001 -0.320095 -0.00671632 -0.009 -0.320095 -0.00826926 -0.009 -0.320095 -0.00961417 -0.009 -0.320872 -0.0103906 0.00900001 -0.322217 -0.0103906 -0.009 -0.322217 -0.0103905 0.00900001 -0.32377 -0.0103905 -0.009 -0.32377 -0.00961401 0.00900001 -0.325115 -0.00961401 -0.009 -0.325115 -0.00826902 0.00900001 -0.325891 -0.00826902 -0.009 -0.325891 -0.00671642 -0.009 -0.325891 -0.00671642 0.00900001 -0.325891 -0.00537151 0.00900001 -0.325114 -0.00537151 -0.009 -0.325114 -0.00459508 0.00900001 -0.323769 -0.00537133 -0.009 -0.320872 -0.0128146 -0.009 -0.313448 -0.0143676 -0.009 -0.313448 -0.0157125 -0.009 -0.314224 -0.0164889 -0.009 -0.315569 -0.0164888 0.00900001 -0.317122 -0.0164888 -0.009 -0.317122 -0.0157123 -0.009 -0.318467 -0.0157123 0.00900001 -0.318467 -0.0143677 0.00900001 -0.319243 -0.0114698 0.00900001 -0.318467 -0.0106934 -0.009 -0.317122 -0.0106935 0.00900001 -0.315569 0.0104248 0.00900001 -0.318586 0.00887212 0.00900001 -0.318586 0.0104248 -0.009 -0.318586 0.00887212 -0.009 -0.318586 0.00752729 -0.009 -0.319362 0.00675086 -0.009 -0.320707 0.00675086 0.00900001 -0.320707 0.00675052 -0.009 -0.32226 0.010425 0.00900001 -0.324382 0.00887202 -0.009 -0.324382 0.01177 -0.009 -0.323605 0.01177 0.00900001 -0.323605 0.0125463 0.00900001 -0.320707 0.0117697 0.00900001 -0.319362 -0.0126522 0.00900001 -0.305281 -0.0126522 -0.009 -0.305281 -0.0139971 0.00900001 -0.304504 -0.0155502 0.00900001 -0.304504 -0.0168951 0.00900001 -0.305281 -0.0168951 -0.009 -0.305281 -0.0176714 -0.009 -0.306626 -0.0168948 0.00900001 -0.309523 -0.0155499 0.00900001 -0.3103 -0.0139972 0.00900001 -0.3103 -0.0155499 -0.009 -0.3103 -0.0139972 -0.009 -0.3103 -0.0126524 -0.009 -0.309523 -0.011876 0.00900001 -0.308179 -0.0118756 -0.009 -0.306626 0.00740221 0.00125 -0.283013 0.0125786 -0.00125 -0.283013 0.00291921 0.00125 -0.285601 0.000331132 -0.00125 -0.290084 0.000331119 -0.00125 -0.295261 0.00740199 0.00125 -0.302332 0.00740199 -0.00125 -0.302332 -0.00264859 0.00236635 -0.0200684 -0.00350001 0.00125 -0.0217197 -0.00829016 0.00151795 -0.0192943 -0.0120868 0.00151795 -0.0171729 -0.0126625 0.00125 -0.0179906 -0.0179847 0.00151795 -0.0108421 -0.0160972 0.00125 -0.0149961 -0.0198325 0.00151795 -0.00690464 -0.0207769 0.00125 -0.00723338 -0.0208296 0.00151795 -0.00267081 -0.0209328 0.00151795 0.00167731 -0.0219298 0.00125 0.0017573 -0.01936 0.00125 0.0104495 -0.0160287 0.00151795 0.0135676 -0.016792 0.00125 0.0142137 -0.0148296 0.00225 -0.0138156 -0.0153655 0.00151795 -0.0143143 -0.0173579 0.00225 -0.0104641 -0.0201034 0.00225 -0.00257784 -0.0202031 0.00225 0.00161872 -0.0194365 0.00225 0.00574624 -0.0201382 0.00151795 0.00595352 -0.01848 0.00151795 0.00997467 -0.0124405 0.00225 0.0160006 -0.0128898 0.00151795 0.0165784 -0.00887759 0.00225 0.0182203 -0.00919807 0.00151795 0.0188782 -0.00800086 0.00225 -0.018622 -0.0116655 0.00225 -0.0165742 -0.0146336 0.00325001 -0.013633 -0.0171284 0.00325001 -0.0103257 -0.018888 0.00325001 -0.00657589 -0.0191412 0.00225 -0.00666381 -0.0198374 0.00325001 -0.00254387 -0.0199362 0.00325001 0.00159765 -0.0191794 0.00325001 0.00567021 -0.0178358 0.00225 0.00962695 -0.01547 0.00225 0.0130946 -0.00486849 0.00325001 0.0193984 -0.0027347 0.00140225 -0.0542382 -0.00253864 0.00158747 -0.0549458 -0.00350001 0.00125 -0.0542381 -0.00408197 0.00138521 -0.054667 -0.00463283 0.00182876 -0.0550729 -0.00463182 0.00325001 -0.0558872 -0.00208816 0.00265758 -0.0557356 -0.0020918 0.00325001 -0.0556581 -0.00287548 0.00325001 -0.0561384 -0.00339271 0.00175227 -0.0555787 -0.00448186 0.00325001 -0.0559806 -0.00388959 0.00236338 -0.0560117 0.0346463 0.00134789 -0.26193 0.0356284 0.00207442 -0.262119 0.0351939 0.00163196 -0.262035 0.0336783 0.00152606 -0.262779 0.0357604 0.00262531 -0.262831 0.0348562 0.0029267 -0.263663 0.0334063 0.00135623 -0.261924 0.0326467 0.00183578 -0.262058 0.032353 0.00268214 -0.262906 0.0346884 0.00183864 -0.263144 0.0330507 0.00325001 -0.263551 0.033494 0.00233283 -0.263544 0.0354539 0.00325001 -0.263227 -0.0017159 0.00252202 -0.0208262 -0.00165229 -0.00248463 -0.0217197 -0.00251874 -0.0022037 -0.0201654 -0.00232604 -0.00325 -0.0201007 -0.00318179 -0.00325 -0.0197453 -0.0027347 -0.00140224 -0.0217198 -0.00511002 -0.00325 -0.0554246 -0.00463182 -0.00325 -0.0558872 -0.00209745 -0.0154374 -0.0556638 -0.00237882 -0.0154995 -0.0558946 -0.00463191 -0.0157019 -0.0558872 -0.00448186 -0.00325 -0.0559806 -0.00422662 -0.015699 -0.0561017 -0.00372123 -0.00322753 -0.0562367 0.0356044 -0.011293 -0.263058 0.0348495 -0.00300972 -0.263666 0.0340232 -0.00325 -0.263812 0.0339568 -0.0113593 -0.263824 0.0329905 -0.0113686 -0.263515 0.0326252 -0.0113655 -0.263226 0.0323288 -0.0113571 -0.262848 0.00823107 -0.0135 -0.0182279 0.00823107 -0.0115023 -0.0182279 0.000183548 -0.0115023 -0.0199992 -0.00789532 -0.0135 -0.0183755 -0.00318179 -0.0115023 -0.0197453 0.00336557 -0.0135 0.0197149 0.00336557 -0.0115023 0.0197149 0.00735476 -0.0135 0.0185986 0.00735476 -0.0115023 0.0185986 -0.00385815 -0.0115023 0.0196245 -0.0122763 -0.0135 0.0157892 -0.0122763 -0.00325 0.0157892 -0.0175998 -0.00325 0.00949942 -0.0191794 -0.00325 0.00567021 -0.0175998 -0.0135 0.00949942 -0.0198374 -0.00325 -0.00254387 -0.018888 -0.00325 -0.00657589 -0.0146336 -0.00325 -0.013633 -0.0146336 -0.0135 -0.013633 -0.0235747 -0.0198246 -0.29352 -0.0241976 -0.0196178 -0.293043 -0.0244944 -0.0194664 -0.292697 -0.024867 -0.00125 -0.289821 -0.0250511 -0.00125 -0.291309 -0.0248558 -0.0185199 -0.289792 2.12268e-06 -0.00499999 0.0361605 -0.00200389 -0.00499999 0.0396349 -0.00200388 -0.00499999 0.0436466 -0.00167867 -0.0110023 0.044605 0.00347624 -0.00499999 0.0491267 2.15064e-06 -0.00499999 0.0471207 0.00748794 -0.0110023 0.0491267 0.0109624 -0.00499999 0.0471206 0.0126429 -0.0110023 0.0446047 0.0109624 -0.0110023 0.0471206 0.0132321 -0.0110023 0.0416367 0.0126403 -0.0110023 0.0386698 0.00844632 -0.0110023 0.03448 0.0109623 -0.00499999 0.0361604 0.0074879 -0.00499999 0.0341548 0.00229999 0.005 0.0448228 0.00113546 0.005 0.040476 0.000982051 0.0110023 0.041643 0.00113555 0.005 0.0428053 0.00431737 0.005 0.0372941 0.00431737 0.0110023 0.0372941 0.00230023 0.005 0.0384585 0.00982859 0.0110023 0.0404761 0.00866415 0.005 0.0384586 0.00664666 0.0110023 0.0372942 0.00548433 0.0110023 0.0371407 0.00229999 0.0110023 0.0448228 0.00431748 0.0110023 0.0459872 0.00664677 0.0110023 0.0459873 0.00982868 0.0110023 0.0428054 0.0133492 -0.0115023 0.0393144 0.0116153 -0.0115023 0.0361414 -0.00997295 -0.0115023 0.0308243 -0.0113253 -0.0115023 0.0303607 -0.0121698 -0.0115023 0.0295459 -0.00231539 -0.0115023 0.0246894 -0.000351406 -0.0115023 0.0358069 -0.00276809 -0.0115023 0.0416416 -0.00214043 -0.0115023 0.044796 -0.000676251 -0.0115023 0.0472295 0.00184886 -0.0115023 0.0490476 0.0113159 -0.0115023 0.0474742 0.00937452 -0.0115023 0.0489147 -0.00283878 -0.0115023 0.0200288 0.00761675 -0.0115023 0.0179509 -0.0272109 -0.0115023 -0.00838658 -0.0274714 -0.0115023 0.00475025 -0.0217898 -0.0115023 0.0156762 -0.0253388 -0.0115023 0.0086597 -0.0256008 -0.0115023 0.0107674 0.0104822 0.0115023 0.0416402 0.0087183 0.0115023 0.0378499 0.0195113 0.0115 0.0525075 0.00482813 0.0115023 0.0465977 0.000482021 0.0115023 0.0416433 0.00252752 0.0115023 0.0524904 -0.0113253 0.0115023 0.0303607 -0.0217898 0.0115023 0.0156762 -0.0273832 0.0115023 -0.00372379 -0.0273202 0.0115023 -0.00675601 -0.00283878 0.0115023 0.0200288 -0.00185347 0.0115023 0.0210425 -0.00144178 0.0115023 0.0223949 -0.00169466 0.0115023 0.0237854 -0.00231539 0.0115023 0.0246894 0.00376213 0.0115023 0.0369459 0.00866425 0.005 0.0448225 0.0210743 0.005 0.0379993 0.00982868 0.005 0.0428054 0.0197776 0.005 0.0539836 0.00982859 0.005 0.0404761 -0.00373197 0.005 0.0496067 0.00431748 0.005 0.0459872 0.00664677 0.005 0.0459873 0.00900313 0.005 0.0186636 0.00664666 0.005 0.0372942 0.0115912 0.005 0.00310567 0.0119768 0.005 -0.000744366 0.0180903 0.005 0.00267103 0.0119768 -0.00499999 -0.000744366 0.012968 -0.00499999 0.0396348 0.0034762 -0.00499999 0.0341548 -0.0113634 -0.00499999 0.0372731 0.0182604 -0.00499999 -0.000895436 0.0113758 -0.00499999 0.0139374 0.0159112 -0.00499999 0.00881613 0.000187781 -0.00499999 0.0534395 0.00748794 -0.00499999 0.0491267 0.0107324 -0.00499999 0.0556161 0.012968 -0.00499999 0.0436465 0.0216828 -0.00499999 0.0532102 0.0231153 -0.00499999 0.0517357 0.00691344 -0.0135 0.0162941 -0.00129816 -0.013 0.0174519 -0.00897116 -0.013 0.0150254 -0.00489025 -0.013 -0.0168028 -0.00310574 -0.013 -0.0115912 -0.0118933 -0.013 -0.0128375 -0.00848519 -0.013 -0.00848534 -0.0174045 -0.013 0.00182507 -0.0115911 -0.013 -0.00310588 -0.0147475 -0.013 0.00942169 0.016398 -0.013 0.0061119 0.0115911 -0.013 -0.00310585 0.0148253 -0.013 -0.00929841 0.00848541 -0.013 -0.00848547 0.0108013 0.0135 -0.0140228 -0.0147475 0.013 0.00942169 -0.00129816 0.013 0.0174519 0.00848541 0.013 -0.00848547 0.010679 0.013 -0.0138642 -0.0118933 0.013 -0.0128375 -0.00310574 0.013 -0.0115912 0.00848537 0.013 0.00848513 0.0119994 0.013 0.0127382 -0.0174045 0.013 0.00182507 -0.016381 0.013 -0.0061573 -0.00848519 0.013 -0.00848534 0.00357808 0.005 0.0223315 0.00357808 -0.00499999 0.0223315 0.00869644 0.005 0.00826866 0.036433 -0.00325 -0.0797522 0.0379026 -0.0160682 -0.0828033 0.0396639 -0.0164669 -0.0865413 0.0426721 0.0171247 -0.0931993 0.0297843 0.0142066 -0.0664159 0.0552576 0.0162885 -0.175145 0.055235 0.00325001 -0.175308 0.056782 0.00325001 -0.152968 0.0567849 0.0183404 -0.153772 0.0564944 0.00325001 -0.145005 0.0564945 0.0187804 -0.145007 0.0563536 0.0188446 -0.143099 0.0539151 0.0189607 -0.126532 0.0539154 0.00325001 -0.126532 0.0520243 0.0187679 -0.118859 0.0523044 0.00325001 -0.119889 0.0421566 0.00125 -0.165494 0.0304737 0.00125 -0.100002 0.0336735 0.00125 -0.108606 0.0433807 0.00125 -0.100002 0.0401043 0.00125 -0.126931 0.0429 0.00125 -0.146206 0.0429138 0.00125 -0.155872 0.054416 0.00125 -0.164083 0.0279999 0.00125 -0.0940014 0.027 0.00151795 -0.0673193 0.0262679 0.00225 -0.0673191 0.026268 0.00225 -0.0940016 -0.00222507 0.0115025 -0.020138 0.000183548 0.0115023 -0.0199992 0.0118094 0.0115023 -0.0161412 -0.00149997 0.0115023 -0.0232094 -0.00149997 0.0115023 -0.0217198 -0.00169646 0.0115023 -0.0208555 0.0144421 0.0114789 -0.0100281 0.0174095 0.013 -0.00177664 0.0148253 0.013 -0.00929841 0.0172979 0.0114447 -0.00265296 0.0162704 0.0113055 -0.00644398 0.0172224 0.0115023 0.00310397 0.016398 0.013 0.0061119 0.00683526 0.0115023 0.01611 0.00910722 0.0115023 0.0149435 0.0195113 -0.0115 0.0525075 0.00319449 -0.0115 0.0533473 -0.0146177 0.0167715 -0.278603 -0.0160104 0.0172233 -0.280175 -0.00149987 0.0139419 -0.0467306 0.00597819 0.0119009 -0.0357298 0.00950427 0.0120788 -0.0395986 0.0149597 0.0119688 -0.0416406 0.0045025 0.0119165 -0.0350539 0.00377712 0.0119705 -0.0352119 -0.00149999 0.0117908 -0.030108 0.00277512 0.0121151 -0.0360642 0.0271234 0.0130468 -0.0573936 0.0236287 0.0126151 -0.0522647 0.0217448 0.0130425 -0.0542685 0.0215969 0.0124165 -0.0495352 0.0154507 0.0124435 -0.04621 0.0286122 0.0141542 -0.0654152 0.0276035 0.0142365 -0.0653438 0.0219995 0.0139598 -0.0603906 0.0267308 0.0143835 -0.0657492 0.0190498 0.0177706 -0.0853955 0.0205865 0.0176972 -0.0855474 0.0208971 0.0176662 -0.0854229 0.0259998 0.0181782 -0.0940014 0.0213846 0.0176012 -0.0850791 0.0260002 0.0174912 -0.0867201 0.026 0.0173324 -0.085319 0.0220003 0.0168098 -0.0790453 0.0259999 0.0161013 -0.0761655 -0.00348046 0.0160615 -0.0588999 0.00613118 0.0170705 -0.0716989 0.0136104 0.0173101 -0.0779818 0.00872447 0.0173152 -0.0752098 0.0145026 0.0173948 -0.0792293 -0.00511002 0.0156728 -0.0554246 -0.00438619 0.0157023 -0.0560313 0.00249991 0.0160686 -0.0623955 0.00249986 0.0144501 -0.0521913 0.00249986 0.0122056 -0.0369678 -0.00150035 0.0129015 -0.0398763 0.0284151 0.0117471 -0.204392 0.0261791 0.0113686 -0.210212 0.0322738 0.0128466 -0.192806 0.0315935 0.0126029 -0.195034 0.0533766 0.0148848 -0.18623 0.0387736 0.0145629 -0.180587 0.0366068 0.0150683 -0.174987 0.0357241 0.0139629 -0.18411 0.0519756 0.0139634 -0.193473 0.0536035 0.0139584 -0.194457 0.0507771 0.0125959 -0.20617 0.0484928 0.0120719 -0.211198 0.0498278 0.0122325 -0.20989 0.0288425 0.0109175 -0.243856 0.0320701 0.0113359 -0.26216 0.0324575 0.0113617 -0.263036 0.0447554 0.0111899 -0.225374 0.0397056 0.0108717 -0.245232 0.0409976 0.0108641 -0.244145 0.0305024 0.0118152 -0.270548 0.0254869 0.0109199 -0.242101 0.02737 0.0108625 -0.235504 0.0247307 0.0111931 -0.213735 0.024196 0.0110651 -0.217504 0.022 0.0109432 -0.222326 0.0259216 0.0108975 -0.22729 0.0427129 0.0173034 -0.0947034 0.0412256 0.0160597 -0.0846621 0.0388085 0.0162742 -0.0847135 0.0309392 0.0144684 -0.0687001 0.0483643 0.0182168 -0.107384 0.0460446 0.0178003 -0.101263 0.0466706 0.0173126 -0.0970637 0.0408402 0.0175699 -0.0960015 0.0422377 0.0174189 -0.0954321 0.0424807 0.0173703 -0.0951454 0.0360856 0.0181928 -0.100002 0.0304737 0.0184254 -0.100002 0.0219016 0.0184037 -0.0947251 0.0260372 0.0182066 -0.0943854 0.0285759 0.018575 -0.101371 0.0389317 0.0176982 -0.151865 0.0409931 0.0176905 -0.153139 0.0387907 0.0172326 -0.156752 0.0409679 0.0175902 -0.154245 0.0379999 0.0162058 -0.165932 0.0403052 0.0165643 -0.164029 0.038876 0.0180614 -0.14742 0.0381279 0.0186184 -0.138126 0.039449 0.0188444 -0.133343 0.0304019 0.0187648 -0.106324 0.0304876 0.0189227 -0.111199 0.0338735 0.0190065 -0.119952 0.0323466 0.0188755 -0.110545 0.0503839 0.0185408 -0.113335 0.051108 0.0182068 -0.108842 0.0538916 0.0186748 -0.117869 0.0532084 0.0189008 -0.123445 0.0586031 0.0187248 -0.14761 0.0551582 0.0190052 -0.133181 0.056397 0.0174721 -0.164419 0.0586673 0.0181298 -0.157916 0.0565495 0.017695 -0.162056 0.0566879 0.0186237 -0.148718 -0.0124819 0.016061 -0.276132 -0.0101089 0.0152598 -0.273281 0.018646 0.0108678 -0.226972 0.00981792 0.0111302 -0.243126 0.014756 0.0109283 -0.236528 0.00840085 0.011293 -0.247373 0.00305492 0.0118787 -0.255638 0.0021738 0.0118789 -0.255137 -0.000208942 0.0122755 -0.258582 -0.00557341 0.0135455 -0.26589 -0.00505256 0.0136551 -0.266913 -0.0078416 0.0145127 -0.27049 0.0306746 0.0118758 -0.271525 0.0340627 0.012647 -0.281926 0.0321031 0.0146853 -0.294495 0.0333238 0.0141539 -0.292143 0.032075 0.0148944 -0.295633 0.0322192 0.0166528 -0.304989 0.0320838 0.0159986 -0.301501 0.0321536 0.0182275 -0.313439 0.0119758 0.0117632 -0.0375169 -0.00150033 0.0117541 -0.0296235 -0.00150015 0.0115264 -0.0251106 -0.0156405 0.0144139 -0.0415093 -0.0167349 0.0139926 -0.0382649 -0.0182841 0.0137067 -0.0355691 -0.0202934 0.0135615 -0.0334791 -0.0268651 0.0115561 -0.0114536 0.0447455 -0.0111883 -0.225412 0.0482867 -0.0117491 -0.215817 0.0360034 -0.0141096 -0.18296 0.0524063 -0.0139079 -0.19422 0.0519474 -0.0145071 -0.188666 0.031594 -0.0126029 -0.195033 0.0325281 -0.0126082 -0.195513 0.0322638 -0.0128428 -0.19284 0.0328284 -0.0127122 -0.194551 0.03468 -0.0139133 -0.18395 0.0219999 -0.010934 -0.222326 0.0320701 -0.0113359 -0.26216 0.0288475 -0.0109179 -0.243892 0.0254979 -0.0109201 -0.242163 0.0277213 -0.0108676 -0.237495 0.0247306 -0.0111931 -0.213734 0.0261692 -0.0113672 -0.210237 0.0449173 -0.0110881 -0.228635 0.0427651 -0.0108977 -0.236996 0.0437092 -0.011049 -0.229355 0.0407589 -0.0108681 -0.245138 0.0418693 -0.0108977 -0.236481 0.0386522 -0.0109203 -0.249724 0.0360032 -0.0112542 -0.262192 0.0498985 -0.0125886 -0.205745 0.0507604 -0.0125892 -0.206235 0.0491357 -0.0119988 -0.212567 0.0481666 -0.0119676 -0.212447 0.0474163 -0.0117496 -0.215306 0.0204826 -0.0177068 -0.0855931 0.0186845 -0.0177674 -0.0851507 0.0169834 -0.0180265 -0.086973 0.026 -0.0147065 -0.0673193 0.0220001 -0.015268 -0.068493 0.0260001 -0.0174901 -0.0867094 0.0213843 -0.0176012 -0.0850787 0.0211325 -0.0176378 -0.085284 0.022 -0.0144437 -0.0633916 0.00250001 -0.0122253 -0.0371102 0.012851 -0.0118369 -0.0389513 0.0276478 -0.0142289 -0.0653226 0.0219999 -0.0131359 -0.055061 0.0216276 -0.0124191 -0.0495744 0.0196042 -0.0122528 -0.0470109 0.0130296 -0.0122812 -0.0434669 0.00950427 -0.0120788 -0.0395986 -0.00149997 -0.0151548 -0.0542382 0.00250003 -0.0142078 -0.0506883 -0.00173254 -0.0153262 -0.0551748 -0.00304728 -0.0156081 -0.0562026 -0.00348442 -0.016061 -0.0588944 -0.00378256 -0.0156772 -0.056218 -0.00498619 -0.0158857 -0.0568734 0.0183437 -0.0177476 -0.0847563 0.0151934 -0.0174593 -0.0802035 0.0136529 -0.0173138 -0.0780412 0.00618791 -0.017076 -0.071775 0.00290553 -0.0162136 -0.0636029 0.0287055 -0.0185536 -0.101066 0.0297911 -0.0184586 -0.100122 0.0301307 -0.0184402 -0.100031 0.0285759 -0.0185751 -0.101371 0.0219655 -0.0184084 -0.0948318 0.0263616 -0.0182506 -0.0951481 0.0338679 -0.0190065 -0.119935 0.0354374 -0.0189942 -0.118367 0.0319869 -0.0188569 -0.109732 0.0265106 -0.0187139 -0.10291 0.0394488 -0.0188449 -0.133343 0.038075 -0.0189737 -0.127064 0.0408079 -0.0183417 -0.14454 0.0366118 -0.0150718 -0.17496 0.0387986 -0.0172491 -0.156589 0.0389318 -0.0176981 -0.151866 0.0388717 -0.0180705 -0.147298 0.0409895 -0.0180312 -0.149033 0.0528972 -0.0145791 -0.188589 0.0561866 -0.0156026 -0.181687 0.0586833 -0.0186219 -0.149906 0.0567847 -0.0183227 -0.154045 0.05655 -0.0176959 -0.16205 0.0563955 -0.0174705 -0.164435 0.0567744 -0.0160548 -0.178091 0.0551991 -0.019005 -0.133441 0.0573963 -0.0190054 -0.134599 0.0542976 -0.0189849 -0.128369 0.0559194 -0.0189312 -0.126224 0.0520252 -0.0187678 -0.118862 0.054536 -0.0187673 -0.120296 0.0418553 -0.0174762 -0.0957249 0.0360856 -0.0181928 -0.100002 0.0451098 -0.0177516 -0.100227 0.0467013 -0.0173199 -0.0971436 0.0460446 -0.0178003 -0.101263 0.0501067 -0.0180188 -0.10598 0.0483659 -0.0182166 -0.107388 0.0428355 -0.0172275 -0.0941357 0.0308759 -0.013666 -0.0636505 0.0293922 -0.0141554 -0.0658688 0.0297843 -0.0142066 -0.0664159 0.0389412 -0.0155178 -0.0798327 0.0349233 -0.0113289 -0.263627 0.0306639 -0.0118719 -0.271462 0.0350325 -0.0118779 -0.274066 0.0348293 -0.0119952 -0.275521 0.0327798 -0.0129721 -0.283879 0.0337513 -0.0130822 -0.285284 0.0320754 -0.0148958 -0.295642 0.0315282 -0.0189341 -0.317339 0.0321542 -0.0182265 -0.313431 0.020173 -0.0108989 -0.223849 0.018639 -0.0108677 -0.226986 0.0150015 -0.0109202 -0.236082 0.00981151 -0.0111307 -0.243137 0.0021738 -0.0118789 -0.255137 0.00209843 -0.0120259 -0.25704 -0.000214842 -0.0122766 -0.25859 -0.00557754 -0.0135466 -0.265895 -0.00382727 -0.0133118 -0.265293 -0.00907861 -0.0149152 -0.272022 -0.0106909 -0.0154551 -0.273989 -0.0187991 -0.0180804 -0.283227 -0.01947 -0.0182744 -0.283943 -0.00511002 -0.0156728 -0.0554246 -0.0155813 -0.0144237 -0.0416038 -0.0167348 -0.0139927 -0.0382649 -0.0221615 -0.0128767 -0.0277883 -0.0238818 -0.0124327 -0.0234469 -0.0255904 -0.0119316 -0.0178672 -0.0261942 -0.0117463 -0.0152806 -0.028061 -0.0115249 -0.00974034 -0.026854 -0.0115587 -0.0115315 0.00578849 -0.0118943 -0.0355467 0.011192 -0.011687 -0.0359708 -0.00149991 -0.0117607 -0.0297121 -0.00150015 -0.0115274 -0.0251423 0.00937887 -0.0115023 -0.0294813 0.0594708 -0.0174628 -0.138944 0.0432697 0.0147696 -0.0859992 0.0567138 -0.0173637 -0.123048 0.0560825 0.0172862 -0.120486 0.0555037 -0.0172076 -0.1183 0.0532059 0.0168445 -0.110684 0.0583672 0.0174984 -0.131141 0.0567137 0.0173637 -0.123048 0.0597806 0.0174006 -0.142079 0.0602801 0.0169756 -0.152632 0.060204 -0.0171562 -0.149101 0.0602062 -0.0165741 -0.158659 0.0599975 0.0162081 -0.16304 0.0596258 0.015742 -0.167847 0.0596117 -0.0157264 -0.167997 0.0593616 -0.0154622 -0.170473 0.0550253 -0.0123969 -0.195217 0.0534641 0.0116082 -0.20178 0.0534658 -0.011609 -0.201773 0.0493925 0.0101492 -0.217615 0.0448683 0.00943747 -0.234842 0.0506676 -0.0105103 -0.212765 0.0461623 -0.0095611 -0.229853 0.0432341 0.0093654 -0.241312 0.0432342 -0.00936541 -0.241311 0.0410162 0.00942044 -0.250601 0.0378217 0.00988138 -0.266067 0.0345503 0.0135712 -0.297349 0.0371876 -0.010069 -0.269713 0.0361224 0.0105813 -0.27676 0.0351621 -0.0115514 -0.285265 0.0348921 -0.0120567 -0.28868 0.0178769 -0.0102427 -0.00363102 0.018296 -0.0105234 -4.1204e-05 0.0180903 -0.00499999 0.00267103 0.0144495 0.0105746 0.010944 0.0159112 0.005 0.00881613 0.0159112 0.0105513 0.00881613 0.0182604 0.005 -0.000895436 0.018296 0.0105234 -4.1204e-05 -0.0235747 0.00125 -0.29352 -0.00861788 0.00200001 -0.312593 -0.00635857 0.00900001 -0.316368 9.53729e-05 0.00900001 -0.318998 0.00131561 0.00200001 -0.318902 0.00480605 0.00200001 -0.317608 0.00779671 0.00200001 -0.314494 0.00779671 0.00900001 -0.314494 -0.00641467 0.00125 -0.301104 0.0273602 0.00125 -0.320579 0.0303316 0.00125 -0.30686 0.0170613 0.00125 -0.299744 0.0196494 0.00125 -0.295261 0.0196495 0.00125 -0.290084 0.0307888 0.00125 -0.283688 0.0170615 0.00125 -0.285602 0.0125786 0.00125 -0.283013 0.0109113 0.00125 -0.311095 0.00291935 0.00125 -0.299744 -0.0244921 0.00125 -0.2927 0.00499857 0.00125 -0.252719 0.000331132 0.00125 -0.290084 -0.0241903 0.00125 -0.288793 0.000331119 0.00125 -0.295261 0.0125783 0.00125 -0.302332 0.00291935 -0.00125 -0.299744 -0.00783477 -0.00125 -0.270481 -0.0244921 -0.00125 -0.2927 -0.0239152 -0.00125 -0.288519 -0.00741456 -0.00125 -0.302838 0.00291921 -0.00125 -0.285601 0.00740221 -0.00125 -0.283013 0.0170615 -0.00125 -0.285602 0.0196495 -0.00125 -0.290084 0.0307888 -0.00125 -0.283688 0.0196494 -0.00125 -0.295261 0.0303316 -0.00125 -0.30686 0.0273602 -0.00125 -0.320579 0.0125783 -0.00125 -0.302332 0.0170613 -0.00125 -0.299744 0.0301341 -0.00125 -0.313486 0.00904578 0.00325001 -0.312328 0.00779713 0.0199993 -0.314494 -0.00654803 0.0198885 -0.303337 0.0269777 0.00140225 -0.321242 0.0104787 0.00144722 -0.311846 0.00912173 0.00248464 -0.312196 0.00904557 0.0199025 -0.312328 0.0257803 0.0198886 -0.321977 -0.0232838 -0.0198884 -0.293688 -0.00779659 -0.0199993 -0.305502 -0.0235747 -0.00125 -0.29352 -0.00741456 -0.002 -0.302838 0.0257803 -0.0198886 -0.321977 0.0263612 -0.00325 -0.322312 0.00904578 -0.00325 -0.312328 0.00904578 -0.0198885 -0.312328 -0.00779659 0.0199993 -0.305502 -0.0234058 -0.00690435 -0.296503 -0.0203584 -0.009 -0.298261 -0.0207753 -0.00897097 -0.29802 -0.0257471 -0.0195191 -0.295152 -0.0233821 0.0199993 -0.296515 -0.0303127 -0.0119993 -0.292519 -0.0234058 0.00690434 -0.296503 -0.0222925 0.00831895 -0.297145 0.00779713 -0.0199993 -0.314494 0.00933522 0.0107919 0.0207818 0.0097213 0.005 0.0158704 0.0105747 0.0108661 0.0146618 0.0113758 0.005 0.0139374 0.00968637 0.005 0.0215778 0.0162382 -0.00499999 -0.326287 0.0131562 -0.00499999 -0.328865 0.0098048 0.005 -0.330804 0.00272041 0.005 -0.332837 0.00272041 -0.00499999 -0.332837 0.00114108 0.005 -0.33297 -0.012119 0.005 -0.329547 -0.0164889 0.00900036 -0.315569 -0.00961417 0.00900001 -0.320872 -0.0128147 0.00900001 -0.319243 -0.0106934 0.00900001 -0.317122 -0.0176714 0.00900001 -0.306626 -0.0176714 0.00900001 -0.308179 -0.00537133 0.00900001 -0.320872 -0.00459482 0.00900001 -0.322217 -0.00313577 0.00900001 -0.318435 -0.0157125 0.00900001 -0.314224 -0.0186147 0.00900001 -0.306192 -0.0143676 0.00900001 -0.313448 -0.0128146 0.00900001 -0.313448 -0.0126524 0.00900001 -0.309523 -0.0114696 0.00900001 -0.314224 -0.00861788 0.00900001 -0.312593 -0.00883779 0.00900001 -0.308297 -0.0118756 0.00900001 -0.306626 -0.00779676 0.00900001 -0.305503 0.00887202 0.00900001 -0.324382 0.0125463 0.00900001 -0.32226 0.00480605 0.00900001 -0.317608 0.00131561 0.00900001 -0.318902 0.00752729 0.00900001 -0.319362 0.00675052 0.00900001 -0.32226 0.00752711 0.00900001 -0.323605 0.01119 0.00900001 -0.325354 -0.000805299 0.00900001 -0.322819 -0.00158167 0.00900001 -0.325717 0.000539494 0.00900001 -0.327838 0.00209244 0.00900001 -0.327839 0.0042137 0.00900001 -0.324164 -0.0225068 0.005 -0.305261 -0.0228387 0.005 -0.312717 -0.0228387 -0.00499999 -0.312717 -0.022668 0.005 -0.313893 -0.01625 0.005 -0.326275 0.0143009 0.00854686 -0.32517 0.012906 -0.0089991 -0.324389 0.0177091 -0.00899969 -0.327135 0.0159537 -0.00656096 -0.326123 0.0204089 0.00690434 -0.328692 0.0162373 0.00561619 -0.326286 0.0208268 0.005 -0.328933 0.0208268 -0.00499999 -0.328933 0.0204089 -0.00690435 -0.328692 -0.0268207 0.005 -0.30146 -0.0268207 -0.00499999 -0.30146 -0.0238231 -0.00500205 -0.296262 -0.0214048 0.00755307 -0.304583 -0.0219476 0.00656097 -0.30427 -0.0237033 0.0089997 -0.303258 -0.0202927 -0.00854812 -0.305224 -0.0222324 0.005 -0.304106 -0.0264027 0.00690434 -0.301701 0.000108354 -0.009 -0.318998 -0.0139971 -0.009 -0.304504 -0.0155502 -0.009 -0.304504 -0.0128147 -0.009 -0.319243 -0.00750212 -0.009 -0.327455 -0.0107403 -0.009 -0.325672 -0.0114698 -0.009 -0.318467 -0.0106935 -0.009 -0.315569 -0.00899458 -0.009 -0.30969 -0.0114696 -0.009 -0.314224 -0.011876 -0.009 -0.308179 -0.00459508 -0.009 -0.323769 -0.00459482 -0.009 -0.322217 -0.00164959 -0.009 -0.318846 -0.0143677 -0.009 -0.319243 -0.0183752 -0.009 -0.314831 -0.0168948 -0.009 -0.309523 -0.0176714 -0.009 -0.308179 -0.0186147 -0.009 -0.306192 0.0125463 -0.009 -0.32226 0.010425 -0.009 -0.324382 0.00752712 -0.009 -0.323605 0.0125463 -0.009 -0.320707 0.0117697 -0.009 -0.319362 0.00837333 -0.009 -0.327054 0.00421378 -0.009 -0.325717 0.0039909 -0.009 -0.328575 -0.00158167 -0.009 -0.325717 -0.00382861 -0.009 -0.328609 8.36305e-05 -0.009 -0.328998 -0.000805315 -0.009 -0.322819 0.000539593 -0.009 -0.322043 0.0207069 -0.00899982 -0.321938 0.0192956 -0.00831894 -0.32805 0.0203583 0.00900001 -0.321737 0.0207752 0.00897098 -0.321977 0.0177105 0.00899955 -0.327136 0.0192956 0.00831895 -0.32805 0.0234059 0.00690434 -0.323494 -0.0237047 -0.00899954 -0.303257 -0.0222925 -0.00831894 -0.297145 -0.0252894 -0.00831894 -0.302343 -0.0264027 -0.00690435 -0.301701 -0.0207074 0.00899983 -0.29806 -0.0252894 0.00831895 -0.302343 -0.0238237 0.005 -0.296262 -0.01625 -0.00499999 -0.326275 -0.0229903 -0.00516965 -0.309303 -0.0225068 -0.00499999 -0.305261 -0.0222318 -0.0055431 -0.304106 -0.0217186 -0.00711972 -0.304402 -0.0209236 -0.00808575 -0.304861 -0.0198672 -0.00890274 -0.309382 -0.0162445 -0.009 -0.319854 -0.0192386 -0.00693254 -0.32167 -0.016994 -0.00890274 -0.320308 -0.0184241 -0.00808212 -0.321176 -0.0207821 -0.00499999 -0.319853 -0.0196541 -0.00517077 -0.321949 -0.0189908 -0.009 -0.30941 -0.0192232 -0.00890274 -0.315054 -0.0215391 -0.00808212 -0.309331 -0.0224914 -0.00693254 -0.309301 -0.0208411 -0.00808212 -0.315479 -0.0217623 -0.00693254 -0.315721 -0.0222433 -0.00517167 -0.315855 0.0061464 -0.009 -0.316573 0.00244073 -0.00900039 -0.3187 0.00258263 -0.002 -0.31862 -0.00563213 -0.009 -0.317018 -0.00812409 -0.002 -0.313872 -0.00812409 -0.009 -0.313872 -0.00899458 -0.002 -0.30969 -0.00779676 -0.009 -0.305503 -0.0243827 0.0100023 0.0162972 -0.0217542 0.0120849 -0.0344037 -0.0184554 0.0127032 -0.0402578 -0.0169886 -0.0129493 -0.0426415 0.0211952 0.0169536 -0.0966569 0.0211951 -0.0169536 -0.096657 -0.017049 0.0129395 -0.0425455 -0.00638067 0.0144016 -0.0579131 -0.0060306 0.0144426 -0.0583844 0.00906745 -0.0159777 -0.0785272 0.0156626 -0.016534 -0.0879371 0.0206248 -0.0169128 -0.0957079 0.0205614 0.0169082 -0.0956028 0.0290229 0.0174203 -0.111679 0.0291197 -0.0174248 -0.111898 0.0324477 -0.0175065 -0.120421 0.0341908 -0.0174734 -0.126065 0.0374382 -0.0165762 -0.14724 0.0370367 0.0169656 -0.14129 0.0373849 -0.0157587 -0.156373 0.0373775 0.0157423 -0.156532 0.0352369 -0.0135852 -0.174513 0.0352317 0.0135817 -0.17454 0.0333182 -0.0124254 -0.183428 0.0309092 -0.0113519 -0.192267 0.0302729 -0.0111222 -0.194346 0.0248161 -0.00986922 -0.20961 0.0224887 -0.00960819 -0.215179 0.0173004 -0.00936776 -0.22631 0.0224887 0.00960818 -0.215179 0.0117464 -0.0094593 -0.236799 0.0173074 0.00936784 -0.226296 0.00849872 -0.00963145 -0.242411 0.00850513 0.00963104 -0.2424 -0.0017022 0.0108197 -0.258123 -0.0124976 0.0138447 -0.272258 -0.0233342 0.017265 -0.284375 -0.0240305 0.0169693 -0.285089 -0.0283707 0.0103852 -0.0170181 -0.0256427 -0.0111886 -0.0258916 -0.0270027 0.0100023 0.0113022 -0.0289378 -0.0100023 0.0050661 -0.0289464 0.0100023 0.00502446 -0.0297749 -0.0100023 -0.000945216 -0.0297749 0.0100023 -0.000945216 -0.0297558 0.0100023 -0.00788739 -0.0293689 -0.0100753 -0.0116026 -0.0293689 0.0100753 -0.0116026 -0.0266557 0.0154218 -0.287717 0.0298981 0.0147293 -0.327236 0.0233833 0.0199993 -0.323479 0.0222925 0.00831895 -0.322852 0.0282839 0.0176562 -0.326305 0.00779671 -0.009 -0.314494 0.0233833 -0.0199993 -0.323479 0.0222925 -0.00831894 -0.322852 0.0238231 0.00500016 -0.323736 0.0238237 -0.00499999 -0.323735 0.0303139 2.42042e-09 -0.327475 0.0234059 -0.00690435 -0.323494 0.0348232 0.0153211 -0.306586 0.0347263 -0.0163034 -0.312004 0.033939 0.017259 -0.317239 0.0334832 -0.0164899 -0.319217 0.030314 0.0119351 -0.327475 0.0324969 0.014972 -0.322542 0.0105705 -0.0110025 0.0146622 0.0097213 -0.00499999 0.0158704 0.00900313 -0.00499999 0.0186636 0.00964773 -0.0105023 0.0214236 0.0096889 -0.00499999 0.0215835 0.0100728 -0.0105023 0.022138 0.0119994 -0.013 0.0127382 0.0117022 -0.0115109 0.0130585 0.00683526 -0.013 0.01611 0.00683526 -0.0115023 0.01611 0.0174095 -0.013 -0.00177664 0.0139673 -0.0115023 0.0105434 0.010679 -0.0115023 -0.0138642 0.014826 -0.0114581 -0.00929774 -0.0113634 0.005 0.0372731 0.0300901 -0.00325 -0.32172 0.0276519 -0.00325 -0.322706 0.0279667 -0.0191502 -0.322711 0.0293235 -0.0185636 -0.322332 0.0323273 -0.00325 -0.30673 0.0324075 -0.00325 -0.308147 0.0324077 -0.0172342 -0.308146 0.0322583 -0.0180387 -0.312429 0.0321281 -0.00325 -0.313656 0.0307436 -0.00325 -0.320539 0.032397 -0.0136588 -0.288527 0.0322131 -0.0166326 -0.304876 0.032082 -0.00325 -0.295303 0.0320839 -0.0160008 -0.301512 0.0320991 -0.0147088 -0.294625 0.0219999 -0.00325 -0.222326 0.0302136 -0.0117202 -0.268909 0.026359 -0.0109941 -0.247048 0.0225114 -0.0108987 -0.225227 -0.00784168 -0.0145119 -0.270492 -0.0124778 -0.0160595 -0.276127 -0.014952 -0.0168809 -0.278982 -0.0160009 -0.0172202 -0.280164 0.00499857 -0.00125 -0.252719 -0.00505214 -0.013655 -0.266912 0.0030534 -0.0118786 -0.255639 0.00795265 -0.0113296 -0.248094 0.00994874 -0.00125 -0.244846 0.0214296 -0.00167195 -0.223533 0.0218473 -0.00236398 -0.222651 0.0219868 -0.00298337 -0.222354 0.0203566 -0.0108816 -0.225758 0.0142351 -0.0109474 -0.237468 -0.0241903 -0.00125 -0.288793 -0.00654803 -0.0198885 -0.303337 -0.00654803 -0.002 -0.303337 0.00779671 -0.002 -0.314494 0.0409842 -0.0176513 -0.153578 0.0403762 -0.0166437 -0.163339 0.0403448 -0.0186222 -0.139327 0.0400223 -0.00325 -0.136846 0.0409922 -0.0176873 -0.153178 0.0398917 -0.0187597 -0.13597 0.0394489 -0.00325 -0.133342 0.0358414 -0.0190013 -0.119535 0.0358414 -0.00325 -0.119535 0.0304034 -0.018765 -0.106328 0.0286982 -0.00325 -0.102922 0.056237 -0.00151795 -0.166445 0.0532453 -0.00151795 -0.186888 0.0552215 -0.0162576 -0.1754 0.0460446 -0.00151795 -0.101263 0.0504238 -0.0185463 -0.113461 0.0497896 -0.00151795 -0.111506 0.0533108 -0.0189106 -0.123872 0.0542979 -0.00151795 -0.128369 0.0566064 -0.00151795 -0.146903 0.0566062 -0.0187057 -0.146904 0.0563973 -0.0188271 -0.143652 0.0562368 -0.0172684 -0.166447 0.056688 -0.0186235 -0.148724 0.0259998 -0.0181782 -0.0940014 0.026 -0.0161045 -0.0761836 0.026 -0.00325 -0.0673193 0.0260008 -0.0173328 -0.0853202 0.0297911 -0.00125 -0.100122 0.0407093 -0.00125 -0.175136 0.0553628 -0.00125 -0.164845 0.0557849 -0.00125 -0.15365 0.0429146 -0.00125 -0.15585 0.0336502 -0.00125 -0.108555 0.0259278 -0.0108973 -0.227325 0.0507043 -0.00325 -0.202539 0.0396602 -0.00325 -0.245423 0.0393732 -0.0108825 -0.24663 0.0430645 -0.00325 -0.23183 0.0519147 -0.0139662 -0.193412 0.025607 -0.0111933 -0.214239 0.024196 -0.0110651 -0.217504 0.0370001 -0.014685 -0.178498 0.0370001 -0.00325 -0.178498 0.0357271 -0.0139638 -0.184102 0.0346303 -0.00325 -0.188348 0.0282868 -0.00325 -0.207609 0.0293632 -0.0117574 -0.204773 0.0290677 -0.0116988 -0.205563 0.0497727 -0.00125 -0.197923 0.0381666 -0.00125 -0.182493 0.0330358 -0.00125 -0.200402 0.0411317 -0.00125 -0.231315 0.0262711 -0.00125 -0.217754 -0.0273202 -0.0115023 -0.00675601 -0.0273832 -0.00325 -0.00372379 -0.0273832 -0.0115023 -0.00372379 -0.0272532 -0.00325 -0.000745277 -0.0272532 -0.0115023 -0.000745277 -0.0264318 -0.00325 0.00482148 -0.02462 -0.00325 0.0105201 -0.023374 -0.0125706 -0.024826 -0.0260534 -0.00325 -0.0159315 -0.0249326 -0.00325 -0.0202419 -0.023374 -0.00325 -0.024826 -0.0273202 -0.00325 -0.00675601 -0.0130724 -0.0145944 -0.0441026 -0.00673503 -0.00325 -0.0532038 -0.0152454 -0.00325 -0.0407156 -0.0183146 -0.013701 -0.0355139 -0.0167343 -0.00325 -0.0382657 -0.00149997 -0.00325 -0.0217198 -0.00149997 -0.0115023 -0.0217198 -0.00150011 -0.0137176 -0.045314 -0.00149997 -0.00325 -0.0542382 -0.00150009 -0.0123999 -0.0360815 -0.00149992 -0.012175 -0.0341487 -0.00169466 -0.0115023 0.0237854 -0.00144178 -0.0115023 0.0223949 -0.00144608 -0.00325 0.0223299 -0.00185347 -0.0115023 0.0210425 -0.00182102 -0.00325 0.0210985 -0.0075834 -0.00325 0.0299574 -0.0085596 -0.0115023 0.0306091 -0.0075834 -0.0115023 0.0299574 -0.0160972 -0.00125 -0.0149961 -0.0126625 -0.00125 -0.0179906 -0.0207769 -0.00125 -0.00723338 -0.0135036 -0.00125 0.0173679 -0.016792 -0.00125 0.0142137 -0.01936 -0.00125 0.0104495 -0.0218214 -0.00125 -0.0027981 0.0327586 -0.00325 -0.283341 0.0327798 -0.00325 -0.283879 0.0327586 -0.0129055 -0.283341 -0.00171553 -0.00287969 -0.0208177 -0.00235993 -0.0115023 -0.0200766 -0.00169646 -0.0115023 -0.0208555 0.0524495 -0.00325 -0.195276 0.0524702 -0.0138039 -0.195191 0.0521747 -0.00325 -0.188689 0.0508508 -0.00325 -0.188105 0.051057 -0.0144889 -0.188311 0.0205162 -0.00125 -0.22543 0.021006 -0.00136123 -0.224418 0.031457 -0.00136861 -0.28357 0.0215518 -0.00181559 -0.223276 0.0321749 -0.00182913 -0.283444 0.0323017 -0.00196932 -0.283422 0.0318422 -0.00155291 -0.283789 0.0321966 -0.00183579 -0.283823 0.0300824 -0.00125 -0.295264 0.0326734 -0.00255157 -0.283583 0.0314963 -0.00183579 -0.295297 0.0324506 -0.00214818 -0.283848 0.0321873 -0.00251381 -0.306739 0.0319414 -0.00251381 -0.295307 0.0308185 -0.00139042 -0.295282 0.032399 -0.00325 -0.310315 0.0317429 -0.00183579 -0.306768 0.0310663 -0.00139042 -0.306812 0.0308649 -0.00139042 -0.313575 0.0305974 -0.00248463 -0.320497 0.0319802 -0.00251381 -0.313711 0.0315379 -0.00183579 -0.313657 0.029399 -0.00140039 -0.320931 0.0288211 -0.00125 -0.319988 0.0269777 -0.00140224 -0.321242 0.0301805 -0.00183579 -0.320377 0.0276104 -0.00190755 -0.322284 0.0293888 -0.00213092 -0.322013 0.0289847 -0.00325 -0.322494 0.00912173 -0.00248463 -0.312196 0.00926539 -0.00200043 -0.31195 0.0264371 -0.00248463 -0.32218 0.0266536 -0.00183579 -0.321805 0.052077 -0.00207443 -0.19519 0.0425323 -0.00134788 -0.228393 0.0505005 -0.00125 -0.194826 0.0437746 -0.00263196 -0.228719 0.0392886 -0.00207443 -0.245334 0.0430715 -0.00163197 -0.228535 0.0395651 -0.00263196 -0.2454 0.0434995 -0.00207443 -0.228647 0.0522085 -0.00228694 -0.19522 0.0357631 -0.00262835 -0.262826 0.0356284 -0.00207443 -0.262119 0.0388582 -0.00163197 -0.245231 0.038316 -0.00134788 -0.245101 0.037715 -0.00125 -0.244958 0.0511671 -0.00134804 -0.194715 0.0510324 -0.00139688 -0.194294 0.0515005 -0.00183579 -0.193826 0.0524134 -0.0029435 -0.194134 0.0519147 -0.00325 -0.193412 0.0524013 -0.00280787 -0.195265 0.0520565 -0.00200723 -0.194641 0.0523537 -0.00263196 -0.195254 0.0516458 -0.00163197 -0.19509 0.0320701 -0.00325 -0.26216 0.0326467 -0.00183579 -0.262058 0.0334063 -0.00135623 -0.261924 0.0360032 -0.00325 -0.262192 0.0344831 -0.00195718 -0.263437 0.0351939 -0.00163197 -0.262035 0.0346463 -0.00134788 -0.26193 0.0354457 -0.00267936 -0.263234 0.0323554 -0.00273211 -0.262906 0.033038 -0.00324557 -0.263547 0.0332094 -0.00228207 -0.263353 0.0335081 -0.0015143 -0.262701 0.037786 -0.0013642 -0.18117 0.0374444 -0.00169058 -0.179999 0.0371238 -0.00236492 -0.178913 0.0518166 -0.00251903 -0.193511 0.0370133 -0.00295332 -0.178542 0.0321916 -0.00255777 -0.262138 0.0322616 -0.00238991 -0.262126 0.0340394 -0.00125 -0.261812 0.033358 -0.00137362 -0.261933 0.0258232 -0.00129707 -0.2177 0.02997 -0.00125 -0.208801 0.0255542 -0.00137308 -0.217668 0.0316263 -0.00325 -0.198307 0.0358632 -0.00138506 -0.188682 0.0328282 -0.00138506 -0.198742 0.0292694 -0.00138506 -0.208608 0.0352025 -0.00182858 -0.188503 0.0317499 -0.00250925 -0.198387 0.0347674 -0.00250925 -0.188385 0.0243603 -0.00246995 -0.217524 0.024196 -0.00325 -0.217504 0.024929 -0.00172455 -0.217592 0.0286317 -0.00182858 -0.20836 0.0282114 -0.00250925 -0.208196 0.032178 -0.00182858 -0.198528 0.0541707 -0.00125 -0.175691 0.0558703 -0.00131263 -0.164715 0.0546622 -0.00131263 -0.175762 0.0519307 -0.00131263 -0.120443 0.0543612 -0.00131263 -0.131457 0.0555259 -0.00125 -0.145525 0.0488467 -0.00125 -0.11184 0.0514505 -0.00125 -0.12057 0.04479 -0.00126837 -0.100095 0.0486659 -0.00131263 -0.109754 0.0524175 -0.00151795 -0.120314 0.0563048 -0.00151795 -0.142519 0.0558033 -0.00131263 -0.142562 0.0562814 -0.00131263 -0.153649 0.0567847 -0.00151795 -0.153648 0.0551607 -0.00151795 -0.175833 0.0517237 -0.00140224 -0.187233 0.0514375 -0.00162808 -0.187519 0.0512649 -0.00183579 -0.187691 0.0527386 -0.00132274 -0.187182 0.0523618 -0.00198491 -0.188279 0.0528972 -0.00325 -0.188589 0.053045 -0.00183825 -0.187874 0.0514556 -0.00277034 -0.18852 0.0279999 -0.00125 -0.0940014 0.0259998 -0.00325 -0.0940014 0.052265 -0.00125 -0.186691 0.0509584 -0.00248463 -0.187998 0.052117 -0.00126098 -0.186839 -0.0032223 -0.00124983 0.0227641 -0.00240092 -0.00151661 0.0233496 -0.00317923 -0.00150189 0.0209427 -0.0025048 -0.00225 0.0244999 -0.00305907 -0.00224315 0.0201897 -0.00267778 -0.00325 0.0201379 -0.0020546 -0.00225 0.0212298 -0.0016845 -0.00221065 0.0228725 -0.00162149 -0.00325 0.023605 -0.00231539 -0.00325 0.0246894 -0.00511176 -0.00151795 0.0203683 -0.00535512 -0.00125 0.0213381 -0.00963623 -0.00125 0.0197773 -0.0160287 -0.00151795 0.0135676 -0.0209328 -0.00151795 0.00167731 -0.0210974 -0.00125 0.00623718 -0.0219298 -0.00125 0.0017573 -0.0208296 -0.00151795 -0.00267081 -0.018841 -0.00125 -0.0113585 -0.0153655 -0.00151795 -0.0143143 -0.00829016 -0.00151795 -0.0192943 -0.00868491 -0.00125 -0.020213 -0.00350001 -0.00125 -0.0217197 -0.00312419 -0.00151698 -0.0207978 -0.0120868 -0.00151795 -0.0171729 -0.0179847 -0.00151795 -0.0108421 -0.0198325 -0.00151795 -0.00690464 -0.0191412 -0.00225 -0.00666381 -0.0201034 -0.00225 -0.00257784 -0.0201382 -0.00151795 0.00595352 -0.01848 -0.00151795 0.00997467 -0.0178358 -0.00225 0.00962695 -0.0128898 -0.00151795 0.0165784 -0.0124405 -0.00225 0.0160006 -0.00919807 -0.00151795 0.0188782 -0.00887759 -0.00225 0.0182203 -0.00800086 -0.00225 -0.018622 -0.00789532 -0.00325 -0.0183755 -0.0115113 -0.00325 -0.0163552 -0.0116655 -0.00225 -0.0165742 -0.0148296 -0.00225 -0.0138156 -0.0171284 -0.00325 -0.0103257 -0.0173579 -0.00225 -0.0104641 -0.0202031 -0.00225 0.00161872 -0.0194365 -0.00225 0.00574624 -0.0199362 -0.00325 0.00159765 -0.01547 -0.00225 0.0130946 -0.0152655 -0.00325 0.0129215 -0.00493365 -0.00225 0.0196583 -0.00876025 -0.00325 0.0179795 -0.00486849 -0.00325 0.0193984 -0.00385815 -0.00325 0.0196245 -0.0116884 -0.00183579 0.029212 -0.0089976 -0.00125 0.0285432 -0.0105265 -0.00125 0.0284061 -0.00859227 -0.00151668 0.0295454 -0.0102044 -0.00150195 0.0297938 -0.00823082 -0.0022406 0.0302102 -0.010438 -0.00225067 0.0305194 -0.00868166 -0.00325 0.0306563 -0.00997295 -0.00325 0.0308243 -0.0112135 -0.00325 0.0304294 -0.0121698 -0.00325 0.0295459 -0.00350001 -0.00125 -0.0542381 -0.0020859 -0.00183579 -0.0217197 -0.00224394 -0.00169353 -0.0542384 -0.00188174 -0.00207458 -0.0217199 -0.0015841 -0.00267669 -0.0217196 -0.0201429 -0.00125 0.0145414 -0.011348 -0.00151795 0.0289759 -0.0119496 -0.00225 0.0293932 -0.0049958 -0.00250938 -0.0553401 -0.00408197 -0.00138521 -0.054667 -0.0027347 -0.00140224 -0.0542382 -0.00165229 -0.00248463 -0.0542381 -0.00208589 -0.00183579 -0.0542381 -0.00221849 -0.00218266 -0.055497 -0.00161056 -0.00325 -0.0548944 -0.00392092 -0.00239711 -0.056022 -0.00287548 -0.00325 -0.0561384 -0.00338553 -0.00167682 -0.0554934 -0.00463283 -0.00182877 -0.0550729 -0.0020918 -0.00325 -0.0556581 -0.0259997 -0.00138479 -0.00112511 -0.0253228 -0.00125 -0.00665351 -0.026683 -0.00182819 -0.00107672 -0.0272372 -0.00268011 -0.00675196 -0.0216881 -0.00255775 0.0156059 -0.0214758 -0.00207448 0.0154595 -0.0240739 -0.00182819 0.0102888 -0.026733 -0.00182107 -0.00672578 -0.0244801 -0.00125 0.00438534 -0.0231482 -0.00125 0.00877362 -0.0253388 -0.00325 0.0086597 -0.0244892 -0.00250901 0.0104648 -0.0217682 -0.00292593 0.0156614 -0.0217898 -0.00325 0.0156762 -0.0209013 -0.00147444 0.0150637 -0.0213014 -0.00182819 0.0153392 -0.0234432 -0.00138479 0.0100212 -0.0251845 -0.00138479 0.00454271 -0.0258526 -0.00182819 0.00469192 -0.0262929 -0.00250901 0.00479046 -0.0271328 -0.00250901 -0.00104503 -0.019594 -0.00250938 -0.0328308 -0.0185863 -0.00138521 -0.0323087 -0.0054251 -0.00125 -0.0516033 -0.00431176 -0.00152269 -0.0548361 -0.0151248 -0.00250938 -0.0406402 -0.0135476 -0.00125 -0.0396585 -0.0231881 -0.00237967 -0.0247547 -0.0191938 -0.00182877 -0.0326236 -0.0141615 -0.00138521 -0.0400404 -0.0147423 -0.00182877 -0.040402 -0.0197205 -0.00325 -0.032896 -0.00489836 -0.00225818 -0.0552683 -0.0217551 -0.00126818 -0.0242132 -0.0240932 -0.00125 -0.0155331 -0.0179444 -0.00125 -0.0319764 -0.0221797 -0.00138515 -0.0243734 -0.0227648 -0.001735 -0.0245647 -0.0259072 -0.00250932 -0.0159343 -0.0262011 -0.00145383 -0.00669903 -0.0247993 -0.00138515 -0.0156876 -0.0254673 -0.0018287 -0.0158363 0.0263612 0.00325001 -0.322312 0.0275216 0.0193346 -0.322694 0.0266066 0.0196852 -0.322447 0.030223 0.0182707 -0.321561 0.0289807 0.0187084 -0.322496 -0.0248545 0.0185196 -0.28979 -0.024867 0.00125 -0.289821 -0.0250511 0.00125 -0.291309 -0.0250506 0.0189019 -0.291313 -0.0250762 0.0187579 -0.290884 0.00994874 0.00125 -0.244846 0.0150018 0.0109201 -0.236081 0.0205165 0.00125 -0.22543 0.0208396 0.0108933 -0.224764 0.021737 0.00211047 -0.222885 -0.0034455 0.0132098 -0.264782 -0.00783477 0.00125 -0.270481 0.0025199 0.011959 -0.256425 -0.0184899 0.0179892 -0.282895 -0.019499 0.0182827 -0.283974 -0.0222487 0.0190115 -0.286841 -0.0239152 0.00125 -0.288519 0.0269513 0.0110618 -0.250411 0.0229716 0.0108773 -0.227835 0.0219999 0.00325001 -0.222326 0.032082 0.00325001 -0.295303 0.0322528 0.0180498 -0.312488 0.0324075 0.00325001 -0.308147 0.0324094 0.0172252 -0.308096 0.0286982 0.00325001 -0.102922 0.0318272 0.00325001 -0.109376 0.0381642 0.00325001 -0.127417 0.0382549 0.0189633 -0.127782 0.0357185 0.0190038 -0.119116 0.0394489 0.00325001 -0.133342 0.0403459 0.0186219 -0.139334 0.0399787 0.0187384 -0.136546 0.04099 0.00325001 -0.14903 0.0409901 0.0180311 -0.149033 0.0408446 0.0183028 -0.145159 0.0387415 0.00325001 -0.17478 0.0500004 0.0145403 -0.187255 0.024196 0.00325001 -0.217504 0.0325207 0.0126065 -0.195534 0.0331117 0.0128145 -0.19363 0.0310511 0.00325001 -0.200029 0.0362187 0.0142278 -0.18204 0.0293627 0.011758 -0.204774 0.0290776 0.0117013 -0.205536 0.0279447 0.00325001 -0.208489 0.0256064 0.0111933 -0.214239 0.0395808 0.0145599 -0.181078 0.0360032 0.0112542 -0.262192 0.0386506 0.01092 -0.249731 0.0474041 0.0117463 -0.215352 0.04405 0.0110904 -0.228055 0.0396602 0.00325001 -0.245423 0.0418671 0.0108975 -0.23649 0.0499087 0.0125931 -0.205703 0.0505005 0.00125 -0.194826 0.0262711 0.00125 -0.217754 0.0419344 0.00125 -0.228237 0.037715 0.00125 -0.244958 -0.0253388 0.0115023 0.0086597 -0.0253388 0.00325001 0.0086597 -0.0272532 0.0115023 -0.000745277 -0.0272532 0.00325001 -0.000745277 -0.0121698 0.00325001 0.0295459 -0.0121698 0.0115023 0.0295459 -0.0085596 0.0115023 0.0306091 -0.00997295 0.00325001 0.0308243 -0.00997295 0.0115023 0.0308243 -0.0075834 0.00325001 0.0299574 -0.0075834 0.0115023 0.0299574 -0.00267778 0.00325001 0.0201379 -0.00144608 0.00325001 0.0223299 -0.00162149 0.00325001 0.023605 -0.00318179 0.00325001 -0.0197453 -0.00385815 0.0115023 0.0196245 -0.00318179 0.0115023 -0.0197453 0.00823107 0.0135 -0.0182279 0.00823107 0.0115023 -0.0182279 0.0118094 0.0135 -0.0161412 0.00336557 0.0115023 0.0197149 0.00336557 0.0135 0.0197149 -0.00789532 0.00325001 -0.0183755 -0.00789532 0.0135 -0.0183755 -0.0115113 0.00325001 -0.0163552 -0.018888 0.0135 -0.00657589 -0.0199362 0.0135 0.00159765 -0.0175998 0.0135 0.00949942 -0.0175998 0.00325001 0.00949942 -0.0152655 0.00325001 0.0129215 -0.0122763 0.00325001 0.0157892 -0.00876025 0.00325001 0.0179795 -0.0122763 0.0135 0.0157892 -0.00486849 0.0135 0.0193984 -0.00149997 0.00325001 -0.0542382 -0.00150001 0.0123841 -0.0359547 -0.023374 0.00325001 -0.024826 -0.0220044 0.0129146 -0.0281458 -0.0167343 0.00325001 -0.0382657 -0.00673503 0.00325001 -0.0532038 -0.0131151 0.014588 -0.0440388 -0.00511002 0.00325001 -0.0554246 -0.0272109 0.0115023 -0.00838658 -0.0273202 0.00325001 -0.00675601 -0.0261935 0.0117464 -0.0152839 -0.0249326 0.00325001 -0.0202419 -0.0256131 0.0119246 -0.0177772 -0.0238823 0.0124326 -0.0234454 -0.023374 0.0125706 -0.024826 -0.0218214 0.00125 -0.0027981 -0.0134886 0.00125 -0.0397532 -0.00868491 0.00125 -0.020213 -0.018841 0.00125 -0.0113585 -0.0210974 0.00125 0.00623718 -0.0245761 0.00125 0.00394128 -0.0223373 0.00125 0.0107279 -0.0135036 0.00125 0.0173679 -0.0105265 0.00125 0.0284061 -0.00963623 0.00125 0.0197773 0.0327798 0.00325001 -0.283879 0.032799 0.0129254 -0.283571 0.0320701 0.00325001 -0.26216 0.0330954 0.0113686 -0.263576 0.0340227 0.0113566 -0.263812 0.033855 0.00325001 -0.263804 0.0349569 0.0113269 -0.26359 0.0356007 0.0112933 -0.263063 -0.00378315 0.00325001 -0.0562179 -0.00365609 0.0156714 -0.0562558 -0.00161056 0.00325001 -0.0548944 -0.00149997 0.0151548 -0.0542382 -0.00161082 0.0152703 -0.0548946 -0.00183529 0.015363 -0.055347 -0.00209702 0.0154373 -0.055664 -0.00271345 0.0155623 -0.0560998 0.0524495 0.013794 -0.195276 0.0524348 0.0138988 -0.194318 0.0219481 0.00272349 -0.222437 0.0211814 0.00146082 -0.224052 0.0215474 0.00180958 -0.223285 0.0319067 0.00159495 -0.283796 0.0321749 0.00182912 -0.283444 0.0323017 0.00196932 -0.283422 0.0326683 0.00255316 -0.28355 0.0327586 0.00325001 -0.283341 0.0300824 0.00125 -0.295264 0.0310663 0.00139043 -0.306812 0.0319414 0.00251381 -0.295307 0.031457 0.0013686 -0.28357 0.0308185 0.00139043 -0.295282 0.0324506 0.00214818 -0.283848 0.0314963 0.00183565 -0.295295 0.0321281 0.00325001 -0.313656 0.0307436 0.00325001 -0.320539 0.0319802 0.00251381 -0.313708 0.0305974 0.00248464 -0.320497 0.0315383 0.00183578 -0.313655 0.0301805 0.00183578 -0.320377 0.0308653 0.00139043 -0.313572 0.0301345 0.00125 -0.313483 0.0323273 0.00325001 -0.30673 0.0317429 0.00183578 -0.306768 0.032399 0.00325001 -0.310315 0.0321873 0.00251381 -0.306739 0.0288211 0.00125 -0.319988 0.0294189 0.00139867 -0.320802 0.0266536 0.00183578 -0.321805 0.0295021 0.00213075 -0.321934 0.0300901 0.00325001 -0.32172 0.0289847 0.00325001 -0.322494 0.0277507 0.0019077 -0.322294 0.0264371 0.00248464 -0.32218 0.0276519 0.00325001 -0.322706 0.0340394 0.00125 -0.261812 0.033358 0.00137362 -0.261933 0.0248055 0.00183416 -0.217578 0.0322616 0.0023899 -0.262126 0.0245488 0.00213427 -0.217546 0.02421 0.00301744 -0.217506 0.0321916 0.00255777 -0.262138 0.0243248 0.00255619 -0.21752 0.0311334 0.00250921 -0.200228 0.0315603 0.00182849 -0.200373 0.0322082 0.00138501 -0.200594 0.0252452 0.00151141 -0.217631 0.0330362 0.00125 -0.200402 0.0357216 0.00125 -0.191868 0.037463 0.00138501 -0.182329 0.0381666 0.00125 -0.182493 0.0362187 0.00325001 -0.18204 0.0372945 0.00146158 -0.18229 0.0387079 0.00140225 -0.181951 0.0515005 0.00183578 -0.193826 0.0391666 0.00183578 -0.181493 0.0394732 0.00248464 -0.181186 0.0519147 0.00325001 -0.193412 0.0430645 0.00325001 -0.23183 0.0360032 0.00325001 -0.262192 0.038316 0.00134789 -0.245101 0.0430715 0.00163196 -0.228535 0.0388582 0.00163196 -0.245231 0.0392886 0.00207442 -0.245334 0.0425323 0.00134789 -0.228393 0.0434995 0.00207442 -0.228647 0.0522085 0.00228694 -0.19522 0.0437746 0.00263196 -0.228719 0.0523537 0.00263196 -0.195254 0.0524013 0.00280786 -0.195265 0.0507043 0.00325001 -0.202539 0.0395651 0.00263196 -0.2454 0.0516458 0.00163196 -0.19509 0.0523277 0.00257676 -0.19437 0.0524229 0.00325001 -0.194275 0.0524495 0.00325001 -0.195276 0.0521764 0.00207137 -0.194791 0.0518068 0.00248182 -0.193521 0.0510371 0.00139957 -0.19429 0.0511027 0.00134789 -0.194965 0.0507075 0.00151795 -0.186548 0.0396496 0.00151826 -0.17549 -0.0217898 0.00325001 0.0156762 -0.0120682 0.00255777 0.0294755 -0.0213077 0.00183577 0.0153437 -0.0119496 0.00225 0.0293932 -0.011348 0.00151795 0.0289759 -0.0207131 0.00137361 0.0149342 -0.0203621 0.00126775 0.0146924 -0.0251851 0.00138508 0.0045428 -0.0273832 0.00325001 -0.00372379 -0.0234441 0.00138508 0.0100217 -0.0211001 0.00162232 0.0152006 -0.02462 0.00325001 0.0105201 -0.0267265 0.00182374 -0.00672715 -0.0270971 0.00233159 -0.00674463 -0.0271329 0.00250927 -0.00104511 -0.026293 0.00250927 0.00479037 -0.0264318 0.00325001 0.00482148 -0.0252798 0.00125 -0.00117594 -0.0260004 0.00138508 -0.00112511 -0.0266832 0.00182858 -0.00107689 -0.0258531 0.00182858 0.00469208 -0.024074 0.00182858 0.0102887 -0.0244893 0.00250927 0.0104648 -0.0216255 0.00237851 0.0155627 -0.0103035 0.00149849 0.0297391 -0.0116884 0.00183578 0.029212 -0.0112135 0.00325001 0.0304294 -0.0104839 0.00219851 0.0304659 -0.00826235 0.00225261 0.0302526 -0.00868166 0.00325001 0.0306563 -0.0240931 0.00125 -0.015533 -0.0260534 0.00325001 -0.0159315 -0.0254673 0.00182869 -0.0158363 -0.0247992 0.00138514 -0.0156875 -0.0217518 0.0012677 -0.0242119 -0.0253228 0.00125 -0.00665351 -0.0262132 0.00145978 -0.00669962 -0.0259071 0.00250933 -0.0159342 -0.0089976 0.00125 0.0285432 -0.00865711 0.00151773 0.0296137 -0.0185863 0.00138521 -0.0323087 -0.0177045 0.00125 -0.0324364 -0.0221795 0.00138515 -0.0243739 -0.0191938 0.00182876 -0.0326236 -0.0227433 0.00173419 -0.0246192 -0.0231866 0.00237838 -0.0247559 -0.0197205 0.00325001 -0.032896 -0.00489836 0.00225818 -0.0552683 -0.00431176 0.00152269 -0.0548361 -0.0049958 0.00250937 -0.0553401 -0.0152454 0.00325001 -0.0407156 -0.019594 0.00250937 -0.0328308 -0.0151248 0.00250937 -0.0406402 -0.0147423 0.00182876 -0.040402 -0.0141614 0.00138521 -0.0400403 -0.00266505 0.00124986 0.0221666 -0.00273055 0.00151675 0.023684 -0.00247111 0.00150906 0.0220892 -0.00338361 0.00151667 0.020836 -0.00301929 0.00224921 0.0201915 -0.00231539 0.00325001 0.0246894 -0.00206767 0.00224103 0.0240477 -0.00176722 0.00221087 0.0218314 -0.00182102 0.00325001 0.0210985 -0.00385815 0.00325001 0.0196245 -0.00224394 0.00169353 -0.0542384 -0.0020859 0.00183578 -0.0217197 -0.00208589 0.00183578 -0.0542381 -0.0015841 0.0026767 -0.0217196 -0.00165229 0.00248464 -0.0542381 -0.0027347 0.00140225 -0.0217198 -0.00188174 0.00207457 -0.0217199 -0.00165229 0.00248464 -0.0217197 -0.00149997 0.00325001 -0.0217198 -0.00294531 0.00155421 -0.0207577 -0.00232604 0.00325001 -0.0201007 0.0293298 0.0185612 -0.322328 0.033202 0.0185096 -0.315784 0.0307436 0.0183173 -0.320539 0.0315282 0.018934 -0.317339 0.0338242 0.0180325 -0.315889 0.0257483 0.0195191 -0.324843 0.0279157 0.0191715 -0.322712 0.0334817 0.0164875 -0.319223 0.0309285 0.0127954 -0.32633 -0.0223812 0.0177403 -0.283626 -0.0294263 0.0131004 -0.291135 -0.0298805 0.0147813 -0.292768 -0.0232838 0.0198884 -0.293688 -0.0238627 0.0197435 -0.293332 -0.0217347 0.0182389 -0.283633 -0.0241903 0.018574 -0.288793 -0.0282595 0.0176828 -0.293703 -0.0257333 0.0195249 -0.29516 -0.0247366 0.0192981 -0.292308 -0.0244952 0.0194658 -0.292696 0.0335973 -0.0182742 -0.315695 0.0339777 -0.0177724 -0.316192 0.0307436 -0.0183173 -0.320539 0.0289808 -0.0187083 -0.322496 0.0282839 -0.0176562 -0.326305 0.0275222 -0.0193344 -0.322694 0.0266017 -0.0196945 -0.322446 0.0257483 -0.0195191 -0.324843 0.0323081 -0.0146969 -0.323078 0.0302222 -0.0182707 -0.321562 0.033939 -0.017259 -0.317239 0.0337777 -0.0169796 -0.317986 0.0298981 -0.0147293 -0.327236 0.0303466 -0.0120286 -0.327494 -0.0250757 -0.0187856 -0.290972 -0.0282827 -0.0176562 -0.29369 -0.0248382 -0.0192073 -0.292092 -0.0250507 -0.0189015 -0.291312 -0.0241903 -0.018574 -0.288793 -0.0217136 -0.0186482 -0.284756 -0.0222487 -0.0190115 -0.286841 -0.0221147 -0.0180006 -0.283604 -0.0233821 -0.0199993 -0.296515 -0.0233342 -0.017265 -0.284375 -0.0298965 -0.0147293 -0.292759 -0.0266806 -0.015457 -0.287748 -0.0293357 -0.013192 -0.291004 -0.00313577 0.00200001 -0.318435 -0.00635857 0.00200001 -0.316368 -0.00741456 0.00200001 -0.302838 -0.00719456 0.00200001 -0.302457 -0.00654803 0.00200001 -0.303337 0.00289606 0.00200001 -0.309213 0.00926536 0.00200005 -0.311949 0.000860543 0.00200024 -0.307102 -0.000776615 0.00200001 -0.307101 -0.00289796 0.00200001 -0.309222 -0.00212375 0.00199997 -0.312116 -0.00883779 0.00200001 -0.308297 -0.00779676 0.00200001 -0.305503 -0.00741456 0.00125 -0.302838 0.00198822 -0.002 -0.307752 0.00212132 -0.002 -0.307877 0.000856332 -0.00200078 -0.307101 0.0061464 -0.002 -0.316573 -0.00164959 -0.002 -0.318846 -0.00563213 -0.002 -0.317018 -0.00289796 -0.002 -0.309222 -0.00779676 -0.002 -0.305503 -0.00719456 -0.002 -0.302457 -0.00684727 -0.00144723 -0.301854 -0.00290734 -0.00199996 -0.310799 -0.00221911 0.00199996 -0.307938 0.00289363 -0.00199996 -0.310891 0.00288457 0.00199992 -0.310938 0.00160601 1.64928e-05 -0.312548 -0.000933041 -0.00199995 -0.312885 0.00177276 0.00194825 -0.307578 -0.00684727 0.00144722 -0.301854 0.00120648 -0.00194825 -0.307252 0.0104787 -0.00144723 -0.311846 -0.00641467 -0.00125 -0.301104 0.0247358 -0.0111321 -0.0515866 0.0247358 0.0111321 -0.0515866 0.0159861 -0.0104778 -0.0407727 0.0320676 -0.0121871 -0.0631776 0.0155635 0.005 -0.0105988 0.0177015 -0.00499999 -0.00472502 0.0155635 -0.00499999 -0.0105988 0.0119741 -0.0100023 -0.0204602 0.0159861 0.0104778 -0.0407727 0.0140343 -0.0103438 -0.0382542 0.012506 -0.0101911 -0.0354552 0.0140367 0.010344 -0.0382579 0.0114466 0.0100602 -0.0324652 0.0108714 -0.0100023 -0.0293295 0.0108714 0.0100023 -0.0293295 0.0107685 0.0100023 -0.0272111 0.0109192 0.0100023 -0.0248465 0.010923 -0.0100023 -0.0248184 0.00290553 0.0162136 -0.0636029 0.0183437 0.00325001 -0.0847563 0.00249988 0.013314 -0.0450027 0.00249991 0.00325001 -0.0623955 0.0130296 0.00325001 -0.0434669 0.0130296 0.0122812 -0.0434669 0.0174904 0.00325001 -0.0486654 0.022 0.0131697 -0.0552792 0.0219985 0.0144481 -0.0634201 0.022 0.0160585 -0.0735703 0.0220001 0.00325001 -0.0836354 0.0159324 0.00125 -0.04992 0.0115515 0.00125 -0.0448141 0.0183437 -0.00575 -0.0847563 0.0107323 -0.00575 -0.0740294 0.0220001 -0.0174043 -0.0836354 0.022 -0.0161135 -0.0739425 0.0154194 -0.0124414 -0.0461733 0.0174904 -0.00575 -0.0486654 0.0216287 -0.00575 -0.0541184 0.0216287 -0.0130312 -0.0541184 0.00249988 -0.0133161 -0.0450149 0.0115515 -0.00374999 -0.0448141 0.00290553 -0.00575 -0.0636029 0.00250007 -0.01611 -0.0626519 0.0218421 -0.00511758 -0.0544972 0.022 0.00325001 -0.0552792 0.00273071 0.0161879 -0.0633286 0.00265018 0.00267567 -0.0631548 0.00290553 0.00325001 -0.0636029 0.0196627 0.00325001 -0.0856066 0.0197873 0.0177523 -0.085648 0.0189659 0.00325001 -0.0853473 0.0183437 0.0177476 -0.0847563 0.0219967 0.0174158 -0.083733 0.0218857 0.00325001 -0.0843014 0.0218857 0.0174861 -0.0843014 0.0216272 0.0175564 -0.084798 0.0213991 0.00325001 -0.0850642 0.00597819 0.00325001 -0.0357298 0.00518946 0.0118942 -0.0351995 0.00541065 0.00325001 -0.0352979 0.00377771 0.00325001 -0.035212 0.00336374 0.0120151 -0.035431 0.00305101 0.0120602 -0.0356979 0.00260181 0.00325001 -0.0364472 0.00250006 0.00325001 -0.0370769 0.0159324 -0.00374999 -0.04992 0.0205994 -0.00389042 -0.0548517 0.0120958 -0.00389042 -0.0443184 0.0122905 -0.00401795 -0.0441405 0.0215142 -0.00501381 -0.0541998 0.0125966 -0.00433579 -0.0438614 0.02 -0.00374999 -0.0552791 0.0217322 -0.00475 -0.0552793 0.0219132 -0.00516727 -0.055279 0.021 -0.00401795 -0.0552791 0.0211518 -0.00433579 -0.0544584 0.0130296 -0.00575 -0.0434669 0.0126706 -0.00486205 -0.0433404 0.0200001 -0.00374999 -0.0836354 0.0217319 -0.00475 -0.0836353 0.022 -0.00575 -0.0552792 0.0214 -0.00503392 -0.0850666 0.0184248 -0.00513197 -0.0847015 0.0185592 -0.00476333 -0.0846103 0.0186598 -0.00457443 -0.084542 0.019488 -0.00384788 -0.0839815 0.0191605 -0.00402578 -0.0842032 0.0190263 -0.00413197 -0.0842942 0.0214732 -0.0048863 -0.0847594 0.0212449 -0.00418465 -0.0836354 0.0220001 -0.00575 -0.0836354 0.0195399 -0.00488579 -0.0854034 0.0210001 -0.00401795 -0.0836354 0.0203107 -0.00414066 -0.0848553 0.021845 -0.00497783 -0.0836354 0.00308584 -0.00433579 -0.0623956 0.00265238 -0.00498463 -0.037077 0.00288202 -0.00457458 -0.0623957 0.00258404 -0.00517671 -0.0623957 0.00249991 -0.00575 -0.0623955 0.00400734 -0.00384788 -0.0627688 0.00298384 -0.00513197 -0.0635442 0.00449995 -0.00374999 -0.0623956 0.00372471 -0.00390425 -0.0626353 0.00265763 -0.00517249 -0.0631766 0.00265223 -0.00498463 -0.0623956 0.00321017 -0.00457443 -0.0633725 0.00337294 -0.00433564 -0.0632495 0.00334269 -0.00412318 -0.0627807 0.02 0.00125 -0.0552791 0.0215142 0.00251381 -0.0541998 0.021 0.00151795 -0.0552791 0.0218525 0.00259412 -0.0545303 0.0216287 0.00325001 -0.0541184 0.0205994 0.00139043 -0.0548517 0.0122905 0.00151795 -0.0441405 0.0211518 0.00183578 -0.0544584 0.0212449 0.00168464 -0.0836354 0.021845 0.00247784 -0.0836354 0.0219132 0.00266728 -0.055279 0.0217322 0.00225 -0.0552793 0.0120958 0.00139043 -0.0443184 0.0125966 0.00183578 -0.0438614 0.0126387 0.00235956 -0.0433036 0.00324396 0.00169353 -0.0370769 0.00523919 0.00151795 -0.0364034 0.00464155 0.00325001 -0.0350818 0.00548486 0.00225332 -0.0355873 0.0045001 0.00125 -0.037077 0.00351361 0.00151019 -0.037077 0.00305948 0.00252385 -0.0356832 0.00381557 0.00234234 -0.0353127 0.0045014 0.00153838 -0.0360091 0.00332049 0.00185474 -0.0361922 0.0107323 0.00325001 -0.0740294 0.0200001 0.00125 -0.0836354 0.00337244 0.00183578 -0.0632493 0.0184696 0.00248464 -0.0846708 0.00449995 0.00125 -0.0623956 0.00373471 0.00140225 -0.037077 0.00339992 0.00157984 -0.0623957 0.00308565 0.00183578 -0.0370767 0.00265238 0.00248464 -0.037077 0.0037352 0.00140209 -0.0626442 0.00308584 0.00183578 -0.0623956 0.00288202 0.00207457 -0.0623957 0.00265223 0.00248464 -0.0623956 0.00258404 0.0026767 -0.0623957 0.003027 0.00248464 -0.0635111 0.000187781 0.005 0.0534395 -0.00128391 0.00999999 0.0523259 0.00707939 0.00999999 0.0558001 0.00525038 0.005 0.055543 0.0107324 0.005 0.0556161 0.0107324 0.00999999 0.0556161 0.0104684 0.0115 0.0541396 0.0201259 -0.0105 0.0366316 0.0197776 -0.00499999 0.0539836 0.00707829 -0.01 0.0558004 0.00525038 -0.00499999 0.055543 -0.00373197 -0.00499999 0.0496067 -0.00749748 -0.0115011 0.0406697 0.0237157 -0.01 0.0477566 0.0237157 -0.00499999 0.0477566 0.0238336 -0.00499999 0.0498091 0.0237157 0.005 0.0477566 0.0238336 0.00999999 0.0498091 0.0238336 0.005 0.0498091 0.0231141 0.0104285 0.0517305 0.0231153 0.005 0.0517357 0.0216828 0.00999999 0.0532102 0.0216828 0.005 0.0532102 0.0108011 -0.0135 -0.0140226 0.0118993 -0.0135 -0.0154485 0.0118993 -0.0115023 -0.0154485 0.01067 -0.013 -0.0138807 0.00761675 -0.0135 0.0179509 -0.00486849 -0.0135 0.0193984 -0.0199362 -0.0135 0.00159765 -0.018888 -0.0135 -0.00657589 0.00367854 -0.0135 -0.0173135 0.000183548 -0.0135 -0.0199992 -0.00080883 -0.0135 0.0176816 0.00339957 -0.0132999 -0.017224 -0.00459843 -0.0135 -0.0170922 -0.00473336 -0.0133009 -0.0168907 -0.0118693 -0.0135 -0.0131305 -0.0165426 -0.0135 -0.00629529 -0.0175958 -0.0135 0.0019177 -0.0147982 -0.0135 0.00971082 -0.00876237 -0.0135 0.0153791 -0.00883953 -0.0132975 0.0151508 -0.00105573 -0.0133025 0.0175273 0.0107076 -0.0133173 -0.0139015 0.0118094 -0.0135 -0.0161412 -0.00897116 0.013 0.0150254 -0.00884136 0.0133009 0.0151502 -0.0163559 0.0133 -0.00622397 -0.0117351 0.0133 -0.0129821 -0.00489025 0.013 -0.0168028 0.00314732 0.013 -0.0172148 0.0069134 0.0135 0.016294 0.00682238 0.013 0.0161227 0.010679 0.0115023 -0.0138642 0.0118993 0.0115023 -0.0154485 0.00735476 0.0135 0.0185986 0.00761675 0.0135 0.0179509 0.000183548 0.0135 -0.0199992 0.00367854 0.0135 -0.0173135 -0.00459843 0.0135 -0.0170922 -0.0118693 0.0135 -0.0131305 -0.0146336 0.0135 -0.013633 -0.0175958 0.0135 0.0019177 0.00685358 0.0133177 0.0161535 0.0105188 0.0133 -0.0139859 0.00735476 0.0115023 0.0185986 0.0118993 0.0135 -0.0154485 0.0280328 0.0182485 -0.0960017 0.0408402 0.00325001 -0.0960015 0.044186 0.0177818 -0.100001 0.0408402 -0.00325 -0.0960015 0.028 -0.00325 -0.0960014 0.0304737 -0.0184254 -0.100002 0.044186 -0.00125 -0.100001 0.0304737 -0.00125 -0.100002 0.0293509 -0.0184885 -0.100346 0.0290402 -0.0185152 -0.100607 0.0284736 -0.0186125 -0.101997 0.0286982 -0.0186538 -0.102922 0.0284831 -0.00250026 -0.102194 0.0387415 -0.015236 -0.17478 0.0388005 -0.00325 -0.175733 0.0387378 -0.0151365 -0.175629 0.0392951 -0.00325 -0.17655 0.0392951 -0.0150668 -0.17655 0.0289915 -0.00137126 -0.100659 0.0329915 -0.00138518 -0.108852 0.029541 -0.00125 -0.100232 0.0371318 -0.00125 -0.117161 0.0394034 -0.00138518 -0.127107 0.0401043 -0.00125 -0.126931 0.0420019 -0.00125 -0.136561 0.0429691 -0.00125 -0.148111 0.0421926 -0.00138518 -0.155821 0.0414385 -0.00138518 -0.165411 0.0421454 -0.00125 -0.165591 0.0285919 -0.00177595 -0.101325 0.0323674 -0.00182873 -0.109133 0.0365984 -0.00138518 -0.117818 0.0412865 -0.00138518 -0.136664 0.0387395 -0.00182873 -0.127273 0.0406092 -0.00182873 -0.136762 0.0421778 -0.00138518 -0.146239 0.0415084 -0.00182873 -0.155793 0.0318272 -0.00325 -0.109376 0.0383023 -0.00250935 -0.127383 0.0381642 -0.00325 -0.127417 0.0401632 -0.00250935 -0.136826 0.04099 -0.00325 -0.14903 0.0410584 -0.00250935 -0.155775 0.0409161 -0.00325 -0.155769 0.0400436 -0.00325 -0.166328 0.0387415 -0.00325 -0.17478 0.0319567 -0.00250935 -0.109318 0.0355283 -0.00250935 -0.118196 0.0359531 -0.00182873 -0.118046 0.0414941 -0.00182873 -0.14627 0.0410441 -0.00250935 -0.14629 0.0407584 -0.00182873 -0.165334 0.0403106 -0.00250935 -0.165282 0.0389432 -0.00223908 -0.175271 0.039325 -0.00182873 -0.174885 0.0396422 -0.00151999 -0.175486 0.0397093 -0.00183579 -0.176136 0.0394846 -0.00225 -0.17636 0.0500004 0.00325001 -0.187255 0.0506992 0.0145319 -0.187732 0.0516457 0.0145814 -0.187849 0.0531643 0.0147999 -0.186839 0.0530337 0.00325001 -0.187016 0.0525394 0.0146791 -0.187519 0.0523929 0.00325001 -0.187586 0.04781 0.0013852 -0.109647 0.0484562 0.00182876 -0.109423 0.0503743 0.00125 -0.120414 0.0527767 0.00125 -0.131088 0.0534881 0.0013852 -0.130961 0.054966 0.0013852 -0.14188 0.0555048 0.0013852 -0.152976 0.0542463 0.00125 -0.141946 0.0547813 0.00125 -0.154851 0.0533332 0.00125 -0.174459 0.048882 0.00250937 -0.109275 0.0531138 0.00225 -0.186178 0.0546477 0.00182876 -0.175226 0.0561894 0.00182876 -0.152972 0.0546055 0.00250937 -0.130761 0.0517316 0.00182876 -0.120043 0.052167 0.00250937 -0.119926 0.0456003 0.00246094 -0.100587 0.0484818 0.00325001 -0.107712 0.0560963 0.00250937 -0.141776 0.0547452 0.00325001 -0.130736 0.0566398 0.00250937 -0.152968 0.0562689 0.00250937 -0.164214 0.0563968 0.00325001 -0.164419 0.0550938 0.00250937 -0.175288 0.0533766 0.00325001 -0.18623 0.0523957 0.00151795 -0.186035 0.0539701 0.0013852 -0.175131 0.0558195 0.00182876 -0.164182 0.0551369 0.0013852 -0.164134 0.0556473 0.00182876 -0.141817 0.0541619 0.00182876 -0.13084 0.0510705 0.0013852 -0.12022 0.0471272 0.00125 -0.109884 0.052618 0.0022399 -0.187126 0.0514146 0.00125 -0.185841 0.0527951 0.00182876 -0.186115 0.0501899 0.00225 -0.187066 0.0507228 0.00325001 -0.187718 0.0515724 0.00325001 -0.187835 0.0515155 0.00180073 -0.187378 0.0297911 0.00125 -0.100122 0.0295494 0.018474 -0.100228 0.0290348 0.00135046 -0.100613 0.0290402 0.0185153 -0.100607 0.0288504 0.00146014 -0.100833 0.0288297 0.0185376 -0.100863 0.0284874 0.0185997 -0.101767 0.0284905 0.018626 -0.10226 0.0286091 0.0186477 -0.102744 0.0392951 0.00325001 -0.17655 0.0392942 0.0150667 -0.176549 0.0388104 0.0151147 -0.17586 0.0388005 0.00325001 -0.175733 0.0387415 0.015236 -0.17478 0.0407093 0.00125 -0.175136 0.0414385 0.00138517 -0.165411 0.0421926 0.00138517 -0.155821 0.0421778 0.00138517 -0.146239 0.0423095 0.00125 -0.138907 0.0412865 0.00138517 -0.136664 0.0394034 0.00138517 -0.127107 0.0372801 0.00125 -0.117578 0.0329915 0.00138517 -0.108852 0.0294414 0.00124696 -0.100282 0.0285702 0.0018221 -0.101388 0.0284946 0.00207675 -0.101714 0.0390053 0.00225 -0.174827 0.0403106 0.00250934 -0.165282 0.028484 0.00253827 -0.102242 0.0401632 0.00250934 -0.136826 0.0410441 0.00250934 -0.14629 0.0415084 0.00182873 -0.155793 0.0400436 0.00325001 -0.166328 0.0410584 0.00250934 -0.155775 0.0409161 0.00325001 -0.155769 0.0409021 0.00325001 -0.146297 0.0383023 0.00250934 -0.127383 0.0355283 0.00250934 -0.118196 0.0358414 0.00325001 -0.119535 0.0319567 0.00250934 -0.109318 0.0323674 0.00182873 -0.109133 0.0359531 0.00182873 -0.118046 0.0365984 0.00138517 -0.117818 0.0387395 0.00182873 -0.127273 0.0406092 0.00182873 -0.136762 0.0414941 0.00182873 -0.14627 0.0407584 0.00182873 -0.165334 0.039325 0.00182873 -0.174885 0.0392027 0.00224932 -0.176077 0.0395808 0.00325001 -0.181078 0.0364324 0.0143073 -0.181463 0.0371859 0.00325001 -0.18075 0.0370617 0.0144246 -0.180803 0.0378161 0.0145066 -0.180523 0.0374057 0.00325001 -0.180643 0.0380777 0.00325001 -0.180494 0.0380775 0.0145273 -0.180495 0.036505 0.00275383 -0.18138 0.0363572 0.00250921 -0.182072 0.0367525 0.00325001 -0.181078 0.0367961 0.00182849 -0.182174 0.0388738 0.00151795 -0.181785 0.0393914 0.00225 -0.181268 0.038967 0.00325001 -0.18066 0.037927 0.00233001 -0.180636 0.0377649 0.00166618 -0.18127 0.0444682 -0.00125 -0.100021 0.044186 -0.0177818 -0.100001 0.0457211 -0.0177634 -0.100696 0.0455704 -0.00142628 -0.100558 0.0280059 -0.0182499 -0.0960016 0.0270731 -0.0182668 -0.0957738 0.027 -0.00325 -0.0957336 0.026268 -0.00325 -0.0950016 0.0260288 -0.0182036 -0.0943416 0.0261236 -0.0182265 -0.0946936 0.0265857 -0.00325 -0.0954156 0.0279999 -0.00151795 -0.0950015 0.026268 -0.00225 -0.0940016 0.0269999 -0.00151795 -0.0940014 0.0267829 -0.00197409 -0.0950921 0.0426721 -0.0171247 -0.0931993 0.0426661 -0.017327 -0.0948617 0.0422377 -0.0174189 -0.0954321 0.0409264 -0.0175654 -0.0960015 0.0280001 -0.00225 -0.0957336 0.0408401 -0.00151795 -0.0950016 0.026195 -0.00325 -0.0664573 0.0267574 -0.0143767 -0.0657192 0.0261554 -0.0145567 -0.0664859 0.0284194 -0.00325 -0.0653639 0.0286156 -0.0141495 -0.0653876 0.0280001 -0.00125 -0.0673193 0.0267428 -0.00325 -0.0657639 0.0275355 -0.00325 -0.0653738 0.0292208 -0.00325 -0.0657351 0.0262679 -0.00225 -0.0673191 0.027 -0.00151795 -0.0673193 0.0266597 -0.00222127 -0.066186 0.0278975 -0.00138045 -0.0663463 0.0284613 -0.00216772 -0.0655878 0.0288922 -0.00151795 -0.0668676 0.0408401 -0.00125 -0.0940015 0.0346065 -0.00125 -0.0805705 0.0350551 -0.00131331 -0.0803511 0.0412974 -0.00131331 -0.0938012 0.0356331 -0.00160783 -0.0800705 0.0295452 -0.00225 -0.0665369 0.0297843 -0.00325 -0.0664159 0.0362816 -0.00252165 -0.0797552 0.0359514 -0.00192229 -0.0799154 0.0427113 -0.00325 -0.0947077 0.0422459 -0.00325 -0.095424 0.0426721 -0.00325 -0.0931993 0.0425463 -0.00252165 -0.0932543 0.0424928 -0.00230433 -0.0933763 0.0422103 -0.00192229 -0.0934015 0.0419502 -0.00157014 -0.0937833 0.0415018 -0.00325 -0.0958888 0.0428345 -0.00325 -0.0938508 0.0415774 -0.00166498 -0.0950693 0.0408663 -0.0016802 -0.0952423 0.041295 -0.00225151 -0.0957339 0.0426009 -0.00237021 -0.0947153 0.0269999 0.00151795 -0.0940014 0.0267934 0.00189824 -0.0950201 0.0272346 0.00325001 -0.0958491 0.0265857 0.00325001 -0.0954156 0.0417616 0.0174879 -0.0957767 0.0427083 0.017133 -0.0932872 0.0428254 0.0172412 -0.0942436 0.0279999 0.00151795 -0.0950015 0.0407875 0.00155112 -0.0951179 0.027649 0.00225165 -0.0957336 0.0426051 0.0027142 -0.0932285 0.0420651 0.00176288 -0.0934651 0.0408401 0.00125 -0.0940015 0.041166 0.0022499 -0.0957333 0.0415018 0.00325001 -0.0958888 0.0422459 0.00325001 -0.095424 0.0427124 0.00252178 -0.0947042 0.0428345 0.00325001 -0.0938508 0.0426721 0.00325001 -0.0931993 0.042324 0.00207693 -0.0933519 0.0422616 0.00204552 -0.0949592 0.036063 0.00207693 -0.0798611 0.036433 0.00325001 -0.0797522 0.0363393 0.0027142 -0.0797271 0.0295452 0.00225 -0.0665369 0.0424528 0.00230114 -0.0932952 0.0358091 0.00176288 -0.0799849 0.0288922 0.00151795 -0.0668676 0.0280001 0.00125 -0.0673193 0.0352723 0.00139213 -0.0802459 0.0416663 0.00138734 -0.0940738 0.0418037 0.00154901 -0.0935794 0.026 0.00325001 -0.0673193 0.0284627 0.00325001 -0.0653742 0.0275355 0.00325001 -0.0653738 0.0286889 0.00223145 -0.0656957 0.0276518 0.00138045 -0.0664049 0.026195 0.00325001 -0.0664573 0.0268064 0.00216749 -0.065983 0.0206439 0.0110119 0.037913 0.0235007 0.0108433 0.0478736 0.0197776 0.00999999 0.0539836 0.0197506 0.0106558 0.0538523 0.0106553 0.0110659 0.0551782 0.0196445 0.011299 0.0532456 -0.00373197 0.00999999 0.0496067 -0.00307465 0.0113266 0.0491507 -0.00249884 0.0115 0.0487514 -0.00336647 0.0110659 0.0493532 0.00261941 0.00999999 0.0547328 0.00265548 0.0105223 0.0546461 -0.00371132 0.0102725 0.0495923 0.000187781 0.00999999 0.0534395 -0.00122279 0.0105223 0.0522548 -0.00047903 0.0114624 0.0515601 0.00319471 0.0115 0.0533478 0.00697211 0.0114507 0.0546826 0.0106012 0.011299 0.0548779 0.0107171 0.0106183 0.0555025 0.00711302 0.0110659 0.055357 0.00708647 0.0105223 0.0557067 0.00279001 0.0110659 0.0543221 -0.00351458 0.0108507 0.0494559 0.00299982 0.0114113 0.0538171 -0.000993598 0.0110659 0.051989 0.0332449 0.0179962 -0.312773 0.0339797 0.0177606 -0.316213 0.0347263 0.0163034 -0.312004 0.0347259 0.0158273 -0.3065 0.0344345 0.0162995 -0.306434 0.0346406 0.0168194 -0.311896 0.0343507 0.0172991 -0.311778 0.0339891 0.0166359 -0.306403 0.0335496 0.0171592 -0.308408 0.0338976 0.0176335 -0.311672 0.0551435 0.01866 -0.120499 0.0320676 0.0121926 -0.0631776 0.0347386 0.0124692 -0.291215 0.0349741 0.011882 -0.287545 0.0346479 0.0129884 -0.291124 0.0348925 0.0120558 -0.288675 0.0388218 0.010206 -0.260284 0.0371877 0.010069 -0.269713 0.0361583 0.0110384 -0.275753 0.0583355 0.0145501 -0.178282 0.0574432 0.0138852 -0.183585 0.0569394 0.0135424 -0.18625 0.0540117 0.0124893 -0.199061 0.0501463 0.0109427 -0.214329 0.0534414 0.0115976 -0.201873 0.0461243 0.0101232 -0.229579 0.058937 0.015058 -0.174041 0.0573213 0.0144464 -0.183634 0.060162 0.017581 -0.151869 0.060206 0.0165739 -0.158661 0.0595098 0.0163055 -0.167895 0.0559361 0.0178224 -0.120323 0.059002 0.0180516 -0.135986 0.0595997 0.0174421 -0.140155 0.0512222 0.0164844 -0.104998 0.0516868 0.0165718 -0.106276 0.0511203 0.0170117 -0.104998 0.0491789 0.0160803 -0.0996724 0.0451057 0.0157288 -0.0902694 0.0338384 0.0125799 -0.0666762 0.0318798 0.0128927 -0.0632009 0.0311488 0.0135863 -0.0635138 0.0308759 0.013666 -0.0636505 0.044414 0.0165461 -0.0904938 0.0404724 0.015881 -0.0830503 0.0462328 0.0172164 -0.0960017 0.0506488 0.0181216 -0.10751 0.0589595 0.018756 -0.14399 0.0577561 0.0189879 -0.137309 0.0573957 0.0190054 -0.134596 0.0561786 0.0189546 -0.127496 0.054532 0.0187668 -0.12028 0.057958 0.0171352 -0.168778 0.0567696 0.0160512 -0.17812 0.0492964 0.0117853 -0.214172 0.0531367 0.01333 -0.198952 0.0540224 0.0141959 -0.192585 0.0482614 0.0117422 -0.215913 0.0454766 0.0111659 -0.226499 0.0452946 0.0109664 -0.229389 0.0427625 0.0108976 -0.237006 0.0414361 0.0107597 -0.24468 0.0395592 0.0109207 -0.250274 0.0375083 0.0111512 -0.259817 0.0353337 0.0117305 -0.272026 0.0380117 0.0110467 -0.260094 0.0334748 0.0136558 -0.28913 0.0348339 0.0119924 -0.275488 0.0350346 0.0118767 -0.274051 0.033213 0.0148938 -0.296287 0.0381031 0.0146183 -0.0760226 0.0383707 0.0141485 -0.0759451 0.0448283 0.0162054 -0.0903445 0.050825 0.017501 -0.105072 0.0556212 0.0183232 -0.120387 0.0577055 0.018017 -0.128126 0.0586693 0.0185613 -0.136034 0.0598147 0.018096 -0.151902 0.0598177 0.0179115 -0.143902 0.0569629 0.0149607 -0.183636 0.0457937 0.0106334 -0.229509 0.0422534 0.00991735 -0.24488 0.0586168 0.0171486 -0.1679 0.0584241 0.0177005 -0.163078 0.0592884 0.018426 -0.151928 0.0586837 0.0186217 -0.149911 0.0316504 0.0132254 -0.0632866 0.0377059 0.0149593 -0.0761784 0.0503808 0.0178404 -0.105212 0.0568878 0.0188578 -0.128274 0.0581626 0.0188947 -0.136105 0.057381 0.0185227 -0.128182 0.0594774 0.0184243 -0.143942 0.0591525 0.0168217 -0.167916 0.0564305 0.0152871 -0.18358 0.0536591 0.013002 -0.199038 0.0498056 0.0114543 -0.21428 0.0419295 0.0104256 -0.2448 0.0353654 0.0118734 -0.275572 0.0385021 0.0107118 -0.260203 0.035847 0.0115375 -0.275668 0.0338931 0.0138066 -0.290948 0.0343519 0.0134709 -0.291028 0.0243998 0.0121157 -0.0517513 0.0246446 0.0116405 -0.0516124 0.0159056 0.0109972 -0.0408222 0.0156786 0.011481 -0.0410073 0.0240349 0.0124574 -0.051986 0.00937887 0.0115023 -0.0294813 0.0105517 0.0114407 -0.0326607 0.00992838 0.011397 -0.0294255 0.0107664 0.0105544 -0.02934 0.0112053 0.0109087 -0.03247 0.0122774 0.0110244 -0.0354957 0.0128536 0.0118371 -0.0389555 0.0111996 0.0116878 -0.0359875 0.0100296 0.0115588 -0.0327964 0.0153376 0.0118222 -0.0413025 0.0134696 0.0115297 -0.0384203 0.0139448 0.0108692 -0.0382911 0.0125131 0.010192 -0.0354711 0.0116828 0.0115579 -0.0357774 0.00943064 0.0115023 -0.0246626 0.00997863 0.011397 -0.0247303 0.0105647 0.0115023 -0.0199471 0.0104833 0.011063 -0.0247928 0.011104 0.0113881 -0.0201435 0.0118669 0.0105763 -0.0204211 0.0104343 0.011063 -0.029374 0.0108147 0.0105544 -0.0248336 0.0176668 0.0100023 -0.00482032 0.0142963 0.0113881 -0.0113737 0.0115613 0.011063 -0.0203099 0.0147536 0.011063 -0.0115402 0.0150591 0.0105763 -0.0116514 0.0119741 0.0100023 -0.0204602 -0.0182133 0.0163273 -0.279037 -0.017909 0.0168148 -0.279172 -0.0175027 0.0171453 -0.279443 -0.0208309 0.0135279 -0.0337643 -0.0256788 0.0111791 -0.0257982 -0.0169704 0.0135381 -0.0424345 -0.00504554 0.0158786 -0.0567931 -0.0161588 0.0143877 -0.0418374 0.00565045 0.0170281 -0.0720623 0.0169246 0.0180218 -0.0868848 0.0164386 0.0179578 -0.0872144 0.0192355 0.0182039 -0.0904272 0.00482285 0.0155861 -0.0727847 -0.00630522 0.0150001 -0.0578047 0.00489998 0.016177 -0.0726846 0.00906745 0.0159777 -0.0785272 0.0156863 0.0171079 -0.0877637 0.0156041 0.0165293 -0.0878499 0.0214082 0.0183291 -0.0950277 0.0264581 0.0187106 -0.102809 0.025955 0.0186254 -0.103078 0.0325529 0.0180589 -0.120403 0.0291885 0.0179822 -0.111787 0.0250922 0.0172128 -0.103579 0.0251825 0.0177783 -0.103513 0.0350088 0.0174206 -0.129247 0.0341903 0.0174736 -0.126065 0.0324535 0.0175065 -0.120438 0.0290934 0.0174232 -0.111839 0.0299744 0.0188272 -0.111427 0.0333509 0.0189015 -0.12013 0.0364471 0.0189201 -0.128934 0.0383431 0.0179372 -0.147429 0.0374738 0.0162757 -0.156591 0.0374424 0.0165672 -0.14736 0.0375435 0.0171036 -0.147396 0.0366791 0.0171226 -0.138214 0.0373273 0.0156419 -0.157496 0.0366073 0.0147183 -0.165585 0.035147 0.0135224 -0.174994 0.0333206 0.0124268 -0.183417 0.0310005 0.0118969 -0.192318 0.0374748 0.0160805 -0.165854 0.0341643 0.0137954 -0.183797 0.0346824 0.0139146 -0.183939 0.0317586 0.0127313 -0.192639 0.0302729 0.0111223 -0.194346 0.0309195 0.0113556 -0.192233 0.0181522 0.0107624 -0.226725 0.0256715 0.0112603 -0.210002 0.0174003 0.00991988 -0.226346 0.0249124 0.0104198 -0.20965 0.0248259 0.00987059 -0.209585 0.020173 0.010899 -0.223849 0.0141373 0.0109199 -0.235584 0.00934225 0.0110248 -0.242847 0.00493839 0.0115326 -0.250969 0.00447283 0.0114262 -0.250675 -0.000664296 0.0121667 -0.258276 -0.00553604 0.0158509 -0.0571596 0.0209473 0.0180033 -0.0953214 0.0254875 0.0182965 -0.103335 0.0328694 0.0185675 -0.120295 0.0359172 0.0188068 -0.129058 0.0354312 0.018471 -0.129167 0.0375895 0.0185004 -0.138155 0.0371026 0.0181636 -0.138205 0.0377842 0.0167698 -0.156656 0.0382618 0.0171065 -0.156713 0.0360849 0.0149455 -0.174874 0.0370025 0.0157446 -0.165756 0.0336993 0.0134608 -0.183641 0.0312955 0.0123968 -0.192463 0.00890004 0.0106909 -0.242596 0.00403704 0.0110924 -0.250416 -0.0255871 0.0117641 -0.0257025 -0.0216711 0.012679 -0.0342956 -0.0213427 0.0132166 -0.0340657 -0.0166536 0.0140787 -0.0421798 -0.00600455 0.015541 -0.0575343 0.005194 0.0167128 -0.0724264 0.015982 0.0176353 -0.0875374 0.0206473 0.0174803 -0.0955256 0.0294995 0.0184956 -0.111641 0.0351115 0.0179669 -0.129233 0.0367825 0.0176635 -0.138225 0.0378598 0.0176001 -0.147422 0.0366981 0.0152511 -0.16566 0.0353179 0.0141159 -0.174625 0.0356169 0.0146102 -0.174744 0.0334032 0.012964 -0.183505 0.0252099 0.010926 -0.209798 0.0176981 0.0104283 -0.226497 0.00860485 0.0101827 -0.242439 0.00374167 0.0105854 -0.250259 -0.00109638 0.0118337 -0.258016 -0.00151676 0.0107843 -0.257859 0.00363639 0.0100351 -0.250229 0.0117465 0.0094593 -0.236799 -0.00675639 0.012605 -0.265191 -0.00139757 0.0113303 -0.257871 -0.00644619 0.0131014 -0.26532 -0.00601722 0.0134326 -0.265576 -0.0123475 0.014374 -0.272235 -0.00689404 0.0120675 -0.265202 -0.0120345 0.0148634 -0.272359 -0.00998763 0.0149126 -0.271484 -0.0216907 0.0186295 -0.284672 -0.017089 0.0172663 -0.279781 -0.0183625 0.0158006 -0.279053 -0.0172231 0.0154315 -0.277778 -0.0116132 0.0151931 -0.272616 -0.0257117 0.0111697 -0.0257118 -0.0252469 0.0122955 -0.0255168 -0.0279247 0.0114786 -0.0168324 -0.024721 0.0126122 -0.0252814 -0.0270528 0.0118092 -0.0155668 -0.024593 0.0125437 -0.0238995 -0.0280604 0.0115249 -0.0097438 -0.0273972 0.0118036 -0.0166859 -0.0293175 0.011063 -0.00785646 -0.0282695 0.0109566 -0.0169513 -0.0256182 0.0115023 0.0107257 -0.0288104 0.011397 -0.00782072 -0.0293607 0.0110682 -0.00143867 -0.0296982 0.0105578 -0.00141878 -0.0296507 0.0105544 -0.00788006 -0.0288424 0.0105578 0.00500238 -0.028512 0.0110682 0.00493157 -0.0288484 0.0114009 -0.0014686 -0.0283074 0.0115023 -0.00150012 -0.0280858 0.0100023 0.00831411 -0.0269042 0.0105578 0.0112612 -0.02801 0.0114009 0.00482392 -0.0277287 0.0115023 0.00344496 -0.0260728 0.0114085 0.0110007 -0.022792 0.0114584 0.0166188 0.00236989 0.0115 0.052409 -0.0217567 0.0115 0.0176244 -0.0226158 0.0115023 0.0162401 -0.0236255 0.0108263 0.0169836 -0.0265901 0.0110683 0.0111356 -0.0231431 0.0113222 0.0167303 -0.0238485 0.0100023 0.0170951 -0.0238423 0.0101252 0.0170953 -0.0237609 0.0105578 0.0170344 -0.0237623 0.0105192 0.0170579 0.0199195 0.0114111 0.0375284 0.0211192 0.00999999 0.0381651 0.0209204 0.0105127 0.037777 0.0200141 0.0110485 0.0368096 0.00925138 0.0115023 0.0227077 0.016155 0.0115017 0.0326613 0.00955357 0.0114321 0.0224981 0.0161657 0.0113683 0.0317991 0.0164664 0.0110023 0.0315906 0.0100151 0.0108704 0.022178 0.0100728 0.0105023 0.022138 0.00983225 0.0112094 0.0223047 0.00889615 0.0113454 0.0207503 0.00857511 0.0113367 0.0178291 0.00900285 0.0107101 0.0186652 0.0092266 0.010711 0.0170775 0.00981536 0.0110667 0.0156448 0.00761887 0.0115063 0.017955 0.0113758 0.0106414 0.0139374 0.016398 0.0115023 0.0061119 0.0178023 0.0111557 0.00321427 0.0179907 0.0105263 0.00325114 0.0139673 0.0115023 0.0105434 0.0164077 0.0112957 0.00717126 0.0167176 0.0107267 0.00726825 0.0116318 0.0115189 0.0131371 0.0142864 0.0111541 0.010879 0.0182438 0.0107543 -0.00107429 0.0179111 0.0112942 -0.00103596 0.0174799 0.0115034 -0.00107778 0.0179067 0.0103841 -0.00345017 0.0177788 0.010962 -0.00351452 0.0177017 0.005 -0.00472445 -0.0125 -0.0138455 -0.272261 -0.021689 -0.0183377 -0.283814 -0.0175036 -0.0171457 -0.279445 -0.0179102 -0.0168152 -0.279173 -0.0182145 -0.0163277 -0.279038 -0.0226339 -0.0175854 -0.283742 -0.0183637 -0.015801 -0.279055 -0.0252112 -0.0123051 -0.0256091 -0.0217151 -0.0120929 -0.0344785 -0.0216319 -0.0126871 -0.0343704 -0.0202545 -0.0135694 -0.0335527 -0.024576 -0.0125482 -0.0239429 -0.0054767 -0.0158579 -0.0572398 -0.0184554 -0.0127032 -0.0402578 -0.00632116 -0.0144086 -0.0579932 -0.00624571 -0.0150071 -0.0578847 0.00487942 -0.0155915 -0.0728603 0.0164971 -0.0179624 -0.0873022 0.0192352 -0.0182039 -0.0904269 0.00872227 -0.017315 -0.0752066 0.0157447 -0.0171125 -0.0878509 0.0251443 -0.017216 -0.103678 0.0290233 -0.0174208 -0.111679 0.0305141 -0.0189243 -0.11126 0.0300007 -0.0188287 -0.111487 0.0333452 -0.0189015 -0.120114 0.0350116 -0.0174201 -0.129257 0.0351145 -0.0179664 -0.129243 0.0366774 -0.0171231 -0.138202 0.0367808 -0.017664 -0.138213 0.038127 -0.0186187 -0.13812 0.0375879 -0.018501 -0.138143 0.0364502 -0.0189196 -0.128944 0.0370367 -0.0169656 -0.14129 0.0373272 -0.0156418 -0.157496 0.0366173 -0.0147284 -0.165502 0.0353228 -0.0141194 -0.174598 0.0317487 -0.0127275 -0.192673 0.0341615 -0.013794 -0.183808 0.0360902 -0.0149489 -0.174847 0.0380102 -0.0162159 -0.165848 0.0382695 -0.017123 -0.156552 0.0383391 -0.0179463 -0.147309 0.035147 -0.0135224 -0.174994 0.0309906 -0.0118932 -0.192352 0.028415 -0.0117471 -0.204393 0.0256617 -0.0112589 -0.210027 0.0173933 -0.00991979 -0.22636 0.00933584 -0.0110252 -0.242857 0.0141373 -0.0109199 -0.235584 0.00362906 -0.0100359 -0.25024 -0.00152266 -0.0107854 -0.257867 -0.00140347 -0.0113314 -0.257879 -0.0017022 -0.0108197 -0.258123 -0.00689783 -0.0120686 -0.265207 -0.0169103 -0.0135479 -0.0425302 -0.0165938 -0.0140886 -0.0422751 0.00525048 -0.0167181 -0.0725021 0.00495688 -0.0161823 -0.0727606 0.0207111 -0.0174849 -0.0956311 0.0252349 -0.0177814 -0.103612 0.0255401 -0.0182996 -0.103435 0.0292152 -0.0179837 -0.111847 0.0325474 -0.0180588 -0.120387 0.0328636 -0.0185675 -0.120278 0.0354341 -0.0184706 -0.129177 0.0375392 -0.0171126 -0.147276 0.0378558 -0.0176092 -0.147302 0.0374814 -0.0162922 -0.156431 0.0367082 -0.0152612 -0.165577 0.0377918 -0.0167863 -0.156496 0.0370128 -0.0157546 -0.165673 0.0334005 -0.0129627 -0.183516 0.0336966 -0.0134594 -0.183651 0.0312852 -0.0123931 -0.192496 0.0249026 -0.0104184 -0.209675 0.0252001 -0.0109246 -0.209823 0.0176911 -0.0104282 -0.226511 0.00859844 -0.0101832 -0.242449 0.00889364 -0.0106913 -0.242606 0.00373434 -0.0105862 -0.25027 -0.00676018 -0.0126062 -0.265196 -0.01235 -0.0143748 -0.272238 -0.0120372 -0.0148642 -0.272361 -0.0246852 -0.0126218 -0.0253731 -0.0213037 -0.0132246 -0.03414 -0.0207921 -0.013536 -0.0338382 -0.0160992 -0.0143975 -0.0419322 -0.00594512 -0.0155479 -0.0576145 0.00570684 -0.0170335 -0.0721381 0.0160407 -0.0176399 -0.087625 0.0210108 -0.0180077 -0.0954271 0.0214719 -0.0183336 -0.0951339 0.0260077 -0.0186285 -0.103178 0.029526 -0.0184971 -0.111701 0.0359202 -0.0188063 -0.129068 0.0371009 -0.0181642 -0.138193 0.0374849 -0.0160906 -0.16577 0.0356222 -0.0146137 -0.174717 0.0181452 -0.0107623 -0.226739 0.0044655 -0.011427 -0.250686 0.0040297 -0.0110932 -0.250427 -0.00110229 -0.0118348 -0.258024 -0.000669859 -0.0121678 -0.258284 -0.00644998 -0.0131025 -0.265326 -0.00602101 -0.0134337 -0.265581 -0.0111856 -0.0153115 -0.272942 -0.0116156 -0.015194 -0.272619 0.00493105 -0.0115334 -0.250981 -0.0170902 -0.0172667 -0.279783 -0.0172231 -0.0154315 -0.277778 -0.0283595 -0.0103889 -0.0170669 -0.0255512 -0.0117737 -0.0257954 -0.0257117 -0.0111701 -0.0257118 -0.0279136 -0.0114824 -0.0168806 -0.0268226 -0.0118812 -0.0165976 -0.0297558 -0.0100023 -0.00788739 -0.0282582 -0.0109603 -0.017 -0.0296507 -0.0105544 -0.00788006 -0.0293175 -0.011063 -0.00785646 -0.0273857 -0.0118073 -0.0167338 -0.0280858 -0.0100023 0.00831411 -0.0243827 -0.0100023 0.0162972 -0.0261101 -0.011397 0.0109803 -0.0226154 -0.0115023 0.0162398 -0.026579 -0.011063 0.0111763 -0.0288347 -0.0105544 0.00504377 -0.0268875 -0.0105544 0.0113054 -0.0269846 -0.0100023 0.011346 -0.0288573 -0.011397 -0.00144778 -0.0293649 -0.011063 -0.00141794 -0.0280112 -0.011397 0.00486658 -0.0296984 -0.0105544 -0.00139813 -0.0285084 -0.011063 0.00497363 -0.0283059 -0.0115023 -0.0014804 -0.0288104 -0.011397 -0.00782072 -0.00839529 -0.0110658 0.0412251 -0.0230698 -0.011397 0.0165548 -0.0234875 -0.011063 0.0168445 -0.00856691 -0.010818 0.0413313 -0.00877318 -0.0100011 0.0414588 -0.0237618 -0.0105544 0.0170348 -0.0238485 -0.0100023 0.0170951 0.0346406 -0.0168194 -0.311896 0.0335496 -0.0171592 -0.308408 0.0328594 -0.0186041 -0.316043 0.0338976 -0.0176335 -0.311672 0.0344345 -0.0162995 -0.306434 0.0343507 -0.0172991 -0.311778 0.0348232 -0.0153211 -0.306586 0.0511783 -0.0170229 -0.105157 0.0332129 -0.0148937 -0.296286 0.033378 -0.0139456 -0.29091 0.0456397 -0.0111901 -0.225877 0.0531108 -0.0133169 -0.199061 0.0534981 -0.0139006 -0.194918 0.0586026 -0.017133 -0.16805 0.0564072 -0.0152707 -0.183708 0.0504386 -0.0178516 -0.105371 0.0511292 -0.0182106 -0.108903 0.0377312 -0.0149652 -0.0762299 0.0412959 -0.0160762 -0.084813 0.0444612 -0.0165571 -0.0906009 0.045762 -0.0171122 -0.0948804 0.038396 -0.0141545 -0.0759967 0.0478039 -0.0157925 -0.096302 0.0451534 -0.0157397 -0.0903768 0.042264 -0.0145368 -0.0838375 0.0422094 -0.0145239 -0.0837208 0.0559766 -0.0178278 -0.120481 0.0522334 -0.0166725 -0.107819 0.0516872 -0.016572 -0.106277 0.059019 -0.0180507 -0.136115 0.0577323 -0.018019 -0.128264 0.057845 -0.0174705 -0.128296 0.060164 -0.0175735 -0.152008 0.0595996 -0.0174421 -0.140156 0.0601625 -0.0164814 -0.159841 0.0583356 -0.01455 -0.178281 0.0576918 -0.0140621 -0.182193 0.0572979 -0.01443 -0.183762 0.0539852 -0.0124762 -0.19917 0.0501213 -0.0109353 -0.214425 0.0415501 -0.00939038 -0.248294 0.0383088 -0.00977021 -0.263444 0.0361536 -0.0110412 -0.275787 0.0362479 -0.0105013 -0.275845 0.036355 -0.0104382 -0.275086 0.0347381 -0.0124712 -0.291227 0.0345719 -0.0132863 -0.295815 0.0346474 -0.0129903 -0.291136 0.0379989 -0.0110487 -0.260156 0.0395596 -0.0109206 -0.250264 0.0371725 -0.0112092 -0.261513 0.031432 -0.0134245 -0.063381 0.0381285 -0.0146243 -0.0760741 0.0556614 -0.0183288 -0.120545 0.0581793 -0.0188939 -0.136233 0.0592901 -0.0184185 -0.152067 0.0591384 -0.0168061 -0.168066 0.0569396 -0.0149443 -0.183763 0.0536327 -0.0129888 -0.199147 0.0497806 -0.0114469 -0.214375 0.0492716 -0.0117779 -0.214267 0.0452731 -0.0109638 -0.229472 0.0414186 -0.01076 -0.244753 0.0384894 -0.0107138 -0.260265 0.0353608 -0.0118762 -0.275606 0.0338927 -0.0138085 -0.29096 0.0339891 -0.0166359 -0.306403 0.0535435 -0.0186218 -0.116625 0.0551833 -0.0186655 -0.120656 0.0569147 -0.0188599 -0.128412 0.0589686 -0.0187523 -0.144119 0.057711 -0.0189915 -0.136945 0.0586159 -0.0187124 -0.147908 0.0586211 -0.0180261 -0.159263 0.058423 -0.0176984 -0.163101 0.0578331 -0.0170049 -0.169984 0.0317455 -0.0131272 -0.0632468 0.0448756 -0.0162165 -0.0904516 0.050883 -0.0175123 -0.105231 0.0574079 -0.0185248 -0.12832 0.0586862 -0.0185605 -0.136163 0.0598271 -0.0179077 -0.144031 0.0594867 -0.0184206 -0.144071 0.0598166 -0.0180885 -0.152041 0.0594959 -0.0162899 -0.168046 0.0461023 -0.0101206 -0.229663 0.0457721 -0.0106307 -0.229592 0.0422358 -0.00991761 -0.244953 0.0419121 -0.0104259 -0.244873 0.0388094 -0.0102081 -0.260347 0.0358421 -0.0115403 -0.275701 0.0347259 -0.0158273 -0.3065 0.0343511 -0.0134728 -0.29104 0.0255748 -0.0128401 -0.0550478 0.0240349 -0.0124574 -0.051986 0.0243998 -0.0121156 -0.0517513 0.031985 -0.0126299 -0.0631569 0.0149597 -0.0119688 -0.0416406 0.0153376 -0.0118222 -0.0413025 0.0246446 -0.0116405 -0.0516124 0.0159056 -0.0109972 -0.0408222 0.0156786 -0.011481 -0.0410073 0.0138601 -0.0111598 -0.0383772 0.0132859 -0.0116973 -0.0386742 0.0119758 -0.0117633 -0.0375169 0.0114452 -0.01006 -0.0324605 0.0112259 -0.0109023 -0.0325259 0.0105504 -0.0114406 -0.032656 0.0104343 -0.011063 -0.029374 0.0124069 -0.0107243 -0.035474 0.0120065 -0.0114026 -0.0357598 0.0100283 -0.0115586 -0.0327917 0.00943435 -0.0115023 -0.0246319 0.00997248 -0.0114009 -0.0246994 0.0104814 -0.0110682 -0.0247629 0.00992838 -0.011397 -0.0294255 0.010817 -0.0105578 -0.024805 0.0107685 -0.0100023 -0.0272111 0.0107664 -0.0105544 -0.02934 0.0110743 -0.0114009 -0.0201328 0.0140065 -0.0115023 -0.0104915 0.0118254 -0.0115024 -0.0161323 0.0159579 -0.011328 -0.00718332 0.0172183 -0.0114033 -0.00331083 0.0118742 -0.0105578 -0.020424 -0.00869352 -0.0105222 0.0414097 -0.00358909 -0.0107008 0.0495075 -0.00793032 -0.0114112 0.0409375 0.00265472 -0.0105223 0.0546461 -0.00128416 -0.01 0.0523256 0.0106531 -0.0110607 0.0551841 -0.00249884 -0.0115 0.0487514 -0.00373197 -0.01 0.0496067 -0.00122296 -0.0105223 0.0522547 -0.00328739 -0.0111522 0.0493455 -0.000993767 -0.0110659 0.0519889 -0.000604289 -0.011455 0.0514797 -0.00281979 -0.0114432 0.048974 0.00722 -0.0109334 0.0554955 0.00525038 -0.01 0.055543 0.00278934 -0.0110659 0.0543221 0.00714174 -0.0114563 0.0547204 0.00261873 -0.01 0.0547328 0.00299948 -0.0114112 0.0538168 0.0104661 -0.0115 0.0541399 0.0196445 -0.011299 0.0532456 0.0105671 -0.0113858 0.054705 0.0196998 -0.0110607 0.0535511 0.0107113 -0.010574 0.0555039 0.0197418 -0.01075 0.053786 0.0197776 -0.01 0.0539836 0.0107324 -0.01 0.0556161 0.0235219 -0.01075 0.0478089 0.0216828 -0.01 0.0532102 0.0231101 -0.0104285 0.0517368 0.0232917 -0.0110607 0.0478714 0.0238292 -0.0103948 0.049814 0.0221083 -0.0114914 0.0513388 0.0213572 -0.0110761 0.0529649 0.022268 -0.0115 0.0481485 0.0230919 -0.011299 0.0496973 0.0229918 -0.011299 0.0479525 0.0203678 -0.0111719 0.0374299 0.0197331 -0.0114409 0.0372111 0.0208032 -0.0106027 0.0374968 0.0210743 -0.00499999 0.0379994 0.0200753 -0.0108461 0.0366667 0.0193041 -0.0115 0.0372017 0.00955357 -0.0114321 0.0224981 0.00925138 -0.0115023 0.0227077 0.00839065 -0.0114499 0.0180697 0.00983225 -0.0112094 0.0223047 0.0100151 -0.0108704 0.022178 0.00929309 -0.0110242 0.0206113 0.00900275 -0.0107223 0.0186661 0.00981088 -0.0109857 0.0156568 0.00922261 -0.0108937 0.0170757 0.00919463 -0.0115023 0.0148968 0.0172224 -0.0115023 0.00310397 0.0174734 -0.0115023 -0.000966241 0.0179903 -0.0107083 0.00326155 0.0166944 -0.0105408 0.00731056 0.0159112 -0.0105513 0.00881613 0.0176782 -0.0112729 0.00319458 0.0165041 -0.0112261 0.00714506 0.016398 -0.0115023 0.0061119 0.0142099 -0.0113024 0.0107724 0.0113758 -0.0106414 0.0139374 0.0144063 -0.0107493 0.0110077 0.0176508 -0.0103651 -0.00473442 0.0175077 -0.011083 -0.00391458 0.0115564 -0.0110682 -0.0203082 0.0176236 -0.0105911 -0.00458699 0.0182287 -0.0107759 -0.0012505 0.0179657 -0.0112523 -0.00133412 0.0176668 -0.0100023 -0.00482032 0.0065429 -0.0181703 -0.316182 0.00780581 -0.0181702 -0.314488 0.0039751 -0.0156771 -0.315517 0.00465588 -0.0181703 -0.3177 0.00165978 -0.0141703 -0.316139 0.00234346 -0.0181703 -0.318685 -0.000334485 -0.0128724 -0.316674 0.000203204 -0.0181703 -0.31899 -0.00214211 -0.0181703 -0.318732 -0.002429 -0.0115093 -0.317237 0.00781163 0.0158297 -0.314502 0.00719962 0.0078297 -0.315407 0.00695585 0.0158297 -0.315731 0.00622498 0.0078297 -0.316516 0.00566613 0.0158297 -0.317006 0.00477954 0.0078297 -0.317637 0.00362923 0.0078297 -0.318232 0.00412755 0.0158297 -0.318007 0.00227512 0.0078297 -0.318716 0.00241183 0.0158297 -0.318679 0.000996792 0.0158297 -0.318938 0.000996792 0.0078297 -0.318938 5.49743e-05 0.0078297 -0.318992 5.49743e-05 0.0158297 -0.318992 -0.000891396 0.0078297 -0.318947 -0.000891396 0.0158297 -0.318947 -0.00183192 0.0158297 -0.318802 -0.00183192 0.0078297 -0.318802 -0.00275604 0.0158297 -0.318557 -0.00275604 0.0078297 -0.318557 -0.00365288 0.0158297 -0.318214 -0.00365288 0.0078297 -0.318214 -0.0044906 -0.0101678 -0.317789 -0.00454505 -0.0181703 -0.317765 -0.00573242 -0.0101703 -0.316937 -0.00585469 -0.0181703 -0.316834 -0.00700396 -0.0101703 -0.31565 -0.00710461 -0.0181703 -0.315522 -0.00800685 -0.0101703 -0.314108 -0.00808054 -0.0181703 -0.313961 -0.00867617 -0.0101703 -0.312396 -0.00871283 -0.0181703 -0.31226 -0.0089364 -0.0101703 -0.31098 -0.0089364 -0.0181703 -0.31098 -0.00899062 -0.0101703 -0.310038 -0.00894556 -0.0101703 -0.309092 -0.00899062 -0.0181703 -0.310038 -0.00894556 -0.0181703 -0.309092 -0.0088004 -0.0101703 -0.308151 -0.0088004 -0.0181703 -0.308151 -0.00855539 -0.0101703 -0.307227 -0.00855539 -0.0181703 -0.307227 -0.00821198 -0.0101703 -0.30633 -0.00821198 -0.0181703 -0.30633 -0.00778747 -0.0181703 -0.305497 0.026741 -0.00792594 -0.331854 0.0267277 -0.00641928 -0.331971 0.0263011 -0.00573541 -0.331812 0.0245463 -0.00716442 -0.335006 0.0238413 -0.00717514 -0.334292 0.025872 -0.00718852 -0.333649 0.0266677 -0.00838663 -0.332879 0.0269577 -0.00576318 -0.332347 0.0260949 -0.00153217 -0.332253 0.0276504 -0.00445626 -0.329859 0.0265435 -0.00879427 -0.3313 0.0236888 -0.00719451 -0.334421 0.0251142 -0.00716154 -0.33296 0.0267133 -0.00308836 -0.331099 0.0237108 -0.00289426 -0.334371 0.0257839 -0.00574191 -0.332205 0.028171 -0.00464813 -0.330765 0.0264322 -0.00695823 -0.331407 0.0261482 -0.00933802 -0.332106 0.0244945 -0.00802705 -0.33504 0.0238535 -0.00691419 -0.334802 0.0243469 -0.00288507 -0.333978 0.024225 -0.00547975 -0.334351 0.025318 -0.00468141 -0.332783 0.0273189 -0.00440155 -0.331052 0.0273233 -0.00370757 -0.330964 0.0272369 -0.00368099 -0.332422 0.0246456 -0.00838224 -0.334905 0.024119 -0.0102633 -0.335371 0.0237049 -0.0141203 -0.335213 0.0233067 -0.0120716 -0.336093 0.0253625 -0.0135097 -0.333736 0.0232155 -0.0164913 -0.334173 0.0222814 -0.0183644 -0.333058 0.0208416 -0.0199855 -0.331387 0.0200051 -0.0205684 -0.330373 0.0274842 -0.00121648 -0.331676 0.0289519 -0.00122417 -0.329668 0.0271903 -0.0173171 -0.328571 0.0284024 -0.0175605 -0.326364 0.0263595 -0.0196491 -0.325186 0.0255613 -0.0117989 -0.333904 0.0256674 -0.0184403 -0.329007 0.0253585 -0.0173048 -0.331027 0.0258638 -0.0160937 -0.331669 0.0250593 -0.0148429 -0.333452 0.0273108 -0.00765968 -0.331894 0.0272919 -0.0117568 -0.331913 0.0269814 -0.0141976 -0.331618 0.0237725 -0.0192942 -0.329744 0.025499 -0.0193081 -0.327415 0.0238108 -0.0200898 -0.327639 0.0223454 -0.0208509 -0.326308 0.0239061 -0.0209331 -0.323795 0.0303304 -0.00121637 -0.327476 0.0289052 -0.00582746 -0.329743 0.0303287 -0.0117069 -0.327475 0.0299522 -0.0142526 -0.327259 0.0289027 -0.0117874 -0.329741 0.0286858 -0.0135097 -0.329593 0.0283429 -0.0148429 -0.329359 0.0278471 -0.0161121 -0.32902 0.0247191 -0.00550009 -0.334836 0.0270951 -0.00552277 -0.33324 0.025329 -0.00457501 -0.334571 0.0261214 -0.00442265 -0.333752 0.0234473 -0.00446548 -0.336433 0.023494 -0.00932898 -0.336343 0.0102631 -0.0116854 -0.343679 0.0119033 -0.0115601 -0.344004 0.0112209 -0.0109015 -0.34436 0.0229055 -0.0159768 -0.335305 0.0201545 -0.020215 -0.332458 0.0209871 -0.0206992 -0.334524 0.0216738 -0.0186871 -0.334794 0.021335 -0.0175356 -0.328061 0.0302232 0.0104213 -0.327414 0.029795 0.0122798 -0.327167 0.0238326 0.0158313 -0.323729 0.0286071 0.0148695 -0.326482 0.0259426 0.0175565 -0.324946 0.021603 0.00782963 -0.322444 0.0227898 0.00721734 -0.323128 0.0236402 0.00607739 -0.323619 0.0238326 -0.0071703 -0.323729 0.0303299 0.00890625 -0.327476 0.0303359 -0.0110465 -0.327479 0.023742 -0.00799981 -0.323677 0.0233021 -0.00896653 -0.323424 0.0222956 -0.0099583 -0.322843 0.0212337 -0.0101703 -0.322231 0.0238313 -0.020927 -0.323731 0.0260002 -0.0199449 -0.324979 0.028474 -0.0174793 -0.326405 0.0296301 -0.0151812 -0.327073 0.0238326 -0.0181703 -0.323729 0.0302113 -0.013044 -0.327407 0.00780601 -0.0181703 -0.314488 0.0240522 -0.00446565 -0.338061 0.0238482 -0.00296829 -0.340286 0.0240441 -0.00931902 -0.33806 0.0250652 -0.00446566 -0.339228 0.0250959 -0.00954906 -0.33926 0.0106237 -0.0109808 -0.346504 -0.000302059 -0.011006 -0.348157 0.0046459 -0.0109314 -0.347581 -0.00706428 -0.0109809 -0.347345 -0.0109047 -0.0110429 -0.346852 -0.0101275 -0.0108604 -0.345766 -0.0118904 -0.010518 -0.346091 -0.011841 -0.00931924 -0.344999 -0.0162141 -0.00955743 -0.345014 -0.0159882 -0.0105508 -0.343596 -0.0142554 -0.00692252 -0.343032 -0.0147857 -0.00930631 -0.342531 -0.0155094 -0.00889155 -0.343387 -0.0148106 -0.00657696 -0.342763 -0.0104118 -0.0150773 -0.345507 -0.00646125 -0.0150132 -0.346049 -0.00710426 -0.0152302 -0.34738 -2.23928e-05 -0.0151432 -0.347444 0.00371597 -0.0152315 -0.347879 0.00407998 -0.0150239 -0.346375 0.00644268 -0.0226056 -0.335455 0.00676649 -0.0163263 -0.342939 0.00366174 -0.0220703 -0.335989 0.00692341 -0.0209334 -0.338742 0.0057801 -0.0196418 -0.339841 0.00490028 -0.0211255 -0.335796 0.00508127 -0.0157694 -0.34435 0.00809298 -0.0176133 -0.343015 0.00445223 -0.0197937 -0.342241 0.00486363 -0.0193064 -0.34141 0.00493459 -0.015594 -0.347647 0.0184029 -0.0155671 -0.341257 0.0227355 -0.0150158 -0.338751 0.0230018 -0.0174323 -0.336845 0.0247149 -0.015711 -0.339131 0.023455 -0.0206867 -0.337371 0.0222416 -0.0226971 -0.335972 0.0197319 -0.0240346 -0.333079 0.0201786 -0.0217192 -0.333594 0.0084663 -0.0141703 -0.325258 0.0148004 -0.0212124 -0.32891 0.0159939 -0.0228193 -0.329598 0.0079073 -0.0141703 -0.320318 -0.0091479 -0.0141703 -0.324316 -0.0110028 -0.0141703 -0.322944 -0.00558148 -0.0141703 -0.321729 -0.00903443 -0.0141703 -0.319331 -0.0126575 -0.0141703 -0.321331 -0.0140967 -0.0141703 -0.319481 -0.0152703 -0.0141703 -0.317446 -0.0104337 -0.0141703 -0.317736 -0.0161692 -0.0141703 -0.315214 -0.012008 -0.0141703 -0.315058 -0.0128201 -0.0141703 -0.312092 -0.0167375 -0.0141703 -0.312919 0.0079073 -0.0181703 -0.320318 -0.00897399 -0.0181703 -0.308996 -0.00778784 -0.0181703 -0.305497 0.00187681 -0.0181703 -0.322899 0.00161915 -0.0181703 -0.318925 -0.0100259 -0.0181703 -0.318374 -0.00579839 -0.0181703 -0.316888 -0.00719906 -0.0181703 -0.32083 -0.00228899 -0.0181703 -0.318753 -0.00437354 -0.0181703 -0.322276 -0.00130021 -0.0181703 -0.322944 -0.0129791 -0.0181703 -0.311486 -0.00878094 -0.0181703 -0.312117 -0.0119394 -0.0181703 -0.315153 -0.00755635 -0.0181703 -0.314944 0.00686829 -0.0181703 -0.315842 0.00495585 -0.0181703 -0.31756 0.00564197 -0.0181703 -0.321763 0.0213349 -0.0181703 -0.328061 -0.00448641 0.0078297 -0.317789 -0.00540543 0.0078297 -0.317182 -0.00573243 0.0158297 -0.316937 -0.00651216 0.0078297 -0.31621 -0.00700398 0.0158297 -0.31565 -0.00763503 0.0078297 -0.314763 -0.00800686 0.0158297 -0.314108 -0.00823063 0.0078297 -0.313612 -0.00867618 0.0158297 -0.312396 -0.00871284 0.0078297 -0.31226 -0.0089364 0.0158297 -0.31098 -0.0089364 0.0078297 -0.31098 -0.00899062 0.0158297 -0.310038 -0.00899062 0.0078297 -0.310038 -0.00894556 0.0158297 -0.309092 -0.00894556 0.0078297 -0.309092 -0.0088004 0.0078297 -0.308151 -0.0088004 0.0158297 -0.308151 -0.00855539 0.0158297 -0.307227 -0.00855539 0.0078297 -0.307227 -0.00821198 0.0158297 -0.30633 -0.00821198 0.0078297 -0.30633 -0.00778747 0.0158297 -0.305497 -0.00838755 0.0158297 -0.313175 -0.0104022 0.0158297 -0.317869 -0.00728759 0.0158297 -0.315293 -0.0121522 0.0158297 -0.314645 0.000227498 0.0158297 -0.319045 -0.00104912 0.0158297 -0.322971 -0.00279428 0.0158297 -0.318566 -0.00389911 0.0158297 -0.322414 -0.0071683 0.0158297 -0.320896 -0.00458342 0.0158297 -0.317739 -0.00579945 0.0158297 -0.316881 0.00376792 0.0158297 -0.318231 0.00606195 0.0158297 -0.32152 0.00262065 0.0158297 -0.322785 -0.0129846 0.0158297 -0.311183 -0.012884 0.0158297 -0.30833 -0.00897514 0.0158297 -0.310805 -0.0238141 0.0158297 -0.296256 -0.00878886 0.0158297 -0.307867 0.00644831 0.0158297 -0.316331 0.0238326 0.0158297 -0.323729 0.00780598 0.0158297 -0.314488 0.021335 0.0158297 -0.328061 -0.0133371 -0.0101703 -0.323516 -0.0147598 -0.0101703 -0.321946 -0.0262134 -0.0101703 -0.318276 -0.0189904 -0.0101703 -0.310116 -0.0174421 -0.0101703 -0.317506 -0.0170413 -0.0101703 -0.318376 -0.0160019 -0.0101703 -0.320223 -0.0186054 -0.0101703 -0.306185 -0.0188857 -0.0101703 -0.307997 0.00224947 -0.0101703 -0.32886 0.0182366 -0.0101703 -0.327429 0.0109685 -0.0101703 -0.325513 0.00916941 -0.0101703 -0.326639 0.000129958 -0.0101703 -0.328993 0.007806 -0.0101703 -0.314488 -0.00778759 -0.0101703 -0.305497 -0.00198678 -0.0101703 -0.328887 -0.00408304 -0.0101703 -0.328547 -0.00612364 -0.0101703 -0.327976 0.0203867 -0.00887962 -0.328649 0.0209694 -0.00826161 -0.326509 0.0210527 -0.00887676 -0.325131 0.019569 -0.00975158 -0.32819 0.0211157 -0.00928155 -0.324215 0.0190271 -0.0100282 -0.327884 0.0211554 -0.00958065 -0.323547 0.018615 -0.0101383 -0.327647 0.0211966 -0.00989123 -0.322854 0.0182366 0.0078297 -0.327429 0.0193364 0.00724009 -0.326701 0.0220242 0.00768756 -0.322687 0.022401 0.00751007 -0.322904 0.0198944 0.00694094 -0.326333 0.0208542 0.00644078 -0.325661 0.0228962 0.00713807 -0.323195 0.0235031 0.00630249 -0.323545 0.0238326 0.0048297 -0.323729 -0.0160271 0.0078297 -0.320183 -0.0151645 0.0078297 -0.321427 -0.0142034 0.0078297 -0.322603 -0.0131552 0.0078297 -0.323694 -0.0131892 0.0078297 -0.334118 -0.00166922 0.0078297 -0.328932 0.00038382 0.0078297 -0.328989 0.00597643 0.0078297 -0.336837 0.00774102 0.0078297 -0.336383 -0.00593828 0.0078297 -0.316763 0.0126296 0.0078297 -0.324196 0.00617309 0.0078297 -0.316572 0.0114442 0.0078297 -0.325166 0.010199 0.0078297 -0.326029 0.00888915 0.0078297 -0.32679 0.00752253 0.0078297 -0.327444 0.00450189 0.0078297 -0.317811 0.00263538 0.0078297 -0.318617 0.000601706 0.0078297 -0.318987 -0.00141239 0.0078297 -0.318893 -0.0031401 0.0078297 -0.318429 -0.0263815 0.0078297 -0.317724 -0.0167868 0.0078297 -0.318876 -0.00691359 0.0078297 -0.315744 -0.00782814 0.0078297 -0.314451 -0.00844399 0.0078297 -0.313082 -0.0189775 0.0078297 -0.310705 -0.00886583 0.0078297 -0.311572 -0.00899075 0.0078297 -0.310026 -0.0189738 0.0078297 -0.30919 -0.0188496 0.0078297 -0.30768 -0.0088513 0.0078297 -0.308497 -0.0186054 0.0078297 -0.306185 -0.00838611 0.0078297 -0.30673 0.00780604 0.0078297 -0.314488 0.00723406 0.0078297 -0.315359 0.0237221 0.00256931 -0.334384 0.0250761 0.00849528 -0.333771 0.0268177 0.00775345 -0.33186 0.0238324 0.0184838 -0.32373 0.021335 0.0158313 -0.328061 0.0227779 0.0135574 -0.33609 0.0194732 0.0183108 -0.331783 0.0206772 0.0188543 -0.334197 0.0217606 0.0158666 -0.334369 0.0191803 0.0132812 -0.342564 0.0242294 0.00849019 -0.339054 0.0240524 0.00688654 -0.33806 0.0240534 0.00147567 -0.338063 0.0234136 0.00203263 -0.336443 0.023411 0.00689531 -0.336665 0.0226887 -0.00099611 -0.336784 0.0175668 -0.00932862 -0.340741 0.0179964 -0.00446491 -0.341101 0.0166311 -0.00446412 -0.340874 0.0187466 -0.00929983 -0.341905 0.0195654 -0.0102346 -0.343033 0.0151424 -0.00931133 -0.343646 0.0158176 -0.00954406 -0.345108 0.015331 -0.0110086 -0.345281 0.0146306 -0.0108459 -0.344203 0.0079973 -0.00932921 -0.344498 0.00895772 -0.00931367 -0.345811 0.008104 -0.00446418 -0.344403 0.00561206 -0.00932911 -0.3447 0.00944887 -0.010562 -0.346525 0.00504239 -0.00931977 -0.34658 0.00567928 -0.00446452 -0.344754 0.00500206 -0.00446553 -0.346268 -0.00200971 -0.00446459 -0.345249 -0.0025183 -0.00933031 -0.345039 -0.0014564 -0.00927224 -0.3465 -0.00112286 -0.0105653 -0.347196 -0.00460539 -0.00446514 -0.344997 -0.00545809 -0.00446561 -0.346544 -0.00426976 -0.00933027 -0.344956 -0.0123544 -0.00954495 -0.346471 -0.0169289 -0.0109166 -0.343525 -0.0155351 -0.00446565 -0.343524 -0.0119206 -0.0156982 -0.345359 -0.00589763 -0.0155852 -0.347505 -0.00388665 -0.0216955 -0.336993 -0.00235868 -0.0223813 -0.337554 -0.00126685 -0.0200262 -0.342486 -0.00212642 -0.0169485 -0.343406 -0.00490569 -0.020028 -0.342501 -0.00507057 -0.0159407 -0.344757 -0.00436308 -0.0194746 -0.341556 -0.00297326 -0.0187223 -0.341448 -0.00343712 -0.0152796 -0.343977 -0.0013016 -0.0213614 -0.338895 -0.00295976 -0.0210155 -0.337509 -0.00344275 -0.0224758 -0.336514 -0.00185756 -0.0192006 -0.341682 -0.00191312 -0.0209278 -0.337976 0.00400252 -0.0218555 -0.33926 0.00396794 -0.0240945 -0.339026 0.0049972 -0.0197819 -0.34616 0.00467419 -0.0187059 -0.343896 0.00460898 -0.0231491 -0.34347 0.0155559 -0.0157333 -0.344842 0.0133098 -0.0226146 -0.332572 0.0149174 -0.0193779 -0.337344 0.0129666 -0.0213731 -0.333242 0.0165861 -0.0158089 -0.339929 0.0167114 -0.0193353 -0.33848 0.0192632 -0.015797 -0.342817 0.0192984 -0.0246283 -0.332653 0.0226302 -0.0226932 -0.336439 0.0230134 -0.0217201 -0.337567 -0.0169804 -0.0141703 -0.310585 -0.0169804 -0.0212158 -0.310585 -0.0167915 -0.0212158 -0.312587 -0.00733088 -0.0141703 -0.325326 -0.00491594 -0.0141703 -0.326263 -0.00234773 -0.0212158 -0.326828 -0.00234773 -0.0141703 -0.326828 0.000354471 -0.0212158 -0.326989 0.000354471 -0.0141703 -0.326989 0.00295698 -0.0188199 -0.32631 0.005595 -0.0163913 -0.325622 0.00305524 -0.0141703 -0.326717 0.00570347 -0.0141703 -0.32601 0.00800759 -0.0141703 -0.324993 -0.0167915 -0.0141703 -0.312587 -0.0161575 -0.0212158 -0.31525 -0.0161575 -0.0141703 -0.31525 -0.015092 -0.0212158 -0.3178 -0.015092 -0.0141703 -0.3178 -0.013644 -0.0212158 -0.320121 -0.013644 -0.0141703 -0.320121 -0.0117791 -0.0141703 -0.322241 -0.0117791 -0.0212158 -0.322241 -0.00958447 -0.0212158 -0.324027 -0.00958447 -0.0141703 -0.324027 -0.00848257 -0.0212158 -0.32472 -0.00733088 -0.0212158 -0.325326 -0.00491594 -0.0212158 -0.326263 -0.00120596 -0.0212116 -0.333224 -0.00832289 -0.0212123 -0.331937 -0.00342614 -0.0212119 -0.333 -0.00580135 -0.0212158 -0.326029 -0.00193205 -0.0212158 -0.326901 0.00210059 -0.0212158 -0.326923 0.00800759 -0.0212158 -0.324993 0.0140431 -0.0212139 -0.328475 0.0117411 -0.0212122 -0.330032 0.00927395 -0.0212122 -0.331254 0.0110405 -0.0212152 -0.331258 0.00797279 -0.0212157 -0.325152 0.00534288 -0.0212122 -0.332668 0.00459617 -0.0212172 -0.333721 0.00345782 -0.0212121 -0.333 -0.026144 -0.0141703 -0.305301 -0.0261293 -0.0234128 -0.30531 -0.0250331 -0.0228107 -0.305942 -0.0169804 -0.0141703 -0.310585 -0.0234712 -0.0212129 -0.306842 -0.0263117 -0.0141703 -0.300587 -0.0263118 -0.0181703 -0.300587 -0.012884 -0.0141703 -0.30833 -0.012884 -0.0181703 -0.30833 -0.0129936 -0.0181703 -0.31056 -0.0130032 -0.0141703 -0.310295 -0.0126273 -0.0141703 -0.313124 -0.012562 -0.0181703 -0.313376 -0.0116015 -0.0141703 -0.315883 -0.0114825 -0.0181703 -0.316112 -0.00979395 -0.0181703 -0.31856 -0.00996692 -0.0141703 -0.318358 -0.00826455 -0.0181703 -0.32002 -0.0078117 -0.0141703 -0.3204 -0.00636507 -0.0181703 -0.321344 -0.00528617 -0.0141703 -0.321885 -0.00370829 -0.0181703 -0.322468 -0.00257002 -0.0141703 -0.322752 0.000298978 -0.0141703 -0.323007 -0.000897538 -0.0181703 -0.322979 0.00200029 -0.0181703 -0.322858 0.00318582 -0.0141703 -0.322618 0.00483845 -0.0181703 -0.322082 0.00593819 -0.0141703 -0.321583 0.00669469 -0.0181703 -0.321142 -0.0238141 -0.0181703 -0.296256 -0.0302473 -0.0125004 -0.292547 -0.0298005 -0.0147103 -0.292804 -0.028404 -0.0175853 -0.293609 -0.0257738 -0.0200759 -0.295126 -0.00778747 -0.0101703 -0.305497 -0.0212152 -0.0101703 -0.297754 -0.0223759 -0.00992135 -0.297085 -0.0303167 -0.0109675 -0.292506 -0.0236226 -0.0084151 -0.296366 -0.0303119 -0.00121637 -0.292509 -0.0237262 0.00564935 -0.296306 -0.0232836 0.00662593 -0.296561 -0.0222771 0.00761768 -0.297142 -0.0212152 0.0078297 -0.297754 -0.00778746 0.0078297 -0.305497 -0.0258088 0.0176163 -0.295106 -0.0284455 0.0150842 -0.293585 -0.0296912 0.0125331 -0.292867 -0.0238141 0.0158313 -0.296256 -0.030168 0.0106604 -0.292592 -0.0303097 0.00849861 -0.292511 0.021335 0.0118313 -0.328061 -0.0263117 0.0118313 -0.300587 0.0079073 0.0158297 -0.320318 0.00603586 0.0158297 -0.321529 0.00627067 0.0118297 -0.321404 0.00362543 0.0118297 -0.322499 0.00337453 0.0158297 -0.322569 0.00072314 0.0118297 -0.322992 0.000465601 0.0158297 -0.323004 -0.00223519 0.0118297 -0.322817 -0.00249648 0.0158297 -0.322769 -0.00452409 0.0158297 -0.322176 -0.00508478 0.0118297 -0.321973 -0.00662525 0.0158297 -0.321194 -0.00762455 0.0118297 -0.320538 -0.00974492 0.0118297 -0.318613 -0.00892621 0.0158297 -0.319458 -0.0107754 0.0158297 -0.317284 -0.0113982 0.0118297 -0.316265 -0.0121238 0.0158297 -0.314712 -0.0125093 0.0118297 -0.313567 -0.0128734 0.0158297 -0.311871 -0.0129892 0.0158297 -0.309792 -0.0129918 0.0118297 -0.31067 -0.012884 0.0118297 -0.30833 -0.0264143 -0.00904809 -0.301682 -0.0262729 -0.00366993 -0.301764 -0.0261214 0.00701392 -0.301851 -0.0267666 0.0054163 -0.301479 -0.0262372 0.0033297 -0.301785 -0.026811 -0.0071703 -0.301454 -0.0262372 0.0013297 -0.301785 -0.0206274 -0.0095759 -0.305019 -0.0247124 -0.0101204 -0.302664 -0.0220273 -0.00765473 -0.304212 -0.0220197 0.00531653 -0.304217 -0.0246804 0.00778712 -0.302682 -0.0206482 0.00722421 -0.305007 -0.0225125 -0.00760029 -0.313918 -0.0228484 -0.00751613 -0.308911 -0.0202838 -0.00999239 -0.312726 -0.0230889 -0.00623664 -0.310243 -0.0196587 -0.0100887 -0.305654 -0.021714 -0.00922833 -0.309285 -0.0219118 -0.00806308 -0.304279 -0.0204016 -0.00986126 -0.312954 -0.0188582 -0.0101703 -0.312232 -0.022674 -0.00619932 -0.314016 -0.0220914 -0.00839897 -0.313743 -0.0216428 -0.00618612 -0.317875 -0.0262134 -0.00567034 -0.318276 -0.0195672 -0.00967521 -0.317692 -0.0210855 -0.0081929 -0.317826 -0.0216384 -0.00617741 -0.317925 -0.0131444 -0.00718747 -0.328757 -0.0124248 -0.00980409 -0.326904 -0.0117444 -0.0101703 -0.324921 -0.0154511 -0.0062749 -0.327112 -0.016667 -0.0101648 -0.320616 -0.0148254 -0.00951408 -0.325243 -0.0154358 -0.00818667 -0.326396 -0.0182047 -0.00925633 -0.321722 -0.0180676 -0.00757421 -0.323944 -0.0191258 -0.00617733 -0.322826 -0.0191256 -0.0099281 -0.317635 -0.0212583 -0.00795798 -0.317869 -0.0201938 -0.00769021 -0.320516 -0.0124262 -0.00971433 -0.326791 -0.0147579 -0.0101703 -0.333191 -0.0147581 -0.00567034 -0.333192 -0.0130688 -0.00794933 -0.328556 -0.0126708 -0.0101703 -0.334395 -0.0126706 -0.0056703 -0.334394 -0.00974763 -0.00649653 -0.330901 -0.00884701 -0.00925975 -0.329824 -0.00955571 -0.00748807 -0.330713 -0.00968929 -0.00617714 -0.330909 0.00390116 -0.0078478 -0.33242 0.00245184 -0.0099115 -0.330571 0.000747124 -0.00733241 -0.332883 2.09231e-05 -0.00617074 -0.333063 -0.000834468 -0.00888199 -0.332009 -0.00449337 -0.00964823 -0.330591 -0.00636349 -0.00867498 -0.331229 -0.00354779 -0.00775807 -0.332424 -0.00373824 -0.00622352 -0.332757 -0.00304531 -0.0101933 -0.328971 -0.00702256 -0.0101703 -0.327643 -0.00846959 -0.00972612 -0.329277 -0.00624635 -0.00727126 -0.332021 0.00343486 -0.00920176 -0.331398 0.00396643 -0.00730634 -0.332536 0.00597644 -0.00567031 -0.336837 0.00597643 -0.0101703 -0.336837 0.00752253 -0.0101703 -0.327444 0.00829305 -0.0101703 -0.336215 0.0077189 -0.00962457 -0.329679 0.0078542 -0.00796417 -0.331219 0.0078903 -0.00617007 -0.331623 0.00829307 -0.00567033 -0.336215 0.0162685 -0.00616828 -0.326293 0.0156842 -0.00821017 -0.326237 0.00785393 -0.00889684 -0.330766 0.00801899 -0.00626391 -0.331638 0.0126302 -0.0101705 -0.324196 0.0129431 -0.00976725 -0.32654 0.0109313 -0.00813863 -0.329737 0.0132436 -0.00629157 -0.32893 0.00754957 -0.0101716 -0.327732 0.0154998 0.00655598 -0.32585 0.0200742 0.006951 -0.328488 0.0192323 0.00766417 -0.328003 0.0159336 -0.00801256 -0.326101 0.019069 -0.0100529 -0.327909 0.0143158 -0.00976373 -0.325168 0.0200738 -0.00931499 -0.328488 -0.0268112 -0.0071703 -0.301454 -0.0237398 -0.00798289 -0.296299 -0.0267172 -0.00811672 -0.301508 -0.0259613 -0.00942367 -0.301943 -0.0230588 -0.00934475 -0.296691 -0.0219478 -0.010068 -0.297332 -0.0247052 -0.0101699 -0.302668 0.00791103 0.00401436 -0.331662 0.0151153 0.0067907 -0.325705 0.0130499 0.00383766 -0.329074 0.0160144 0.00529135 -0.32625 0.00792038 0.00589117 -0.331047 0.0132633 0.00781694 -0.324505 0.0111904 0.00586674 -0.329628 0.00909833 0.00758028 -0.328586 0.00829307 0.0033297 -0.336215 0.00829305 0.0078297 -0.336215 0.00787797 0.00495446 -0.33149 0.00774322 0.00712877 -0.329956 0.00402538 0.00383466 -0.332662 0.00597644 0.0033297 -0.336837 0.00384625 0.00564345 -0.332278 0.00319389 0.00729016 -0.330882 -0.00940543 0.00521591 -0.330863 0.00402784 0.00415293 -0.332741 -0.00338451 0.0038941 -0.33296 0.00155862 0.00569153 -0.332546 0.00295165 0.00756401 -0.330545 -0.00121177 0.00638605 -0.332115 -0.00227351 0.0073841 -0.330789 -0.00179381 0.0078518 -0.329201 -0.00286984 0.00484349 -0.332748 -0.00533739 0.00645461 -0.331468 -0.00792152 0.00761233 -0.328973 -0.0126708 0.0078297 -0.334395 -0.00852336 0.00723344 -0.329438 -0.00458143 0.0078297 -0.328443 -0.009734 0.00457826 -0.330884 -0.0126706 0.0033297 -0.334394 -0.0131803 0.00383474 -0.328861 -0.0130351 0.00564541 -0.328463 -0.0147581 0.0033297 -0.333192 -0.0147579 0.0078297 -0.333191 -0.0125078 0.00729069 -0.327016 -0.0215708 0.00477856 -0.317881 -0.0125628 0.00722496 -0.32719 -0.0150607 0.0051573 -0.327177 -0.0132038 0.00432627 -0.328887 -0.0182217 0.00417408 -0.324196 -0.0155545 0.00743481 -0.323925 -0.0118377 0.00786108 -0.325075 -0.0161006 0.00645075 -0.325168 -0.0156106 0.00784698 -0.32106 -0.0205242 0.00420583 -0.320472 -0.0190416 0.0066409 -0.320992 -0.0191327 0.00760905 -0.317603 -0.0207404 0.0063123 -0.317796 -0.019329 0.00744338 -0.317672 -0.0262134 0.0078297 -0.318276 -0.0217525 0.00382064 -0.317884 -0.0262134 0.0033297 -0.318276 -0.0226573 0.0038337 -0.314007 -0.0208261 0.00732026 -0.313152 -0.022273 0.0056659 -0.313828 -0.0212989 0.00719961 -0.309447 -0.0224883 0.0059575 -0.308777 -0.0231257 0.00401162 -0.309751 -0.0203801 0.00751579 -0.305118 -0.0197121 0.00780349 -0.312944 -0.0225877 0.00499496 -0.313952 -0.0238141 0.00482971 -0.296256 -0.0237257 0.00567429 -0.296307 -0.0267671 0.00544509 -0.301479 -0.0263765 0.00653629 -0.301704 -0.0232037 0.00680073 -0.296608 -0.0252767 0.00762426 -0.302339 -0.0220885 0.00770039 -0.297251 -0.0242123 0.0078297 -0.302952 0.0243984 0.00291169 -0.333682 0.0267292 0.00639095 -0.331014 0.0255244 0.00779926 -0.332434 0.0161419 0.0205219 -0.329684 0.00800732 0.0187826 -0.324993 0.0146602 0.0187802 -0.32883 0.0244824 0.0149945 -0.338553 0.0200155 0.0193678 -0.333406 0.0209117 0.0213442 -0.334439 0.0224585 0.0161419 -0.336222 0.0228291 0.0195575 -0.336649 0.0239657 0.012913 -0.338785 0.00797045 0.0140209 -0.343451 0.00566027 0.017932 -0.33863 0.00757872 0.0176606 -0.340671 0.00426897 0.0182647 -0.341129 0.00485035 0.0141429 -0.345404 0.0048495 0.0169543 -0.341165 0.00637862 0.0146112 -0.342444 0.00615666 0.0192887 -0.335631 0.00372102 0.0128 -0.347898 0.00560604 0.012937 -0.344002 -0.0107205 0.0128006 -0.346538 -0.0111177 0.0126154 -0.344892 -0.00710579 0.012798 -0.347379 -0.0138927 0.00689728 -0.342281 -0.0155351 0.0016842 -0.343524 -0.0144389 0.00203267 -0.342332 -0.0155398 0.00770505 -0.343515 -0.0118414 0.00755206 -0.345001 -0.0117122 0.00203263 -0.344525 -0.0122272 0.00203194 -0.342973 -0.0119699 0.00690373 -0.343139 -0.0105738 0.00846589 -0.345943 -0.00706583 0.00853553 -0.347257 0.0143679 0.00851326 -0.344848 0.0202709 0.0084858 -0.34164 0.0250623 0.000772035 -0.339232 0.0231984 0.00053335 -0.338855 0.0208507 -0.0105474 -0.34297 0.0198697 -0.00446267 -0.343542 0.0229011 -0.010549 -0.341593 0.0252489 -0.00446575 -0.339696 0.0227258 -0.00346566 -0.341726 0.0250862 -0.00955312 -0.339879 0.0187063 -0.00446567 -0.341875 0.0153687 -0.00932939 -0.341602 0.0150629 -0.0044643 -0.341906 0.0151577 -0.00446564 -0.343693 0.00933146 -0.00446566 -0.347351 0.0124049 -0.0105491 -0.346995 0.0158438 -0.00446277 -0.345648 0.0125626 -0.0034654 -0.346947 0.00506442 -0.00445095 -0.346604 0.00529039 -0.00954904 -0.348177 0.00528177 -0.00446566 -0.348134 -0.00157214 -0.00446126 -0.348464 -0.0015715 -0.00954442 -0.348464 0.000281179 -0.0105531 -0.349013 0.0021974 -0.0034655 -0.348962 0.00329188 -0.0105492 -0.348867 -0.00547421 -0.00931878 -0.346502 -0.00567733 -0.00954331 -0.348074 -0.00567733 -0.00446566 -0.348074 -0.012197 -0.00954362 -0.347043 -0.00910225 -0.00346569 -0.347936 -0.0110771 -0.0105502 -0.347401 -0.00884847 -0.0105491 -0.347986 -0.0059384 -0.00446281 -0.348551 -0.0122172 -0.00446003 -0.347033 -0.0123745 -0.00446566 -0.346538 -0.0123588 -0.00422883 -0.346493 -0.0166619 -0.00296973 -0.344698 -0.0163902 -0.00446576 -0.345326 -0.0166746 -0.00954337 -0.345258 -0.00738551 -0.0227718 -0.334174 -0.00493949 -0.0245953 -0.339417 -0.00547664 -0.023783 -0.343082 -0.00591031 -0.0207071 -0.346132 -0.00634945 -0.0157484 -0.348024 -0.0117999 -0.0166399 -0.346433 -0.0100436 -0.0240838 -0.341326 -0.0111144 -0.0213566 -0.344456 -0.00875614 -0.0245394 -0.337588 -0.00869455 -0.0186956 -0.346554 -0.00901805 -0.022015 -0.344555 -0.00446399 -0.0238082 -0.336507 -0.00153279 -0.0171375 -0.347613 -0.000939998 -0.0159427 -0.348518 -0.000985286 -0.019303 -0.347334 -0.000862002 -0.0234403 -0.344164 0.00394474 -0.0241354 -0.342464 -0.000556902 -0.0241866 -0.337798 0.00420566 -0.0228907 -0.34461 0.00456839 -0.019853 -0.34675 0.00470279 -0.0160329 -0.348162 -0.000698147 -0.0245566 -0.340535 0.00173989 -0.0210584 -0.346325 0.00275321 -0.0183503 -0.347586 0.0034965 -0.0245546 -0.339259 -0.00498835 -0.0192358 -0.343266 -0.00529513 -0.0163979 -0.34541 -0.00479222 -0.0237893 -0.341906 -0.00527332 -0.021374 -0.345255 -0.00448582 -0.0216593 -0.339759 -0.00426604 -0.0239307 -0.338226 0.00411038 -0.0244489 -0.340476 0.00323624 -0.0237763 -0.336626 -0.000197309 -0.0227443 -0.335269 0.0136319 -0.0189343 -0.340136 0.0122519 -0.0208757 -0.336646 0.0111606 -0.021573 -0.333947 0.0149375 -0.0155502 -0.343203 0.0148021 -0.0170238 -0.33987 0.0133969 -0.0227242 -0.331448 0.0143322 -0.0240709 -0.333299 0.0170767 -0.0238207 -0.330772 0.0213565 -0.0238023 -0.335722 0.0238424 -0.0194295 -0.338594 0.0217137 -0.0182678 -0.340853 0.0245943 -0.0159089 -0.339654 0.0197583 -0.0169427 -0.342696 0.0197686 -0.0226775 -0.338977 0.0175089 -0.0236907 -0.338797 0.0217345 -0.0201611 -0.339782 0.0194224 -0.0246127 -0.333491 0.0160402 -0.0245465 -0.336263 -0.0153137 -0.0212119 -0.327451 -0.0135624 -0.021213 -0.328856 -0.018242 -0.0212124 -0.324432 -0.0216447 -0.0212124 -0.318556 -0.0239026 -0.0212133 -0.311109 -0.0223594 -0.0212114 -0.31637 -0.0230035 -0.0212127 -0.307112 -0.0232163 -0.0212121 -0.309899 -0.016828 -0.0212158 -0.312284 -0.0169806 -0.0212179 -0.310585 -0.0160588 -0.0212158 -0.315724 -0.0133984 -0.0212158 -0.320585 -0.0102686 -0.0212158 -0.323508 0.00800619 -0.0216094 -0.333173 0.00182993 -0.0218044 -0.334625 -0.00577117 -0.0216219 -0.333839 -0.0320361 -0.019738 -0.303965 -0.0263808 -0.0223777 -0.305129 -0.0337343 -0.0158737 -0.303254 -0.030625 -0.0191482 -0.303123 -0.0325612 -0.0145124 -0.321347 -0.0339733 -0.00784507 -0.301626 -0.0334221 -0.00893961 -0.299588 -0.0327083 -0.00870176 -0.297503 -0.0276902 -0.0205974 -0.302909 -0.0316285 -0.0177441 -0.302192 -0.0320513 -0.0162287 -0.299764 -0.0330062 -0.0157128 -0.301936 -0.0339243 -0.013622 -0.302555 -0.0342643 -0.0118976 -0.302749 -0.0349398 -0.0125999 -0.309449 -0.0345324 -0.0141947 -0.311661 -0.0336949 -0.0126385 -0.319249 -0.0287647 -0.013588 -0.329435 -0.0213873 -0.0141929 -0.337164 -0.0193702 -0.012723 -0.33901 -0.021343 -0.0112052 -0.337748 -0.0271629 -0.0126896 -0.331951 -0.028653 -0.0114828 -0.330115 -0.0331155 -0.0104714 -0.321482 -0.0321479 -0.0127091 -0.32361 -0.0346642 -0.0127362 -0.314077 -0.0350106 -0.0104729 -0.311684 -0.0343947 -0.0131091 -0.30452 -0.0320218 -0.00995219 -0.295856 -0.029994 -0.0140881 -0.292693 -0.0286384 -0.0171331 -0.293474 -0.0273604 -0.0187626 -0.294211 -0.0253277 -0.0202997 -0.295387 -0.0326453 -0.0111418 -0.297337 -0.0315285 -0.0156804 -0.297366 -0.0302692 -0.0162287 -0.295305 -0.0301098 -0.0183027 -0.298973 -0.0292984 -0.0177603 -0.295753 -0.0285435 -0.0190617 -0.297367 -0.0268806 -0.0203984 -0.299245 -0.033371 -0.0121841 -0.299588 -0.0329974 -0.013861 -0.299462 -0.0322965 -0.0133325 -0.297067 -0.0309781 -0.0172968 -0.298767 -0.0298016 -0.0194856 -0.302516 -0.027533 -0.0198087 -0.297765 -0.0238209 -0.0209615 -0.296266 -0.0325993 -0.0150692 -0.299589 -0.0307867 -0.0150692 -0.295054 -0.0312915 -0.0133345 -0.294794 -0.0314936 -0.0113306 -0.294729 -0.0303153 -0.0113399 -0.292507 -0.0268112 0.0048297 -0.301454 -0.0238141 -0.0071703 -0.296256 -0.0126037 0.0118297 -0.313298 -0.0129735 0.0118297 -0.310212 -0.0263117 0.0118297 -0.300587 -0.012884 0.0118297 -0.30833 -0.0274931 0.0118297 -0.303141 -0.0167548 0.0118297 -0.312725 -0.0146169 0.0118297 -0.318735 -0.0110974 0.0118297 -0.316821 -0.0160716 0.0118297 -0.315461 -0.0119377 0.0118297 -0.322144 -0.00213486 0.0118297 -0.322856 -0.0017657 0.0118297 -0.32694 -0.0056778 0.0118297 -0.321727 -0.00592428 0.0118297 -0.325967 -0.00909403 0.0118297 -0.324367 -0.00876894 0.0118297 -0.319635 0.000992207 0.0118297 -0.322974 0.00186669 0.0118297 -0.326908 0.0041086 0.0118297 -0.32237 0.00536767 0.0118297 -0.326168 0.00790904 0.0118297 -0.320319 0.021335 0.0118297 -0.328061 0.0171712 0.0118297 -0.330277 0.0196214 0.0118297 -0.330789 -0.0263117 0.0157343 -0.300587 -0.0272921 0.0182429 -0.30229 -0.0238151 0.018488 -0.296257 -0.0222248 0.000830317 -0.304098 -0.0269372 0.0013297 -0.304532 -0.0229973 0.000830211 -0.308272 -0.0272941 0.0013297 -0.306763 -0.026987 0.00133215 -0.315896 -0.022684 0.00083001 -0.314013 -0.0274751 0.0013297 -0.309868 -0.0226391 -0.0031703 -0.313999 -0.0226391 0.000829698 -0.313999 -0.02288 0.000829698 -0.312314 -0.022902 -0.0031703 -0.312082 -0.0229958 -0.0031703 -0.309625 -0.0230014 0.000829698 -0.309259 -0.0228155 -0.0031703 -0.307095 -0.0226608 0.000829698 -0.306065 -0.0222381 -0.00317121 -0.30409 -0.0228812 -0.0031703 -0.307922 -0.0272288 -0.0036703 -0.306428 -0.0268974 -0.00367155 -0.315982 -0.0226523 -0.00317031 -0.314003 -0.0274453 -0.0036703 -0.310971 -0.0229515 -0.0031703 -0.311023 -0.0226628 -0.00616953 -0.31401 -0.0229718 -0.00617031 -0.310765 -0.0274068 -0.0056703 -0.312064 -0.0273901 -0.0056703 -0.30784 -0.0228812 -0.00617031 -0.307922 -0.027081 -0.0056703 -0.305298 -0.0262491 -0.00567021 -0.301778 -0.0222389 -0.00616735 -0.30409 -0.0268503 -0.0056703 -0.315965 -0.0268486 0.0033297 -0.315965 -0.022654 0.00382983 -0.314005 -0.027328 0.0033297 -0.312976 -0.0274448 0.0033297 -0.309021 -0.0229812 0.0038297 -0.310396 -0.0223013 0.00382695 -0.304055 -0.026914 0.0033297 -0.304535 -0.0263185 0.0013297 -0.301829 -0.0272187 0.0013297 -0.306134 -0.0263321 0.0033297 -0.301836 -0.0272187 0.0033297 -0.306134 -0.0274841 0.0013297 -0.309388 -0.0274841 0.0033297 -0.309388 -0.0273592 0.0013297 -0.312679 -0.0273592 0.0033297 -0.312679 -0.0262134 -0.0056703 -0.318276 -0.0268355 -0.0036703 -0.31596 -0.0268355 -0.0056703 -0.31596 -0.0268355 -0.0101703 -0.31596 -0.0268355 0.0013297 -0.31596 -0.0268355 0.0078297 -0.31596 -0.0268355 0.0033297 -0.31596 -0.0147579 0.0033297 -0.333191 -0.0262199 0.0013297 -0.318291 -0.0246144 0.0013297 -0.322237 -0.0262314 0.0033297 -0.318301 -0.0246144 0.0033297 -0.322237 -0.0229269 0.0013297 -0.325164 -0.0229269 0.0033297 -0.325164 -0.0208798 0.0013297 -0.327878 -0.0208798 0.0033297 -0.327878 -0.0184976 0.0013297 -0.330333 -0.0182447 0.0033297 -0.33056 -0.0147579 -0.00367026 -0.333191 -0.0101327 -0.0036703 -0.335554 -0.0126708 0.0013297 -0.334395 -0.0158166 0.0013297 -0.332482 -0.0147579 0.0013297 -0.333191 -0.013014 -0.0101703 -0.334213 -0.013014 0.0078297 -0.334213 -0.0126708 0.0033297 -0.334395 0.0082959 -0.00367043 -0.336227 -0.0101327 0.0013297 -0.335554 -0.0101327 0.0033297 -0.335554 -0.00708846 0.0013297 -0.336561 -0.00708846 0.0033297 -0.336561 -0.00391951 0.0013297 -0.33721 -0.00391951 0.0033297 -0.33721 -0.000667327 0.0013297 -0.337484 -0.000667327 0.0033297 -0.337484 0.00262368 0.0033297 -0.337368 0.00262471 0.0013297 -0.337368 0.00597629 0.00332879 -0.336837 0.00597433 -0.00566794 -0.336839 0.0122157 0.0033297 -0.334635 0.0083155 0.00132976 -0.336232 0.00830667 0.0033297 -0.336221 0.0122065 0.0013297 -0.33464 0.0151454 0.0013297 -0.332952 0.0151454 0.0033297 -0.332952 0.0178617 0.0013297 -0.33091 0.0178617 0.0033297 -0.33091 0.00830692 -0.00567032 -0.336227 0.0122157 -0.00567032 -0.334635 0.0122157 -0.0036703 -0.334635 0.0151454 -0.00567032 -0.332952 0.0151454 -0.0036703 -0.332952 0.0178617 -0.0036703 -0.33091 0.0178617 -0.00567032 -0.33091 -0.0101327 -0.0056703 -0.335554 -0.00708846 -0.0056703 -0.336561 -0.00708846 -0.0036703 -0.336561 -0.00391951 -0.0056703 -0.33721 -0.00391951 -0.0036703 -0.33721 -0.000667327 -0.0036703 -0.337484 -0.000667327 -0.0056703 -0.337484 0.00262368 -0.0056703 -0.337368 0.00262498 -0.0036703 -0.337368 -0.0216963 -0.00567041 -0.326959 -0.0226593 -0.00367014 -0.325589 -0.020779 -0.00367028 -0.328002 -0.0185672 -0.00567034 -0.330312 -0.0162057 -0.00567032 -0.332217 -0.0182099 -0.00367031 -0.330664 -0.0147579 -0.00567034 -0.333191 -0.0245616 -0.00367011 -0.322408 -0.024734 -0.00567011 -0.322112 -0.0262215 -0.00366958 -0.318285 -0.0273592 -0.0036703 -0.312679 -0.0273592 -0.0056703 -0.312679 -0.0274841 -0.0036703 -0.309388 -0.0274841 -0.0056703 -0.309388 -0.0272187 -0.0036703 -0.306134 -0.0272187 -0.0056703 -0.306134 -0.0263321 -0.0036703 -0.301836 -0.0263185 -0.0056703 -0.301829 -0.0262256 -0.00567162 -0.318278 -0.0216206 -0.00616938 -0.317875 -0.0250492 -0.00567032 -0.321295 -0.0238012 -0.00567033 -0.323735 -0.0201635 -0.00567029 -0.328737 -0.0195092 -0.0061696 -0.322295 -0.0224599 -0.00567027 -0.325835 -0.0147669 -0.00567047 -0.33321 -0.0131789 -0.00617002 -0.328856 -0.0174075 -0.00567015 -0.331265 -0.0160252 -0.0061687 -0.326556 0.00402919 -0.00616822 -0.332669 0.00267372 -0.00566984 -0.337404 0.00597643 -0.00567031 -0.336837 -0.00971307 -0.00616896 -0.330871 -0.0126841 -0.00567027 -0.334441 -0.00838349 -0.00567049 -0.336202 -0.00571668 -0.00617005 -0.33231 -0.00323259 -0.0056704 -0.337364 -0.000261369 -0.0061705 -0.33306 0.0141004 -0.00567022 -0.333679 0.00789074 -0.00617016 -0.331617 0.00840969 -0.00566845 -0.336264 0.0109459 -0.00617031 -0.330207 0.0177602 -0.00567026 -0.330979 0.0140632 -0.00617028 -0.328249 0.0202638 -0.00567158 -0.328597 0.0202626 0.00132855 -0.328597 0.0162682 0.00083038 -0.326293 0.0160521 0.00133039 -0.332384 0.00796356 0.000829915 -0.331654 0.00830549 0.00133093 -0.33628 0.012523 0.00132966 -0.334466 0.0126591 0.000829727 -0.329236 0.00830346 0.00332247 -0.336319 0.0126485 0.00332971 -0.334401 0.015856 0.00332876 -0.332501 0.0112152 0.00383049 -0.330139 0.01431 0.0038297 -0.327999 0.0202848 0.00333537 -0.328628 0.0162537 0.00382587 -0.326285 0.0138228 -0.00317119 -0.328419 0.0202646 -0.00366819 -0.328599 0.0162489 -0.00317112 -0.326282 0.0131445 -0.0036698 -0.334182 0.0103007 -0.00317057 -0.330594 0.0170909 -0.00367123 -0.331595 0.00839611 -0.00367129 -0.336265 0.00788784 -0.00317032 -0.331601 0.0078878 -0.0031703 -0.331601 0.007913 0.000829697 -0.331619 0.010176 -0.0031703 -0.330642 0.0107935 0.000829698 -0.330317 0.0127537 -0.0031703 -0.329148 0.0129368 0.000829698 -0.329025 0.0147683 -0.0031703 -0.327644 0.0149321 0.000829698 -0.327505 -0.00899042 0.00332945 -0.336001 -0.00971016 0.00382948 -0.330857 -0.0126829 0.00332968 -0.334412 -0.00459945 0.00332891 -0.337149 0.00355022 0.00332957 -0.337276 -0.000871586 0.00382971 -0.333003 -0.000697232 0.0033297 -0.337492 -0.00563434 0.00382932 -0.332355 0.00597643 0.0033297 -0.336837 0.00399167 0.0038271 -0.332707 -0.0262353 0.00333075 -0.31828 -0.013184 0.00382945 -0.328858 -0.0147653 0.00332985 -0.333207 -0.0163954 0.0038297 -0.326103 -0.0185787 0.00332947 -0.33034 -0.0225766 0.0033302 -0.325785 -0.0188002 0.00382938 -0.323299 -0.0217175 0.00382633 -0.317902 -0.0247446 0.00332971 -0.321972 0.0269394 0.00359484 -0.332591 0.0262055 0.00384115 -0.333138 0.0264848 0.00489812 -0.33229 0.0264504 0.00699623 -0.332829 0.0244892 0.00706261 -0.333602 0.0250519 0.00698004 -0.334444 0.0251817 0.00606793 -0.332844 0.0260905 0.00625123 -0.333372 0.0251855 0.0049035 -0.332991 0.0262147 0.00508492 -0.333357 0.0252139 0.00449624 -0.333804 0.0248787 0.00110398 -0.334371 0.025659 0.000268442 -0.332315 0.025687 -0.000381807 -0.33298 0.0260106 -0.00111097 -0.33337 -0.0170038 0.0187816 -0.310605 -0.00895981 0.0118297 -0.324434 -0.010483 0.0187816 -0.323368 -0.0118996 0.0187816 -0.322124 -0.010483 0.0118297 -0.323368 -0.0118996 0.0118297 -0.322124 -0.0131638 0.0187816 -0.320738 -0.0131638 0.0118297 -0.320738 -0.0142627 0.0187816 -0.319229 -0.0142627 0.0118297 -0.319229 -0.0149736 0.0187816 -0.318025 -0.0149736 0.0118297 -0.318025 -0.0157575 0.0118297 -0.316349 -0.0157575 0.0187816 -0.316349 -0.016353 0.0187816 -0.314605 -0.016353 0.0118297 -0.314605 -0.0167549 0.0187816 -0.312814 -0.0167549 0.0118297 -0.312814 -0.0170023 0.0118297 -0.310604 -0.00736705 0.0187816 -0.325309 -0.00736705 0.0118297 -0.325309 -0.00574074 0.0118297 -0.325991 -0.00574074 0.0187816 -0.325991 -0.00404032 0.0118297 -0.326503 -0.00404032 0.0187816 -0.326503 -0.00228318 0.0187816 -0.326837 -0.00228318 0.0118297 -0.326837 -0.000487002 0.0118297 -0.326985 -0.000487002 0.0187816 -0.326985 0.00120289 0.0187816 -0.326951 0.00120289 0.0118297 -0.326951 0.00301532 0.0187816 -0.326725 0.00301532 0.0118297 -0.326725 0.00480219 0.0187816 -0.326303 0.00480219 0.0118297 -0.326303 0.00654064 0.0118297 -0.325688 0.00654064 0.0187816 -0.325688 0.00800757 0.0118297 -0.324993 0.00800759 0.0187816 -0.324993 -0.0072849 0.0187779 -0.332059 0.00343391 0.0187783 -0.333003 -0.00261161 0.0187785 -0.333241 0.00554327 0.0187781 -0.332552 0.00953761 0.018778 -0.331209 0.0117247 0.0187779 -0.330047 0.0110512 0.0187805 -0.331376 0.00613004 0.0187816 -0.32588 0.00210067 0.0187816 -0.326923 -0.00193201 0.0187816 -0.326901 -0.00951813 0.0187789 -0.331189 -0.00580144 0.0187816 -0.326028 0.0230811 0.0194381 -0.337485 0.0185706 0.021635 -0.331734 0.0147792 0.0182004 -0.335779 0.0181763 0.0138183 -0.340959 0.0167601 0.0165606 -0.33867 0.0164709 0.0139928 -0.339727 0.0152052 0.0132381 -0.3439 0.0143007 0.0127931 -0.345268 0.0038731 0.0214955 -0.338369 0.00349903 0.0200391 -0.335954 0.00447179 0.0212113 -0.342519 0.00431935 0.0183176 -0.341461 0.00484489 0.0147009 -0.345092 0.00492857 0.0182755 -0.345685 -0.00154765 0.0135839 -0.348026 0.00400318 0.0125798 -0.346381 0.00497276 0.0131929 -0.347642 -0.000997227 0.0126547 -0.347021 -0.00630407 0.0125947 -0.346055 -0.00563865 0.0133991 -0.347749 -0.0122021 0.0134591 -0.346073 -0.00497486 0.0140084 -0.344408 -0.00322236 0.0132529 -0.343644 -0.00145322 0.0167347 -0.342276 -0.00366904 0.0160921 -0.341705 -0.00155538 0.0141088 -0.344718 -0.00360286 0.0190285 -0.336336 -0.00159317 0.01903 -0.335977 -0.00098924 0.0199847 -0.335982 -0.00397389 0.0185867 -0.338783 -0.00484326 0.0177752 -0.342122 -0.00216567 0.0179793 -0.338847 -0.00117365 0.018984 -0.339847 -0.0161871 0.00203292 -0.344971 -0.0166629 0.00858498 -0.34466 -0.0204653 0.00849402 -0.341568 -0.0161758 0.00711056 -0.344929 -0.0119863 0.00828372 -0.34652 -0.0123457 0.00711055 -0.34646 -0.00568046 0.00786539 -0.348072 -0.00546589 0.00772004 -0.346524 -0.00359869 0.00203209 -0.344817 -0.00545816 0.00181377 -0.346545 -0.00506053 0.00203264 -0.345516 -0.0044618 0.0068964 -0.344997 -0.000968887 0.00841441 -0.347223 -0.00155549 0.00855141 -0.348462 0.00470688 0.00858454 -0.348156 -0.00190034 0.0020319 -0.345341 -0.001499 0.00173728 -0.34692 -0.00218842 0.00689648 -0.345188 -0.00149856 0.00688581 -0.346919 0.00506113 0.00824429 -0.346688 0.00506597 0.00203215 -0.345702 0.00511857 0.00689305 -0.345535 0.00640483 0.00203134 -0.344386 0.00970347 0.0084205 -0.345951 0.00981212 0.008578 -0.34719 0.00891616 0.00687338 -0.345577 0.00933228 0.00711053 -0.347389 0.015171 0.00713912 -0.343697 0.0154755 0.00828367 -0.345192 0.00636366 0.00689917 -0.344373 0.0075844 0.0020316 -0.344353 0.00896665 0.00188942 -0.34584 0.00794402 0.00689592 -0.344498 0.018706 0.00737759 -0.341873 0.0197188 0.00826402 -0.342992 0.0173846 0.00203137 -0.340733 0.0187058 0.00203294 -0.341872 0.0171096 0.00689703 -0.340829 0.0250653 0.00711055 -0.339228 0.0250074 0.00778933 -0.33994 0.0252162 0.00711055 -0.339639 0.0252271 0.00203291 -0.339554 0.0199144 -0.00954328 -0.343532 0.0194788 -0.00954329 -0.343211 0.0200158 -0.00297505 -0.343007 0.0194788 -0.00446566 -0.343211 0.0205802 -0.00233129 -0.338861 0.00976658 -0.0095438 -0.347757 0.00983913 -0.00446562 -0.347745 0.00932986 -0.00954494 -0.347365 0.00940408 -0.00446566 -0.34754 0.0089651 -0.0044325 -0.345851 0.0157457 -0.00954773 -0.345685 0.0040565 -0.00296824 -0.346806 0.00476644 -0.00298164 -0.348243 0.0049522 -0.00954329 -0.34869 0.00516515 -0.00446565 -0.348666 -0.00144909 -0.00954329 -0.348905 -0.00142021 -0.00446285 -0.348956 -0.000575147 -0.00296756 -0.348535 -0.000696006 -0.00296884 -0.347032 -0.00149899 -0.00445603 -0.346921 -0.00592444 -0.0095458 -0.348536 -0.00616352 -0.00304111 -0.348011 -0.021438 -0.0109507 -0.341524 -0.0208668 -0.00932908 -0.338357 -0.021185 -0.00931801 -0.3402 -0.0212076 -0.00433114 -0.340232 -0.021039 -0.00446513 -0.338123 -0.0161204 -0.00296864 -0.343361 -0.0179726 -0.00346562 -0.344615 -0.0202043 -0.00346558 -0.343366 -0.0192673 -0.0105494 -0.343927 -0.00897948 -0.0239257 -0.336706 -0.0112438 -0.0219362 -0.343264 -0.012063 -0.0173807 -0.346027 0.018816 -0.0210699 -0.341135 -0.0175254 -0.0216447 -0.32718 -0.0196726 -0.0212122 -0.322304 -0.0354515 -0.0206635 -0.303413 -0.0301728 -0.0242335 -0.304424 -0.0334674 -0.0228151 -0.303794 -0.0313617 -0.021209 -0.304198 -0.0353223 -0.0151959 -0.303785 -0.0339959 -0.00316697 -0.301652 -0.0328622 -0.00946414 -0.300128 -0.0320199 -0.00865762 -0.298592 -0.0324834 -0.00555881 -0.296981 -0.0316076 -0.00331329 -0.297393 -0.0325297 -0.00137927 -0.297089 -0.0339475 0.00102559 -0.301462 -0.0348973 0.0102992 -0.309262 -0.0349608 0.00914401 -0.312046 -0.0331183 0.00803992 -0.321474 -0.0336753 0.0102766 -0.319204 -0.0298679 0.0102898 -0.328016 -0.0285363 0.00845901 -0.330314 -0.0216917 0.00852092 -0.337502 -0.0213664 0.0120265 -0.337082 -0.0233594 0.010265 -0.335931 -0.0197281 0.0101763 -0.33884 -0.0270749 0.010192 -0.332082 -0.0281136 0.0118033 -0.3301 -0.0325995 0.0120791 -0.321237 -0.0321907 0.0102079 -0.323588 -0.0345568 0.011708 -0.311697 -0.0324349 0.0142808 -0.302035 -0.0292619 0.0173759 -0.302615 -0.0308406 0.0161377 -0.302337 -0.0321109 0.00241924 -0.296087 -0.0314792 0.00631562 -0.294718 -0.0327329 0.0086098 -0.297549 -0.027244 0.0182483 -0.302149 -0.0299371 0.016148 -0.299269 -0.0317213 0.0133335 -0.297956 -0.0325994 0.0126364 -0.299589 -0.0332895 0.0106437 -0.299675 -0.0338655 0.0113263 -0.302469 -0.0340842 0.00688846 -0.301899 -0.0264629 0.0179656 -0.298299 -0.0292357 0.0154174 -0.295807 -0.0309596 0.0148548 -0.298702 -0.0322965 0.0108999 -0.297067 -0.0314877 -0.00122383 -0.294728 -0.0314798 0.00894456 -0.294709 -0.0303134 0.00889178 -0.292508 -0.0301496 0.0108072 -0.292602 -0.0312773 0.0109925 -0.294815 -0.0294627 0.0131438 -0.292999 -0.0305085 0.0133478 -0.29519 -0.0279441 0.0157294 -0.293874 -0.0279576 0.0171188 -0.297642 -0.0257106 0.0176373 -0.295162 -0.0373882 -0.0151345 -0.308446 -0.0231604 -0.0125407 -0.336166 -0.0362381 -0.0108476 -0.306084 -0.0348737 -0.0117915 -0.305826 -0.0354347 -0.0113393 -0.30837 -0.0366448 -0.0108331 -0.3042 -0.0342649 -0.00446546 -0.302453 -0.034765 -0.00932822 -0.30311 -0.0362292 -0.00432581 -0.303296 -0.0238218 0.0187807 -0.306641 -0.0252278 0.0205816 -0.305829 -0.0169804 0.0187816 -0.310585 -0.0169804 0.0118297 -0.310585 -0.0268355 0.0013297 -0.31596 -0.0226392 0.000829699 -0.313999 -0.0226392 -0.0031703 -0.313999 -0.0268355 -0.0036703 -0.31596 -0.00191844 -0.00367017 -0.337446 -0.00711934 -0.00367112 -0.336619 -0.00569277 -0.00317059 -0.332316 -0.0126848 -0.00367026 -0.334441 -0.00971229 -0.00316982 -0.330871 0.00201671 -0.00367035 -0.337442 -0.000224433 -0.00316959 -0.333061 0.00597622 -0.00366869 -0.336859 0.00402155 -0.00317223 -0.332658 -0.0147669 -0.00366992 -0.33321 -0.0131789 -0.00317108 -0.328856 -0.0160211 -0.00317104 -0.32656 -0.0174075 -0.00367045 -0.331265 -0.0229591 -0.00367031 -0.325081 -0.0195092 -0.0031703 -0.322295 -0.0201752 -0.00367064 -0.328724 -0.0262255 -0.00367029 -0.318278 -0.0216206 -0.00317116 -0.317875 -0.0244452 -0.00367028 -0.322554 0.00829307 0.00132969 -0.336215 0.00788773 0.000829694 -0.331601 0.00788779 -0.0031703 -0.331601 0.00597644 0.0013297 -0.336837 0.00401578 0.0008297 -0.332641 0.00401578 -0.0031703 -0.332641 0.00597643 -0.0036703 -0.336837 0.00597643 0.00132969 -0.336837 0.00401594 0.000829662 -0.332641 0.00226589 0.00132973 -0.337451 -0.00263173 0.00132955 -0.337385 0.000346663 0.000829009 -0.333056 -0.0126706 0.00132974 -0.334394 -0.0102377 0.00132982 -0.335537 -0.00971024 0.000830504 -0.330857 -0.00696758 0.00132984 -0.336604 -0.00565922 0.000830183 -0.332349 -0.0126706 -0.0036703 -0.334394 -0.00969934 -0.00317031 -0.330843 -0.0126708 -0.0056703 -0.334395 -0.00969934 0.000829699 -0.330843 -0.0126706 0.0013297 -0.334394 -0.0147579 -0.00367014 -0.333191 -0.0147581 0.0013297 -0.333192 -0.0131725 0.000829697 -0.32884 -0.0262353 0.00132871 -0.31828 -0.0217176 0.000833065 -0.317902 -0.0247446 0.00132968 -0.321972 -0.0187935 0.000829533 -0.323308 -0.022057 0.00132957 -0.32651 -0.0160316 0.000830388 -0.326508 -0.0147653 0.00132955 -0.333207 -0.0131843 0.000828502 -0.328858 -0.018057 0.00133024 -0.330773 -0.0262134 -0.0036703 -0.318276 -0.0215994 -0.0031703 -0.317871 -0.0215994 0.000829698 -0.317871 -0.0262134 0.0013297 -0.318276 0.026947 0.00387007 -0.333584 0.0275526 0.0051977 -0.332854 0.0268689 0.00595291 -0.332807 0.0257574 0.00701677 -0.334862 0.0251848 0.00574411 -0.334237 0.0263109 -0.000921311 -0.334288 0.0252276 -0.000407047 -0.334858 -0.0225455 0.0187807 -0.317817 -0.0215175 0.018778 -0.318805 -0.0133232 0.0187816 -0.320528 -0.0194735 0.0187789 -0.322985 -0.018201 0.018778 -0.324443 -0.0150905 0.0187791 -0.32769 -0.00877593 0.0187816 -0.324561 -0.013297 0.0187779 -0.329023 -0.0109582 0.0187816 -0.323055 -0.0144756 0.0187816 -0.318877 -0.0160588 0.0187816 -0.315724 -0.0170568 0.018783 -0.310565 -0.0230108 0.0187742 -0.307108 -0.02323 0.0187778 -0.310022 -0.0231413 0.018778 -0.312351 -0.0240636 0.0187823 -0.311136 0.019742 0.0146039 -0.342679 0.0182656 0.0201624 -0.340074 0.0245306 0.0137884 -0.339651 0.0238822 0.0168867 -0.338648 0.0220229 0.0207457 -0.336512 0.018297 0.0220773 -0.332201 0.0160079 0.0203232 -0.329569 0.0167109 0.021912 -0.33742 0.0206371 0.0218026 -0.334895 0.014839 0.0220086 -0.334203 0.01283 0.0183277 -0.33821 0.0135953 0.0172143 -0.337476 0.0117332 0.0188391 -0.333805 0.0150701 0.0136695 -0.340256 0.00455667 0.0176451 -0.34665 -0.000535424 0.0133489 -0.34856 -0.0010117 0.0163726 -0.347505 0.00472621 0.0136586 -0.348154 0.00329142 0.0216884 -0.337246 0.00362824 0.0221301 -0.34017 0.00423211 0.0204525 -0.344569 0.00261018 0.0202942 -0.335138 -0.000838837 0.0211961 -0.343697 -0.00092573 0.0196939 -0.345576 -0.000742721 0.0219944 -0.341574 0.0039761 0.0216009 -0.342651 0.00173495 0.0189584 -0.346094 -0.000519244 0.0213535 -0.336838 -0.000636943 0.0220788 -0.339188 0.00192161 0.0165508 -0.347391 -0.00483725 0.022105 -0.338667 -0.00453975 0.020307 -0.334851 -0.00925391 0.0221323 -0.339048 -0.008199 0.0216029 -0.336037 -0.0115159 0.0165581 -0.345618 -0.0117415 0.0138236 -0.346512 -0.00633894 0.0133669 -0.348029 -0.0053213 0.0217545 -0.342006 -0.00566253 0.020416 -0.344404 -0.00885991 0.0163035 -0.346498 -0.0102867 0.0212983 -0.342067 -0.0109757 0.0190864 -0.344426 -0.00525768 0.0145648 -0.34516 -0.00451584 0.0217716 -0.339977 -0.00459476 0.0189095 -0.340519 -0.00518983 0.0197325 -0.344672 -0.0167048 0.000544917 -0.344748 -0.0204602 0.00817189 -0.339442 -0.0123284 0.000608175 -0.346483 -0.0116213 0.00102293 -0.345113 -0.0123223 0.00711054 -0.346988 -0.0123422 0.00203 -0.346962 -0.00885104 0.00103286 -0.348 -0.0109602 0.00811705 -0.347434 -0.00867207 0.00811639 -0.348026 -0.00567826 0.00133763 -0.348074 0.00330285 0.00103281 -0.348867 0.000757503 0.00103289 -0.349002 0.00245054 0.00811622 -0.348946 -0.000296427 0.00811095 -0.349 0.00528834 0.00711053 -0.348146 0.00528146 0.00155169 -0.348134 0.0135054 0.00103272 -0.346608 0.0132097 0.0081164 -0.346705 0.0112325 0.00811651 -0.347353 0.0113304 0.00103267 -0.347326 0.0194905 0.00711053 -0.343248 0.0157494 0.00689789 -0.341278 0.0148926 0.00689289 -0.342646 0.0151067 0.00203166 -0.341911 0.0151674 0.00201002 -0.343693 0.0208883 0.00811645 -0.34295 0.0227232 0.00103287 -0.341727 0.0229874 0.00811625 -0.341529 0.0250093 0.00201453 -0.339942 0.0192179 -0.00298773 -0.341689 0.0233913 -0.00297155 -0.338716 0.0203431 -0.00080518 -0.338461 0.0158138 -0.00446566 -0.345103 0.00983697 -0.00298569 -0.345697 0.00987741 -0.00297765 -0.347273 0.0146948 -0.00297217 -0.344017 0.0153214 -0.00298175 -0.345366 -0.0112799 -0.00296577 -0.346886 -0.0061063 -0.00297169 -0.34654 -0.0113834 -0.00298692 -0.345262 -0.0240082 -0.00446537 -0.337435 -0.0223935 -0.00454219 -0.337088 -0.0164265 0.000535149 -0.343191 -0.0103362 -0.0237768 -0.34064 -0.00984883 -0.0212416 -0.339231 -0.0117704 -0.0192643 -0.344794 -0.0109551 -0.0186665 -0.342434 -0.000995085 -0.0230428 -0.336203 -0.00122888 -0.024102 -0.34118 -0.00117097 -0.0217207 -0.339948 -0.0014258 -0.0217561 -0.345331 -0.00136493 -0.0188068 -0.344075 0.0166314 -0.023647 -0.338286 0.0170777 -0.0192801 -0.339058 0.0181963 -0.0208449 -0.340993 0.0151342 -0.0218395 -0.335697 0.0145026 -0.0239182 -0.334604 -0.0355298 -0.0159945 -0.303398 -0.036502 -0.0150598 -0.304423 -0.0373668 -0.0168337 -0.302987 -0.0329396 -0.00186255 -0.301585 -0.0329863 -0.00568605 -0.301704 -0.0323827 -0.00690553 -0.299615 -0.032974 -0.00813727 -0.301709 -0.0315784 -0.0066831 -0.297382 -0.0319927 -0.00688934 -0.29849 -0.0321468 -0.00167375 -0.29853 -0.0321405 -0.00556986 -0.298534 -0.0330619 0.00349778 -0.301798 -0.0336292 -0.000372163 -0.301786 -0.0328904 0.000638784 -0.301402 -0.0362809 0.00707483 -0.303276 -0.0343462 0.00689704 -0.302577 -0.0346061 0.00203274 -0.302943 -0.0320741 0.0091604 -0.324617 -0.0332545 0.00841547 -0.325154 -0.0307578 0.00872951 -0.327818 -0.0224962 0.00887429 -0.336871 -0.0342621 0.00958863 -0.302807 -0.0318755 0.0175193 -0.304039 -0.0269568 0.0196188 -0.304863 -0.0304702 0.0169686 -0.303242 -0.0333583 0.0133311 -0.302735 -0.0325758 0.00148123 -0.297189 -0.0312914 0.00233527 -0.296604 -0.0320569 0.00487798 -0.295963 -0.032516 0.00607732 -0.297067 -0.0361927 -0.0155421 -0.309725 -0.0378733 -0.0162583 -0.309781 -0.0315956 -0.016879 -0.322385 -0.0323264 -0.0160565 -0.320287 -0.0255444 -0.0221089 -0.317371 -0.0252081 -0.0236715 -0.320361 -0.030786 -0.0194395 -0.322614 -0.0278118 -0.0206707 -0.321059 -0.0243748 -0.0211116 -0.318878 -0.0277776 -0.0202509 -0.31924 -0.0312203 -0.0195401 -0.319047 -0.0306627 -0.0181612 -0.320072 -0.0333812 -0.0150072 -0.324998 -0.0249949 -0.0150095 -0.336716 -0.0282891 -0.0150463 -0.333271 -0.0269381 -0.0152353 -0.336946 -0.023841 -0.00961887 -0.337263 -0.0255948 -0.0107159 -0.338674 -0.025363 -0.00954331 -0.338954 -0.0258055 -0.0109148 -0.337227 -0.035407 -0.011016 -0.324997 -0.0301435 -0.0106878 -0.329056 -0.02774 -0.0107945 -0.331732 -0.0359129 -0.010844 -0.319801 -0.0368609 -0.0108558 -0.314849 -0.0381532 -0.011057 -0.304424 -0.0371314 -0.0106401 -0.303505 -0.0363273 -0.00931929 -0.303245 -0.0378454 -0.00446563 -0.302953 -0.038038 -0.00304035 -0.303483 -0.0365671 -0.00297603 -0.304229 0.00401577 -0.00317031 -0.332641 0.00400714 0.000829698 -0.332663 0.00201442 -0.00317031 -0.332907 0.00118503 0.000829698 -0.332973 -0.00054357 -0.00317031 -0.332996 -0.0017642 0.000829698 -0.332935 -0.00261914 -0.00317031 -0.332842 -0.00468253 0.000829698 -0.33252 -0.00493822 -0.00317031 -0.332465 -0.00752851 0.000829698 -0.331733 -0.00969937 0.000829698 -0.330843 -0.00777787 -0.00317031 -0.331645 -0.00969937 -0.00317031 -0.330843 -0.0131725 -0.0031703 -0.32884 -0.0131969 0.000829698 -0.328849 -0.0148279 -0.0031703 -0.327574 -0.0155866 0.000829698 -0.326911 -0.0167742 -0.0031703 -0.325734 -0.0175671 0.000829698 -0.324843 -0.0186101 -0.0031703 -0.323513 -0.0192857 0.000829698 -0.32253 -0.0207096 0.000829698 -0.320003 -0.0201606 -0.0031703 -0.321067 -0.0215993 0.000829698 -0.317871 -0.0216139 -0.0031703 -0.317895 0.0275599 0.000484775 -0.332842 0.0268848 0.000412319 -0.333626 0.0254804 0.00219619 -0.335126 0.0267274 0.00498173 -0.333828 0.0267551 0.00616919 -0.33379 0.0254835 0.00372572 -0.334786 0.0192315 0.0173377 -0.341737 0.018362 0.0178498 -0.341281 -0.00596345 0.016901 -0.346808 -0.00538424 0.0186409 -0.345701 -0.00387639 0.020441 -0.335655 -0.00540222 0.0212763 -0.343486 -0.0165675 0.00711058 -0.345284 -0.0167605 0.00202298 -0.345218 -0.0198341 0.00103294 -0.343594 -0.0220416 0.00709329 -0.342176 -0.0197032 0.00811668 -0.343676 -0.0221255 0.00711641 -0.341508 -0.0211795 0.00763995 -0.34023 -0.020777 0.00203271 -0.338717 -0.021014 0.00689693 -0.338139 -0.0212221 0.00203272 -0.340242 -0.00591017 0.00711055 -0.348519 -0.0059246 0.00203319 -0.348535 0.00503167 0.00711106 -0.348673 0.00504041 0.00203283 -0.348679 0.00529522 0.00203291 -0.348216 -0.00142643 0.00203302 -0.348944 -0.00141769 0.00711053 -0.34896 -0.000466523 0.000533913 -0.347021 0.00505663 0.000594692 -0.346627 0.0158274 0.00711056 -0.34563 0.0158138 0.00711055 -0.345103 0.015848 0.00203291 -0.345629 0.00983927 0.00711053 -0.347745 0.00963732 0.00203293 -0.347801 0.00933211 0.00140612 -0.347351 0.0100181 0.000546502 -0.345639 0.0194794 0.00140584 -0.343211 0.0192506 0.000551127 -0.341667 0.0198605 0.00203301 -0.343537 0.0200731 0.00711078 -0.343448 0.0206588 0.000532055 -0.342578 0.0105756 0.00053272 -0.347072 -0.0243526 -0.00446567 -0.337787 -0.0253621 -0.00444883 -0.338955 -0.0219941 -0.00956125 -0.342205 -0.0222354 -0.00954331 -0.34189 -0.0221194 -0.00954331 -0.341502 -0.0222465 -0.00446566 -0.341863 -0.0221189 -0.00388315 -0.341502 -0.0204625 -0.00296648 -0.340936 -0.0109232 -0.0224682 -0.333373 -0.0137371 -0.0164931 -0.3411 -0.0123834 -0.0208006 -0.337183 -0.0110779 -0.0194062 -0.338748 -0.00999594 -0.0211399 -0.334275 -0.00855186 -0.0226645 -0.335497 -0.0107191 -0.0188728 -0.341479 -0.00867678 -0.0216898 -0.334694 -0.0143217 -0.0183207 -0.340932 -0.0121085 -0.0158862 -0.341677 0.00680728 -0.0237357 -0.336975 -0.0306034 -0.0245641 -0.30928 -0.0278573 -0.0242214 -0.309284 -0.0357816 -0.0219393 -0.309262 -0.0376392 -0.0184449 -0.309274 -0.0384592 -0.0160118 -0.309092 -0.0379257 -0.0159913 -0.303512 -0.0367436 -0.0193232 -0.303682 -0.0296715 -0.0245902 -0.305034 -0.0272299 -0.0241092 -0.305503 -0.0344158 -0.0228005 -0.304143 -0.0320537 -0.0241675 -0.304583 -0.0373574 -0.0187946 -0.306406 -0.0356728 -0.0213674 -0.303795 -0.033572 -0.0237321 -0.309262 -0.0249557 -0.022753 -0.30604 -0.033195 -0.00467546 -0.299053 -0.0321307 -0.00634853 -0.297801 -0.0326993 -0.00795434 -0.300555 -0.0334487 -0.00730493 -0.301157 -0.0335669 -0.00590638 -0.299377 -0.0323416 -0.00573648 -0.299521 -0.0335887 -0.00546861 -0.300033 -0.033072 -0.00434891 -0.300797 -0.0324512 0.00629459 -0.299828 -0.0318271 0.0078847 -0.297909 -0.032926 0.00499955 -0.301412 -0.0331153 0.00654387 -0.302093 -0.0315588 0.00726382 -0.2972 -0.0316622 -0.000123457 -0.297622 -0.0319498 0.0028584 -0.298381 -0.0321731 -0.000761405 -0.298992 -0.0380268 0.000556017 -0.303485 -0.0363251 0.00202752 -0.303244 -0.036514 0.000681912 -0.303952 -0.0382833 0.00203295 -0.302878 -0.0378444 0.00830841 -0.303341 -0.0370504 0.00847219 -0.30454 -0.0294995 0.00860442 -0.334662 -0.025808 0.00847442 -0.337191 -0.028371 0.00838493 -0.333686 -0.0237668 0.00203249 -0.337275 -0.0221306 0.00209318 -0.337195 -0.0229328 0.00689548 -0.337052 -0.0247609 0.00775763 -0.338137 -0.0253677 0.00711219 -0.338967 -0.02783 0.0125755 -0.333765 -0.0287854 0.0127974 -0.334879 -0.0309347 0.016716 -0.322658 -0.0244115 0.0191165 -0.31951 -0.0249484 0.0194661 -0.317284 -0.026738 0.0196073 -0.320973 -0.0286563 0.0174285 -0.321004 -0.0308898 0.0156799 -0.320028 -0.0322085 0.0154688 -0.319487 -0.0315845 0.0142448 -0.322281 -0.0287169 0.0184431 -0.318375 -0.0270951 0.0181481 -0.319166 -0.0350421 0.0131546 -0.324601 -0.0339831 0.0127648 -0.323891 -0.0327181 0.0129881 -0.32031 -0.0363728 0.0131341 -0.309771 -0.0381291 0.0127914 -0.308521 -0.0373485 0.0127353 -0.304397 -0.0365472 0.0125846 -0.308271 -0.034944 0.0137508 -0.303524 -0.0373752 0.0139891 -0.303042 -0.0335416 0.0166578 -0.30378 -0.0301358 0.0194077 -0.304434 -0.0328426 0.0208528 -0.303914 -0.0287266 0.02173 -0.304701 -0.037664 -0.0152307 -0.304527 -0.0333335 -0.0183505 -0.309931 -0.0261291 -0.0217363 -0.310057 -0.0321304 -0.0183491 -0.311177 -0.0295869 -0.0207383 -0.310107 -0.034051 -0.0153877 -0.311308 -0.0377755 -0.0160483 -0.313863 -0.0375496 -0.0152039 -0.315314 -0.0355752 -0.0159742 -0.313659 -0.028968 -0.0210691 -0.32186 -0.0303759 -0.0236443 -0.322424 -0.0332334 -0.0165184 -0.323568 -0.0333378 -0.0207244 -0.323612 -0.0236514 -0.0162868 -0.336979 -0.0252389 -0.0157291 -0.338575 -0.0283542 -0.0192119 -0.327957 -0.021871 -0.0228103 -0.323798 -0.0265423 -0.0173012 -0.329669 -0.0278665 -0.0163868 -0.332257 -0.0255292 -0.0209932 -0.326309 -0.0256984 -0.0187856 -0.330106 -0.0210853 -0.0213503 -0.326132 -0.0248668 -0.0195775 -0.3277 -0.0217169 -0.0215266 -0.324217 -0.0244246 -0.0208813 -0.329516 -0.0240447 -0.0206599 -0.326171 -0.028621 -0.0164571 -0.328665 -0.0229624 -0.0208245 -0.327618 -0.0293528 -0.0105826 -0.333811 -0.0279979 -0.00446524 -0.331532 -0.0288685 -0.00931813 -0.333027 -0.0279932 -0.0093289 -0.331549 -0.0326103 -0.0109779 -0.329563 -0.0324938 -0.00962776 -0.330634 -0.0356419 -0.00954331 -0.324536 -0.0340523 -0.0108554 -0.324953 -0.0290226 -0.00446451 -0.329759 -0.0305593 -0.00446539 -0.329485 -0.0306571 -0.00941006 -0.329485 -0.0288722 -0.00933073 -0.329868 -0.0328704 -0.00933133 -0.321969 -0.0340383 -0.00947616 -0.323905 -0.0335152 -0.00446492 -0.323575 -0.0329215 -0.00446426 -0.322087 -0.0370967 -0.0110101 -0.320105 -0.0382007 -0.0110167 -0.314408 -0.0367568 -0.0097751 -0.313755 -0.033676 -0.00446425 -0.320431 -0.0342033 -0.00932787 -0.320125 -0.0372364 -0.010862 -0.308768 -0.0369496 -0.00986939 -0.309782 -0.0350686 -0.00446419 -0.311006 -0.0369484 -0.00446241 -0.309783 -0.0360052 -0.00446489 -0.309976 -0.0353166 -0.00932937 -0.310456 -0.0384084 -0.00954922 -0.303193 -0.0383691 -0.00446566 -0.303054 -0.037856 -0.00956515 -0.302945 0.0172083 0.0165503 -0.339284 0.0172122 0.0205697 -0.339291 0.015446 0.0191334 -0.336236 0.0152339 0.0216737 -0.335869 0.0128864 0.0203317 -0.331782 0.0140599 0.0187757 -0.328479 -0.00144427 0.014103 -0.345764 -0.00144356 0.0185842 -0.345748 -0.00130509 0.0175272 -0.342802 -0.00133965 0.0207673 -0.343537 -0.00115247 0.0217015 -0.339554 -0.001117 0.0197384 -0.338789 -0.0114768 0.0185675 -0.343944 -0.0105741 0.0210276 -0.341331 -0.00959341 0.0192393 -0.338491 -0.00945388 0.0217329 -0.338073 -0.0110049 0.0160737 -0.342578 -0.00641353 0.000529762 -0.346466 -0.00700236 0.000532822 -0.347886 -0.00156638 0.000709101 -0.348465 0.0041455 0.000533007 -0.348349 0.014913 0.000536171 -0.345513 0.0158135 0.00165906 -0.345103 0.0144643 0.00053533 -0.344099 -0.0248157 -0.00297117 -0.337507 -0.0258317 -0.00954328 -0.339199 -0.0257985 -0.00446566 -0.339203 -0.0221195 0.00203267 -0.341502 -0.0207023 0.000541982 -0.340722 -0.0215167 0.000537617 -0.342002 -0.0125496 -0.0241255 -0.336979 -0.0148836 -0.0172943 -0.342096 -0.0159973 -0.0160206 -0.344532 -0.0150063 -0.0211979 -0.342365 -0.0140288 -0.0233131 -0.340222 -0.012945 -0.0214098 -0.337846 -0.0253581 -0.0228499 -0.309778 -0.0324708 -0.000792797 -0.297953 -0.0323652 -0.00360105 -0.29801 -0.0332341 -0.00450661 -0.297557 -0.0338896 -0.0049472 -0.298488 -0.0332411 -0.00787013 -0.299177 -0.0333606 -0.00777956 -0.297063 -0.0333653 -0.00691917 -0.299375 -0.0345198 -0.00717995 -0.300965 -0.0338545 -0.00864631 -0.299645 -0.0343904 -0.00460966 -0.300346 -0.0334416 -0.00167967 -0.300225 -0.0313006 0.00469108 -0.296659 -0.0323068 0.00707209 -0.297816 -0.0334491 0.00630111 -0.299332 -0.0325432 0.0055449 -0.297787 -0.0323995 0.00488886 -0.298079 -0.0339415 0.00629188 -0.301291 -0.0329763 0.00627286 -0.301556 -0.0334279 0.00769208 -0.297729 -0.0332929 -0.000479554 -0.300877 -0.0339169 -0.000485433 -0.298895 -0.0326545 0.000342073 -0.300102 -0.0332739 0.00360984 -0.300445 -0.0323529 0.00379684 -0.299516 -0.0326736 0.00280352 -0.297548 -0.0316358 0.00355558 -0.296986 -0.0323574 0.00164674 -0.297921 -0.0328322 0.00072418 -0.298485 -0.0380306 0.0071351 -0.302918 -0.0366256 0.00684056 -0.309781 -0.0354591 0.00203177 -0.310224 -0.0351573 0.00689771 -0.310722 -0.0369503 0.00203292 -0.309783 -0.0377338 0.00848948 -0.309141 -0.037793 0.00823044 -0.314189 -0.0335455 0.00203147 -0.320587 -0.0334356 0.00689772 -0.320737 -0.0351147 0.00684129 -0.320051 -0.0367625 0.00853906 -0.319891 -0.0370052 0.00711521 -0.320645 -0.0348746 0.00850882 -0.324817 -0.032888 0.00203147 -0.322376 -0.0338667 0.00203283 -0.323822 -0.0329035 0.00689779 -0.322184 -0.033944 0.00750393 -0.323919 -0.0308598 0.00199498 -0.329543 -0.0290515 0.00203181 -0.329738 -0.0289581 0.00689781 -0.329797 -0.0309452 0.00685272 -0.329605 -0.0321056 0.00819191 -0.329937 -0.0287262 0.00759785 -0.332978 -0.0279955 0.00203226 -0.331474 -0.0281773 0.00689774 -0.330918 -0.0243501 0.00688633 -0.337784 -0.025363 0.00203291 -0.338954 -0.0257155 0.0126801 -0.33702 -0.0246562 0.0132906 -0.338073 -0.0280383 0.0138449 -0.332367 -0.0295654 0.0132232 -0.333823 -0.0312289 0.0126057 -0.329147 -0.034507 0.0127947 -0.326265 -0.0214741 0.0202648 -0.323267 -0.0271992 0.0128424 -0.330932 -0.0253247 0.0179135 -0.330247 -0.0262382 0.0161909 -0.328172 -0.0261525 0.0154556 -0.330077 -0.0283551 0.0154302 -0.328195 -0.0206365 0.0188889 -0.325677 -0.0231406 0.0183735 -0.32593 -0.0257221 0.0185249 -0.326351 -0.0234369 0.0181649 -0.328017 -0.0305496 0.0173794 -0.322494 -0.0263302 0.0214618 -0.320802 -0.0332425 0.0185364 -0.323574 -0.0300314 0.0213241 -0.322286 -0.0371351 0.0128596 -0.31444 -0.0312925 0.0168665 -0.310757 -0.0263136 0.0190866 -0.31029 -0.0337556 0.0134044 -0.311277 -0.0318995 0.0180456 -0.309825 -0.0350153 0.0188263 -0.303497 -0.0331653 0.0212664 -0.30404 -0.0354326 0.0192601 -0.303938 -0.0319926 -0.0186474 -0.312213 -0.0317876 -0.0197205 -0.313127 -0.0265032 -0.021641 -0.312479 -0.0315641 -0.02336 -0.323041 -0.0350627 -0.015628 -0.324556 -0.0318632 -0.0190584 -0.329611 -0.0328613 -0.015953 -0.330028 -0.0354375 -0.0160298 -0.325049 -0.030207 -0.0240479 -0.32291 -0.031999 -0.0229294 -0.323627 -0.0339339 -0.0201561 -0.324403 -0.02322 -0.0227891 -0.32005 -0.0269469 -0.0244271 -0.326465 -0.0321217 -0.0214117 -0.326573 -0.0337498 -0.018413 -0.326691 -0.0270285 -0.0245905 -0.321618 -0.0249692 -0.0245153 -0.325199 -0.0290097 -0.0234595 -0.327788 -0.0297361 -0.0159207 -0.334494 -0.0256878 -0.0239066 -0.33116 -0.0221382 -0.0240064 -0.334457 -0.0204973 -0.024565 -0.332566 -0.0240991 -0.0216496 -0.336813 -0.0255963 -0.0167556 -0.338445 -0.0271921 -0.0190327 -0.335698 -0.0282923 -0.0208222 -0.333215 -0.0227298 -0.0245634 -0.328823 -0.025927 -0.0220653 -0.334508 -0.0171345 -0.0228215 -0.328647 -0.0209706 -0.0239662 -0.327444 -0.018909 -0.0242746 -0.33074 -0.0274633 -0.0175053 -0.331915 -0.0296413 -0.0157948 -0.333662 -0.0281543 -0.0207153 -0.332459 -0.0233259 -0.0241727 -0.328655 -0.0245273 -0.0209862 -0.329603 -0.0261426 -0.0232379 -0.330875 -0.0269131 -0.0105498 -0.338231 -0.028564 -0.0105491 -0.336554 -0.0284225 -0.00346542 -0.336727 -0.0301133 -0.00954329 -0.333995 -0.0301002 -0.00405606 -0.333991 -0.0359509 -0.00446579 -0.32512 -0.0348105 -0.00346549 -0.327626 -0.0341251 -0.0105569 -0.328917 -0.035922 -0.0105484 -0.325206 -0.0311974 -0.00446568 -0.329798 -0.0385806 -0.0105491 -0.315696 -0.0382463 -0.00346545 -0.317712 -0.0382828 -0.0105491 -0.317441 -0.0379618 -0.0105491 -0.318935 -0.0375357 -0.00446567 -0.320601 -0.0367552 -0.00446564 -0.313756 -0.0351365 -0.00932929 -0.312899 -0.0352228 -0.00446444 -0.313039 -0.038974 -0.0105492 -0.308434 -0.0388457 -0.010549 -0.306548 -0.0388854 -0.00346567 -0.307081 -0.0386664 -0.010549 -0.304911 -0.038674 -0.00346571 -0.304997 -0.010582 0.0191111 -0.333692 -0.0142589 0.0134781 -0.341527 -0.0113739 0.0167222 -0.338814 -0.00806691 0.0198365 -0.334062 -0.0124848 0.0191952 -0.336877 -0.0115478 0.0178336 -0.337071 -0.0137634 0.0162573 -0.339967 -0.0120349 0.0138419 -0.341397 -0.00963112 0.0185155 -0.337894 -0.0111385 0.0147465 -0.342738 -0.0222465 0.00203291 -0.341863 -0.0158253 -0.0150927 -0.343031 -0.0340329 -0.018913 -0.309781 -0.0354381 -0.0217045 -0.309782 -0.0302057 -0.021694 -0.309779 -0.0307385 -0.0242048 -0.30978 -0.0335947 -0.0012076 -0.297644 -0.0336072 -0.00332687 -0.29765 -0.0345106 -0.00324317 -0.300485 -0.0344429 -0.0077855 -0.300142 -0.0341827 -0.00652046 -0.299373 -0.0338362 -0.00636357 -0.298323 -0.0333892 0.00707839 -0.297387 -0.0333525 0.000266182 -0.299351 -0.0336143 0.00195063 -0.300846 -0.0344082 0.00406304 -0.300056 -0.0342374 0.00460948 -0.30092 -0.0333135 0.00391964 -0.298612 -0.033918 0.00355554 -0.299128 -0.033356 0.00281474 -0.296987 -0.0337464 0.000291291 -0.298041 -0.0389694 0.0081205 -0.308102 -0.0389237 0.00103291 -0.307628 -0.0386995 0.00103297 -0.305237 -0.03842 0.00712047 -0.303264 -0.038757 0.00811625 -0.30564 -0.0384938 0.00203291 -0.309783 -0.03526 0.00689483 -0.313033 -0.0350949 0.00203162 -0.312715 -0.0375626 0.00711631 -0.320468 -0.0379633 0.00103288 -0.318929 -0.0385484 0.0010329 -0.315899 -0.0382828 0.0081164 -0.317441 -0.0342091 0.00202611 -0.32396 -0.0357432 0.00712534 -0.324577 -0.0357602 0.00203291 -0.324585 -0.0311971 0.00203291 -0.329798 -0.032597 0.00712706 -0.330698 -0.0330967 0.00711087 -0.330625 -0.0331318 0.00202215 -0.33057 -0.0348158 0.00103276 -0.327618 -0.0339066 0.00812051 -0.329289 -0.0353442 0.00811628 -0.326482 -0.0288867 0.00203291 -0.333036 -0.0301011 0.00202777 -0.33399 -0.0259429 0.00711087 -0.339117 -0.0268064 0.00811732 -0.338336 -0.0269295 0.00103273 -0.338214 -0.0287981 0.00103293 -0.336314 -0.0284439 0.00811631 -0.336684 -0.0302482 0.0071203 -0.334615 -0.0259231 0.0020329 -0.33913 -0.0254158 0.00203291 -0.339018 -0.0258256 0.000544457 -0.338627 -0.0243522 0.00202898 -0.337788 -0.0172143 0.0203387 -0.328506 -0.0222815 0.0220574 -0.328472 -0.0274537 0.0198374 -0.332572 -0.0272533 0.0162708 -0.335861 -0.028947 0.0165621 -0.333732 -0.0296219 0.0137509 -0.334395 -0.0258027 0.0134927 -0.338577 -0.0245861 0.0181198 -0.337269 -0.0227906 0.0210958 -0.335212 -0.019264 0.0220163 -0.331151 -0.0204475 0.0212155 -0.327036 -0.0247585 0.0218737 -0.330426 -0.0209853 0.0220447 -0.333128 -0.0306368 0.0192065 -0.328859 -0.0266395 0.0220678 -0.326273 -0.031566 0.0208167 -0.32345 -0.0239622 0.0218537 -0.324537 -0.0317464 0.0191968 -0.327026 -0.0321432 0.0158659 -0.32977 -0.0328436 0.0134699 -0.330027 -0.0352527 0.0134677 -0.325506 -0.0345847 0.0162504 -0.324713 -0.0336196 0.0183744 -0.324275 -0.0288291 0.0211577 -0.327661 -0.0296168 0.0218326 -0.322666 -0.0270671 0.0221218 -0.321636 -0.0284271 0.0175889 -0.332674 -0.0264887 0.0165757 -0.331148 -0.026828 0.0202221 -0.331415 -0.0236658 0.0217908 -0.328925 -0.0235001 0.0192227 -0.328796 -0.0232939 0.0204645 -0.320143 -0.0309786 0.0181796 -0.313129 -0.026125 0.019937 -0.312701 -0.0302972 0.0175051 -0.312322 -0.0346412 0.0138366 -0.313319 -0.0263761 0.0189242 -0.312023 -0.0251421 0.0202912 -0.308012 -0.0265254 0.0213883 -0.305631 -0.029085 0.0220916 -0.305147 -0.0367803 0.0168902 -0.303701 -0.0379618 0.0135245 -0.303654 -0.0384692 0.0136436 -0.309183 -0.0375858 0.0162732 -0.309233 -0.0360266 0.0192133 -0.309362 -0.0335163 0.02133 -0.309274 -0.0307572 0.0221138 -0.309279 -0.0274329 0.0216661 -0.309355 -0.0318782 0.0218236 -0.304613 -0.0340082 0.0206961 -0.304235 -0.0230664 -0.0239201 -0.324223 -0.0299695 -0.0224764 -0.328667 -0.0202607 -0.0228313 -0.326257 -0.0193913 -0.0227555 -0.326204 -0.0295151 -0.0029654 -0.334857 -0.0302903 -0.00954329 -0.334555 -0.0303011 -0.0044659 -0.334547 -0.0301662 -0.00446566 -0.334041 -0.0288874 -0.00415206 -0.333036 -0.0283424 -0.00299556 -0.33381 -0.0359636 -0.00954331 -0.324832 -0.0356452 -0.00444365 -0.324536 -0.0330163 -0.00954328 -0.330735 -0.0330167 -0.00446567 -0.330719 -0.0324947 -0.00446566 -0.330633 -0.0328762 -0.00297368 -0.330223 -0.0342097 -0.00419113 -0.323962 -0.0353315 -0.00300525 -0.325298 -0.0387575 -0.00954301 -0.314155 -0.0387674 -0.00446318 -0.314137 -0.0382042 -0.00296407 -0.315172 -0.0375375 -0.009543 -0.320585 -0.0369931 -0.0095435 -0.320639 -0.0355119 -0.00412378 -0.320204 -0.0369933 -0.00383846 -0.320638 -0.0384938 -0.00383834 -0.309782 -0.0370259 -0.00296971 -0.309071 -0.0389958 -0.00954353 -0.30939 -0.0385292 -0.00957633 -0.309794 -0.038967 -0.00446577 -0.309617 -0.0385503 -0.00296444 -0.308446 -0.0279523 0.0216395 -0.317982 -0.0126904 0.0217298 -0.337288 -0.0151012 0.0183869 -0.342573 -0.0142613 0.020549 -0.340732 -0.0131432 0.0187546 -0.33828 -0.0150848 0.0140881 -0.342537 -0.0201864 -0.0151141 -0.341315 -0.017469 -0.0152374 -0.34386 -0.0125909 -0.0227204 -0.331855 -0.0173507 -0.0229131 -0.340108 -0.0147686 -0.0245393 -0.335622 -0.0119987 -0.0241244 -0.334588 -0.0134522 -0.0238628 -0.333342 -0.0138686 -0.0244848 -0.338666 -0.0161861 -0.0242363 -0.338082 -0.0154181 -0.022168 -0.342041 -0.0190126 -0.0172781 -0.342986 -0.0166272 -0.0162221 -0.344617 -0.016099 -0.0195062 -0.343524 -0.034371 -0.00292527 -0.300126 -0.0342064 0.00627121 -0.29944 -0.0338391 -0.00107066 -0.298332 -0.0389961 0.00711074 -0.309376 -0.0385423 0.00711845 -0.309794 -0.0389759 0.00202993 -0.309612 -0.0370405 0.00053871 -0.309236 -0.0339483 -0.00116882 -0.301423 -0.0375693 0.00203283 -0.320476 -0.037072 0.00203291 -0.320665 -0.0357713 0.000572846 -0.319549 -0.0354637 0.00203043 -0.320177 -0.0369931 0.00203289 -0.320639 -0.0387523 0.00203322 -0.314125 -0.0387689 0.00711322 -0.314151 -0.0382953 0.00711055 -0.313903 -0.0355419 0.000593962 -0.325069 -0.0359858 0.00203291 -0.325038 -0.035993 0.00711054 -0.325019 -0.0317806 0.000534219 -0.32899 -0.0326405 0.00202529 -0.330728 -0.0303683 0.00203324 -0.334416 -0.0301359 0.00711707 -0.334016 -0.0294593 0.000533413 -0.334841 -0.0170992 0.0203916 -0.329408 -0.0225984 0.0209428 -0.33555 -0.0241478 0.0171111 -0.337554 -0.0208803 0.0196489 -0.326578 -0.0299564 0.0192067 -0.329003 -0.0378398 0.0140643 -0.309795 -0.0319626 -0.0165171 -0.330294 -0.0301989 -0.0164235 -0.329156 -0.0303866 -0.0206471 -0.329277 -0.0286505 -0.0189775 -0.32816 -0.0290915 -0.0225617 -0.328443 -0.0255559 -0.0215834 -0.326169 -0.0260333 -0.024128 -0.326476 -0.02245 -0.0229211 -0.335589 -0.0196698 -0.0241647 -0.332378 -0.0220347 -0.0195434 -0.33511 -0.0239346 -0.0201141 -0.337304 -0.0262223 -0.00296632 -0.338254 -0.0339496 -0.00296771 -0.324779 -0.0315088 -0.00309777 -0.329438 -0.0382953 -0.0095433 -0.313903 -0.0382952 -0.00385122 -0.313904 -0.0373754 -0.00296546 -0.319423 -0.0358801 -0.00296587 -0.319076 -0.0367761 -0.00304476 -0.314263 -0.0158699 0.0143007 -0.344259 -0.0163736 0.0130542 -0.344268 -0.0158961 0.0126285 -0.343 -0.015007 -0.0238505 -0.332357 -0.0171146 -0.0234179 -0.339686 -0.0181977 -0.0209438 -0.341567 -0.0194079 -0.0230745 -0.338565 -0.0173332 -0.0245788 -0.335636 -0.0148463 -0.0246386 -0.335757 -0.0343408 0.00141685 -0.299942 -0.0330899 0.0030138 -0.299231 -0.0330861 0.00125746 -0.298858 -0.0385455 0.000541424 -0.309226 -0.0367573 0.00688665 -0.313756 -0.0382958 0.00200981 -0.3139 -0.0371995 0.000544032 -0.320041 -0.0381854 0.000533042 -0.315139 -0.0367156 0.0019842 -0.313761 -0.0367024 0.000533581 -0.314819 -0.0338613 0.000534922 -0.324969 -0.033099 0.000533747 -0.329809 -0.0285948 0.000538327 -0.33355 -0.0248873 0.000612107 -0.337409 -0.0197111 0.0217243 -0.332428 -0.0204739 0.0187775 -0.333307 -0.0224626 0.0205071 -0.335604 -0.0226746 0.0160017 -0.335849 -0.0261296 0.0217484 -0.326538 -0.0258679 0.0190229 -0.32637 -0.0289978 0.0160584 -0.328383 -0.032149 0.0137924 -0.330411 -0.0246037 0.0193007 -0.308654 -0.036262 0.0179375 -0.309782 -0.0339092 0.0165587 -0.309781 -0.031048 0.0188137 -0.30978 -0.0262995 0.0203633 -0.309778 -0.0291273 0.02162 -0.309779 -0.0331357 0.0210164 -0.309781 -0.016544 -0.0211865 -0.330182 -0.0227144 -0.0172955 -0.336017 -0.01985 -0.0185429 -0.334773 -0.0186568 -0.0223804 -0.331202 -0.0177896 -0.0204597 -0.332638 -0.0191146 -0.0205616 -0.332558 -0.0198484 -0.0213613 -0.332601 -0.0186629 -0.0201941 -0.33665 -0.021606 -0.0161137 -0.336087 -0.0196548 -0.0174076 -0.337215 -0.0170192 -0.0209267 -0.333471 -0.0312604 -0.00209215 -0.326161 -0.0111211 0.0202886 -0.332642 -0.0136128 0.0216157 -0.33361 -0.0169931 0.0210512 -0.33948 -0.0151067 0.0204971 -0.341357 -0.0192091 0.013408 -0.343323 -0.0166984 0.0134832 -0.344686 -0.0160867 0.0168876 -0.343657 -0.0137067 0.0220383 -0.338307 -0.015476 0.0220888 -0.336848 -0.0121143 0.0218756 -0.33524 -0.019529 0.0128028 -0.342708 -0.0218805 -0.0158364 -0.341177 -0.0207958 -0.0158337 -0.339669 -0.0204814 -0.0211501 -0.339998 -0.0215066 -0.0171476 -0.341509 -0.0326493 0.00190309 -0.300483 -0.032177 0.000426982 -0.326664 -0.0320003 -0.000789243 -0.324334 -0.0201621 0.0155709 -0.335328 -0.0216709 0.0167714 -0.334778 -0.0200749 0.0138345 -0.337863 -0.0152117 0.0197408 -0.331596 -0.0166495 0.018574 -0.331819 -0.0163006 0.0197868 -0.33332 -0.0189916 0.018042 -0.332637 -0.0223402 0.0138936 -0.336067 -0.0190789 0.0191179 -0.331793 -0.0167959 0.0190125 -0.329924 -0.0186755 0.0168358 -0.336418 -0.0168926 -0.0241046 -0.334152 -0.0149003 -0.0218171 -0.331128 -0.0168425 -0.02192 -0.334087 -0.0188609 -0.0235103 -0.33692 -0.0204049 -0.0214423 -0.339091 -0.0192592 -0.0194207 -0.33748 -0.0156317 0.0221314 -0.337115 -0.0141628 0.0204523 -0.331019 -0.017008 0.0222539 -0.335176 -0.0191049 0.0210048 -0.338139 -0.0177863 0.0197205 -0.340874 -0.0205567 0.0184942 -0.340185 -0.0216223 0.013787 -0.341737 -0.0187571 0.0163075 -0.342531 -0.018974 0.0174502 -0.337079 -0.0169681 0.0217002 -0.334259 -0.0205417 0.0139916 -0.339283 -0.0202136 0.0193672 -0.338822 -0.0188762 0.0210495 -0.336942 -0.021708 0.0145759 -0.34092 -0.0207546 0.0126957 -0.340559 0.0122507 -0.01808 -0.345761 0.0099721 -0.0159631 -0.347141 0.00954441 -0.019311 -0.346072 0.00827469 -0.0243579 -0.340879 0.00693396 -0.0227261 -0.334309 0.0133431 -0.0236968 -0.340921 0.0108806 -0.0242356 -0.335425 0.0151233 -0.0158771 -0.345443 0.0149008 -0.0190054 -0.344336 0.0122347 -0.0245211 -0.338482 0.00758414 -0.0244741 -0.338057 0.0117603 -0.0208678 -0.344528 0.00904606 -0.0227374 -0.343872 0.00707724 -0.0238259 -0.335956 0.0142426 -0.0223027 -0.342565 0.0148438 -0.0204182 -0.342981 0.0136511 -0.0195907 -0.340373 0.0137901 -0.0231888 -0.340677 0.0122561 -0.0217799 -0.337323 0.0120563 -0.0241477 -0.336883 0.0072662 -0.0217566 -0.338861 0.0077843 -0.0239021 -0.340997 0.00815425 -0.0190353 -0.342512 0.00861898 -0.0215877 -0.344422 0.00857158 -0.0164234 -0.344227 0.00936891 -0.0156762 -0.346834 0.0106983 -0.0152322 -0.346526 0.0142368 -0.015231 -0.345286 0.0134029 -0.0149574 -0.343603 0.0102031 -0.0149437 -0.344594 0.00907304 -0.0152299 -0.344738 -0.0382114 -0.0159663 -0.314719 -0.0359216 -0.0213576 -0.314192 -0.0250686 -0.0227376 -0.31322 -0.0333807 -0.0230509 -0.319045 -0.0288418 -0.0245619 -0.31772 -0.0348834 -0.0214388 -0.319459 -0.036204 -0.0188354 -0.319867 -0.0372066 -0.0158678 -0.31981 -0.0345388 -0.0229226 -0.314073 -0.0322256 -0.0242056 -0.313827 -0.0295914 -0.0245597 -0.313568 -0.0372486 -0.0189319 -0.314368 -0.0312642 -0.0242412 -0.318423 -0.0265718 -0.0240754 -0.317053 -0.0270615 -0.0240081 -0.313326 -0.0243169 -0.0227334 -0.316779 -0.0369551 -0.0152318 -0.319054 -0.0362943 -0.0167921 -0.320434 -0.0362127 -0.0200025 -0.313702 -0.035141 -0.0149553 -0.318496 -0.0356871 -0.0149429 -0.315149 -0.0340082 -0.0161716 -0.319762 -0.0318065 -0.0194846 -0.319114 -0.0341513 -0.0214136 -0.319803 -0.031466 -0.0236157 -0.319014 -0.0284061 -0.0218336 -0.318114 -0.027454 -0.0240217 -0.317835 -0.033809 -0.0189516 -0.313472 -0.0300746 -0.021678 -0.313113 -0.0289209 -0.0241615 -0.313001 -0.0339382 -0.0229066 -0.313484 -0.034597 -0.0152793 -0.319609 -0.0366333 -0.0154773 -0.320032 0.0101286 0.013476 -0.347114 0.0152846 0.0134662 -0.345354 0.0145946 0.0182077 -0.343659 0.0134648 0.0210713 -0.341201 0.0120966 0.022189 -0.338175 0.0104027 0.0211456 -0.334186 0.0088358 0.0207901 -0.34317 0.00819422 0.0220273 -0.340543 0.00722057 0.0217508 -0.336574 0.00924508 0.0191067 -0.344841 0.00962742 0.0159662 -0.346421 0.0122093 0.01638 -0.345485 0.0120315 0.0195795 -0.343659 0.00691586 0.0202852 -0.334293 0.010258 0.0125218 -0.344675 0.0106854 0.0127995 -0.346528 0.0134283 0.0125108 -0.34347 0.00874283 0.0182513 -0.344931 0.00861951 0.0138332 -0.344424 0.00803303 0.0211551 -0.342018 0.00779392 0.017963 -0.341031 0.0070685 0.0196247 -0.338049 0.00694716 0.0214804 -0.337549 0.0107463 0.0203621 -0.334034 0.0123592 0.0217283 -0.337547 0.0127429 0.0187673 -0.338387 0.0141375 0.0159553 -0.341437 0.0147323 0.0185289 -0.342738 0.0137012 0.0207904 -0.340483 0.00905812 0.0128108 -0.344713 0.00957449 0.0130923 -0.346752 -0.0361884 0.0164159 -0.3199 -0.0314454 0.021791 -0.318482 -0.0244509 0.0202952 -0.316392 -0.0257192 0.0212268 -0.316808 -0.0353135 0.0196812 -0.31413 -0.031357 0.022038 -0.313742 -0.0369096 0.0172394 -0.314286 -0.0338943 0.0209489 -0.313996 -0.0279411 0.0220249 -0.317456 -0.0286604 0.0220191 -0.313478 -0.0381948 0.0133037 -0.315214 -0.0368699 0.0157455 -0.317859 -0.0361087 0.0175431 -0.317697 -0.0342139 0.0198946 -0.319257 -0.026674 0.0213724 -0.313284 -0.0250306 0.0202935 -0.313124 -0.0372233 0.0154646 -0.313799 -0.0349962 0.015044 -0.313583 -0.0322538 0.0212707 -0.313323 -0.0349959 0.0194043 -0.313586 -0.0307275 0.0189677 -0.313176 -0.0285098 0.0216136 -0.312959 -0.0286132 0.0193229 -0.318175 -0.0311227 0.0212732 -0.318913 -0.0316041 0.0171758 -0.319054 -0.0341018 0.0191542 -0.319789 -0.0338692 0.0141581 -0.319721 -0.0362634 0.014279 -0.320425 -0.0369557 0.0127987 -0.319047 -0.0357282 0.0125156 -0.315346 -0.0376678 0.0127988 -0.31536 0.020586 -0.0206802 -0.329366 0.017285 -0.0233174 -0.330327 0.0205857 -0.0141703 -0.32936 0.0197467 -0.0206514 -0.330253 0.0198258 -0.0141703 -0.330253 0.018374 -0.0213733 -0.330659 0.0181889 -0.0141703 -0.330632 0.0171713 -0.0141703 -0.330277 0.0205826 0.0118312 -0.329384 0.0178661 0.0194836 -0.330577 0.0205859 0.0182578 -0.32936 0.0197545 0.0181868 -0.330303 0.0195812 0.01183 -0.330345 0.018359 0.0118297 -0.33064 0.0171715 0.0209537 -0.330276 -0.0268114 0.0118297 -0.304757 -0.0273648 0.0118299 -0.303698 -0.0272659 0.0118311 -0.302245 -0.027212 0.01866 -0.304182 -0.026144 0.0118297 -0.305301 -0.0261741 0.0208298 -0.305286 -0.0272166 -0.0188076 -0.302208 -0.0266733 -0.0161475 -0.303309 -0.0263974 -0.0187377 -0.305173 -0.0271614 -0.0212268 -0.30426 -0.0273507 -0.0188028 -0.303705 -0.0274143 -0.0206034 -0.302774 -0.0273359 -0.0185403 -0.302672 -0.0268627 -0.0151767 -0.302616 -0.0270516 -0.0141731 -0.301885 -0.0270609 -0.0206905 -0.301887 0.0100782 0.0115046 0.0370446 0.011362 0.0115046 0.0388699 0.0119818 0.0115046 0.0416807 0.0117587 0.0135046 0.0433302 0.00952671 0.0115046 0.046729 0.0109703 0.0135053 0.045177 0.0114697 -0.0135459 0.0388645 0.0119818 -0.0115 0.0416807 0.0120405 -0.0135249 0.0413578 0.0113274 -0.0115 0.0444836 0.0106345 -0.0135 0.0456034 0.00952671 -0.0115 0.046729 0.023889 0.0050023 0.0491425 0.0233368 0.0050023 0.0513484 0.0185088 0.0050023 0.0564933 0.023889 -0.0049977 0.0491425 0.0218649 -0.0049977 0.0530816 0.024104 -0.0049977 0.0549923 0.0185088 -0.0049977 0.0564933 0.0197776 -0.0049977 0.0539837 0.0159079 -0.0049977 0.0546821 0.0240728 -0.0049977 0.0490862 0.0251641 -0.0049977 0.0531548 0.0251641 0.0050023 0.0531548 0.0240728 0.0115046 0.0490862 0.0207605 0.0155046 0.0375463 0.0135346 0.0155046 0.0389189 0.0139104 0.0155046 0.0405382 0.01369 0.0155046 0.04385 0.0131031 0.0155046 0.0454049 0.0122199 0.0155046 0.0468226 0.025164 0.0155046 0.0531547 0.00972607 0.0155046 0.0490054 0.000300176 0.0155046 0.0483784 -0.000916943 0.0155046 0.0472355 -0.00188278 0.0155046 0.0458846 -0.00257029 0.0155046 0.0443623 -0.00294607 0.0155046 0.042743 -0.00299927 0.0155046 0.0410767 -0.00272557 0.0155046 0.0394312 -0.00508438 0.0155046 0.0297247 -0.0098147 0.0155046 0.0270418 -0.0160739 0.0155046 0.0218393 -0.0177784 0.0155046 0.0197228 -0.0226164 0.0155046 0.0124261 -0.0309812 0.0155046 0.010734 -0.0326072 0.0155046 0.00462636 -0.0330767 0.0155046 0.00149586 -0.0333351 0.0155046 -0.00166018 -0.00272557 -0.0155 0.0394312 -0.00294607 -0.0155 0.042743 -0.00188278 -0.0155 0.0458846 -0.000435937 -0.0155 0.0478031 -0.00398926 -0.0155 0.0546028 0.00327002 -0.0155 0.0498478 0.00657661 -0.0155 0.0500699 0.0110837 -0.0155 0.0480338 0.0251642 -0.0155 0.0531549 0.00820904 -0.0155 0.0496914 0.01369 -0.0155 0.04385 0.021113 -0.0155 0.0380545 0.0139633 -0.0155 0.0422049 0.0207605 -0.0155 0.0375462 0.0135346 -0.0155 0.0389189 -0.0266795 -0.0155 0.0191755 -0.0141359 -0.0155 0.023749 -0.00981462 -0.0155 0.0270419 -0.00749426 -0.0155 0.0284633 -0.000119387 -0.0155 0.0352474 -0.0330204 -0.0155 0.0019642 -0.0256874 -0.0155 0.00354831 -0.0239374 -0.0155 0.0095791 -0.0057134 0.0135046 0.0557271 -0.00476746 0.0135615 0.0565071 0.0159079 0.0050023 0.0546821 -0.00706303 0.0135046 0.0542878 -0.00559245 0.0155046 0.0529315 -0.00383298 0.0155046 0.0547182 -0.00115147 0.0155046 0.0567096 -0.0029183 0.0137088 0.0577305 -0.00101082 0.0139068 0.05865 0.00103626 0.0141792 0.0592992 0.00106753 0.0155046 0.0578772 0.00398376 0.0146691 0.0597023 -0.00186624 -0.0155 0.0562746 0.00185053 -0.0155 0.0581713 -0.000181282 -0.0140056 0.0589522 0.00188636 -0.0143039 0.0594769 -0.00476425 -0.0135575 0.0565097 -0.00571399 -0.0135 0.0557265 -0.00559245 -0.0155 0.0529315 -0.00825132 -0.0135 0.0527414 0.0218649 0.0050023 0.0530816 0.023889 -0.0115 0.0491425 0.0233368 -0.0049977 0.0513484 0.0233368 -0.0115 0.0513484 -0.00833334 0.0135046 0.052623 -0.00833334 -0.0135 0.052623 -0.0353006 -0.0135415 -0.00754707 -0.0353942 0.0135046 -0.00484546 -0.0353365 -0.0135 -0.00164525 -0.0353365 0.0135046 -0.00164525 -0.0352994 0.0135046 -0.000962135 -0.0352994 -0.0135 -0.000962135 -0.034533 0.0135046 0.00520504 -0.033846 0.0135046 0.00822469 -0.033846 -0.0135 0.00822469 -0.032867 -0.0135 0.0114 -0.0312054 0.0135046 0.0153489 -0.0283803 -0.0135 0.0202281 -0.0308877 -0.0152906 -0.0276049 -0.0344791 0.0139566 -0.0146073 -0.0338392 -0.0142378 -0.0178314 -0.0327084 -0.0146882 -0.0222006 -0.0327084 0.0146928 -0.0222006 -0.0308877 0.0152952 -0.0276049 -0.0287047 0.0158736 -0.0327743 -0.0299387 0.0155654 -0.0299723 -0.0197506 0.0135012 0.0133661 -0.0203846 0.0144899 -0.0242668 -0.0201266 0.00970505 -0.0249145 -0.0133356 0.0159477 -0.0381125 -0.00270456 0.012676 -0.0536455 -0.00582224 0.0122776 -0.0493528 -0.00988206 0.016502 -0.0435003 -0.0103709 0.016428 -0.0427659 -0.0239713 0.00855017 -0.0105558 -0.0224535 0.013923 -0.0180405 -0.0224097 0.00903539 -0.0181957 -0.0243356 0.0135046 -0.0066036 -0.0243316 0.0135046 -0.00184404 -0.019327 0.00850461 0.0139804 -0.0161347 0.0135046 0.0185827 -0.00164963 -0.0134968 0.0290332 -0.00745473 -0.00849999 0.0261676 -0.00925751 -0.0134885 0.0250306 -0.00952794 -0.00849999 0.0248267 -0.0161347 -0.00849999 0.0185827 0.00564816 -0.0115 0.0351427 -0.0223065 0.0115046 0.0149189 -0.014954 0.0115046 0.0315376 -0.029897 0.0115046 -0.00417188 -0.0270912 0.0115046 0.00101841 -0.0295222 0.0115046 0.00171906 -0.0128198 0.0153568 -0.0489621 -0.00512912 0.0156786 -0.0554348 -0.020924 0.0131682 -0.0305098 -0.0282555 0.0120528 -0.0175535 -0.025839 0.0118611 -0.0169052 -0.0276036 0.0122842 -0.0200441 -0.0272453 0.0124056 -0.0212719 -0.0232822 0.0126023 -0.0250988 -0.0217559 0.0129788 -0.0287279 -0.0257229 0.0128756 -0.0257121 -0.0253501 0.0129803 -0.0266623 -0.0287537 0.0118675 -0.0152998 -0.0290575 0.0117518 -0.0136741 -0.0293613 0.0116379 -0.0117351 -0.0269615 0.0115398 -0.010831 -0.0295829 0.0115614 -0.00996674 -0.0272228 0.0115046 -0.00838143 -0.0296577 0.0115382 -0.00922622 -0.014954 -0.0115 0.0315376 -0.0257229 -0.012871 -0.0257121 -0.028754 -0.0118627 -0.0152987 -0.0279982 0.0121457 -0.0185836 -0.0283974 -0.0119959 -0.016951 -0.0279983 -0.0121406 -0.0185837 -0.0276086 -0.0122773 -0.0200262 -0.0298286 0.0115046 -0.00687906 -0.029897 -0.0115 -0.00417188 -0.0297822 -0.0115 -0.000882913 -0.0295222 -0.0115 0.00171906 -0.0283527 0.0115046 0.00746064 -0.026506 0.0115046 0.012462 -0.0248639 -0.0115 0.0155492 -0.0238554 0.0115046 0.0171018 -0.00714095 -0.0160785 -0.05692 -0.0166974 -0.0147715 -0.0431197 -0.0165027 0.0148074 -0.0434254 -0.0221437 0.0137604 -0.033671 -0.0200989 0.0141771 -0.037464 -0.0195587 0.0142794 -0.0384087 -0.0197453 -0.0142402 -0.0380849 -0.0181382 0.0145347 -0.040803 -0.0181381 -0.0145303 -0.0408029 -0.0253502 -0.0129752 -0.0266624 -0.0242229 0.0132768 -0.0293351 -0.022283 0.0137301 -0.0333982 -0.0238554 -0.0115 0.0171018 -0.0149249 -0.0115 0.0315168 -0.0223064 -0.0115 0.014919 -0.026506 -0.0115 0.012462 -0.0272363 -0.0115 0.0107558 -0.0249895 -0.0115 0.00963971 -0.0259329 -0.0115 0.0068297 -0.0283527 -0.0115 0.00746064 -0.0289085 -0.0115 0.00525611 -0.0266275 -0.0115 0.0039482 -0.0272228 -0.0115 -0.00838143 -0.0298286 -0.0115 -0.00687906 -0.02964 -0.0115387 -0.0094115 -0.0151861 -0.0142586 -0.0408281 -0.020924 -0.0131636 -0.0305098 -0.0181957 -0.0137245 -0.0357462 -0.0201025 -0.0141722 -0.0374575 -0.022287 -0.0137246 -0.0333904 -0.0271888 -0.01242 -0.0214581 -0.0244485 -0.0122758 -0.0218334 -0.0242619 -0.0132621 -0.029246 -0.0232822 -0.0125977 -0.0250988 -0.0291604 -0.0117081 -0.0130623 -0.0265343 -0.0116454 -0.0135783 -0.0294236 -0.0116109 -0.0112809 -0.0119647 -0.0147611 -0.0457833 -0.0130674 -0.0153177 -0.0486028 -0.00512914 -0.0156741 -0.0554348 -0.0133593 0.00850461 0.0217446 -0.00745473 0.00850461 0.0261676 -0.0236035 0.00850456 0.00385087 -0.0229316 0.0085046 0.00640122 -0.0250273 0.0085047 0.00960176 -0.0221478 0.00850462 0.00871426 -0.0209368 0.00850461 0.0113664 -0.0236408 0.00850459 0.012669 -0.024181 0.00850464 9.92272e-05 -0.0242582 0.00850706 -0.0078101 -0.0273488 0.00850472 -0.00638123 -0.0273893 0.00850497 -0.00510671 -0.0243356 0.00850455 -0.0066036 -0.0273653 0.00850423 -0.00248248 -0.024381 0.00850457 -0.00302635 -0.0264696 0.00866918 -0.0139355 -0.0234056 0.00871509 -0.0140637 -0.0211974 0.00940662 -0.0220761 -0.0103745 0.0116306 -0.0427608 -0.0239647 0.00941951 -0.0233163 -0.018483 0.0101135 -0.0286582 -0.0157998 0.0106918 -0.033916 -0.0129991 0.0112045 -0.0386627 -0.00790429 0.0119939 -0.0463981 -0.014381 0.0113945 -0.0421034 -0.0273211 -0.00850001 -0.0015845 -0.0273885 -0.00850013 -0.00510662 -0.0243676 -0.00849028 -0.00670557 -0.0272413 -0.00849673 -0.00827402 -0.0241028 -0.00849999 0.00074158 -0.0228928 -0.00849999 0.00652977 -0.0263136 -0.00849999 0.00538086 -0.0222116 -0.00849999 0.0150671 -0.0133593 -0.00849999 0.0217446 -0.0105906 -0.0119572 -0.047787 -0.00913773 -0.0118078 -0.0445822 -0.018285 -0.0107071 -0.0355867 -0.0139431 -0.011034 -0.0371083 -0.0110916 -0.0115139 -0.0416685 -0.0205234 -0.0102523 -0.0313339 -0.0242561 -0.0093307 -0.0224124 -0.0232792 -0.00959642 -0.0250979 -0.0205793 -0.00957838 -0.0237649 -0.0119647 0.0147658 -0.0457833 -0.0273918 0.0115048 -0.00490019 -0.027342 0.0115043 -0.00193651 -0.0272612 0.011502 -0.00786286 -0.0270295 0.00852673 -0.0102834 -0.0265051 0.0116585 -0.0137403 -0.0254516 0.00898081 -0.0184842 -0.0251616 0.0120689 -0.0194997 -0.0244477 0.0122806 -0.0218359 -0.0174192 0.0108746 -0.0371135 -0.0181742 0.0137327 -0.0357855 -0.0199511 0.0103782 -0.0324683 -0.0219976 0.00992183 -0.0281867 -0.0121744 0.00850461 0.0295472 -0.0218483 0.00850461 0.0156077 -0.0189381 0.0115046 0.0198012 -0.0249894 0.0115046 0.00963979 -0.0237829 0.0115046 0.0123487 -0.0270422 0.00850459 0.00158725 -0.0266275 0.0115046 0.0039482 -0.0259328 0.0115046 0.00682978 -0.0260782 0.00850462 0.00625987 -0.0108021 0.0119322 -0.0474812 -0.00512894 0.0126781 -0.0554347 -0.0158597 -0.0111455 -0.0397376 -0.0225245 -0.00978871 -0.026965 -0.0217523 -0.0129751 -0.0287358 -0.0253012 -0.00902137 -0.0189933 -0.0251616 -0.0120643 -0.0194997 -0.0261414 -0.00876395 -0.015581 -0.0258393 -0.0118564 -0.0169041 -0.0267788 -0.00857833 -0.0121211 -0.0269627 -0.0115349 -0.0108214 -0.0273918 -0.0115002 -0.00490019 -0.027342 -0.0114997 -0.00193651 -0.0270912 -0.0115 0.00101841 -0.0269727 -0.00849999 0.00192119 -0.0253156 -0.00849999 0.00875926 -0.0237828 -0.0115 0.0123488 -0.0239536 -0.00849999 0.0120068 -0.0189381 -0.0115 0.0198012 -0.020211 -0.00849999 0.0179679 -0.0121742 -0.00849999 0.0295471 0.0107324 0.0115046 0.0556162 0.00661211 0.0115046 0.0557571 0.00261894 -0.0115 0.0547325 -0.00473187 0.0135046 0.0276665 -0.00952794 0.00850461 0.0248267 -0.0161347 0.00850461 0.0185827 0.00339676 0.0135046 0.0354842 0.0100701 0.0135274 0.0369259 0.00821111 0.0115046 0.0357413 0.00771096 0.0135167 0.0354878 0.00521509 0.0135104 0.0351063 -0.0149249 0.0115046 0.0315168 -0.0121742 0.0115046 0.0295471 0.0107324 -0.0115 0.0556162 0.0197776 0.0050023 0.0539837 -0.00512894 -0.0126735 -0.0554347 -0.00270456 0.017477 -0.0536455 -0.00501979 0.0196558 -0.0553543 -0.00714095 0.0160831 -0.05692 -0.00270456 -0.0174724 -0.0536455 0.023889 0.0115046 0.0491425 -0.00373209 0.0115046 0.0496068 -0.000981865 0.0115046 0.0409571 -0.000924769 0.0115046 0.0526258 0.00581813 0.0115046 0.048132 0.0113274 0.0115046 0.0444836 0.0233368 0.0115046 0.0513484 0.0218649 0.0115046 0.0530816 0.0197776 0.0115046 0.0539837 0.00261894 0.0115046 0.0547325 -0.00745473 0.0115046 0.0261676 0.00564816 0.0115046 0.0351427 0.00339676 0.0115046 0.0354842 -0.00473187 0.0115046 0.0276665 -0.00745473 -0.0115 0.0261676 0.0100782 -0.0115 0.0370446 0.011362 -0.0115 0.0388699 0.021113 -0.0115 0.0380545 0.0189677 -0.0115 0.0349618 0.00821111 -0.0115 0.0357413 0.00339676 -0.0115 0.0354842 0.000764208 -0.0115 0.046112 -0.000674271 -0.0115 0.0437261 -0.000981865 -0.0115 0.0409571 -0.0121742 -0.0115 0.0295471 -0.00473187 -0.0115 0.0276665 0.00180403 -0.0115 0.0362813 -5.98898e-05 -0.0115 0.029579 -0.00373209 -0.0115 0.0496068 -0.000924769 -0.0115 0.0526258 0.00306964 -0.0115 0.0476763 0.00756756 -0.0115 0.047797 0.00661211 -0.0115 0.0557571 0.0197776 -0.0115 0.0539837 0.0218649 -0.0115 0.0530816 5.86974e-06 0.0115046 0.0296064 0.0189677 0.0115046 0.0349618 0.021113 0.0155046 0.0380545 0.021113 0.0115046 0.0380545 -0.024827 0.0165794 -0.0394704 -0.00753292 -0.017783 -0.0572088 -0.00953556 0.0178287 -0.0563765 -0.00953556 -0.0178241 -0.0563765 -0.010562 0.0178301 -0.0557959 -0.0114641 -0.0178153 -0.0552016 -0.0131894 -0.0177678 -0.0538722 -0.01477 0.0176971 -0.0524445 -0.01477 -0.0176925 -0.0524445 -0.0176424 0.0174895 -0.0494082 -0.0214472 0.0170742 -0.0445395 -0.0202263 -0.0172195 -0.0462001 -0.0226072 -0.0169129 -0.0428781 -0.024827 -0.0165747 -0.0394704 -0.00666003 0.0155046 0.051526 -0.0283803 0.0135046 0.0202281 -0.0350639 0.0135046 0.00172456 -0.0319128 0.0155046 0.00771193 -0.0332057 0.0135046 0.0103998 -0.0299433 0.0155046 0.0133428 -0.0319278 0.0135046 0.0138039 -0.0283195 0.0155046 0.0164681 -0.0266795 0.0155046 0.0191755 -0.0347763 0.0138148 -0.012727 -0.0338392 0.0142424 -0.0178314 -0.0325182 0.0147625 -0.0228378 -0.0326394 0.0158365 -0.012693 -0.0353006 0.0135461 -0.00754707 -0.0330699 0.0156357 -0.00952292 -0.0114641 0.01782 -0.0552016 -0.0131894 0.0177724 -0.0538722 -0.0117274 0.0197411 -0.0520352 -0.0137153 0.0177506 -0.0534182 -0.0173579 0.0175142 -0.049734 -0.0202263 0.0172241 -0.0462001 -0.0207723 0.0188835 -0.0414329 -0.0226072 0.0169175 -0.0428781 -0.00753292 0.0177876 -0.0572088 -0.0267191 0.0178493 -0.0315952 -0.0304008 0.0154369 -0.0288477 -0.0229479 0.0185452 -0.038093 -0.0250053 0.0181824 -0.0346659 -0.0184492 0.0191907 -0.0446772 -0.0159486 0.0194569 -0.0477893 -0.0132097 0.0196654 -0.050694 -0.00767257 0.018987 -0.0496285 -0.00668754 0.0197539 -0.0550237 -0.00901328 0.0198063 -0.0540218 -0.027919 0.0175343 -0.0288941 -0.0198371 0.0169798 -0.0298424 -0.0180968 0.0173308 -0.0332345 -0.0148625 0.0179148 -0.0388409 -0.029755 0.0169801 -0.0241106 -0.0304495 0.0167383 -0.0219884 -0.0243564 0.0158917 -0.0181106 -0.0233238 0.0161642 -0.0214531 -0.0316906 0.0162538 -0.0174527 -0.0253377 0.0156397 -0.0140909 -0.0333943 0.0155046 -0.00482338 -0.0258273 0.0155383 -0.0114387 -0.0230357 0.0135046 0.00604761 -0.0222741 0.0135046 0.00834133 -0.0208517 0.0135046 0.011484 -0.0263717 0.0155046 -0.00270746 -0.0262168 0.0155046 -0.000219278 -0.025689 0.0155046 0.00353997 -0.0241638 0.0135046 0.000211879 -0.0236453 0.0135046 0.00356129 -0.0249575 0.0155046 0.00659999 -0.0238056 0.0155046 0.00990312 -0.0261645 0.0155046 -0.00899147 -0.0241738 0.0135046 -0.00879794 -0.0263338 0.0155046 -0.00668932 -0.00404956 0.0194554 -0.0546383 -0.00622584 0.0170209 -0.0487867 -0.023776 0.013561 -0.0119068 -0.0250775 0.0157033 -0.0152785 -0.0233586 0.0136672 -0.0143176 -0.0225758 0.0163532 -0.0235232 -0.021566 0.0141755 -0.0209941 -0.0191279 0.0147976 -0.0272707 -0.0209573 0.0167365 -0.0274458 -0.0161388 0.0154364 -0.0333155 -0.0113605 0.0184679 -0.0442936 -1.47873e-05 0.0155046 0.0316788 -0.00167847 0.0135002 0.0290205 -0.00258954 0.0155046 0.0308041 -0.00650735 0.0135046 0.0267211 -0.00749434 0.0155046 0.0284632 -0.0102653 0.0135022 0.0243389 -0.012037 0.0155046 0.0254756 -0.0133593 0.0135046 0.0217446 -0.0141359 0.0155046 0.023749 -0.0145992 0.0135046 0.0204885 0.000528649 0.0135046 0.0297541 0.0189677 0.0135046 0.0349618 -0.00666003 -0.0155 0.051526 -0.0283195 -0.0155 0.0164681 -0.0312054 -0.0135 0.0153489 -0.0299433 -0.0155 0.0133428 -0.0319278 -0.0135 0.0138039 -0.0309812 -0.0155 0.010734 -0.0332057 -0.0135 0.0103998 -0.0319095 -0.0155 0.00772407 -0.034533 -0.0135 0.00520504 -0.0350639 -0.0135 0.00172456 -0.0326068 -0.0155 0.00462602 -0.0333351 -0.0155 -0.00166018 -0.0353942 -0.0135 -0.00484546 -0.0325182 -0.0147579 -0.0228378 -0.0304495 -0.0167337 -0.0219884 -0.0344791 -0.0139519 -0.0146073 -0.0347763 -0.0138102 -0.012727 -0.0287054 -0.015869 -0.0327728 -0.0267191 -0.0178446 -0.0315952 -0.0105619 -0.0178255 -0.0557958 -0.00915397 -0.0197996 -0.0539271 -0.0117274 -0.0197365 -0.0520352 -0.0132097 -0.0196608 -0.050694 -0.0173579 -0.0175095 -0.049734 -0.0159486 -0.0194523 -0.0477893 -0.013715 -0.017746 -0.0534186 -0.0229479 -0.0185405 -0.038093 -0.0207723 -0.0188788 -0.0414329 -0.0214472 -0.0170696 -0.0445395 -0.0176424 -0.0174849 -0.0494082 -0.00662814 -0.0197478 -0.0550483 -0.00500732 -0.0196244 -0.0553447 -0.0304008 -0.0154323 -0.0288477 -0.0299387 -0.0155608 -0.0299723 -0.022204 -0.0164402 -0.0244943 -0.029755 -0.0169755 -0.0241106 -0.0198358 -0.0169755 -0.0298451 -0.0288489 -0.0172613 -0.0265965 -0.0250053 -0.0181778 -0.0346659 -0.027919 -0.0175297 -0.0288941 -0.00767257 -0.0189824 -0.0496285 -0.0148625 -0.0179102 -0.0388409 -0.0184492 -0.0191861 -0.0446772 -0.0316906 -0.0162492 -0.0174527 -0.0250775 -0.0156987 -0.0152785 -0.0326394 -0.0158319 -0.012693 -0.0330699 -0.0156311 -0.00952292 -0.0253377 -0.015635 -0.0140909 -0.0333943 -0.0155 -0.00482338 -0.00270456 -0.0126714 -0.0536455 -0.00622584 -0.0170162 -0.0487867 -0.007074 -0.0121047 -0.0475868 -0.0153508 -0.0107718 -0.0346863 -0.0153513 -0.0155797 -0.0346868 -0.0167922 -0.0104824 -0.0320439 -0.0191496 -0.0147893 -0.0272266 -0.0189364 -0.0100031 -0.0277001 -0.0218126 -0.00922086 -0.02027 -0.0231995 -0.0137046 -0.0149872 -0.0232455 -0.00875901 -0.0149545 -0.023776 -0.0135564 -0.0119068 -0.0239468 -0.00855145 -0.0107417 -0.0243356 -0.0135 -0.0066036 -0.0243316 -0.0135 -0.00184404 -0.0243657 -0.00849999 -0.00225298 -0.0241627 -0.0135 0.000221741 -0.0236084 -0.00849998 0.00378534 -0.0222741 -0.0135 0.00834133 -0.0221313 -0.00849996 0.00874907 -0.019327 -0.00849999 0.0139804 -0.0208458 -0.00849999 0.0114953 -0.0197426 -0.0135001 0.0133808 -0.0208118 -0.0135012 0.0115705 -0.0226153 -0.0155 0.0124279 -0.023034 -0.0135 0.00605334 -0.0236453 -0.0135 0.00356129 -0.024956 -0.0155 0.00660623 -0.0261511 -0.0155 0.000440573 -0.0241738 -0.0135 -0.00879794 -0.0263715 -0.0155 -0.00269507 -0.016505 -0.0153559 -0.0325888 -0.0180968 -0.0173261 -0.0332345 -0.0261645 -0.0155 -0.00899147 -0.0234872 -0.0136265 -0.0135688 -0.0233238 -0.0161595 -0.0214531 -0.0243564 -0.0158871 -0.0181106 -0.0224535 -0.0139184 -0.0180405 -0.0209573 -0.0167318 -0.0274458 -0.021566 -0.0141708 -0.0209941 -0.0133356 -0.0159431 -0.0381125 -0.00404955 -0.0194507 -0.0546383 -0.0113605 -0.0184632 -0.0442936 -0.0101263 -0.0164604 -0.0431333 -0.0161347 -0.0135 0.0185827 -0.0177784 -0.0155 0.0197228 -0.0160739 -0.0155 0.0218393 -0.00473187 -0.0135 0.0276665 -0.0120369 -0.0155 0.0254757 -0.0130061 -0.0135001 0.0220949 -0.0145992 -0.0135 0.0204885 -0.00258971 -0.0155 0.0308039 -0.00508438 -0.0155 0.0297247 0.0189679 -0.0135 0.0349619 0.0103064 -0.0155016 0.0345959 0.00764102 -0.0152967 0.0336296 0.000528649 -0.0135 0.0297541 -1.47873e-05 -0.0155 0.0316788 -0.00706303 -0.0135 0.0542878 -0.00825132 0.0135046 0.0527414 0.00581813 -0.0115 0.048132 0.00556677 -0.0135114 0.0481771 -0.000101846 -0.0115 0.0383137 0.00148944 -0.0135146 0.0364464 0.00180403 0.0115046 0.0362813 0.00756756 0.0115046 0.047797 0.00306964 0.0115046 0.0476763 0.000764208 0.0115046 0.046112 -0.000149708 0.0135046 0.0448859 -0.000674271 0.0115046 0.0437261 -0.000900316 0.0135054 0.0430187 -0.00103391 0.013537 0.040617 -0.000101846 0.0115046 0.0383137 0.0052739 -0.0135149 0.035078 0.00339676 -0.0135 0.0354842 0.00275494 -0.0155 0.0335901 0.0093717 -0.0135173 0.0469177 0.00972607 -0.0155 0.0490054 0.0122199 -0.0155 0.0468226 0.0131031 -0.0155 0.0454049 0.0116644 -0.013507 0.0437815 0.0139104 -0.0155 0.0405382 0.0078176 -0.0135229 0.0355002 0.00986791 -0.0135226 0.0367683 0.0118813 -0.0155 0.0360458 0.0128468 -0.0155 0.0373969 0.00493516 -0.0155186 0.0330979 0.00655321 -0.0153412 0.0333686 0.00123825 -0.0155 0.0342758 -0.00125558 -0.0155 0.0364586 -0.00213914 -0.0155 0.0378766 -5.67776e-08 -0.0135117 0.0380805 -0.000980484 -0.0135079 0.0405014 -0.00299927 -0.0155 0.0410767 -0.000874526 -0.0135131 0.0431899 -0.00257029 -0.0155 0.0443623 0.00756756 -0.0135 0.047797 0.00491644 -0.0155 0.0501219 0.00339003 -0.013512 0.0478462 0.00171218 -0.0155 0.049259 0.00101343 -0.0135267 0.0464674 -0.000149708 -0.0135 0.0448859 0.00157904 0.0135163 0.036397 0.000444981 0.015504 0.034741 -0.00125558 0.0155046 0.0364586 5.15179e-05 0.0135167 0.0379804 -0.00213914 0.0155046 0.0378766 0.00787218 0.0135205 0.0477248 0.00546694 0.013519 0.0481921 0.00657661 0.0155046 0.0500699 0.00491644 0.0155046 0.0501219 0.00327002 0.0155046 0.0498478 0.00171218 0.0155046 0.049259 0.00329027 0.0135162 0.0477989 0.00109634 0.0135114 0.0465097 0.00820904 0.0155046 0.0496914 0.0096989 0.0135093 0.0466107 0.0110837 0.0155046 0.0480338 0.0118813 0.0155046 0.0360458 0.0128468 0.0155046 0.0373969 0.0115508 0.0135183 0.0391757 0.0139633 0.0155046 0.0422049 0.012015 0.0135154 0.0413759 0.00292839 0.0155043 0.0335223 0.00565788 0.0154273 0.0332001 0.00706479 0.0153156 0.0334816 0.0088863 0.0153449 0.0340265 0.010317 0.0155097 0.0346033 0.0240728 0.0050023 0.0490862 0.0240728 -0.0115 0.0490862 0.024104 0.0050023 0.0549923 0.00396951 0.0155046 0.0588411 0.00580871 0.0142389 0.059658 0.0075954 0.0140285 0.0593967 0.024104 0.0140046 0.0549923 0.00396951 -0.0155 0.0588411 0.024104 -0.014 0.0549923 0.00309741 0.0145094 0.0596434 -0.0029183 -0.0137047 0.0577305 -0.00214406 -0.0137775 0.0581439 0.00666084 -0.0141075 0.0595606 0.0084203 -0.014 0.0591999 0.0084203 0.0140046 0.0591999 0.00398376 -0.0146645 0.0597023 0.00509475 -0.0143769 0.059702 + + + + + + + + + + -0.33849 0.572487 0.746782 0.294871 0.603455 -0.740873 0.311705 0.781768 -0.540073 0.61305 0.595111 -0.519628 -0.334827 0.742519 0.580135 -0.600074 0.643502 0.475202 -0.531416 0.789634 0.306717 -0.781867 0.595977 0.183015 -0.703899 0.704219 0.0927469 -0.696068 0.696277 -0.17518 -0.911412 0.393625 -0.119947 -0.439704 0.836563 -0.326839 -0.622914 0.694744 -0.359595 -0.385647 0.698764 -0.602499 -0.326128 0.758002 -0.564866 -0.0861601 0.629412 -0.772281 -0.105077 0.59268 -0.798554 0.0888773 0.732858 -0.674552 0.555755 0.748623 -0.361525 0.789127 0.585498 -0.185664 0.703002 0.703108 -0.106902 0.696278 0.696216 0.174588 0.910051 0.396857 0.119632 0.440558 0.836034 0.327041 0.622928 0.69471 0.359637 0.385039 0.698612 0.603064 0.326704 0.756934 0.565964 0.0841884 0.630715 0.771434 0.10529 0.589368 0.800974 -0.089092 0.732771 0.674618 -0.216851 -0.451158 -0.865698 -0.2496 -0.629962 -0.735424 -0.365384 -0.789939 -0.492433 -0.39657 -0.700213 -0.593661 -0.61432 -0.696526 -0.370759 0.364598 -0.754806 -0.545285 0.23955 -0.668257 -0.704307 0.195563 -0.503362 -0.841654 0.0928781 -0.704083 -0.704018 -0.0925234 -0.704043 -0.704104 0.217859 -0.449617 0.866246 0.25001 -0.627791 0.737139 0.365 -0.790884 0.4912 0.396581 -0.700225 0.59364 0.614213 -0.696561 0.37087 -0.364216 -0.754963 0.545323 -0.239187 -0.667742 0.704919 -0.195163 -0.503652 0.841573 -0.0926759 -0.704219 0.703908 0.0926186 -0.704191 0.703943 0.419545 -0.696025 -0.582693 0.519682 -0.780622 -0.347217 0.609453 -0.702921 -0.3667 0.670515 -0.706147 -0.227523 0.797264 -0.582412 -0.158639 0.703904 -0.704223 -0.0926778 0.703945 -0.704189 0.0926197 0.731611 -0.672622 0.111021 0.660535 -0.716539 0.2242 0.707034 -0.526321 0.472323 -0.468398 -0.63508 0.614229 -0.557305 -0.741981 0.372662 -0.743813 -0.530589 0.406471 -0.694066 -0.680236 0.235694 -0.759221 -0.643079 0.10016 -0.702315 -0.702385 0.1158 -0.704102 -0.704046 -0.0925233 -0.731266 -0.673074 -0.110553 -0.660502 -0.716602 -0.224096 -0.707548 -0.525374 -0.472608 0.117107 0.967924 -0.222281 0.0641819 0.982834 -0.172971 -0.00136494 0.999983 -0.00558717 -0.11666 0.990545 -0.0721876 0.144917 0.988771 -0.036474 -0.000422887 0.999999 -0.00162666 0.00152772 0.999999 0.000383282 -0.126769 0.991917 0.00542685 -0.964903 0.261486 -0.024232 -0.993971 0.10964 0.000690477 -0.966833 0.109532 0.230733 -0.957175 0.242508 0.15813 -0.953696 0.197808 0.226577 -0.714732 0.109942 -0.690704 -0.817491 0.108858 -0.56556 -0.817491 0.108862 -0.565559 -0.893997 0.110018 -0.434356 -0.937004 0.169468 -0.305458 -0.947667 0.109577 -0.299866 -0.983572 0.110465 -0.142769 -0.604543 0.22797 -0.763255 -0.613786 0.191241 -0.765959 -0.513628 0.110474 -0.850871 -0.373741 0.109319 -0.921069 -0.373679 0.108568 -0.921183 -0.228986 0.109708 -0.967228 -0.0938601 0.165145 -0.981793 -0.0866066 0.1091 -0.990251 0.192212 0.108335 -0.975355 0.212997 0.347333 -0.913232 0.0834112 0.110034 -0.990422 0.631042 0.110578 -0.767827 0.46321 0.109628 -0.879442 0.457877 0.439652 -0.772693 0.377898 0.109397 -0.919362 -0.374417 0.924232 0.074876 -0.274158 0.961664 -0.00635809 -0.275771 0.961198 -0.00692968 -0.261985 0.961285 -0.0854093 -0.262079 0.96126 -0.0854093 -0.226812 0.96126 -0.15664 -0.172099 0.961274 -0.215252 -0.103641 0.961263 -0.255405 -0.103621 0.961271 -0.255382 -0.026237 0.961271 -0.274352 -0.0262846 0.961238 -0.274463 0.0531075 0.961247 -0.270526 0.15268 0.968718 -0.19564 0.15249 0.97002 -0.189227 0.432578 0.745478 -0.507088 0.430986 0.767303 -0.474865 0.298619 0.768156 -0.566359 0.298816 0.767291 -0.567427 0.124254 0.767549 -0.628833 0.124132 0.766641 -0.629962 -0.0611243 0.766642 -0.639158 -0.0610472 0.766802 -0.638974 -0.241361 0.766789 -0.594794 -0.241356 0.766795 -0.594788 -0.401556 0.766767 -0.500821 -0.40096 0.76734 -0.500421 -0.526813 0.767671 -0.364898 -0.527933 0.766733 -0.365249 -0.610392 0.766696 -0.198993 -0.610407 0.766684 -0.198993 -0.641759 0.766737 -0.0161264 -0.641863 0.766651 -0.016097 -0.632262 0.769908 0.0865241 -0.673428 0.72861 0.124992 0.577258 0.384064 -0.720603 0.589575 0.438995 -0.678001 0.419206 0.436565 -0.796039 0.419217 0.436775 -0.795917 0.173913 0.436781 -0.882596 0.173926 0.43684 -0.882565 -0.085552 0.436836 -0.895464 -0.0856144 0.436664 -0.895542 -0.338263 0.436676 -0.833602 -0.338244 0.436716 -0.833589 -0.562515 0.436696 -0.70205 -0.562594 0.436552 -0.702076 -0.739843 0.436616 -0.511858 -0.739869 0.43657 -0.511859 -0.855339 0.436626 -0.278841 -0.855349 0.436608 -0.278839 -0.899376 0.436595 -0.0225551 -0.899327 0.436693 -0.0225851 -0.882913 0.439771 0.164514 -0.856625 0.503793 0.111291 0.32152 -0.848829 -0.419661 0.516366 -0.581318 -0.628837 0.549159 -0.546666 -0.632124 0.409932 -0.546985 -0.729906 0.62944 -0.193782 -0.752499 0.632458 -0.186958 -0.751693 0.491945 -0.18709 -0.850287 0.477854 -0.218449 -0.850844 0.316696 -0.147057 -0.937058 0.0581182 -0.320933 -0.945317 -0.468672 -0.236203 -0.851208 -0.454005 -0.186861 -0.871185 -0.29447 -0.186425 -0.937301 -0.302378 -0.217705 -0.927994 -0.0980078 -0.149894 -0.983833 -0.669647 -0.0758252 -0.738799 -0.590394 -0.271036 -0.760246 -0.620735 -0.0224921 -0.783698 0.161611 -0.186813 -0.969011 0.302497 -0.186101 -0.934806 0.257671 -0.547305 -0.79628 0.4096 -0.547452 -0.729742 0.269527 -0.834731 -0.480188 0.347234 -0.83522 -0.426422 -0.502355 -0.637024 -0.584671 -0.52081 -0.548088 -0.654489 -0.403611 -0.547255 -0.733219 -0.403626 -0.547444 -0.73307 -0.250876 -0.547306 -0.798447 -0.250862 -0.547241 -0.798496 -0.0830213 -0.547179 -0.832888 -0.0829791 -0.54706 -0.83297 0.0902893 -0.547072 -0.832202 -0.32347 -0.864182 -0.385431 -0.339481 -0.835347 -0.432375 -0.265616 -0.834681 -0.482448 -0.265622 -0.834625 -0.482541 -0.165191 -0.83453 -0.525616 -0.16518 -0.834473 -0.525709 -0.0546451 -0.834414 -0.548422 -0.0546612 -0.834445 -0.548373 0.0594743 -0.83445 -0.547865 0.0594325 -0.8345 -0.547793 0.169611 -0.834565 -0.52415 -0.107701 -0.185645 -0.976697 0.106018 -0.185843 -0.976843 0.0903244 -0.547 -0.832245 0.257825 -0.547052 -0.796405 0.169728 -0.834461 -0.524278 0.269756 -0.834562 -0.480351 0.0893292 -0.983218 -0.159067 0.102548 -0.980885 -0.165376 0.10087 -0.980053 -0.171237 0.0585199 -0.983944 -0.168613 0.0579918 -0.9821 -0.179212 0.0203326 -0.982092 -0.1873 0.0202626 -0.982121 -0.18716 -0.0186656 -0.98212 -0.187329 -0.0186375 -0.9821 -0.187436 -0.0564634 -0.982107 -0.179658 -0.10321 -0.982275 -0.156474 -0.0908165 -0.982115 -0.164934 -0.0908196 -0.98211 -0.164959 -0.0564592 -0.982095 -0.17973 0.36876 0.197008 0.908407 0.301135 0.593205 0.746609 0.381723 0.254702 0.88849 0.656707 0.256003 0.709365 0.900874 0.347763 0.259782 0.0993574 0.96449 0.24472 0.232143 0.786883 0.571774 0.949533 0.30889 -0.0545441 0.968267 0.249292 -0.0176958 0.292775 0.701979 0.649237 0.544658 0.694399 0.470274 0.542049 0.711271 0.447522 0.639803 0.697506 0.322705 0.656691 0.748867 -0.0891872 0.10346 0.976956 0.186689 0.361728 0.93206 0.020393 0.266994 0.963695 -0.00230683 -1 0 1.6043e-05 -0.986923 0 0.161194 -0.99884 -0.0481518 1.60244e-05 -0.995022 0 -0.0996564 -0.866026 0 -0.5 -0.872255 0 -0.489052 -0.865988 0.00931915 -0.499978 -0.715982 0 -0.698119 -0.872213 -0.00977965 -0.489028 -0.715982 0 -0.698119 -0.500005 0 -0.866022 -0.500005 0 -0.866022 -4.84263e-05 0 -1 -4.84263e-05 0 -1 0.500036 0 -0.866005 0.500036 0 -0.866005 0.866002 0 -0.500041 0.866002 0 -0.500041 1 0 3.22342e-05 1 0 3.22342e-05 0.86602 0 0.500009 0.86602 0 0.500009 0.500004 0 0.866023 0.500004 0 0.866023 0 0 1 0 0 1 -0.499976 0 0.866039 -0.499976 0 0.866039 -0.866042 0 0.499972 -0.866042 0 0.499972 -0.986923 0 0.161194 -0.992056 0.0771588 -0.0993593 0.975354 0 -0.220644 -0.809858 0 -0.586626 -0.00037767 0.00273328 -0.999996 -0.0708384 -0.00278417 -0.997484 -0.521249 0.00393357 -0.853395 -0.429877 -0.00644503 -0.902865 -0.770344 0.00372788 -0.637617 0.976026 0.000236439 -0.217654 0.798997 -0.000203455 -0.601335 0.784675 0.00166693 -0.619905 0.441542 0.00166429 -0.897239 0.421247 -0.000129868 -0.906946 0.995291 0 0.0969366 0.980745 0.00256119 0.195276 0.943258 -0.0012151 0.332059 0.831475 0.00182741 0.55556 0.805264 0 0.592916 0.555495 0 0.83152 0.517491 -0.00234075 0.855686 0.195161 0.00182629 0.98077 0.143088 -0.000292452 0.98971 -0.200551 0 -0.979683 -0.152497 0.00244128 -0.988301 -0.518977 -0.00224671 -0.854785 -0.835664 0 -0.549241 -0.892577 -0.00632684 -0.450852 -0.773619 0 -0.633651 -0.558508 0 -0.829499 -0.137003 0.632381 -0.762447 -0.29515 0.701326 0.648867 -0.333934 0.605015 0.722804 -0.123125 0.702258 -0.701195 0.257243 0.379771 -0.888594 0.20804 0.701251 -0.681884 0.595672 0.492789 -0.634298 0.495322 0.698206 -0.51688 0.674613 0.697315 -0.242175 0.674702 0.697217 -0.242212 0.711023 0.697232 0.0911786 0.711514 0.696726 0.0912175 0.591984 0.696948 0.404745 0.591731 0.697254 0.404589 0.342988 0.697217 0.629482 0.427503 0.480581 0.765691 0.0191227 0.698642 0.715216 0.0383204 0.356741 0.933417 -0.411648 -0.108281 0.904887 -0.380174 -0.345978 0.857769 0.040943 0.00384309 0.999154 0.0494825 -0.256261 0.96534 0.49272 0.00267047 0.870184 0.481001 -0.161684 0.861682 0.818483 0.166586 0.54985 0.82418 -0.0562791 0.563524 0.990398 0.0546393 0.126989 0.990374 0.0551245 0.126968 0.942546 -0.0541115 -0.329666 0.9288 0.161726 -0.33343 0.687734 -0.156374 -0.708921 0.691891 0.00171001 -0.722 -0.160883 -0.152417 -0.975134 -0.159872 -0.357564 -0.920103 0.301519 0.00386474 -0.953452 0.281464 -0.264362 -0.922437 -0.966804 0.194195 0.166069 -0.500922 0.794745 0.342721 -0.531913 0.781165 0.326879 -0.733875 0.632116 0.24871 0.0177498 0.950221 0.31107 0.179712 0.85223 0.491332 0.261598 0.734022 0.62672 0.258177 0.753943 0.604081 0.465979 0.579154 0.668913 0.527976 0.313856 0.789136 0.533348 0.41719 0.735862 0.54568 0.332359 0.769266 0.708197 0.192383 0.679299 -0.498914 0.216927 0.839064 -0.0619815 0.233952 0.970271 -0.242554 0.423234 0.87295 -0.244644 0.41279 0.877356 -0.856346 0.425215 0.293026 0.343007 0.180856 0.921758 -0.252137 0.940987 0.225767 -0.886966 0.327559 0.325572 -0.828878 0.182804 0.528719 0.59777 -0.665842 -0.446459 -0.604113 -0.25556 -0.754809 -0.4195 -0.37659 -0.825954 -0.413724 -0.698457 -0.583943 0.192378 -0.967123 -0.166326 -0.0258065 -0.938173 -0.345204 0.432051 -0.884996 -0.173531 0.549237 -0.807868 -0.213748 0.980602 -0.195152 0.0183439 0.826536 -0.551878 -0.110771 0.358832 -0.605391 -0.710452 -0.0346752 -0.897977 -0.438673 0.290402 -0.411502 -0.863906 -0.409906 -0.372055 -0.832798 0.308465 -0.329253 -0.892436 0.680376 -0.650911 -0.336753 0.671441 -0.634107 -0.383504 0.971059 0.00122078 -0.238837 0.985159 0.0124599 -0.171194 0.856662 -0.0095619 -0.51579 0.107206 -0.0059633 -0.994219 0.546129 -0.00234838 -0.837698 0.646842 0.0141734 -0.762492 -0.736952 0.0026114 -0.67594 0.148395 -7.78698e-05 -0.988928 -0.247486 -0.000769705 -0.968891 -0.174963 -0.0101006 -0.984523 -0.471057 0.00825428 -0.882064 -0.612546 -0.00464049 -0.790421 0.756731 0 0.653726 0.721676 -0.00225772 0.692228 -0.970746 0 0.240108 -0.985549 0.00589573 0.169289 -0.845838 -0.00370674 0.533427 -0.798718 0.000417929 0.601706 -0.631918 4.36746e-05 0.775035 -0.506109 -0.0041338 0.86246 0.556074 0.000570993 0.831133 0.47173 0.00337403 0.881736 0.348757 -0.00246434 0.93721 0.224047 -1.73574e-05 0.974578 0.134949 -2.07294e-05 0.990853 -0.0169491 0.00171611 0.999855 -0.0981355 -0.00293585 0.995169 -0.429508 0.00028672 0.903063 0.00711093 0.023507 0.999698 -0.388989 0.000363078 0.921242 -0.499479 0.0556369 0.864538 -0.639243 -0.000346779 0.769005 -0.846725 -0.00120254 0.53203 0.00063028 -0.0975226 0.995233 -0.499743 0.0291276 0.865684 -0.460029 -0.0707297 0.885082 0.500956 -0.017203 0.865302 0.0552534 0.00062565 0.998472 0.866035 -0.00498654 0.499958 0.999997 -0.00236453 5.14231e-05 0.988324 0.0538593 -0.142532 0.883752 -0.0225304 -0.467413 0.943784 -0.330516 -0.00562095 0.858768 0.128631 -0.495956 0.541219 -0.00052329 0.840882 0.85947 -2.03195e-06 0.511186 -0.539486 -0.0152599 -0.841856 -0.395388 0.000279267 -0.918514 -0.000527886 -0.000148418 -1 -0.000164256 0 -1 0.50209 0 -0.864815 0.499856 -0.00107633 -0.866108 0.806325 0.0106488 -0.591377 -0.999975 -0.00218911 0.00666161 -0.999997 -0.000448924 0.00251371 -0.866034 0.000744856 -0.499985 -0.849313 -0.0117696 -0.527758 -0.684552 0 -0.728964 -0.628316 0 -0.777958 -0.46204 0.0138688 -0.886751 -0.500233 0 -0.865891 -0.500233 0 -0.865891 0 0 -1 0 0 -1 0.499753 0 -0.866168 0.499763 9.84811e-07 -0.866162 0.866055 4.9186e-08 -0.499948 0.866055 0 -0.499949 1 0 5.14986e-05 1 0 5.14986e-05 0.866033 0 0.499986 0.866033 0 0.499986 0.499835 0 0.866121 0.499835 0 0.866121 0.000633297 0 1 0.000633297 0 1 -0.50024 0 0.865887 -0.50024 0 0.865887 -0.866054 0 0.499951 -0.866054 0 0.499951 -1 0 -5.15736e-05 -1 0 -5.15736e-05 -0.865963 0 -0.500108 -0.865963 0 -0.500108 -0.50023 0 -0.865893 -0.50023 0 -0.865893 0 0 -1 0 0 -1 0.500252 0 -0.86588 0.500252 0 -0.86588 0.866051 0 -0.499955 0.866051 0 -0.499955 1 0 6.47668e-05 1 0 6.47668e-05 0.86604 0 0.499975 0.86604 0 0.499975 0.49974 0 0.866175 0.49974 0 0.866175 0 0 1 0 0 1 -0.500238 0 0.865888 -0.500238 0 0.865888 -0.866056 0 0.499946 -0.866056 0 0.499946 -1 0 0.00016742 -1 0 0.00016742 -0.866029 0 -0.499993 -0.866029 0 -0.499993 -0.499738 0 -0.866177 -0.499738 0 -0.866177 0 0 -1 0 0 -1 0.499766 0 -0.866161 0.499766 0 -0.866161 0.866069 0 -0.499925 0.866065 -7.59239e-07 -0.499932 1 1.03504e-06 7.67634e-05 1 0 6.47668e-05 0.866032 0 0.499988 0.866032 0 0.499988 0.499863 0 0.866104 0.499863 0 0.866104 0 0 1 0 0 1 -0.49978 0 0.866152 -0.49978 0 0.866152 -0.86606 0 0.49994 -0.86606 0 0.49994 -1 0 -6.41671e-05 -1 0 -6.41671e-05 -0.866148 0 -0.499787 -0.866148 0 -0.499787 -0.49978 0 -0.866152 -0.49978 0 -0.866152 0 0 -1 0 0 -1 0.499799 0 -0.866141 0.499799 0 -0.866141 0.866052 0 -0.499955 0.866052 0 -0.499955 1 0 -0.000218888 1 0 -0.000218888 0.866012 0 0.500024 0.86601 2.46441e-07 0.500026 0.500252 1.42357e-07 0.86588 0.500253 0 0.865879 0 0 1 0 0 1 -0.500227 0 0.865894 -0.500227 0 0.865894 -0.866093 0 0.499884 -0.866093 0 0.499884 -1 0 0 -1 0 0 -0.866004 0 -0.500037 -0.866004 0 -0.500037 -0.500255 0 -0.865878 -0.500255 0 -0.865878 0 0 -1 0 0 -1 0.500255 0 -0.865878 0.500255 0 -0.865878 0.866088 0 -0.499892 0.866088 0 -0.499892 1 0 0 1 0 0 0.865846 0 0.500311 0.865846 0 0.500311 0.500255 0 0.865878 0.500255 0 0.865878 0 0 1 0 0 1 -0.500283 0 0.865862 -0.500283 0 0.865862 -0.865902 0 0.500214 -0.865902 0 0.500214 -1 0 0.000257868 -1 0 0.000257868 -0.866004 0 -0.500037 -0.866004 0 -0.500037 -0.500118 0 -0.865957 -0.500118 0 -0.865957 0 0 -1 0 0 -1 0.499963 0 -0.866047 0.499963 0 -0.866047 0.866041 0 -0.499972 0.866041 0 -0.499972 1 0 -2.51293e-06 1 0 -2.51293e-06 0.866029 0 0.499994 0.866029 0 0.499994 0.499993 0 0.86603 0.499993 0 0.86603 0 0 1 0 0 1 -0.499963 0 0.866047 -0.499963 0 0.866047 -0.86604 0 0.499975 -0.86604 0 0.499975 -1 0 1.94288e-05 -1 0 1.94288e-05 -0.865999 0 -0.500046 -0.865999 0 -0.500046 -0.199006 0.675381 -0.710111 -0.269677 0.257203 -0.927966 -0.26 0.189347 -0.946862 -0.0776171 0.962582 -0.259636 -0.072742 0.965426 -0.250322 -0.126892 0.96557 -0.227097 -0.126876 0.965576 -0.22708 -0.170938 0.965578 -0.196059 -0.170921 0.965583 -0.196047 -0.207646 0.965582 -0.156634 -0.207675 0.965574 -0.156647 -0.235495 0.965572 -0.110515 -0.235488 0.965573 -0.110514 -0.253201 0.965574 -0.0596307 -0.253211 0.965572 -0.0596307 -0.260071 0.96557 -0.00617262 -0.260004 0.965588 -0.00618705 -0.255696 0.965589 0.047513 -0.255686 0.965592 0.0475088 -0.240418 0.965593 0.099141 -0.240485 0.965572 0.0991895 -0.214895 0.96557 0.146613 -0.214875 0.965577 0.146591 -0.18006 0.965577 0.187721 -0.18006 0.965577 0.187721 -0.137537 0.965577 0.220781 -0.137525 0.965587 0.220744 -0.0830369 0.96539 0.247239 -0.0815981 0.967798 0.238135 -0.199405 0.70441 -0.681208 -0.345884 0.705146 -0.618977 -0.345832 0.705214 -0.61893 -0.465925 0.705207 -0.534413 -0.465953 0.705176 -0.534429 -0.566001 0.705217 -0.426979 -0.56606 0.705158 -0.426999 -0.641902 0.705146 -0.301215 -0.641842 0.705204 -0.301208 -0.690142 0.705189 -0.162521 -0.690102 0.705227 -0.162524 -0.708768 0.705241 -0.0168386 -0.708816 0.705193 -0.0168233 -0.697082 0.705205 0.129469 -0.697246 0.705026 0.129561 -0.655617 0.705008 0.270426 -0.655468 0.705197 0.270295 -0.585685 0.705199 0.399583 -0.585692 0.705189 0.399592 -0.490812 0.705193 0.51167 -0.490833 0.705145 0.511717 -0.37494 0.70514 0.601829 -0.374955 0.705076 0.601894 -0.226394 0.704039 0.673108 -0.226355 0.704434 0.672709 -0.47128 0.257662 -0.843508 -0.471367 0.257417 -0.843534 -0.635014 0.257425 -0.728347 -0.635003 0.257455 -0.728346 -0.771425 0.257454 -0.581911 -0.771384 0.257567 -0.581916 -0.874742 0.257561 -0.410473 -0.874739 0.257571 -0.410474 -0.940527 0.25761 -0.221461 -0.940501 0.257695 -0.221477 -0.965944 0.257722 -0.0230436 -0.966045 0.257352 -0.0229509 -0.950069 0.257291 0.17655 -0.949991 0.257654 0.176441 -0.893222 0.257658 0.368466 -0.893204 0.257778 0.368425 -0.798183 0.257803 0.544464 -0.798206 0.257497 0.544575 -0.668944 0.257497 0.697287 -0.668944 0.257263 0.697373 -0.510943 0.257287 0.820208 -0.510955 0.257444 0.820151 -0.330989 0.257442 0.907838 -0.314795 0.159799 0.935611 -0.204824 0.346876 0.915273 -0.937306 0.186577 0.294357 -0.860747 0.487926 0.145063 -0.84367 -0.0747623 0.53163 -0.508595 0.856958 0.0833958 -0.659976 0.732931 0.165057 -0.0552507 0.928332 0.367623 -0.0635936 0.941491 0.330986 0.167662 0.864059 0.474648 0.28664 0.755987 0.58849 0.305251 0.703225 0.642103 0.441603 0.583277 0.681744 0.503034 0.307663 0.807651 0.511755 0.413742 0.752944 0.521697 0.325991 0.788392 0.683162 0.185927 0.706201 -0.519135 -0.114049 0.847049 -0.0760877 0.489468 0.868695 -0.185689 0.243639 0.951924 -0.206519 0.448378 0.869659 -0.369108 0.647483 0.666727 -0.785442 0.54591 0.291654 -0.787912 0.526521 0.319327 0.316413 0.178646 0.931648 -0.191202 0.961242 0.198634 -0.0934955 0.94765 0.305315 -0.612539 0.67849 0.405521 -0.151975 0.918209 0.36578 0.473924 0.817744 0.326636 0.280718 0.920439 0.272011 0.88737 0.38785 0.249293 0.764836 0.568694 0.302677 -0.382534 0.86117 0.334745 -0.614563 0.675066 0.408164 -0.0423216 0.287466 0.956855 -0.637384 0.164028 0.752886 -0.529119 0.429973 0.731544 0.121277 0.965542 0.230261 0.546264 0.679852 0.489282 0.512875 0.649477 0.561372 0.0456669 0.692824 0.719659 -0.115301 0.441518 0.889813 0.957365 0.175329 0.229592 0.531052 0.262465 0.805665 0.296654 0.150158 0.943106 -0.383546 0 -0.923522 -0.975119 0 -0.221683 -0.972275 0.00134041 -0.233835 -0.805092 -0.000195559 -0.59315 -0.762123 0.0063979 -0.647401 -0.379726 0.000464143 -0.925099 -0.974295 -0.142911 -0.174143 -0.921722 -0.327362 -0.207996 -0.746873 -0.58828 -0.310011 -0.810696 -0.453819 -0.369891 -0.714029 -0.610189 -0.343268 -0.524125 -0.784422 -0.331625 -0.380456 -0.126678 -0.916082 -0.704298 -0.172271 -0.688685 -0.54068 -0.775934 -0.324949 -0.191174 -0.960896 -0.200328 0.695286 0 0.718733 -0.970527 0 0.240994 -0.986076 0.0061015 0.166185 -0.846032 -0.00383307 0.533118 -0.801455 9.1864e-05 0.598055 -0.634191 -6.75801e-05 0.773176 -0.52254 -0.00421718 0.852604 0.695353 -5.01877e-06 0.718668 0.528677 -3.81577e-06 0.848823 0.467768 0.000992899 0.883851 0.31915 -0.00267529 0.9477 0.253347 0.000204263 0.967376 -0.0211215 0.00160494 0.999776 -0.115529 -0.00355211 0.993298 -0.418596 0.00110321 0.908172 0.936008 -0.000531578 0.351977 0.933977 0 0.357334 -0.908315 0 0.418288 -0.932819 0.00746204 0.360268 -0.78849 -0.00199113 0.615044 -0.64126 0.00382506 0.767314 -0.586482 -0.00142312 0.809961 -0.200035 0.00280105 0.979785 -0.174127 -6.24208e-05 0.984723 0.2597 -0.00358389 0.965683 0.304786 0.00197519 0.952419 0.62043 -0.000532673 0.784261 0.786672 -0.0155895 0.617174 0.68585 0.00275345 0.727738 -0.218384 0 0.975863 0.50368 -0.000172456 -0.86389 0.503752 0 -0.863848 0.21496 0 -0.976623 0.21496 0 -0.976623 -0.0752321 0 -0.997166 -0.192938 -0.203014 -0.959979 -0.279065 0 -0.960272 -0.0124425 -0.106238 0.994263 -0.0384094 0 0.999262 0.269479 0 0.963006 0.269479 0 0.963006 -0.218384 0 0.975863 -0.342535 0 0.939505 -0.437613 -0.0418186 0.898191 -0.528743 0 0.848782 -0.692289 0 0.72162 -0.762636 -0.0418189 0.645475 -0.826108 0 0.563512 -0.924434 0 0.381341 -0.95812 -0.0418186 0.283297 -0.983168 0 0.182701 -0.999716 0 -0.0238493 -0.99101 -0.0417985 -0.12709 -0.97338 0 -0.229197 -0.905285 0 -0.424805 -0.855664 -0.0418219 -0.51584 -0.798337 0 -0.602211 -0.657162 0 -0.753749 -0.57505 -0.0418233 -0.817048 -0.487749 0 -0.872984 -0.279065 0 -0.960272 0.607997 0 0.793939 0.666421 -0.0032375 0.745569 0.758989 1.06766e-05 0.651104 0.869427 -2.89618e-05 0.494062 0.927864 -0.00525817 0.372882 0.964832 -2.29364e-05 0.262868 0.835274 0 -0.549834 0.832233 -0.000391198 -0.554425 0.992433 0.000437455 -0.122787 0.983261 -0.00487978 -0.182139 0.997308 1.01225e-05 0.0733261 0.86555 -0.0328921 0.499742 0.999034 -0.0439414 -2.49322e-06 0.991455 0 0.130448 0.946939 0 0.321412 0.865529 -0.0329055 -0.499777 0.946967 0 -0.32133 0.991444 0 -0.130536 0.499771 -0.0330086 -0.865528 0.555834 0 -0.831294 0.831487 0 -0.555544 0 -0.0439573 -0.999033 0.130792 0 -0.99141 0.322006 0 -0.946738 -0.499752 -0.0328828 -0.865544 -0.32139 0 -0.946947 -0.130286 0 -0.991477 -0.865576 -0.0328893 -0.499697 -0.831557 0 -0.55544 -0.555472 0 -0.831535 -0.999033 -0.0439572 0 -0.991476 0 -0.130286 -0.94698 0 -0.321293 -0.865578 -0.0330778 0.49968 -0.946893 0 0.32155 -0.99141 0 0.130791 -0.499665 -0.0328865 0.865594 -0.555404 0 0.831581 -0.831275 0 0.555862 0 -0.0439406 0.999034 -0.130533 0 0.991444 -0.321318 0 0.946971 0.831525 0 0.555488 0.555496 0 0.831519 0.499718 -0.0329116 0.865563 0.321191 0 0.947014 0.130447 0 0.991455 0.865921 0.0199323 -0.499783 0.834499 0 -0.55101 0.499871 0 -0.8661 0.999673 0.0255575 -3.86209e-05 0.989779 -0.00229957 -0.142591 -4.31676e-05 0.0255569 0.999673 0.130331 0 0.991471 0.499937 0 0.866062 0.499937 0 0.866062 0.866032 0 0.499989 0.866032 0 0.499989 0.99147 0 0.130335 -0.999674 0.0255427 3.87708e-05 -0.991431 0 0.130632 -0.866093 0 0.499883 -0.866093 0 0.499883 -0.499871 0 0.8661 -0.499871 0 0.8661 -0.130926 0 0.991392 0.499871 0 -0.8661 0.130629 0 -0.991431 4.31677e-05 0.0255402 -0.999674 -0.13046 0 -0.991454 -0.500003 0 -0.866024 -0.500003 0 -0.866024 -0.866052 0 -0.499954 -0.866052 0 -0.499954 -0.991451 0 -0.13048 0.000223801 -1 9.26287e-05 0.000364952 -1 -6.01743e-05 0 1 0 0.000323567 -1 -0.000176819 0.000306623 -1 -5.39553e-05 0 -1 0 0 -1 0 1.83718e-05 -1 0.000120658 3.85858e-05 -1 0.000112231 -4.57425e-05 -1 0.000133434 -0.000175075 -1 0.000181456 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.00107088 -0.999999 0.000484541 -0.000866626 -1 0.000503049 -0.000586248 -0.999999 0.000838833 -0.000748589 -0.999995 0.00322174 0.000153574 -1 0.000206974 0 -1 0 0 -1 0 0 -1 0 0 -1 0 9.39621e-06 -1 -3.98883e-06 0.0625798 -0.997516 0.0323228 0.0636009 -0.997644 0.0257261 0.0408953 -0.998985 -0.0188759 0 -1 0 0 -1 0 0 -1 0 0.0240134 -0.99971 0.00160966 0.017403 -0.999843 0.00325159 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.000394487 -1 0.000273616 2.35829e-05 -1 3.45458e-05 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.000108307 1 1.77873e-05 4.76726e-05 1 -3.77522e-05 2.91469e-05 1 -6.43044e-05 6.04001e-05 1 1.34052e-05 0 1 0 0.000331292 1 0.000517579 3.90755e-05 1 0.000350246 0 1 0 0.00229592 0.999997 0.000896366 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.00710826 0.99997 0.00295433 0.028158 0.999603 0.000585037 0.0240228 0.99971 0.00161029 0 1 0 0 1 0 0 1 0 0 1 0 -0.00092086 0.999998 -0.00179354 0 1 0 0 1 0 0 1 0 0 1 0 0.939693 0 0.342018 0.939693 0 0.342018 0 -1 0 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.07664e-08 -1 5.33073e-08 2.04647e-09 -1 5.52943e-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 -8.85426e-07 -1 -1.11992e-07 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1.86097e-07 1 -2.75249e-07 0 1 0 -3.88393e-08 1 6.72833e-08 0 1 0 3.49867e-08 1 6.0834e-08 5.14518e-08 1 -2.97021e-08 5.7444e-08 1 0 2.03584e-08 1 -5.32361e-08 0 1 7.40834e-08 -1.52567e-07 1 -1.31465e-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 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 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.92571e-07 -1 1.34889e-06 2.49029e-07 -1 -1.75588e-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 -1.86774e-07 -1 -1.45659e-06 6.46195e-07 -1 -1.11932e-06 0 -1 -3.2543e-06 0 1 0 1.17015e-06 1 -1.95981e-06 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1.51845e-06 1 1.25459e-06 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1.04684e-06 1 1.81315e-06 1.29405e-10 1 2.67156e-06 -8.41595e-07 1 4.51578e-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.939695 0 0.342015 0.939695 0 0.342015 -0.894949 0 -0.446169 -0.89593 0.00301086 -0.444185 -0.904703 -0.0023145 -0.426037 -0.907103 -0.00555464 -0.420872 -0.9113 0 -0.411742 0 -1 0 0 -1 0 1 0 -1.13702e-05 1 0 -5.49996e-05 1 -9.53252e-05 0.000131443 1 -9.63658e-06 -7.53935e-06 1 1.69608e-05 1.32696e-05 -0.907117 0 -0.420879 -0.910394 0.0084742 -0.413655 -0.897276 -0.00450503 -0.441447 -0.894948 0.00128703 -0.446169 -0.892418 0 -0.45121 -0.985907 0 0.167297 -0.985831 -0.000388183 0.167741 -0.99441 0.000403692 0.105589 -0.994356 1.38043e-05 0.106093 -0.997924 1.38538e-05 0.0644023 -0.999422 0.00506534 0.0336195 -0.999599 0.00169855 0.0282726 -0.999816 -0.000827656 -0.0191434 -0.999341 0.00386098 -0.0360932 -0.998645 -2.23584e-07 -0.0520443 -0.997284 -3.00993e-06 -0.073647 -0.992552 0.00590972 -0.121674 -0.992773 0.00743618 -0.119778 -0.982961 -0.00275556 -0.183794 -0.981071 -1.8843e-05 -0.193648 -0.974783 -1.87222e-05 -0.223154 -0.971828 0.00258515 -0.235679 -0.968239 -0.000881376 -0.250024 -0.958642 0.00158765 -0.284612 -0.954059 0.00854368 -0.299498 -0.946947 -0.000390949 -0.321388 -0.935428 0.000403561 -0.353516 -0.935102 0 -0.354379 0 1 0 0 1 0 0 1 0 -0.00719721 0.999969 -0.00329354 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.258796 0.965932 -1.93309e-06 0.25882 0.965926 -9.75666e-07 0.707082 0.707132 -2.66547e-06 0.707179 0.707035 2.6658e-06 0.965939 0.258771 3.64122e-06 0.965866 0.259043 -7.282e-06 4.71319e-05 1 0.000624711 0.00633941 0.99998 -0.00011912 0 1 0 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.51738e-05 1 -0.000208955 0.713861 0 -0.700287 0.733541 0.134789 -0.666146 0.9934 -0.00676796 -0.114499 0.939526 0.114455 -0.322786 0.905235 0.337806 -0.257754 0.890659 -0.00626393 -0.454628 0.952491 0.279008 0.122132 0.995267 0.0754066 0.0612936 0.743111 -0.00420272 0.669155 0.801401 0.273415 0.531978 0.876769 0 0.480912 0.964433 0 0.264328 0.456745 -0.00361727 0.88959 0.538933 0.173121 0.824366 0.579956 0.0745577 0.811229 0.000198229 -1 0.000791357 -0.000349723 -1 0.000429385 -0.0266959 0.999368 0.0234547 -0.00308934 0.999959 -0.00847952 0.106885 0.976716 0.186017 -0.0118137 0.99982 -0.0148345 0.0919195 0.983021 0.158812 0.0500548 0.99456 0.0913538 0.0554791 0.994839 0.084956 0.052529 0.993614 0.0998602 0.0657868 0.99278 0.100295 0.0572509 0.992365 0.109245 0.0638069 0.991892 0.109901 0.0505151 0.995048 0.0856064 0.0543906 0.994467 0.0898731 0.0578713 0.99397 0.0931408 0.0366818 0.99647 0.0755059 0.0604235 0.993442 0.0970715 0.064973 0.992789 0.100744 0.0650308 0.992877 0.0998311 0.0646361 0.994702 0.0799381 0.0877039 0.98478 0.150056 0.0864225 0.984567 0.152182 0.0806473 0.987138 0.138039 0.0723646 0.987144 0.142515 0.0824055 0.98766 0.133184 0.0763207 0.988165 0.133061 0.0901584 0.983563 0.156447 0.0900572 0.983552 0.156574 0.0913893 0.983151 0.158312 0.0918319 0.98303 0.158806 0.0913997 0.98313 0.158432 0.0918297 0.982948 0.159311 0.0920193 0.982889 0.15957 0.0885759 0.983763 0.156094 0.0901133 0.983778 0.155114 0.0560887 0.994565 0.087716 0.0546875 0.994647 0.0876714 0.0569143 0.994094 0.0923981 0.061107 0.993604 0.0949557 0.0285976 0.99666 0.0764953 0.0638429 0.99321 0.0972542 0.0570296 0.993958 0.0937783 0.0611361 0.992546 0.105423 0.0641861 0.991588 0.112395 0.0636146 0.992185 0.107342 0.0642956 0.991833 0.110148 0.0712478 0.989233 0.127833 0.0793245 0.987953 0.132875 0.0773704 0.987746 0.135539 0.0847285 0.985507 0.146958 0.0839292 0.985741 0.145843 0.0756894 0.987988 0.134728 0.0843645 0.986824 0.138061 0.0691884 0.990344 0.120129 0.065995 0.991229 0.114499 0.055033 0.993586 0.0987876 0.047452 0.994207 0.0964401 0.0521114 0.994269 0.0933416 0.0874213 0.984481 0.152169 0.0885191 0.984527 0.151229 0.0905725 0.983891 0.154124 0.08817 0.984575 0.151125 0.0871337 0.984675 0.151071 0.0886386 0.984312 0.152556 0.0916819 0.983673 0.154861 0.0927524 0.983472 0.155499 0.0936326 0.983315 0.155965 0.0926983 0.983183 0.157346 0.0771394 0.988455 0.130406 0.0727797 0.987992 0.136291 0.0900071 0.984662 0.149466 0.0872883 0.98397 0.155508 -0.0423798 0.996153 -0.0767051 -0.0359701 0.997504 -0.0607665 -0.025903 0.998152 -0.0549625 -0.0576906 0.997713 -0.0352272 -0.0233436 0.99892 -0.0401644 -0.018269 0.999342 -0.0313472 -0.0628566 0.992745 -0.102498 -0.0627907 0.992747 -0.102525 -0.0529583 0.994295 -0.0925867 -0.0534844 0.99432 -0.0920215 -0.0449154 0.996087 -0.0761187 -0.0659794 0.991421 -0.112832 -0.0621296 0.991773 -0.111924 -0.0661983 0.991281 -0.113926 -0.0672411 0.991177 -0.114221 -0.0685179 0.991129 -0.113881 -0.0675128 0.991149 -0.114304 -0.0684538 0.991075 -0.114391 -0.0659119 0.991156 -0.115178 -0.0663426 0.991134 -0.11512 -0.0663829 0.991131 -0.115122 -0.0648921 0.991518 -0.112609 -0.0647978 0.991528 -0.11258 -0.0664489 0.99113 -0.115092 -0.0658977 0.991156 -0.115183 -0.0661705 0.991157 -0.115021 -0.0651126 0.991252 -0.114799 -0.064415 0.991304 -0.11475 -0.0599532 0.991566 -0.114901 -0.061275 0.991593 -0.113971 -0.0642921 0.991678 -0.111544 -0.0651437 0.991481 -0.112789 -0.063714 0.99184 -0.110426 -0.0636081 0.991951 -0.109489 -0.0728788 0.992655 -0.0965675 -0.0578245 0.993146 -0.101573 -0.0474161 0.995487 -0.0822041 -0.0326359 0.995504 -0.0889207 -0.0583172 0.99632 -0.0628098 -0.0412965 0.996664 -0.0703931 -0.0262717 0.998528 -0.0474463 -0.0377143 0.998254 -0.0454535 0.0938926 0.994807 0.0392961 0.0439182 0.997842 0.0488097 0.0329515 0.99812 0.0516807 0.086335 0.994515 0.0590497 0.0201802 0.998611 0.0486775 0.0125515 0.998752 0.0483435 -0.00897927 0.998759 0.0489852 -0.0174561 0.999319 -0.0324951 -0.0389573 0.999159 -0.0127679 -0.0129019 0.99967 -0.0221953 -0.00158607 0.999996 -0.00255914 0.0124101 0.999893 -0.00776 -0.00392423 0.999924 0.0116552 0.00416472 0.999957 0.00825687 0.013534 0.999622 0.0239341 0.0458249 0.998847 0.0142778 -0.00894482 0.99876 0.0489829 -0.0330937 0.998955 0.0315386 0.0106227 0.999764 0.0189437 0.00458161 0.999962 0.00739268 0.0280582 0.999606 0.00068824 9.29535e-05 0.999576 -0.0291081 0.0276424 0.998901 -0.0378456 -0.0129083 0.999729 -0.019398 -0.00449138 0.999909 -0.0127505 -0.00716565 0.999973 0.00172261 0.0679156 0.990719 0.117741 0.0678042 0.990763 0.117436 0.0693976 0.990281 0.120531 0.0711203 0.989885 0.122756 0.0824956 0.987114 0.137118 0.0846557 0.986884 0.137456 0.0842773 0.985296 0.148623 0.0816472 0.985123 0.151213 0.0912212 0.983314 0.157396 0.0883504 0.983575 0.157401 0.0892202 0.983552 0.157053 0.0466663 0.994404 0.094782 0.0458813 0.995778 0.0795106 0.0396217 0.996917 0.0677233 0.0902339 0.990724 0.10161 0.068093 0.992131 0.105074 0.0620004 0.992329 0.10695 0.0526591 0.993918 0.0967116 0.0626998 0.99249 0.105036 0.0569399 0.993176 0.101778 0.0657063 0.991994 0.10785 0.0629448 0.992333 0.106363 0.065273 0.991478 0.112745 0.0663694 0.991129 0.11515 0.0504668 0.994864 0.0877466 0.0413125 0.996741 0.0692923 0.0362403 0.997147 0.0662153 0.0232842 0.99791 0.060282 0.0406039 0.997327 0.0607494 0.0412739 0.996285 0.0755814 0.0415704 0.99653 0.0721137 0.0508888 0.994809 0.0881252 0.0329397 0.997378 0.0644303 0.0392254 0.996895 0.0682799 0.0319423 0.997394 0.0646861 0.0293659 0.997597 0.0627513 0.0250088 0.997826 0.0609681 0.0229596 0.997917 0.060288 0.025505 0.998074 0.0565541 0.0271199 0.998204 0.053423 0.0276328 0.998289 0.0515372 -0.0482534 0.995468 -0.0819439 -0.047336 0.995457 -0.0826094 -0.0538648 0.994192 -0.0931657 -0.0610784 0.994178 -0.0887667 -0.0390969 0.993409 -0.107747 -0.0724852 0.992429 -0.0991514 -0.0588487 0.991562 -0.115507 -0.0669472 0.991366 -0.112747 -0.0666468 0.991058 -0.115596 -0.0261669 0.998636 -0.0451761 -0.0356854 0.997397 -0.0626498 -0.0541871 0.996772 -0.0592431 -0.0401984 0.996637 -0.0714084 0.00516568 0.999954 -0.00813875 -0.0176284 0.999796 -0.00982895 -0.00267078 0.999442 -0.0332884 -0.0525781 0.998084 -0.0326301 -0.0320039 0.998752 -0.0383451 0.0277906 0.998528 0.0465774 0.015356 0.999349 0.0326387 0.0139002 0.999371 0.0326138 0.0193773 0.999667 0.0170664 -0.00450291 0.999903 0.0131935 0.0721964 0.995439 0.0623636 0.0191924 0.998151 0.057667 0.0259354 0.99865 0.0449957 0.00602486 0.999951 0.00781889 0.0152537 0.999449 0.0294917 0.0354052 0.998995 0.0274893 0.0197346 0.999225 0.0340525 0.00243985 0.999676 -0.0253324 -0.0235771 0.999541 -0.019027 -0.00455037 0.999965 -0.00705452 0.00497483 0.999956 0.0080074 -0.0494731 0.994289 -0.0945637 -0.0706487 0.992274 -0.101991 -0.0566524 0.992539 -0.107963 -0.0522261 0.994531 -0.0904434 -0.0468604 0.995645 -0.0805952 -0.0558731 0.995543 -0.0759742 -0.0232434 0.997851 -0.0612695 -0.0328116 0.99786 -0.0565646 -0.0262955 0.998611 -0.045665 -0.0274922 0.998671 -0.0436021 -0.016679 0.999253 -0.0348552 0.109358 0.983357 0.145088 0.10322 0.979011 0.175734 0.0863913 0.976735 0.196277 0.0998617 0.979823 0.173132 0.104849 0.976159 0.190055 0.111917 0.977018 0.181414 0.112116 0.977034 0.181205 -0.029121 0.999425 0.0173886 0.00249526 0.999986 0.00474325 0.00783647 0.999871 0.0140339 0.0154538 0.9997 0.0190249 -0.0186227 0.998836 0.0445021 0.0449151 0.998719 0.0232973 -0.0133572 0.996763 0.0792754 0.034387 0.997601 0.0600776 0.0418566 0.996437 0.0732149 0.0548735 0.995546 0.0766573 -0.00526937 0.988413 0.151698 0.107786 0.989825 0.0928927 0.079483 0.98607 0.146112 0.103813 0.981957 0.158059 0.115807 0.982589 0.145283 0.0978135 0.978343 0.182423 0.0266665 0.998184 0.0540223 0.0277657 0.998185 0.0534479 0.0396666 0.99684 0.0688216 0.0428064 0.996321 0.0742407 0.0656306 0.99301 0.0980982 0.10323 0.990724 0.0883684 0.0421195 0.989925 0.135185 0.156634 0.976602 0.147355 0.126652 0.979666 0.155609 0.0836879 0.98045 0.178084 0.0995458 0.979999 0.172314 0.107463 0.976568 0.18646 0.104867 0.977029 0.185518 0.093177 0.977925 0.187034 0.10628 0.977157 0.184034 0.102494 0.979686 0.172365 0.104663 0.978041 0.180225 0.105745 0.97799 0.17987 0.10674 0.980391 0.165652 0.0983796 0.981859 0.162092 0.0477702 0.995352 0.0836257 0.0470257 0.995569 0.0814331 0.0400023 0.996784 0.0694437 0.0311552 0.998173 0.0517741 0.0307692 0.998257 0.0503662 0.00563897 0.999904 0.0126744 0.0110769 0.999754 0.0192132 0.0827422 0.984909 0.152013 0.087089 0.984118 0.154683 0.0907661 0.983212 0.158292 0.0961911 0.982416 0.160018 0.0929943 0.983098 0.157703 0.0797802 0.986179 0.145213 0.115349 0.980999 0.155996 0.0815912 0.987347 0.13597 0.0740933 0.989239 0.12616 0.0821193 0.990103 0.113811 0.0997304 0.988165 0.11655 0.0458202 0.995593 0.0818228 0.0537647 0.996869 0.0579737 0.0598032 0.996406 0.05999 -0.0012048 0.999848 0.0174029 -0.0271463 -0.998462 -0.0483384 -0.0446585 -0.996114 -0.0759086 -0.058378 -0.991668 -0.114833 -0.061351 -0.991517 -0.114589 -0.0638648 -0.991831 -0.11042 -0.066034 -0.991451 -0.11254 -0.0651701 -0.991506 -0.112553 -0.0646861 -0.991547 -0.112475 -0.0668257 -0.991054 -0.11553 -0.066855 -0.991056 -0.115496 -0.066575 -0.991055 -0.115666 -0.0531861 -0.994289 -0.0925239 -0.0492198 -0.994528 -0.0921527 -0.0727031 -0.992354 -0.0997358 -0.0626251 -0.992857 -0.101553 -0.0639633 -0.991744 -0.111142 0.00805885 -0.999433 -0.0327002 -0.0107913 -0.999891 -0.0100993 0.0332014 -0.998285 0.048218 0.0126449 -0.998025 0.0615337 0.0261546 -0.998325 0.0516096 0.0305626 -0.998314 0.0493396 0.040054 -0.998146 0.0458182 0.0524442 -0.997724 0.0423859 0.00130845 -0.999732 0.0231062 0.00932275 -0.999816 0.016789 0.00518655 -0.999948 0.00877573 0.0152944 -0.999875 0.00396045 -0.00155169 -0.999994 -0.00319397 -0.00791936 -0.999877 -0.013563 -0.015985 -0.999674 -0.019899 0.0215482 -0.999084 -0.0369768 -0.0182844 -0.999342 -0.0313372 -0.0233489 -0.998922 -0.0401264 -0.0571876 -0.997738 -0.0353213 -0.0251346 -0.998157 -0.0552281 -0.0352104 -0.997527 -0.0608231 -0.0417766 -0.996136 -0.0772456 -0.0186847 -0.999311 -0.0320636 -0.0134028 -0.999405 -0.031785 -0.0221902 -0.999608 -0.0170516 -0.0106263 -0.999773 -0.0184836 -0.00183066 -0.999993 -0.00318428 0.0163252 -0.999852 -0.00551257 -0.000850407 -0.999945 0.0104403 0.00609432 -0.999923 0.0107962 0.0132576 -0.999651 0.0228333 0.0261455 -0.999433 0.0212104 0.00836817 -0.998624 0.0517702 -0.0203559 -0.998328 0.0541028 0.00871199 -0.998577 0.0526059 -0.063932 -0.991815 -0.110525 -0.067144 -0.99284 -0.0987974 -0.0577182 -0.993281 -0.100305 -0.0466648 -0.995633 -0.0808601 -0.0421355 -0.995792 -0.0813804 -0.0402796 -0.997001 -0.0660779 -0.0381804 -0.997088 -0.0660088 -0.0276879 -0.998457 -0.0481382 0.0266962 -0.996697 0.0766919 0.0588541 -0.994461 0.0870827 0.0543294 -0.994681 0.0875048 0.0557585 -0.994608 0.0874375 0.0533177 -0.994365 0.0916278 0.0920625 -0.982892 0.159522 0.0913896 -0.983064 0.158848 0.0925529 -0.983551 0.155117 0.0877821 -0.984363 0.152724 0.0766575 -0.988167 0.132853 0.07311 -0.988596 0.131652 0.0649886 -0.991554 0.112241 0.0634317 -0.991881 0.110225 0.0551326 -0.994063 0.0938013 0.0695402 -0.992539 0.100156 0.0647049 -0.993111 0.0976916 0.091564 -0.983046 0.158858 0.0894297 -0.983942 0.15447 0.093629 -0.983267 0.156266 0.0911371 -0.98367 0.155199 0.0897833 -0.983522 0.156919 0.0552676 -0.994146 0.0928357 0.0537743 -0.994532 0.0895205 0.0728847 -0.990657 0.115266 0.0618122 -0.993347 0.0971695 0.05299 -0.994654 0.0886297 0.0511312 -0.994938 0.0865118 0.0478046 -0.995442 0.082518 0.046369 -0.995765 0.0793858 0.0912444 -0.983692 0.154999 0.0810582 -0.986161 0.144625 0.0811068 -0.986609 0.141505 0.0797755 -0.987538 0.135661 0.0747327 -0.988701 0.129943 0.0682874 -0.990643 0.118165 0.0684633 -0.990523 0.119071 0.0610372 -0.992568 0.105278 0.0598748 -0.992509 0.106497 0.0542162 -0.994348 0.0912803 0.0535939 -0.994091 0.0944015 0.0781546 -0.987583 0.13628 0.088455 -0.986087 0.140738 0.0872134 -0.984107 0.154684 0.0922266 -0.983071 0.15832 0.0940305 -0.983219 0.156327 0.0943768 -0.983161 0.156485 0.0918746 -0.983615 0.155116 0.0905842 -0.983864 0.154291 0.0892177 -0.984139 0.15333 0.0870787 -0.98461 0.151526 0.0893725 -0.984466 0.15113 0.0883156 -0.984577 0.151028 0.088021 -0.984522 0.151552 0.0875134 -0.984492 0.152044 0.0872743 -0.9845 0.152131 0.0509316 -0.994283 0.0938436 0.0475906 -0.994254 0.0958901 0.0529514 -0.993848 0.0972737 0.0653651 -0.991411 0.113279 0.0693293 -0.990329 0.120175 0.0844542 -0.986817 0.13806 0.0756121 -0.988006 0.134634 0.081121 -0.986528 0.142063 0.022181 -0.997896 0.0609206 0.0283313 -0.997624 0.0628029 0.0340105 -0.997299 0.0650976 0.0314946 -0.997418 0.0645395 0.0344388 -0.997262 0.0654424 0.0362776 -0.997144 0.0662331 0.0257839 -0.99813 0.0554188 0.0217543 -0.997912 0.0608069 0.0386179 -0.997484 0.0594508 0.0409803 -0.996533 0.0724032 0.0604261 -0.993667 0.0947361 0.0513533 -0.994703 0.0890431 0.0415398 -0.996538 0.0720125 0.0410608 -0.996272 0.0758718 0.0411158 -0.996383 0.0743614 -0.00117508 -0.999959 0.00902086 0.0206791 -0.999494 0.0241556 0.0130957 -0.999419 0.0314617 0.0178676 -0.999217 0.0352881 0.0276878 -0.998536 0.0464622 0.0277078 -0.998299 0.0513011 -0.0316447 -0.998756 -0.0385306 -0.00762834 -0.999725 -0.0221762 -0.0166188 -0.999758 -0.0144071 0.00318651 -0.999991 -0.00272031 0.00131107 -0.999978 0.00653248 -0.049128 -0.99677 -0.0635251 -0.0323506 -0.997875 -0.0565673 -0.0257142 -0.998684 -0.044376 -0.0334465 -0.998717 -0.0380302 -0.0666201 -0.991035 -0.115811 -0.066769 -0.99121 -0.114209 -0.0588356 -0.99178 -0.113622 -0.0681401 -0.992145 -0.10491 -0.0454606 -0.993971 -0.0997732 -0.054876 -0.994156 -0.0929636 -0.0511437 -0.994762 -0.0885056 -0.046855 -0.995549 -0.0817771 -0.049211 -0.995366 -0.0826148 -0.0392343 -0.996742 -0.070468 -0.065919 -0.991455 -0.112564 -0.0712128 -0.991037 -0.113022 -0.0693749 -0.991067 -0.113902 -0.067447 -0.991232 -0.113624 -0.0539796 -0.992902 -0.105978 -0.0190119 -0.997807 -0.063408 -0.0560336 -0.995509 -0.0763067 -0.0476421 -0.995449 -0.0825355 -0.0521717 -0.994519 -0.0906097 -0.0485842 -0.994194 -0.0960067 -0.0486569 -0.994189 -0.0960252 -0.0727589 -0.991624 -0.106712 -0.0340272 -0.999022 -0.0282421 -0.00355513 -0.999973 -0.00640133 0.00210426 -0.999988 0.00433686 0.0235775 -0.999615 -0.0146491 -0.0226893 -0.998991 -0.0387506 -0.0263701 -0.998588 -0.0461212 -0.0266252 -0.998573 -0.0462973 -0.0329701 -0.997829 -0.057007 0.0173438 -0.999779 0.0119161 0.00872443 -0.999792 0.0184333 0.0231405 -0.99914 0.0344165 0.0184371 -0.99932 0.0319326 0.0283918 -0.998377 0.0493626 0.0220113 -0.99872 0.0455349 0.0468508 -0.996448 0.0699724 0.066574 -0.992008 0.107182 0.0577816 -0.992949 0.103508 0.0373742 -0.997066 0.0668077 0.0413127 -0.996745 0.0692231 0.0526761 -0.994345 0.0922081 0.0504327 -0.994208 0.0949012 0.0637987 -0.99235 0.105694 0.0625976 -0.992327 0.106624 0.0621746 -0.99233 0.106842 0.067334 -0.991743 0.109146 0.0701208 -0.992049 0.104513 0.0683377 -0.992142 0.104808 0.0446855 -0.995413 0.0845911 0.0469887 -0.995544 0.0817618 0.0377491 -0.997177 0.0649026 0.0694871 -0.990372 0.11973 0.0693844 -0.990395 0.119598 0.0901262 -0.983527 0.156691 0.0892574 -0.983551 0.157038 0.0835275 -0.984653 0.153235 0.08758 -0.984524 0.151795 0.083174 -0.986023 0.144361 0.0875125 -0.986232 0.140312 0.0757456 -0.988369 0.131872 0.0697745 -0.990211 0.120884 0.0205963 -0.998397 0.0527207 0.0306763 -0.998082 0.0537635 0.0429346 -0.996309 0.0743245 0.0661702 -0.992977 0.0980678 0.0326237 -0.99372 0.107037 0.0689468 -0.989729 0.125232 0.0884387 -0.986413 0.13845 0.0831468 -0.982756 0.165157 0.1238 -0.97787 0.168654 0.0683568 -0.986786 0.146903 0.102349 -0.978768 0.177589 0.106033 -0.977171 0.184101 0.100045 -0.977543 0.185473 0.11114 -0.975945 0.187563 0.0834289 -0.982827 0.164591 0.112254 -0.978719 0.171778 0.124827 -0.976877 0.173581 0.105538 -0.977985 0.180018 0.106838 -0.976714 0.18605 -0.00150958 -0.999956 -0.00920724 -0.0171077 -0.999774 0.0126118 0.00242101 -0.999986 0.00480348 0.00831179 -0.999853 0.015026 0.0213055 -0.99965 0.0156975 -0.0191975 -0.998698 0.0472717 0.0453051 -0.998706 0.0230838 -0.00544907 -0.997086 0.07609 0.0345782 -0.9976 0.0599929 0.0432798 -0.996226 0.0752409 0.0578987 -0.995531 0.0746082 0.00757234 -0.988863 0.148638 0.0984869 -0.990118 0.0998349 0.0815995 -0.985732 0.147223 0.100668 -0.982498 0.156729 0.130909 -0.981234 0.141569 0.110498 -0.97943 0.168839 0.103892 -0.977576 0.183169 0.108646 -0.97666 0.18529 0.111987 -0.976543 0.183907 0.105875 -0.976502 0.187708 0.106663 -0.976792 0.185742 0.104467 -0.978234 0.179288 0.0937512 -0.978327 0.184627 0.101567 -0.980127 0.170396 0.112204 -0.983408 0.142542 0.0824292 -0.98497 0.151786 0.087041 -0.984132 0.154622 0.0907301 -0.98322 0.158263 0.0960599 -0.982431 0.160003 0.0922677 -0.98324 0.157243 0.0795022 -0.986259 0.144819 0.114727 -0.981095 0.155851 0.0808803 -0.987519 0.135147 0.0743392 -0.989205 0.126286 0.0824466 -0.989926 0.115107 0.0747436 -0.990907 0.111879 0.0431477 -0.995747 0.0814058 0.0623638 -0.996198 0.0608238 -0.0016719 -0.999841 0.0177411 0.0470708 -0.995553 0.0816038 0.0400598 -0.996777 0.0694991 0.0313321 -0.998167 0.0517839 0.0311136 -0.998216 0.0509629 0.0098596 -0.999772 0.0189372 0.00523191 -0.999959 0.00733327 0 -1 0 -1.87321e-06 -1 -7.03351e-06 0 -1 0 0 -1 0 -0.000296439 -1 0.000126015 -2.86157e-05 1 7.97448e-05 0 -1 0 0 -1 0 0 -1 0 0.971483 -4.44966e-07 -0.237111 0.972855 1.37338e-06 -0.231416 0.995609 -5.5496e-06 0.0936105 0.994401 -5.89164e-06 0.105677 0.892223 0 0.451594 0.896611 -0.00155359 0.442817 0.898596 0.00160174 0.438774 0.931824 -0.00182358 0.362905 0.917858 0.00237393 0.396902 0.913755 -0.00139044 0.406263 0.905778 0.000173428 0.423753 0.945433 1.55672e-06 0.325818 0.939823 1.01114e-06 0.341661 0.933657 -0.000724363 0.358167 0.969018 -0.000607295 0.246989 0.959511 0.00174991 0.281667 0.954575 -0.00222758 0.297962 0.942636 0.00118395 0.33382 0.988542 0.00158603 0.150938 0.990771 -0.00377195 0.135494 0.977556 0.00254072 0.210659 0.97976 2.83773e-06 0.200177 0.970966 2.81226e-06 0.239218 0.998874 -0.00257386 0.0473827 0.997703 0.00476528 0.0675654 0.999921 -0.00347684 -0.0120579 1 6.08261e-06 0.000230717 0.998868 3.19694e-06 -0.0475601 0.99932 0.00143948 -0.0368342 0.997039 -0.00248839 -0.0768542 0.997727 -0.000125803 -0.0673911 0.993873 8.15774e-05 -0.110532 0.994958 0.00211919 -0.100275 0.990131 -0.00260581 -0.140118 0.991477 -1.17077e-06 -0.130284 0.986727 -2.28695e-06 -0.162386 0.986127 0.000504134 -0.165992 0.979645 -0.00128399 -0.200734 0.982763 -0.00868137 -0.184668 0.975761 0.00363731 -0.218809 0.96848 -5.52288e-05 -0.249092 0.969137 0.00194306 -0.246516 0.967201 6.4052e-05 -0.254011 0.966941 -0.00110344 -0.254998 0.969545 0.00172333 -0.244909 0.968864 -7.99439e-06 -0.247594 0.972659 -7.15552e-06 -0.232238 0.972129 -0.00116128 -0.234445 0.979341 0.0029989 -0.202193 0.977883 -0.00367405 -0.209123 0.985228 0.00156455 -0.171239 0.98438 -4.91666e-06 -0.176054 0.988766 -4.93857e-06 -0.149473 0.999523 -0.00095851 -0.0308551 0.999735 0.00211345 0.0229258 0.999564 0 0.0295314 0.988218 -0.00125352 -0.153049 0.990193 -0.000169005 -0.139706 0.994396 0.00133126 -0.105715 0.993457 -0.00313731 -0.114162 0.997414 0.00100944 -0.0718683 0.996889 -2.11373e-07 -0.0788166 0.998169 -4.01731e-06 -0.0604802 0.998177 9.0853e-06 -0.0603538 0.999345 -2.56918e-06 -0.0362009 0.998475 -0.002096 -0.0551626 0.989512 0.00297447 -0.14442 0.989365 0.00350189 -0.14541 0.995419 0.0208471 0.0933137 0.998786 -0.0125758 0.0476365 0.952485 0.0147796 0.304226 0.94165 0.0423705 0.333917 0.887143 0 0.461494 0.74863 0 0.662988 0.693859 0.0906859 0.714378 0.82435 0 0.56608 0.697687 0 0.716403 0.747427 -0.0566803 0.661922 0.824261 0 0.56621 0.990114 -0.00150695 -0.140257 0.998741 0.00131863 -0.0501472 0.998769 -0.0138044 0.0476357 0.995695 0.00825377 0.0923234 0.942342 -0.0180942 0.334162 0.95125 -0.0517728 0.304046 0.886858 0 0.462042 0.984841 0.00354511 -0.173423 0.989515 -0.00350527 -0.144386 0.499039 0 0.86658 0.49948 -2.84661e-05 0.866325 0.499514 1.21465e-05 0.866306 0.499515 0 0.866305 0.937068 0 -0.349147 0.937068 0 -0.349147 0.998692 0 0.0511226 0.998692 0 0.0511226 0.858063 0 0.513544 0.858063 0 0.513544 0.53987 0 0.841748 0.53987 0 0.841748 0.171654 0 0.985157 0.10428 0.0318138 0.994039 -0.0784496 0 0.996918 -0.347605 0 0.937641 -0.347605 0 0.937641 -0.721245 0 0.692681 -0.721245 0 0.692681 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.0512168 -0.99063 0.126608 0 -1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.866164 -0.00159632 0.499758 -0.866328 0.000189651 0.499476 -0.86628 0 0.499558 -0.866297 -1.4575e-05 0.499529 -0.866401 3.3085e-05 0.499349 0.866268 3.26364e-05 -0.499579 0.866339 0 -0.499456 0.866339 0 -0.499456 0.414143 0.555088 0.721362 0.311763 0.783904 0.536934 0.276412 0.831783 0.481386 0.111807 0.975072 0.191662 0.0974437 0.980786 0.169005 0.430154 0.508353 0.746019 0.489905 0.195177 0.849647 0.489909 0.195114 0.849659 0.0225432 0.999037 0.0376537 0.0193134 0.999252 0.0335028 0.022154 -0.999016 0.0384201 0.0221176 -0.999019 0.0383723 0.500099 0 0.865968 0.499515 0 0.866305 0.499514 -1.21465e-05 0.866306 0.499039 0.000549946 0.86658 0.49948 0 0.866325 0.495768 0.000177174 0.868455 0.499509 3.3378e-06 0.866309 0.499507 0 0.86631 0.499507 1.39836e-07 0.86631 0.499509 -3.33781e-06 0.866309 0.494567 -0.000232876 0.869139 0.0221175 0.999019 0.0383723 0.022154 0.999016 0.0384201 -0.499609 -5.61172e-05 -0.866251 -0.499641 -2.0657e-05 -0.866233 -0.499719 0.000120206 -0.866188 -0.49946 -8.75267e-05 -0.866337 -0.499529 -0.000193391 -0.866297 -0.500436 0.000139015 -0.865773 -0.499356 -0.000201336 -0.866397 -0.499604 -4.59316e-05 -0.866254 -0.499547 -6.92556e-05 -0.866287 -0.499664 3.04485e-05 -0.86622 -0.499529 8.75081e-05 -0.866297 -0.499461 0.000216254 -0.866336 -0.499354 0.000250924 -0.866398 -0.499817 -4.34903e-05 -0.866131 -0.499597 -3.00513e-05 -0.866258 -0.49966 2.07331e-06 -0.866221 -0.499644 1.58355e-05 -0.866231 -0.499608 5.51275e-05 -0.866252 -0.499611 5.01438e-05 -0.86625 -0.499632 3.1994e-05 -0.866238 0.0221062 -0.99902 0.0383499 0.0221116 -0.999019 0.0383569 0.877262 -0.012753 -0.479842 0.973227 0.0276482 -0.228179 0.924958 -0.000210334 0.38007 0.968027 0.0312467 0.248893 0.990216 9.1972e-06 0.139545 0.987893 9.3e-05 -0.155134 0.79239 0.0103912 0.609926 0.759505 0.0234482 0.650078 0.670688 0 0.74174 0.821743 0.000311533 -0.569858 0.821686 -4.17928e-05 -0.569941 0.649764 9.22519e-05 -0.760136 0.641597 -0.00369268 -0.767033 0.509786 0.00403922 -0.860292 0.500788 0 -0.86557 0.380179 0 -0.924913 0.320142 -0.0148195 -0.947254 0.227117 0.0136579 -0.973772 0.164507 0 -0.986376 0.0839208 0 -0.996472 0.0613639 -0.00358424 -0.998109 -0.0871205 0.011849 -0.996127 -0.109606 0 -0.993975 -0.230377 0 -0.973101 -0.309807 -0.00307757 -0.950794 -0.375795 0.0236549 -0.926401 -0.462142 -0.00352773 -0.886799 -0.516792 0 -0.856111 -0.620892 0 -0.783896 -0.620892 0 -0.783896 -4.55798e-05 1 8.28375e-07 0.000386474 -1 0.000223124 8.16227e-05 -1 0.000141426 0.00012409 -1 0.000165945 0 1 0 -1.20048e-05 1 -2.08073e-05 -3.36962e-05 1 -1.94532e-05 -4.47159e-05 -1 -2.8961e-09 5.93514e-05 1 2.33036e-06 0 1 -4.73029e-05 1.65061e-05 -1 -2.85713e-05 2.05858e-05 -1 -4.09574e-05 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -2.93572e-05 1 5.54148e-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.000274432 1 9.91605e-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 5.40001e-06 1 3.35153e-05 0 1 2.78924e-05 -1.10196e-05 1 1.90736e-05 0 1 0 0 1 0 0 1 0 0 -1 0 0 1 0 0 1 0 3.23534e-05 1 -0.000101597 0 1 0 0 1 0 0 1 0 0 1 0 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.16814e-06 1 -2.57942e-05 -0.00015596 -1 -9.00403e-05 0 1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 -4.55363e-06 1 2.62868e-06 -3.78429e-06 1 -1.95857e-10 -4.58859e-05 1 -7.95118e-05 -4.12572e-08 1 -6.51466e-05 7.55199e-05 1 -0.000130721 1.2227e-05 1 -5.54987e-05 0 1 0 0 1 0 -0.97292 -6.06776e-05 0.231144 -0.972795 0 0.231668 -0.986627 0 0.162996 -0.992836 -0.00891118 0.119152 -0.999885 0.0151434 0.000694584 -0.999015 0 -0.0443744 -0.989629 0 -0.143648 -0.982511 -0.00511801 -0.186135 -0.953247 0.0183854 -0.301632 -0.93923 0 -0.343288 -0.880588 0 -0.473882 -0.899415 -0.00969108 -0.436989 -0.786074 0.0317099 -0.617318 -0.822304 -0.0134334 -0.56889 -0.719091 0 -0.694916 -0.499434 0.000126714 -0.866352 -0.499443 -8.16317e-05 -0.866347 -0.499545 8.83994e-05 -0.866288 -0.499564 0.000275769 -0.866277 -0.494136 0.0941611 -0.864271 -0.499605 -0.000665096 -0.866253 -0.499385 0.000179127 -0.86638 -0.499529 2.65345e-05 -0.866297 -0.499531 -2.42806e-05 -0.866296 -0.499491 7.72894e-05 -0.866319 -0.499527 -3.28924e-05 -0.866298 -0.499538 1.55116e-05 -0.866292 -0.49954 -1.69188e-06 -0.866291 -0.499543 0 -0.866289 -0.499543 -1.42459e-05 -0.866289 0.86633 0 -0.499472 0.866326 5.15368e-06 -0.499479 -0.866319 -5.21101e-05 0.499491 -0.866275 0 0.499567 -0.49955 0.000724651 -0.866285 -0.499543 -0.00169424 -0.866288 -0.499508 0.000107436 -0.866309 -0.499527 -2.03065e-05 -0.866298 -0.499527 -1.99185e-05 -0.866298 -0.499531 0.000123198 -0.866296 -0.499539 -1.59121e-05 -0.866291 -0.49955 -4.20532e-05 -0.866285 -0.499732 0.000317655 -0.86618 -0.499359 -0.00119251 -0.866394 -0.499531 3.52039e-05 -0.866296 -0.499493 -0.000115346 -0.866318 -0.499565 -1.06246e-05 -0.866277 -0.499563 -1.81421e-05 -0.866278 -0.499562 -3.31386e-06 -0.866278 -0.499567 0 -0.866275 -0.499567 1.92963e-05 -0.866275 -0.000140122 -1 -0.000225642 0 -1 0 0 -1 0 -0.00010435 -1 -2.29422e-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 2.20261e-05 -1 0 0 1 0 0 -1 0 0.000362576 -1 -0.000278402 0.000361578 -1 -0.000625892 0.000567514 -1 -0.000327553 -0.000403832 -1 -0.000491638 2.35666e-05 -1 -3.9038e-05 2.41275e-05 -1 1.39314e-05 2.62984e-05 -1 2.14633e-05 0 -1 0 0.000104422 -1 2.79703e-05 9.80769e-05 -1 1.43405e-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.301819 -0.937332 -0.174109 0.302066 -0.937244 -0.174156 0.641219 -0.672431 -0.369694 0.641195 -0.672456 -0.369692 0.839792 -0.245566 -0.484197 0.839808 -0.245525 -0.48419 0.0541653 0.998176 -0.0266492 0.302198 0.937169 -0.174329 0.302031 0.937259 -0.174135 0.641204 0.67245 -0.369686 0.641218 0.672426 -0.369706 0.839802 0.245521 -0.484203 0.839799 0.245568 -0.484183 -0.050144 -0.99818 0.0334943 -0.302287 -0.937163 0.174205 -0.302084 -0.937236 0.174166 -0.64122 -0.672431 0.369694 -0.641219 -0.672431 0.369694 -0.839799 -0.245566 0.484185 -0.839783 -0.245607 0.484192 -0.301945 0.93731 0.174009 -0.302079 0.937238 0.174163 -0.641224 0.672426 0.369696 -0.641224 0.672426 0.369697 -0.839789 0.24561 0.484179 -0.839791 0.245569 0.484197 -0.966629 -0.2236 0.125028 -0.955281 -0.270246 0.12002 -0.934498 -0.329451 0.134817 -0.765267 -0.636455 0.0963934 -0.743816 -0.660574 0.101884 -0.438366 -0.896816 0.0596329 -0.587784 -0.80897 0.00884448 -0.110674 -0.993777 -0.012568 -0.102596 -0.993771 -0.04352 -0.785221 -0.0227546 -0.618797 -0.756674 -0.271157 -0.594911 -0.756665 -0.272593 -0.594265 -0.607314 -0.635351 -0.476969 -0.607337 -0.635295 -0.477013 -0.395219 -0.86455 -0.310411 -0.359565 -0.897333 -0.255941 -0.0849262 -0.993733 -0.072682 -0.0699585 -0.995352 -0.0661851 -0.102538 -0.993777 -0.0435055 -0.408868 -0.895953 -0.173477 -0.408846 -0.895968 -0.173457 -0.711884 -0.634037 -0.302024 -0.711834 -0.634116 -0.301976 -0.88621 -0.270728 -0.375951 -0.886494 -0.268755 -0.376695 -0.567413 -0.787316 -0.241199 -0.244522 -0.969223 0.0285783 -0.107678 -0.991462 0.0735391 -0.110687 -0.993776 -0.0125675 -0.441294 -0.895963 -0.0501046 -0.441285 -0.895967 -0.0501003 -0.768273 -0.634152 -0.0872241 -0.768339 -0.634067 -0.0872576 -0.956479 -0.270828 -0.108624 -0.956771 -0.269642 -0.109006 -0.582183 -0.810364 -0.0661298 -0.783229 0 0.621733 -0.783229 0 0.621733 -0.498075 0 0.867134 -0.497898 0.00012001 0.867236 -0.0533189 -0.0104011 0.998523 -0.126363 -0.0532465 0.990554 0.0861554 0 0.996282 0.417155 0 0.908835 0.417155 0 0.908835 0.783878 0 0.620915 0.783878 0 0.620915 0.979016 0 0.203783 0.979016 0 0.203783 0.961431 0 -0.275048 0.961431 0 -0.275048 -0.983364 -0.000103469 -0.181647 -0.909395 -0.000183826 -0.415933 -0.871207 0.000109911 -0.490916 -0.871005 0 -0.491274 -0.851673 0 -0.524074 -0.851892 -4.55354e-05 -0.523718 -0.821197 0.000200081 -0.570644 -0.857158 3.96688e-06 -0.515054 -0.821455 -0.000111262 -0.570273 -0.802776 -3.53418e-07 -0.59628 -0.798707 -0.000115107 -0.601721 -0.798581 1.05069e-05 -0.601887 -0.804214 -1.80125e-05 -0.59434 -0.804166 0 -0.594404 -0.818896 0 -0.573942 -0.81879 6.54315e-05 -0.574094 -0.84282 -7.17624e-05 -0.538196 -0.842498 9.46958e-05 -0.538699 -0.857012 -5.23713e-06 -0.515296 -0.783086 9.48054e-07 0.621914 -0.759659 -4.14989e-06 0.650321 -0.759649 0 0.650334 -0.871582 3.93802e-06 -0.490251 -0.871398 9.20385e-05 -0.490576 -0.899827 -0.000107212 -0.436247 -0.899665 -1.03409e-05 -0.436582 -0.915251 -1.052e-05 -0.402884 -0.9151 -7.94152e-06 -0.403227 -0.931506 -8.72022e-05 -0.363727 -0.931416 -2.24367e-05 -0.363955 -0.95547 1.49896e-05 -0.295088 -0.95552 -1.36488e-05 -0.294926 -0.968493 -1.38341e-05 -0.249042 -0.968473 -6.37883e-06 -0.249118 -0.983098 -2.65066e-05 -0.18308 -0.98309 -1.54572e-05 -0.183121 -0.993299 8.73931e-06 -0.115573 -0.99331 0 -0.115477 -0.997731 0 -0.0673259 -0.997774 -0.000114921 -0.066681 -0.999983 0.000147961 0.00584888 -0.999975 -0.000199167 0.00709383 -0.998682 2.43576e-05 0.0513155 -0.998647 3.21083e-06 0.0520021 -0.996092 3.20262e-06 0.0883248 -0.996061 -8.84133e-05 0.0886696 -0.988467 9.10808e-05 0.151436 -0.988406 -3.82999e-05 0.151836 -0.98298 -5.57821e-06 0.183714 -0.98304 0 0.183392 -0.977289 0 0.211912 -0.977289 5.7179e-07 0.21191 -0.96481 -2.32172e-05 0.262949 -0.964856 4.41587e-05 0.26278 -0.956216 -4.50588e-06 0.29266 -0.95623 0 0.292617 -0.941637 0 0.33663 -0.941655 4.12107e-05 0.33658 -0.922666 -3.03107e-05 0.3856 -0.922704 0 0.38551 -0.906376 0 0.422473 -0.90639 2.28122e-05 0.422441 -0.883753 -1.96715e-05 0.467954 -0.883771 4.65516e-06 0.46792 -0.865518 4.55902e-06 0.500878 -0.865515 2.07413e-06 0.500884 -0.84914 -1.89521e-05 0.528169 -0.849184 2.07758e-05 0.528097 -0.828673 -4.04917e-06 0.559733 -0.828701 1.86573e-05 0.559691 -0.818723 1.05398e-05 0.574188 -0.818318 0 0.574766 -0.806367 0 0.591416 -0.806373 3.9406e-06 0.591408 -0.783098 -6.0389e-06 0.621898 -0.745815 0 0.666153 -0.745648 -1.37994e-05 0.666341 -0.7307 -1.54004e-05 0.682699 -0.730748 0 0.682648 -0.715913 0 0.69819 -0.709815 0.000253289 0.704388 -0.707448 -0.000135152 0.706766 -0.956152 0.000172471 -0.29287 -0.956272 0 -0.292479 -0.933613 0 -0.358284 -0.934537 -2.22943e-05 -0.355866 -0.909858 0.000264125 -0.41492 -0.830959 0 0.556333 -0.830959 0 0.556333 -0.885212 0 0.465187 -0.885571 0.000215804 0.464504 -0.939923 -0.000102939 0.341386 -0.940144 0 0.340776 -0.967275 0 0.25373 -0.967443 0.000110916 0.253091 -0.990443 -0.000138695 0.137923 -0.990506 0 0.137467 -0.999996 0 -0.00275149 -0.999996 0 -0.00275149 -0.994621 0 -0.103579 -0.994621 0 -0.103579 -0.983434 0 -0.181269 -0.958309 0.0181193 0.285158 -0.840473 -0.000196212 0.541853 -0.774845 0.000479875 0.632151 -0.776838 -2.45843e-06 0.6297 -0.499445 7.98669e-05 -0.866346 -0.499222 -0.000167003 -0.866474 -0.499635 0.000588788 -0.866236 -0.499511 1.90747e-05 -0.866308 -0.499429 0.000143463 -0.866355 -0.498911 -4.62126e-05 -0.866653 -0.499579 0.000164293 -0.866268 -0.499523 0.000128803 -0.866301 -0.499453 0.000100264 -0.866341 -0.499464 0.000108976 -0.866335 -0.499429 -1.90463e-05 -0.866355 -0.499509 -0.000170713 -0.866309 -0.499575 -0.000192068 -0.866271 -0.499391 -7.47914e-05 -0.866377 -0.499162 -8.13839e-07 -0.866509 -0.499225 -0.000109619 -0.866472 -0.499287 -1.63181e-06 -0.866436 -0.499361 -9.30749e-05 -0.866394 -0.49921 0.000180132 -0.866481 -0.499445 -7.98675e-05 -0.866345 -0.499464 -0.000108976 -0.866335 -0.499453 -0.000100264 -0.866341 0.99984 0 -0.0178824 0.99984 0 -0.0178824 0.988879 0 -0.148719 0.978152 0.00944725 -0.207674 0.988841 -0.00140825 -0.148971 0.972599 0.000490467 -0.232488 0.961697 0.0498498 -0.269543 0.914591 0.00312141 -0.404367 0.9336 -8.34607e-06 -0.358318 0.890628 -0.0324725 -0.453571 0.926065 -0.0108335 -0.377208 0.95869 -8.02588e-06 -0.284453 0.974449 3.56237e-06 -0.224607 0.859351 0.00843156 -0.511317 0.668978 0 0.743282 0.759506 -0.0233991 0.650079 0.794618 -0.00976686 0.607032 0.968034 -0.0310075 0.248895 0.923758 0.000160014 0.382976 0.973156 -0.0270519 -0.228553 0.98904 -0.000129864 -0.147647 0.990579 -5.00171e-06 0.136939 0.915313 0.00485647 -0.402714 0.821686 4.34731e-05 -0.569941 0.821709 -9.89927e-05 -0.569907 0.590209 -0.0554362 0.805345 0.53778 -0.179998 0.823646 0.457286 0 0.88932 0.98581 -0.110457 0.126405 0.918326 -0.391753 0.0566307 0.964433 0 0.264328 0.833147 0 0.553051 0.800358 -0.408297 0.439 0.743059 0.00435273 0.669212 0.994079 0.0157629 -0.107514 0.933689 -0.183577 -0.30745 0.921755 -0.223786 -0.316681 0.881628 -0.000194671 -0.471945 0.74077 0.00292386 -0.671752 0.701757 -0.167884 -0.692352 0.824434 -0.000127845 -0.565958 0.70711 0 0.707104 0.70711 0 0.707104 0.29197 -0.00352048 0.956421 -0.89095 0 0.454101 -0.874975 -0.00260184 0.484161 -0.651062 0.00225879 0.759021 -0.573565 -0.0040237 0.81915 0.260701 -0.00138133 0.965419 0.0380069 0.000439692 0.999277 -0.157098 -0.00341943 0.987577 -0.207364 -7.40664e-05 0.978264 -0.431673 -7.64958e-06 0.90203 -0.998231 0.000281389 -0.0594577 -0.998402 -1.84566e-05 -0.0565062 -0.999992 -1.4101e-05 0.00392115 -0.999411 0.00464988 0.0339887 -0.996727 -0.00206979 0.0808182 -0.994643 -0.000180309 0.103371 -0.987431 0.000653788 0.158052 -0.980326 -0.00880866 0.19719 -0.971232 0 0.238134 -0.996626 0 0.0820808 -0.998095 0.00948278 0.0609659 -0.99882 0.00138208 0.0485559 -0.999236 0.00312897 -0.0389652 -0.999717 0.0103014 -0.0214608 -0.999999 0.000612003 -0.0015628 -0.999728 -0.000112444 0.023319 -0.984809 0 -0.17364 -0.984806 0 -0.173657 -0.984799 -5.66807e-05 -0.173697 -0.984808 3.39142e-05 -0.173646 -0.984807 1.30416e-05 -0.17365 -0.984817 -0.000167391 -0.173595 -0.984806 8.07985e-06 -0.173661 0.788794 9.86608e-05 -0.614657 0.777642 0.00011613 -0.628707 0.773238 0.00112676 -0.634115 0.746374 0.0142478 -0.665374 0.760251 0.0448572 -0.648079 0.751319 0.0285513 -0.659322 0.74491 0.0202793 -0.666856 0.736666 0.0113252 -0.676162 0.728851 0.00628273 -0.684644 0.826117 0.00361562 -0.563487 0.810453 0.0166848 -0.585566 0.810858 0.0177983 -0.584973 0.796964 0.00499588 -0.604006 0.838822 -0.00395552 -0.544392 0.846561 0.00387178 -0.532277 0.860889 -0.00654641 -0.508751 0.903114 -0.00250344 -0.429394 0.904126 -0.000446622 -0.427265 0.904387 0 -0.426714 0.901935 -0.00065762 -0.431871 0.899664 -0.0161281 -0.436285 0.902165 -0.00081944 -0.431391 0.900113 -7.90521e-05 -0.435657 0.878333 0.00172543 -0.478046 0.886664 0.0463154 -0.460089 0.87482 0.0183671 -0.484099 0.721516 0.00228457 -0.692394 0.70898 -0.000104236 -0.705229 0.705693 0 -0.708518 0.866267 0 -0.499581 0.866385 -3.26095e-05 -0.499377 0.866339 0 -0.499456 -0.866352 -3.30831e-05 0.499433 -0.86628 0 0.499558 -0.86628 0 0.499558 -0.866328 -0.000189651 0.499476 -0.866055 0.00275652 0.49994 0.98834 0 -0.152262 0.999934 0.00330288 -0.0109651 0.999802 0.00170809 -0.0198475 0.996573 -0.00781594 -0.0823478 0.998074 0.0111684 -0.0610155 0.989797 -0.00717842 -0.142307 0.991018 -0.000791684 0.133727 0.996025 0.0065586 0.0888352 0.996795 0.0115265 0.0791693 0.999184 -4.19271e-05 0.0403827 1 -3.39033e-05 0.000648774 0.986077 0.00108877 0.166283 0.986874 -1.6468e-05 0.161493 0.976891 -1.97507e-05 0.213737 0.97729 -0.000786857 0.211903 0.9587 0.000946528 0.284417 0.959215 0 0.282677 0.945063 0 0.326889 0.930023 0.00339771 0.367487 0.928612 0.00103818 0.371052 0.906693 -0.00034351 0.421792 0.899821 0.00312694 0.436247 0.894196 0 0.447675 0.707076 1.87848e-05 0.707138 0.707085 0 0.707128 -0.984824 0 0.173556 -0.993631 -1.59432e-06 0.112681 -0.993492 -0.000752136 0.1139 -0.98532 0.000950671 0.170718 -0.980993 0.0189843 0.193112 -0.410754 -0.377358 0.829989 -0.98302 0.0101212 0.18322 -0.935098 0 -0.354391 -0.939185 -0.00460659 -0.343381 -0.947074 0.00158231 -0.321012 -0.958775 -0.0030855 -0.28415 -0.958257 -0.00227243 -0.2859 -0.96861 0.00110406 -0.248584 -0.973811 -0.00351069 -0.227331 -0.97676 1.68739e-05 -0.214335 -0.990039 -0.0102948 -0.140418 -0.984569 1.70088e-05 -0.174998 -0.999649 -0.00195549 -0.0264251 -0.998992 1.43392e-05 -0.0448991 -0.997642 1.57226e-05 -0.0686333 -0.99794 -0.00113402 -0.0641472 -0.993188 0.00231851 -0.116504 -0.996904 2.76381e-06 0.0786334 -0.997918 -0.00179123 0.0644751 -0.999056 -0.00771288 0.0427587 -0.999572 -0.000691066 0.0292526 -0.999835 0.000428689 -0.0181463 1 0 -4.11254e-05 1 0 0 1 5.19904e-06 -7.53935e-06 1 0.000115377 7.19477e-05 1 -0.000224104 -0.000478765 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.984806 0 0.173657 0.984804 -2.00097e-05 0.173672 0.984808 4.22968e-05 0.173649 0.984853 -0.000818383 0.173391 0.984794 0 0.173724 -0.968244 -0.00227913 0.249998 -0.971506 0.00246363 0.237003 -0.972324 -1.74321e-05 0.233636 -0.967148 0.000724705 0.254211 -0.967628 -0.000856886 0.252381 -0.966892 -0.00903446 0.255027 -0.967346 -0.0063823 0.253379 -0.977036 0 0.213073 -0.97816 0.0121952 0.207497 -0.973908 0.000732875 0.226942 -0.970039 -0.0019427 0.242941 -0.971039 0.0065088 0.238832 -0.96825 -0.000708265 0.249983 -0.707093 0 -0.707121 -0.707094 -4.37692e-06 -0.707119 0.924115 -0.0071052 -0.382049 0.929017 0.0130193 -0.369809 0.917948 0 -0.3967 0.975948 -1.825e-07 -0.218002 0.972138 0.00704801 -0.234305 0.972234 0.00682946 -0.233909 0.963344 -0.00765536 -0.268162 0.957371 0.00699742 -0.288778 0.954661 0.00312036 -0.297678 0.941136 -0.0101845 -0.337876 0.946531 0.0122931 -0.322378 0.936663 0.00176037 -0.350228 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.999784 0 0.0207725 0.999784 0 0.0207725 0.999049 0 -0.0436049 0.999049 0 -0.0436049 0.989289 0 -0.145974 0.979235 0.0369898 -0.199325 0.876622 0 -0.48118 0.892087 0.0240206 -0.451225 0.932797 0 -0.360403 0.961764 0 -0.273879 0.938407 0 0.345532 0.955917 -0.00878172 0.293507 0.984834 -0.00303088 0.173471 0.973839 0.00127024 0.227236 0.967807 -0.00449522 0.251652 0.946646 0.0163127 0.321861 0.992918 -0.0356634 0.113321 0.990508 -0.0139019 0.136753 0.997761 0 0.0668817 0.844299 -0.0431379 0.534134 0.818157 0.00423408 0.574979 0.807025 0 0.590518 0.82628 0.0138976 0.563088 0.854561 -9.88619e-07 0.51935 0.867182 -3.16749e-06 0.497992 0.87394 -0.00417837 0.486016 0.89551 0.00900983 0.444951 0.910922 -0.0121697 0.412398 0.925476 0 0.378807 -1 4.43894e-05 -5.477e-05 -1 0 5.25867e-05 -1 0 -1.5693e-05 -1 1.35762e-05 2.31145e-07 -1 0.000152424 7.0202e-05 -1 -5.59576e-06 0 -1 -1.00445e-05 3.1946e-06 -0.398855 0 0.917014 -0.82437 0 -0.566051 -0.842305 -0.00431405 -0.538985 -0.990653 0.00580461 -0.13628 -0.98386 -0.00192198 -0.178927 -0.956636 0.00179577 0.291279 -0.956655 0.00178556 0.29122 -0.746291 -0.00158232 0.665618 -0.717069 0.00477518 0.696986 -0.368674 -0.00509647 0.929545 -0.707106 0 -0.707107 -0.707106 0 -0.707107 -0.536879 0 -0.843659 0.694339 0 -0.719648 0.678593 -0.00307864 -0.734508 0.303326 0.00382329 -0.952879 0.324285 0 -0.94596 -0.129015 0 -0.991643 -0.150527 0.00342813 -0.9886 -0.555227 -0.00345522 -0.831692 0.821696 0 -0.569927 0.821696 0 -0.569927 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.0898079 -0.986843 0.134447 6.10286e-05 -1 3.08525e-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.999225 0 -0.0393743 -0.999225 0 -0.0393743 -0.972619 0 -0.232407 -0.373877 0 -0.927478 -0.383546 -0.00112181 -0.923521 -0.76169 0.00123589 -0.64794 -0.76126 0.00116031 -0.648446 -0.975118 -0.00118438 -0.221683 -0.822797 0 -0.568335 -0.854444 0.00462898 -0.519523 -0.997846 0.00116106 -0.0655912 -0.999517 -0.00221327 -0.0309967 -0.137083 0 0.99056 -0.0805223 0.00366171 0.996746 0.227387 -0.00260232 0.973801 0.37054 0.00395625 0.928808 0.568089 -0.00465194 0.822954 -0.164123 -0.986015 -0.0289398 -0.169585 -0.985064 -0.0298395 -0.47075 -0.878348 -0.0830627 -0.526133 -0.845396 -0.0921463 -0.64651 -0.754344 -0.113975 -0.795988 -0.588804 -0.140404 -0.725257 -0.676255 -0.129157 -0.851589 -0.502362 -0.149761 -0.941844 -0.291936 -0.166445 -0.969311 -0.177175 -0.170429 -0.982629 -0.0664732 -0.173266 -0.53788 -0.84287 -0.0159841 -0.776762 -0.628906 -0.0334201 -0.743112 -0.668836 0.0210771 -0.849942 -0.521022 -0.0783254 -0.990179 -0.134249 -0.0390178 -0.176726 -0.984193 0.0114673 -0.420056 -0.907165 0.0245894 -0.581559 -0.673803 -0.455827 -0.548317 -0.835601 0.0334657 -0.187102 -0.982274 0.0114175 -0.620628 -0.782858 0.0442121 -0.980544 -0.18694 0.0598939 -0.982611 -0.175445 0.0607861 -0.834564 -0.548607 0.0503408 -0.890327 -0.451095 0.0619024 -0.773175 -0.632434 0.0471897 -0.982128 -0.187028 -0.0210833 -0.982006 -0.187662 -0.021123 -0.835871 -0.548632 -0.0179796 -0.835952 -0.548509 -0.017971 -0.549248 -0.835576 -0.0118075 -0.549285 -0.835551 -0.0118052 -0.187472 -0.982262 -0.00402913 -0.187477 -0.982261 -0.00402891 -0.980755 -0.187187 -0.0555074 -0.956064 -0.293134 0.0037489 -0.978449 -0.190641 0.0793361 -0.917712 -0.396311 0.0272603 -0.836382 -0.547584 0.0248444 -0.836587 -0.547268 0.0248947 -0.550406 -0.834737 0.0163787 -0.550491 -0.83468 0.0163935 -0.188033 -0.982147 0.00559958 -0.188078 -0.982138 0.005606 -0.961678 -0.194312 0.193439 -0.964173 -0.179082 0.195702 -0.81587 -0.554531 0.163867 -0.819893 -0.54804 0.165613 -0.54185 -0.833318 0.10945 -0.539367 -0.835036 0.108617 -0.190976 -0.980804 0.0393873 -0.184194 -0.982186 0.0371957 -0.199173 -0.923788 0.327025 -0.00688471 -0.93334 0.358927 0.199749 -0.828556 0.523063 -0.18603 -0.813608 0.550848 -0.652115 -0.625532 0.428318 0.339481 -0.553025 0.760866 -0.714585 -0.541142 0.443322 0.176381 -0.184246 0.966925 0.280298 -0.279933 0.918189 -0.180254 -0.299999 0.936755 -0.147462 -0.344857 0.927 -0.567659 -0.143192 0.810715 -0.771848 -0.343422 0.535082 -0.859011 -0.190167 0.475328 0.428553 -0.507307 0.747651 0.279663 -0.831768 0.479532 0.310179 -0.781791 0.540917 0.0985495 -0.980788 0.168353 0.110775 -0.9751 0.192114 0.489903 -0.195177 0.849648 0.489911 -0.195114 0.849657 0.415485 -0.555103 0.720579 -0.150044 -0.987917 0.0388276 -0.684998 -0.707062 0.175616 -0.684905 -0.707158 0.175589 -0.439759 -0.891011 0.112741 -0.440043 -0.890861 0.11282 -0.168771 -0.984705 0.0432671 -0.151197 -0.987865 0.0355318 -0.966302 -0.111122 0.232189 -0.886263 -0.401377 0.231159 -0.959063 -0.139275 0.246579 -0.933367 -0.267528 0.239278 -0.889204 -0.396676 0.227957 -0.863818 -0.454206 0.217981 -0.685667 -0.707053 0.173025 -0.685569 -0.707152 0.173006 -0.440192 -0.891006 0.111084 -0.44021 -0.890997 0.111088 -0.145901 -0.988614 0.0368185 -0.151809 -0.987679 0.0380184 -0.95811 -0.156359 0.239954 -0.962965 -0.116812 0.243007 -0.863747 -0.454347 0.217969 -0.862742 -0.454358 0.221889 -0.817931 -0.535739 0.209696 -0.96479 -0.157832 0.210402 -0.965013 -0.156325 0.210506 -0.870461 -0.454168 0.189816 -0.870461 -0.454167 0.189816 -0.690906 -0.707072 0.150661 -0.690872 -0.707107 0.150652 -0.443663 -0.890956 0.0967457 -0.443636 -0.890971 0.0967386 -0.152816 -0.987693 0.0333228 -0.152919 -0.987676 0.0333493 -0.965401 -0.259937 -0.0208394 -0.645299 -0.707424 -0.288342 -0.548059 -0.816584 -0.181168 -0.551579 -0.808213 -0.206282 -0.764153 -0.525935 -0.373447 -0.769878 -0.185645 -0.610593 -0.994114 -0.108313 -0.00234986 -0.756752 -0.50995 -0.408996 -0.922158 -0.382548 -0.0572854 -0.9222 -0.382456 -0.0572217 -0.70811 -0.703576 0.0596788 -0.847791 -0.529295 0.0331304 -0.593672 -0.66245 0.456852 -0.591041 -0.666617 0.454195 0.953994 -0.175176 0.243329 0.880061 -0.386707 0.275593 0.496438 -0.831481 0.249375 0.628695 -0.50908 0.58786 0.292123 -0.928976 0.227306 0.124808 -0.968934 0.213519 -0.366619 -0.848096 0.382524 -0.0746461 -0.921697 0.380661 -0.145686 -0.921111 0.361013 -0.493498 -0.727945 0.475979 0.551437 -0.257889 0.793354 0.119335 -0.216381 0.968988 0.24197 -0.348528 0.905527 -0.0995884 -0.244152 0.96461 0.642272 -0.670424 0.371509 0.592842 -0.642764 0.485174 0.219726 -0.67984 0.69967 -0.426637 -0.331271 0.84157 -0.119427 -0.985633 -0.119436 -0.124206 -0.984494 -0.123876 -0.166934 -0.971882 -0.16607 -0.342631 -0.874362 -0.34365 -0.391899 -0.833425 -0.389639 -0.5493 -0.627514 -0.551811 -0.592841 -0.547118 -0.590933 -0.674091 -0.299213 -0.675331 -0.69578 -0.186871 -0.69352 -0.705195 -0.0732248 -0.705223 0.530725 -0.84229 0.094222 0.965128 -0.198914 0.170179 0.969578 -0.1756 0.17054 0.79329 -0.59243 0.140416 0.907775 -0.389654 0.155288 0.804746 -0.576601 0.141118 0.160541 -0.986623 0.0283066 0.106838 -0.994082 0.0196493 0.328679 -0.942683 0.0576197 0.276972 -0.959636 0.0488411 0.496225 -0.863774 0.0874936 0.969317 -0.0777119 -0.233207 0.0995222 -0.994186 -0.0411172 0.169182 -0.98283 -0.0736377 0.258508 -0.960034 -0.107275 0.502943 -0.83908 -0.207349 0.462475 -0.864871 -0.195232 0.922192 -0.314812 -0.224622 0.955648 -0.188192 -0.226543 0.940286 -0.1882 -0.283625 0.161608 -0.986099 -0.0386275 0.454163 -0.883622 -0.113795 0.529182 -0.839117 -0.125891 0.511658 -0.839135 -0.18455 0.511771 -0.839054 -0.184603 0.164895 -0.984516 -0.0594798 0.172196 -0.983055 -0.0628549 0.738927 -0.648094 -0.184286 0.81111 -0.552003 -0.193373 0.798285 -0.552033 -0.240834 0.94039 -0.187555 -0.283706 0.923516 -0.190079 -0.333149 0.92757 -0.169472 -0.333006 0.904479 -0.204529 -0.374279 0.905409 -0.200305 -0.374315 0.742329 -0.594542 -0.308978 0.771485 -0.552429 -0.315646 0.784149 -0.552353 -0.282874 0.784408 -0.551956 -0.282928 0.798314 -0.551985 -0.240848 0.520708 -0.839157 -0.157095 0.520739 -0.839137 -0.157102 0.186982 -0.980742 -0.0564106 0.246194 -0.966651 -0.0705327 -0.123637 -0.992317 0.00459311 -0.12596 -0.991939 0.0138445 -0.124457 -0.992132 0.0136106 -0.122263 -0.992131 -0.0269803 -0.0552039 -0.998434 -0.00901534 -0.0941551 -0.995483 -0.012227 -0.152759 -0.988242 -0.00658736 -0.125143 -0.992131 -0.00398917 -0.125159 -0.992125 0.00471907 -0.0615979 -0.997898 -0.020145 -0.10513 -0.993696 -0.0389466 -0.135853 -0.98986 -0.0414943 -0.119939 -0.992137 -0.0357727 -0.203952 -0.978931 -0.00989399 -0.294826 -0.948731 -0.113958 -0.387177 -0.911074 -0.141558 -0.327721 -0.939457 -0.100098 -0.36192 -0.925934 -0.10798 -0.123337 -0.992135 0.0213676 -0.128855 -0.991406 0.0225821 -0.367784 -0.925939 -0.0858574 -0.314463 -0.94673 -0.0693939 -0.479459 -0.874926 -0.0680018 -0.374859 -0.925803 -0.0486792 -0.376853 -0.92591 -0.0259258 -0.316223 -0.948587 -0.0136363 -0.377689 -0.925879 -0.00998395 -0.377711 -0.925817 0.0140319 -0.422207 -0.906319 0.0180701 -0.346224 -0.937387 0.037863 -0.37524 -0.925929 0.0430199 -0.372318 -0.925928 0.0635331 -0.392818 -0.917094 0.0680601 0.654885 -0.194175 0.730357 0.120405 -0.834164 0.538213 0.242809 -0.730414 0.638388 0.316479 -0.592433 0.740854 0.43742 -0.545047 0.715254 0.0607845 -0.957325 0.28255 -0.0373878 -0.993109 0.111067 -0.50915 -0.782816 0.357722 0.0420708 -0.86166 0.505739 -0.147874 -0.823378 0.547889 -0.131269 -0.28814 0.948548 0.0164427 -0.310584 0.950404 0.25882 -0.965926 -1.93326e-06 0.258796 -0.965932 -9.75576e-07 0.707179 -0.707035 -2.66583e-06 0.707082 -0.707132 2.66543e-06 0.965865 -0.259045 3.64094e-06 0.965938 -0.258773 -7.28254e-06 0.693585 -0.19448 0.693627 0.0370432 -0.998627 0.0370454 0.184999 -0.965882 0.181238 0.587811 -0.555806 0.587842 0.458698 -0.761032 0.458722 0.431118 -0.7934 0.429714 0.344119 -0.873184 0.345154 0.176264 -0.969277 0.171561 0.559166 -0.60808 0.563536 0.685162 -0.259179 0.68072 -0.381759 -0.916719 0.117838 -0.558345 -0.634028 0.535032 -0.576362 -0.796784 0.1815 -0.629754 -0.760119 0.160091 -0.761209 -0.513477 -0.396109 -0.391244 -0.194421 0.899516 -0.688339 -0.294756 0.662804 -0.721976 -0.253187 0.643931 -0.943504 -0.249078 0.21854 -0.896753 -0.348252 0.273046 -0.978816 -0.154234 -0.134651 -0.832327 -0.352136 -0.428056 -0.814874 -0.253157 -0.521432 -0.273181 -0.204272 -0.940024 -0.0663455 -0.965911 0.250227 -0.0891276 -0.965566 0.244415 -0.0890848 -0.965586 0.24435 -0.137517 -0.965588 0.220748 -0.137544 -0.965578 0.220775 -0.18006 -0.965577 0.187721 -0.18006 -0.965577 0.187721 -0.214871 -0.965578 0.146597 -0.214898 -0.96557 0.146607 -0.240494 -0.965571 0.0991724 -0.240412 -0.965593 0.0991595 -0.255686 -0.965592 0.0475111 -0.255696 -0.965589 0.0475106 -0.260003 -0.965588 -0.006171 -0.260069 -0.96557 -0.00618861 -0.25321 -0.965572 -0.059633 -0.253201 -0.965574 -0.0596285 -0.235489 -0.965573 -0.110512 -0.235494 -0.965572 -0.110516 -0.207672 -0.965573 -0.156654 -0.207651 -0.965582 -0.156629 -0.170925 -0.965584 -0.196044 -0.170934 -0.965578 -0.196062 -0.126881 -0.965576 -0.227077 -0.126887 -0.96557 -0.227099 -0.0726776 -0.965424 -0.250349 -0.072644 -0.965521 -0.249985 -0.185016 -0.749003 -0.636211 -0.187067 -0.703551 -0.685582 -0.345864 -0.705148 -0.618987 -0.345851 -0.705215 -0.618918 -0.465933 -0.705207 -0.534407 -0.465945 -0.705175 -0.534437 -0.566014 -0.705216 -0.426964 -0.566049 -0.705157 -0.427015 -0.641893 -0.705147 -0.301232 -0.641849 -0.705205 -0.30119 -0.690138 -0.70519 -0.162533 -0.690104 -0.705227 -0.162512 -0.708769 -0.70524 -0.0168222 -0.708816 -0.705192 -0.0168397 -0.697074 -0.705202 0.129529 -0.697261 -0.705023 0.129502 -0.655638 -0.705011 0.270365 -0.65544 -0.7052 0.270353 -0.585684 -0.705199 0.399586 -0.585694 -0.705189 0.399589 -0.4908 -0.705192 0.511682 -0.490846 -0.705144 0.511706 -0.374923 -0.705138 0.601841 -0.374974 -0.705075 0.601883 -0.242939 -0.705084 0.666211 -0.242881 -0.705171 0.66614 -0.196125 -0.706864 0.679616 -0.188316 -0.714755 0.673545 -0.259887 -0.256882 -0.930844 -0.471335 -0.257662 -0.843477 -0.471312 -0.257417 -0.843565 -0.635008 -0.257428 -0.728351 -0.635009 -0.257457 -0.72834 -0.771407 -0.257458 -0.581933 -0.771401 -0.257571 -0.581892 -0.874741 -0.257563 -0.410475 -0.874739 -0.257573 -0.410472 -0.940522 -0.257613 -0.221482 -0.940505 -0.257698 -0.221456 -0.965947 -0.257722 -0.0229485 -0.966043 -0.257352 -0.023046 -0.950085 -0.257296 0.176459 -0.949973 -0.257659 0.176533 -0.893233 -0.257661 0.368437 -0.893192 -0.257781 0.368453 -0.798139 -0.257804 0.544529 -0.798251 -0.257497 0.54451 -0.668901 -0.257498 0.697328 -0.668987 -0.257264 0.697331 -0.510977 -0.25729 0.820185 -0.51092 -0.257448 0.820171 -0.331004 -0.257445 0.907832 -0.330983 -0.257508 0.907821 -0.262561 -0.258707 0.929587 -0.204515 -0.350686 0.913889 -0.183077 -0.965919 -0.182985 -0.183207 -0.965875 -0.183086 -0.4996 -0.707921 -0.499247 -0.497609 -0.710331 -0.49781 -0.680943 -0.265848 -0.682379 -0.683015 -0.258802 -0.683017 0.373552 -0.77674 -0.507083 -0.0457708 -0.969805 -0.23955 0.0163461 -0.983109 -0.182287 0.166054 -0.962763 -0.213337 -0.11466 -0.702378 -0.702508 -0.0991612 -0.676378 -0.729849 0.391532 -0.700453 -0.596714 0.482976 -0.588289 -0.648575 -0.532189 -0.131891 -0.836289 -0.128259 -0.352402 -0.927018 -0.121288 -0.340867 -0.932255 0.299993 -0.147897 -0.942407 0.556287 -0.36439 -0.746837 0.656507 -0.253071 -0.710601 -0.195103 -0.980783 0 -0.195103 -0.980783 0 -0.510411 -0.859931 0 -0.555601 -0.831448 -0.000937138 -0.669003 -0.743259 -2.05972e-07 -0.760069 -0.649842 -2.34009e-07 -0.831434 -0.555622 0.00113968 -0.872667 -0.488315 0 -0.942366 -0.334583 0 -0.980766 -0.195187 0.000903819 -0.989404 -0.145189 0 0.194578 -0.971558 -0.134957 0.211989 -0.96591 -0.14859 0.48409 -0.808374 -0.334946 0.500131 -0.793387 -0.346995 0.622953 -0.652138 -0.432025 0.65128 -0.608837 -0.452937 0.72553 -0.470788 -0.501961 0.792286 -0.255862 -0.553911 0.791711 -0.258832 -0.553353 0.819026 -0.0805373 -0.568075 0.683162 -0.185932 0.706201 0.531288 -0.31874 0.784945 0.517959 -0.414755 0.748129 0.181668 -0.869231 0.45982 0.289679 -0.756993 0.585703 -0.0161975 -0.947094 0.320547 -0.186014 -0.935291 0.301048 -0.367432 -0.850416 0.376546 -0.485483 -0.818145 0.308131 -0.808355 -0.540199 0.233983 -0.645302 -0.716364 0.265346 -0.224531 -0.396651 0.890087 -0.513295 -0.18732 0.83752 -0.967633 -0.192595 0.163076 -0.889297 -0.324672 0.322085 -0.832529 -0.177991 0.52461 0.505473 -0.293013 0.811567 0.319094 -0.164515 0.933335 -0.118191 -0.275042 0.95414 -0.203786 -0.476288 0.855349 0.30326 -0.699962 0.646596 0.442316 -0.583453 0.681131 0.568464 -0.822643 -0.0103504 0.204568 -0.97142 -0.120393 0.190961 -0.979719 -0.0606957 0.140818 -0.987313 -0.073373 0.121738 -0.992519 -0.00929338 0.225872 -0.974149 0.00390478 0.983252 -0.177124 -0.0429155 0.834151 -0.551477 -0.00808258 0.862446 -0.506149 -0.000602199 0.956508 -0.291576 -0.00875604 0.98933 -0.144236 0.0205552 0.773708 -0.46894 -0.425996 0.848179 -0.25455 -0.464539 0.666012 -0.650193 -0.365618 0.73506 -0.550645 -0.395571 0.795522 -0.550637 -0.252872 0.795342 -0.550947 -0.252761 0.544043 -0.839037 -0.00587587 0.53884 -0.838836 -0.0775013 0.182229 -0.982907 -0.0262099 0.176141 -0.982912 -0.0534612 0.944556 -0.18832 -0.268979 0.898174 -0.334322 -0.285502 0.91614 -0.188135 -0.353968 0.863952 -0.187389 -0.46741 0.873801 -0.0801487 -0.479632 0.522024 -0.80653 -0.277489 0.477986 -0.838258 -0.262398 0.519398 -0.838434 -0.165087 0.51952 -0.838355 -0.165104 0.539211 -0.838586 -0.0776199 0.825812 -0.551274 -0.118876 0.825882 -0.551171 -0.118869 0.972135 -0.188087 -0.139919 0.966225 -0.214671 -0.142571 0.159719 -0.982921 0.0914142 0.894664 -0.188468 0.405038 0.889341 -0.222679 0.399359 0.739498 -0.584183 0.334475 0.452158 -0.868117 0.204761 0.227805 -0.968226 0.103166 0.166043 -0.982933 0.0792032 0.152133 -0.982931 0.103451 0.172134 -0.977905 0.118622 0.148443 -0.982956 0.108458 0.501392 -0.793244 0.3455 0.741892 -0.4339 0.511202 0.839228 -0.188582 0.510032 0.811553 -0.188455 0.553052 0.789347 -0.284787 0.543901 0.792573 -0.1884 0.579943 0.159651 -0.982936 0.0913673 0.472387 -0.838907 0.270344 0.493976 -0.838873 0.228645 0.758716 -0.551617 0.34651 0.723858 -0.551744 0.414257 0.472376 -0.838915 0.270336 0.449492 -0.838863 0.307029 0.357586 -0.900783 0.246421 0.858262 -0.188612 0.477297 0.832752 -0.281786 0.476571 0.723842 -0.551775 0.414244 0.687999 -0.551671 0.471504 0.653258 -0.608785 0.450149 0.182591 -0.982864 0.0252843 0.239475 -0.968212 0.0722248 0.177235 -0.982908 0.0497993 0.0200234 -0.999771 0.00748752 0.473171 -0.869335 0.142706 0.522815 -0.838627 0.152874 0.780305 -0.580772 0.232011 0.882432 -0.387791 0.266331 0.922963 -0.222852 0.313809 0.979778 -0.143689 0.139242 0.972287 -0.19141 0.134237 0.950793 -0.18674 0.247227 0.798797 -0.551039 0.241412 0.826601 -0.550851 0.115301 0.855242 -0.505428 0.114475 0.224623 -0.974055 0.0275881 0.563465 -0.822101 0.0815927 0.539822 -0.838368 0.0757001 0.29197 0.00350975 0.956421 -0.157098 0.00297448 0.987579 0.0454717 -0.00037756 0.998966 0.260899 0.00139271 0.965365 -0.650256 0.00641987 0.759688 -0.433628 4.21389e-06 0.901092 -0.198745 7.51775e-05 0.980051 -0.573566 -0.00359594 0.819151 -0.874975 0.0026168 0.484161 -0.891056 0 0.453893 0.523913 -0.000499641 0.851772 0.666422 0.00279925 0.74557 0.832232 0 -0.554428 0.835274 0.000382215 -0.549834 0.980062 -0.0003528 -0.19869 0.992423 0.0044034 -0.122786 0.70907 -3.39397e-05 0.705138 0.84907 2.86537e-05 0.52828 0.927868 0.00447123 0.372883 0.953637 4.1019e-05 0.300959 0.998225 -1.48595e-05 0.0595626 0.875903 -0.0207761 -0.48204 0.87804 -0.0256453 -0.4779 0.888724 0.00188416 -0.458438 0.900649 -0.00016527 -0.434548 0.902478 0.000188761 -0.430736 0.902958 0.00039016 -0.429729 0.904379 4.80462e-06 -0.42673 0.902871 0.00259154 -0.429904 0.903964 0.00121237 -0.427607 0.846536 0.00862819 -0.532261 0.839402 -0.00737047 -0.543461 0.862847 0.00581187 -0.505431 0.78861 -1.11424e-05 -0.614894 0.797841 -0.0055479 -0.602843 0.810428 -0.0184082 -0.585549 0.812895 -0.0133473 -0.582258 0.826832 -0.00326285 -0.562439 0.737283 -0.0120141 -0.675477 0.729452 -0.00661214 -0.684 0.745371 -0.0207962 -0.666326 0.751976 -0.0297403 -0.658519 0.746305 -0.0196814 -0.665313 0.768137 -0.00327933 -0.640277 0.776165 -2.8162e-05 -0.63053 0.721428 -0.00226764 -0.692485 0.705693 0.000723465 -0.708518 0.708992 0 -0.705217 -0.984801 -9.37983e-06 -0.173684 -0.984819 -0.00014853 -0.173585 -0.984804 -2.08727e-05 -0.173668 -0.984807 -0.000100302 -0.17365 -0.984826 0.000298473 -0.173542 -0.984802 1.70234e-05 -0.17368 -0.98481 4.98259e-05 -0.173636 -0.99813 -0.000110678 -0.0611232 -0.99814 4.08602e-05 0.0609687 -0.998 -0.00262098 0.0631553 -0.999695 9.91312e-05 0.024703 -0.999769 -0.00120922 -0.021462 -0.999842 -0.0171582 -0.00472797 -0.999221 -0.00294874 -0.0393425 -0.971232 0 0.238134 -0.980326 0.00880873 0.19719 -0.987402 -0.000611295 0.158228 -0.996729 0.000526081 0.0808183 -0.994481 0.0055593 0.104773 -0.999949 -0.00930225 0.00392098 -0.999364 8.99732e-06 0.0356452 -0.998402 0.00034235 -0.0565062 0.894165 -1.18123e-05 0.447738 0.899821 -0.00315252 0.436247 0.930025 -0.00252331 0.367488 0.930586 -0.00354705 0.366056 0.90823 0.00111729 0.418469 0.977291 7.26291e-06 0.211903 0.97771 -0.000766633 0.209957 0.959215 0.00102934 0.282677 0.959739 1.28102e-05 0.280894 0.993662 -0.0145353 0.111462 0.991378 -0.00684178 0.130857 0.9866 4.0823e-06 0.163161 0.997682 0.00361808 -0.0679553 0.999742 -0.00120229 -0.0226678 0.999934 -0.0033347 -0.0109651 1 -6.65672e-06 0.000730912 0.999483 -2.87664e-07 0.0321451 0.999298 0.000985052 0.0374624 0.996339 -0.00265377 0.0854457 0.996589 -0.00536179 -0.0823492 0.988317 0.00687207 -0.152258 0.989587 0 -0.143933 0.707097 0 0.707117 0.707096 1.11302e-06 0.707117 0.984807 0 0.173654 0.984807 0 0.173654 0.984808 1.21377e-05 0.173649 0.984812 -6.66292e-05 0.173627 0.984807 -1.1345e-07 0.173654 0.946038 0.00705267 -0.32398 0.955267 -0.00801344 -0.295636 0.960889 -0.0223425 -0.276029 0.964529 -0.00646082 -0.263899 0.972621 0 -0.232396 0.936774 -0.00919385 -0.349814 0.938705 -0.00539757 -0.34468 0.928731 0.00503795 -0.370719 0.923334 -0.006128 -0.383949 0.91801 0 -0.396558 -0.70711 -6.9993e-07 -0.707103 -0.70711 0 -0.707104 -0.978168 0 0.207816 -0.976997 -0.00893044 0.213065 -0.966776 -0.00195736 0.255617 -0.967617 0.00475345 0.252378 -0.967426 0.00589557 0.253086 -0.967077 -0.000972217 0.254484 -0.968112 0.00106916 0.250514 -0.970034 -0.00384697 0.24294 -0.970766 -0.000232624 0.240027 -0.97359 7.7962e-05 0.228305 -0.968413 0.00197574 0.249344 -0.972318 -0.00367681 0.233635 -0.971571 0 0.236747 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.876622 0 -0.48118 0.892087 -0.0240207 -0.451225 0.932797 0 -0.360403 0.961764 0 -0.273879 0.979235 -0.0369899 -0.199325 0.989289 0 -0.145974 0.999049 0 -0.0436049 0.999049 0 -0.0436049 0.999784 0 0.0207725 0.999784 0 0.0207725 0.821696 0 -0.569927 0.821696 0 -0.569927 0.678596 0 -0.734511 -0.55523 0 -0.831697 -0.536877 0.0031154 -0.843655 -0.129014 -0.0037637 -0.991636 -0.150528 0 -0.988606 0.303329 0 -0.952886 0.324283 -0.00348173 -0.945954 0.694335 0.00341566 -0.719643 -0.707106 0 -0.707107 -0.707106 0 -0.707107 -0.842312 0 -0.53899 -0.368679 0 0.929557 -0.398851 0.00434195 0.917006 -0.74628 -0.00575993 0.665608 -0.717076 0.00191011 0.696993 -0.956636 -0.00178509 0.291279 -0.956655 -0.00179529 0.29122 -0.990669 0.00158963 -0.136282 -0.983851 -0.00481204 -0.178926 -0.824359 0.0050647 -0.566044 -0.279065 0 -0.960272 -0.218384 0 0.975863 -0.038242 0.0932623 0.994907 -0.0671213 0.45166 -0.889662 -0.197041 0 -0.980395 0.21496 0 -0.976623 0.21496 0 -0.976623 0.503752 0 -0.863848 0.503752 0 -0.863848 -0.0125133 0 0.999922 0.269479 0 0.963006 0.269479 0 0.963006 -0.279065 0 -0.960272 -0.487749 0 -0.872984 -0.57505 0.0418233 -0.817048 -0.657162 0 -0.753749 -0.798337 0 -0.602211 -0.855664 0.041822 -0.51584 -0.905285 0 -0.424805 -0.97338 0 -0.229197 -0.99101 0.0417985 -0.12709 -0.999716 0 -0.0238493 -0.983168 0 0.182701 -0.95812 0.0418186 0.283297 -0.924434 0 0.381341 -0.826108 0 0.563512 -0.762636 0.041819 0.645475 -0.692289 0 0.72162 -0.528743 0 0.848782 -0.437613 0.0418186 0.898191 -0.342535 0 0.939505 -0.218384 0 0.975863 -1 1.7127e-05 9.48826e-05 -1 0 0 -1 0 1.33199e-05 -1 5.28869e-05 -6.19986e-05 -1 -5.51031e-06 3.96286e-05 -0.999999 -0.000747252 -0.000758458 -1 -2.34445e-06 0 -1 -9.34199e-06 2.47675e-06 -1 -0.000140729 6.8115e-05 0.924421 0 0.381375 0.910918 0.0125695 0.412396 0.894341 -0.00850568 0.447305 0.866608 0.00849759 0.498917 0.873948 1.25667e-05 0.48602 0.854561 8.98989e-06 0.51935 0.847427 -0.0036151 0.5309 0.82632 0.00979287 0.563115 0.806807 -0.0232099 0.590359 0.818048 0 0.57515 0.997761 0 0.0668817 0.993646 0.00900688 0.11219 0.99034 0.023067 0.13673 0.984943 0.00306613 0.172851 0.967812 -0.00322265 0.251653 0.973707 0.0117447 0.227503 0.956571 -0.00775361 0.291397 0.946765 0.00401007 0.321901 0.938419 0 0.3455 2.11863e-05 1 -1.54351e-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.999219 0.00324011 -0.039374 0.935032 0 0.354563 0.914603 -0.00495813 0.404322 0.646073 0.0036451 0.763267 0.679418 -0.00148093 0.73375 0.300056 0.00128588 0.953921 0.246592 -0.00414289 0.96911 -0.138638 0.00384739 0.990336 -0.231362 -0.0056302 0.972852 -0.588979 8.07438e-05 0.808149 -0.633542 -0.00420992 0.773696 -0.789064 0.00187783 0.614309 -0.932365 -0.00751692 0.36144 -0.907762 0 0.419486 -0.0872537 0.00393546 0.996178 0.321586 -0.000397313 0.94688 0.294023 0.0016327 0.955797 0.528677 -0.00060569 0.848823 0.642461 -0.00380504 0.766309 0.695286 0 0.718733 -0.52254 0.00420155 0.852605 -0.163455 -0.000944331 0.98655 -0.986094 0 0.166188 -0.986039 -1.85378e-05 0.166515 -0.846038 -9.37467e-06 0.533122 -0.895154 0.00750925 0.445694 -0.771131 -2.22186e-05 0.636677 -0.577232 0.000147883 0.81658 -0.999647 0 -0.0265626 -0.99988 0.00105483 -0.0154578 -0.878689 -0.000945455 -0.477394 -0.861691 0.00201293 -0.507429 -0.169561 0.985066 -0.0298977 -0.976148 0.132322 -0.172123 -0.969342 0.176905 -0.17053 -0.892482 0.422607 -0.157732 -0.851858 0.501884 -0.149833 -0.749727 0.648377 -0.132351 -0.225029 0.973516 -0.040359 -0.569163 0.816179 -0.0995289 -0.526043 0.845396 -0.0926546 -0.725494 0.676232 -0.127944 -0.510401 0.842629 -0.171663 -0.686241 0.72629 0.0396946 -0.744318 0.666441 0.0429871 -0.717875 0.694972 0.0408721 -0.852048 0.517211 -0.0806619 -0.989386 0.139982 -0.0389866 -0.187485 0.982259 -0.00402908 -0.549231 0.835587 -0.011804 -0.982008 0.18766 -0.0210807 -0.982128 0.187026 -0.0211256 -0.836045 0.548366 -0.0179834 -0.18749 0.982258 -0.00402951 -0.187115 0.982272 0.0114183 -0.176712 0.984196 0.0114682 -0.439145 0.898051 0.0256146 -0.548136 0.835568 0.0370532 -0.549113 0.835665 -0.0117915 -0.835875 0.548626 -0.0179577 -0.980861 0.185262 0.0599133 -0.980538 0.186936 0.0599964 -0.895542 0.441701 0.0538887 -0.834329 0.548559 0.0545781 -0.978389 0.190948 0.0793313 -0.964346 0.180028 0.193976 -0.961362 0.194336 0.194978 -0.820386 0.547563 0.164746 -0.815674 0.554553 0.164761 -0.539193 0.83511 0.108913 -0.539856 0.834677 0.108952 -0.184112 0.982172 0.0379518 -0.191314 0.980769 0.0386274 -0.980755 0.187185 -0.0555074 -0.188046 0.982144 0.00559629 -0.18809 0.982136 0.00559262 -0.550373 0.834758 0.0163646 -0.550473 0.834693 0.0163536 -0.836627 0.547209 0.0248547 -0.836591 0.547263 0.0248612 -0.917693 0.396354 0.0272714 -0.956065 0.29313 0.0037489 -0.0563261 0.988656 0.139238 -0.0294564 0.935514 0.352061 -0.178155 0.931639 0.316716 -0.613299 0.683027 0.396658 -0.212243 0.827624 0.519607 0.182745 0.827021 0.53164 -0.726369 0.544318 0.419649 0.3093 0.551104 0.774996 -0.803009 0.184482 0.566695 -0.821362 0.344671 0.454495 -0.56765 0.143305 0.810702 -0.231125 0.347857 0.908612 -0.150819 0.279916 0.948104 0.212865 0.300995 0.929565 0.286633 0.190353 0.938939 0.251671 0.966795 0.0443745 0.160914 0.986621 0.0261923 0.328744 0.942681 0.0572692 0.530658 0.842295 0.0945569 0.59665 0.795575 0.10521 0.760087 0.635852 0.134016 0.804503 0.576602 0.142494 0.876574 0.455871 0.15427 0.906979 0.389632 0.159927 0.95765 0.233227 0.168856 0.9694 0.175597 0.171551 0.983168 0.0576826 0.17336 0.921037 0.193175 -0.338192 0.921754 0.0588006 -0.383292 0.895988 0.234443 -0.377151 0.927213 -0.0826184 -0.365308 0.827051 0.459079 -0.324398 0.775544 0.551719 -0.30682 0.714501 0.641028 -0.280307 0.506558 0.839021 -0.198602 0.559286 0.798514 -0.222655 0.235525 0.967521 -0.091825 0.175097 0.982451 -0.0642731 0.172973 0.983421 -0.0544297 0.133311 0.990332 -0.0383533 0.177808 0.982972 -0.0463722 0.945771 0.178057 -0.271686 0.943843 0.188192 -0.27156 0.80149 0.551757 -0.230603 0.801688 0.551453 -0.230643 0.522953 0.838978 -0.150452 0.560972 0.812367 -0.159281 0.389496 0.914186 -0.112057 -0.136747 0.981121 -0.136756 -0.137792 0.980814 -0.137901 -0.312691 0.896925 -0.312649 -0.393188 0.83249 -0.390339 -0.430893 0.792866 -0.430924 -0.587532 0.556383 -0.587575 -0.562867 0.60901 -0.558827 -0.634037 0.442636 -0.63409 -0.693483 0.19538 -0.693475 -0.693486 0.195354 -0.69348 -0.690872 0.707107 0.150654 -0.690906 0.707072 0.15066 -0.443611 0.890984 0.0967343 -0.443639 0.890969 0.0967392 -0.95811 0.156357 0.239954 -0.965025 0.156322 0.210454 -0.9645 0.159518 0.21046 -0.151759 0.987675 0.038295 -0.152935 0.987673 0.0333488 -0.15283 0.98769 0.03333 -0.151718 0.987682 0.0382862 -0.440168 0.891019 0.111077 -0.440185 0.89101 0.111082 -0.685665 0.707053 0.17303 -0.68557 0.707152 0.173001 -0.863751 0.454341 0.217964 -0.151568 0.987683 0.0388598 -0.151581 0.987681 0.0388629 -0.439733 0.891024 0.11274 -0.440015 0.890877 0.112807 -0.684999 0.707062 0.175613 -0.684811 0.707255 0.17557 -0.816257 0.538463 0.209243 -0.862746 0.454352 0.221889 -0.889204 0.396676 0.227957 -0.933364 0.267542 0.239277 -0.966303 0.111117 0.232189 -0.88627 0.401361 0.23116 -0.959063 0.139272 0.246579 -0.962966 0.116811 0.243007 -0.863819 0.4542 0.217987 -0.870463 0.454161 0.189822 -0.870537 0.454015 0.189832 -0.909161 0.39547 0.130499 -0.955673 0.294269 -0.00973161 -0.965399 0.260496 -0.0121265 -0.988337 0.145906 -0.0436017 -0.993835 0.107678 -0.0264082 -0.846123 0.189242 -0.498261 -0.846289 0.189897 -0.49773 -0.739173 0.547639 -0.392065 -0.746137 0.538732 -0.391213 -0.560698 0.80439 -0.196402 -0.559672 0.806276 -0.191539 -0.48084 0.869465 -0.113245 -0.180515 0.979217 -0.0924531 0.183224 0.965845 0.183229 0.183038 0.965921 0.183016 0.50013 0.706927 0.500124 0.499942 0.707221 0.499897 0.682882 0.259783 0.682777 0.683057 0.258533 0.683077 0.800939 0.223347 -0.55553 0.810364 0.175779 -0.558939 0.743682 0.424656 -0.516338 0.670279 0.579526 -0.463546 0.651847 0.608828 -0.452133 0.530909 0.763236 -0.368249 0.499629 0.793396 -0.347697 0.384984 0.883805 -0.26585 0.195845 0.970504 -0.140595 0.210969 0.965906 -0.150059 0.0263425 0.999498 -0.0175994 0.966234 0.21463 -0.142572 0.519633 0.83827 -0.165185 0.983264 0.177057 -0.042916 0.951283 0.308296 -0.00363577 0.971485 0.236241 0.0201845 0.544462 0.838771 -0.00488618 0.578811 0.815385 -0.0111692 0.152575 0.987009 -0.0503321 0.179325 0.979315 -0.0937285 0.212709 0.970208 -0.115985 0.411366 0.882846 -0.226629 0.858493 0.187122 -0.477468 0.854701 0.222233 -0.469148 0.568039 0.761595 -0.311937 0.481475 0.838144 -0.256313 0.52 0.838031 -0.165238 0.166232 0.984671 -0.0528227 0.191595 0.98112 -0.0263473 0.807841 0.589363 -0.00668873 0.834042 0.551571 -0.0119562 0.825882 0.551171 -0.118869 0.972144 0.188038 -0.139921 0.93604 0.187892 -0.297534 0.881753 0.399329 -0.251095 0.91615 0.188076 -0.353972 0.229411 0.973328 -0.00180097 0.18466 0.982784 0.00612037 0.182394 0.982875 -0.0262364 0.539213 0.83859 -0.0775628 0.539354 0.838495 -0.077608 0.826012 0.550979 -0.118855 0.795523 0.550629 -0.252887 0.79546 0.550737 -0.252848 0.732036 0.550468 -0.401383 0.718126 0.577304 -0.388607 0.668518 0.171706 -0.723603 0.490302 0.589852 -0.641622 0.0344513 0.922611 -0.384191 0.0938821 0.990217 -0.103231 -0.029166 0.971852 -0.233779 0.379858 0.778265 -0.50001 0.395082 0.708686 -0.584529 -0.0616472 0.711187 -0.700295 -0.086483 0.679696 -0.728378 0.548786 0.406772 -0.730322 0.552023 0.356875 -0.753599 0.298666 0.174663 -0.938239 -0.0978028 0.363315 -0.926519 -0.121881 0.327919 -0.936811 -0.533319 0.114983 -0.838063 0.182578 0.982866 0.0252848 0.950764 0.186897 0.24722 0.922794 0.223634 0.313751 0.882294 0.388107 0.266327 0.7997 0.551025 0.238438 0.776847 0.584337 0.234647 0.522691 0.838665 0.153086 0.475105 0.868184 0.143286 0.238675 0.968428 0.0719821 0.177219 0.98291 0.0498129 0.0188486 0.999797 0.0071238 0.227872 0.973295 0.0277668 0.573449 0.81498 0.0834488 0.53988 0.838387 0.0750827 0.826791 0.550716 0.114586 0.800497 0.588194 0.115037 0.97285 0.191688 0.129687 0.962739 0.235513 0.132919 -0.179134 0.967603 -0.177918 -0.183215 0.965837 -0.183279 -0.499516 0.707895 -0.499368 -0.501081 0.705229 -0.501568 -0.681966 0.265907 -0.681334 -0.682309 0.262504 -0.68231 0.858263 0.188607 0.477297 0.16426 0.981866 0.0946456 0.162081 0.983718 0.0776437 0.227006 0.968452 0.102805 0.449736 0.869631 0.203665 0.493838 0.838885 0.228902 0.760102 0.55154 0.343582 0.740029 0.581083 0.338672 0.896149 0.188428 0.401762 0.887997 0.223251 0.40202 0.792573 0.188395 0.579944 0.741887 0.433912 0.511199 0.687999 0.551671 0.471504 0.151453 0.982939 0.104368 0.357587 0.900783 0.246418 0.449421 0.838919 0.306977 0.501381 0.793254 0.345493 0.653264 0.608776 0.450153 0.789348 0.28478 0.543902 0.811554 0.188451 0.553052 0.839229 0.188577 0.510032 0.832754 0.281779 0.476572 0.723859 0.551744 0.414254 0.72384 0.551775 0.414247 0.47238 0.838913 0.270338 0.472297 0.838971 0.270302 0.158793 0.98312 0.0908796 0.152584 0.982673 0.10522 -0.812264 0.567484 -0.134871 -0.635744 0.614892 0.466624 -0.702435 0.701957 -0.117652 -0.721397 0.684189 -0.107105 -0.562297 0.715978 0.413761 -0.572497 0.683351 0.453077 -0.834629 0.134764 -0.534073 -0.926658 0.352555 -0.130418 -0.928645 0.34828 -0.12775 -0.945218 0.154055 0.287802 -0.73608 0.36428 0.570514 -0.716699 0.278806 0.639225 -0.392183 0.18213 0.901677 -0.195116 0.98078 0 -0.195116 0.98078 0 -0.510398 0.859938 0 -0.555584 0.83146 -0.00093702 -0.668977 0.743283 -2.05775e-07 -0.760069 0.649842 -2.34009e-07 -0.831442 0.55561 0.00113981 -0.989404 0.145189 0 -0.980766 0.195187 0.000903819 -0.942366 0.334583 0 -0.872678 0.488297 0 -0.381399 0.105669 -0.918351 -0.514278 0.769731 -0.378195 -0.747564 0.638997 -0.181192 -0.869702 0.486672 -0.0822681 -0.939271 0.333526 -0.0808143 -0.982266 0.1441 -0.119952 -0.191438 0.962166 -0.193876 -0.607219 0.753533 -0.25194 -0.541504 0.650172 -0.532964 -0.637527 0.205583 -0.742492 0.431396 0.846243 -0.312684 0.493264 0.811115 -0.314298 0.529056 0.786689 -0.318152 0.559554 0.764427 -0.320235 0.469594 0.838398 -0.276714 0.518205 0.761302 -0.389721 0.125784 0.983735 -0.128233 0.167862 0.977479 -0.127896 0.485337 0.842903 -0.232299 0.24542 0.897866 -0.365521 0.347382 0.876245 -0.333947 0.81014 0.168617 -0.561464 0.57357 0.749093 -0.331478 0.558743 0.765321 -0.319514 0.628339 0.688706 -0.361765 0.679288 0.617433 -0.396668 0.719929 0.536931 -0.439781 0.756669 0.480142 -0.443751 0.847192 0.226177 -0.480738 -0.628271 0.688347 0.362567 -0.82879 0.258328 0.496361 -0.737883 0.541872 0.402372 -0.72963 0.55181 0.403914 -0.662792 0.64587 0.378892 -0.172821 0.983943 0.0446084 -0.194293 0.977516 0.0819258 -0.262541 0.952428 0.154765 -0.459712 0.846834 0.267463 -0.492504 0.821382 0.287698 -0.57593 0.751056 0.322831 -0.53554 0.783965 0.313999 -0.556392 0.766751 0.32019 -0.521127 0.805844 0.281143 -0.500242 0.829443 0.248559 -0.487017 0.844398 0.223173 -0.421781 0.880249 0.217402 -0.33496 0.922786 0.190443 0.142383 -0.977572 -0.155177 0.131329 -0.984197 -0.118782 0.567879 -0.755 -0.327853 0.477044 -0.833857 -0.277692 0.500612 -0.816474 -0.287674 0.52897 -0.786766 -0.318104 0.492965 -0.811301 -0.314286 0.434384 -0.844675 -0.312786 0.350084 -0.875512 -0.333045 0.448004 -0.843137 -0.297344 0.315765 -0.931493 -0.180592 0.73163 -0.537052 -0.419873 0.734892 -0.501493 -0.456551 0.6869 -0.603767 -0.404518 0.558419 -0.765568 -0.31949 0.573237 -0.749402 -0.331354 0.627686 -0.689534 -0.361321 0.660769 -0.644978 -0.38391 0.850363 -0.188143 -0.491411 -0.520466 -0.807109 0.278729 -0.500786 -0.829862 0.246054 -0.286931 -0.943342 0.166661 -0.470805 -0.843564 0.258344 -0.453535 -0.883061 0.120452 -0.479131 -0.853671 0.204154 -0.495755 -0.81071 0.311411 -0.51933 -0.809358 0.274291 -0.644139 -0.722132 0.252212 -0.50628 -0.814962 0.281989 -0.174013 -0.983731 0.0446415 -0.181716 -0.981631 0.0581324 -0.227423 -0.966139 0.121874 -0.884148 -0.172947 0.434018 -0.560171 -0.762599 0.323498 -0.542332 -0.777167 0.319197 -0.641494 -0.672533 0.369032 -0.715249 -0.570322 0.403921 -0.743349 -0.536803 0.399092 -0.829115 -0.261608 0.494095 4.58048e-05 1 -4.39907e-05 4.13671e-06 1 -1.11585e-05 -6.0221e-07 1 -5.74052e-06 -1.98554e-06 1 -3.09579e-06 -2.8795e-05 1 -5.07018e-05 0 1 0 -5.00009e-05 1 -3.67352e-05 -1.51252e-05 1 2.43179e-05 0 1 0 -6.8362e-06 1 1.40527e-05 -3.48563e-05 1 0.000264851 -2.72658e-05 1 -4.10495e-05 -9.57369e-06 1 -5.94902e-06 -0.000141905 1 -0.000217585 -1.76761e-05 1 -2.71032e-05 6.90315e-06 1 -3.97976e-06 2.03396e-05 1 2.67921e-05 2.45337e-05 1 -1.51803e-05 0 1 0 0 1 0 0 1 0 0 1 0 -0.865992 0.00140905 0.500057 -0.866335 0 0.499463 -0.866291 -0.00050787 0.499539 -0.000154858 -1 -0.000164905 -0.000167391 -1 -0.000122981 0 -1 0 -9.06986e-05 -1 -5.23627e-05 -7.82819e-05 -1 -2.33781e-05 -9.37902e-05 -1 -0.000116714 1.06063e-05 -1 2.53549e-05 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -3.04182e-05 -1 1.24054e-05 3.80581e-06 -1 8.29152e-06 3.00331e-05 -1 -2.15269e-05 0 -1 0 -6.61658e-06 -1 2.26696e-05 6.00314e-06 -1 1.24956e-06 1.71262e-06 -1 -2.23109e-05 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.000475634 -1 -0.000729299 -0.865992 0 0.500057 -0.866374 -0.000447902 0.499396 -0.866291 0.000507988 0.499539 -0.838384 0.00445119 0.545062 0.110842 0.975073 0.192218 0.110954 0.975025 0.192393 0.310979 0.782614 0.539265 0.353085 0.682322 0.640131 0.304377 0.792967 0.527786 0.349354 0.728041 0.589837 0.310706 0.783 0.538863 0.369451 -0.695905 0.61581 0.310751 -0.783011 0.538821 0.310844 -0.782882 0.538954 0.33774 -0.722856 0.602837 0.304228 -0.793196 0.527528 0.110959 -0.975023 0.192402 0.845121 0 0.534575 0.7774 0 0.629007 0.7774 0 0.629007 0.845121 0 0.534575 0.939687 -1.38649e-06 -0.342034 0.939688 3.00821e-06 -0.342033 0.939688 2.42512e-06 -0.342033 0.939688 0 -0.342032 0.939688 0 -0.342032 0.939688 -2.42512e-06 -0.342033 0.790421 0 0.612565 0.790349 1.78606e-05 0.612657 0.877688 -1.61294e-05 0.479233 0.877427 6.85418e-05 0.479711 0.942609 -6.79024e-05 0.333899 0.942438 1.25656e-05 0.33438 0.983619 -2.63107e-05 0.180262 0.983589 0 0.180425 0.998822 0 0.0485172 0.998822 0 0.0485172 0.997922 0 -0.0644372 0.997975 0.000100221 -0.0636027 0.972127 -0.00014468 -0.234455 0.972277 0 -0.233831 0.799746 0 0.600338 0.801976 0.0037538 0.597345 0.81348 -0.00303119 0.581585 0.815543 -0.00464986 0.578678 0.821168 0 0.570687 1 1.32194e-05 -5.92225e-06 1 2.19576e-05 5.17331e-06 1 0 4.90568e-06 1 6.12527e-06 -1.81739e-06 -0.739099 0 -0.673597 -0.739085 2.42295e-05 -0.673612 -0.739113 0 -0.673582 -0.796583 0.000178516 -0.60453 -0.787689 -0.0102413 -0.615987 -0.7589 0 -0.651207 -0.750001 0.0102376 -0.661357 -1 0 9.76619e-05 -1 0.000120214 0.000349543 -1 -0.000136479 -3.54712e-06 -1 9.6233e-05 -0.000132456 -1 3.17645e-05 -5.04156e-05 -1 -0.000235146 0.000738064 0 1 0 0 1 0 0 1 0 0 1 0 0.82233 0 0.56901 0.815539 0.00558524 0.578675 0.81458 0.00450423 0.580033 0.79973 -0.00628677 0.600327 0.802164 0 0.597103 -1 0 -1.0377e-05 -1 2.35509e-05 1.48033e-05 -1 -5.64319e-06 -3.54712e-06 -1 2.1665e-05 -2.32174e-05 -1 7.08905e-06 -7.59702e-06 -0.74959 0 -0.661903 -0.758878 -0.0076507 -0.651188 -0.7964 0.0213919 -0.604391 -0.787919 0 -0.615779 -0.739099 -1.72422e-05 -0.673597 -0.739113 0 -0.673582 1 -8.04905e-06 -1.5001e-05 1 -1.75741e-05 -5.92225e-06 1 4.16893e-05 1.98762e-05 1 1.56604e-05 1.07158e-06 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.864469 0 0.502685 0.920093 0.00553577 0.391662 0.980888 -0.004798 0.194513 -0.871227 0 -0.49088 -0.930121 0.00750993 -0.367175 -0.981095 -0.0057084 -0.193443 -0.981148 0 -0.193257 -0.969445 -0.003847 -0.245278 -0.876663 0.00301935 -0.481096 0.980977 0 0.194125 0.970822 -0.00270269 0.239784 0.868142 0.00120802 0.496314 0.843292 0 0.537455 -0.0637503 0.00339626 0.99796 0.348758 -0.000320979 0.937213 0.323938 0.0012686 0.946078 0.556074 -0.000454205 0.831133 0.67117 -0.00328037 0.741296 0.721677 0 0.69223 -0.511081 0.00358706 0.859525 -0.372059 -5.2016e-06 0.928209 -0.124878 -1.12231e-05 0.992172 -0.985565 0.000929488 0.169292 -0.981462 0 0.191655 -0.843085 0 0.537781 -0.886688 0.00553315 0.462336 -0.757057 -8.84941e-05 0.653349 -0.576303 0.000263777 0.817236 -0.605585 0 -0.79578 -0.557924 -0.00482922 -0.829878 -0.207191 0.00583458 -0.978283 -0.270505 -0.00123816 -0.962718 0.149035 0.00557733 -0.988816 0.212859 2.56703e-05 -0.977083 0.54852 4.67547e-05 -0.836138 0.469006 0.00843297 -0.883155 0.649119 -0.000595264 -0.760686 0.85784 -2.98236e-05 -0.513917 0.799479 0.0103185 -0.600605 0.956409 -0.00608355 -0.291968 0.987194 0.00196585 -0.159515 -0.149319 -0.982273 -0.113334 -0.142264 -0.982274 -0.122063 -0.198078 -0.967054 -0.159909 -0.339237 -0.899953 -0.273868 -0.429363 -0.835457 -0.343013 -0.47419 -0.792837 -0.382824 -0.782476 -0.187359 -0.593824 -0.628065 -0.590282 -0.507052 -0.65221 -0.548261 -0.523481 -0.706641 -0.419773 -0.569604 -0.742088 -0.209319 -0.636781 -0.25856 -0.96492 0.0455717 -0.688626 -0.688705 -0.226894 -0.915849 -0.397312 -0.0579998 -0.985899 -0.146825 -0.0802872 -0.507643 -0.830883 -0.227888 -0.747435 -0.654281 -0.115141 -0.650368 -0.548181 -0.525851 -0.691662 -0.184774 -0.698185 -0.724344 -0.198814 -0.66015 -0.710269 -0.258524 -0.654739 -0.585282 -0.610528 -0.533573 -0.518483 -0.706747 -0.481334 -0.449933 -0.793368 -0.410033 -0.321749 -0.900272 -0.293236 -0.187911 -0.965853 -0.178375 -0.138488 -0.982289 -0.126214 -0.258829 -0.965923 -9.18775e-07 -0.258829 -0.965923 -9.18775e-07 -0.562854 -0.826556 -1.9965e-06 -0.707033 -0.707178 -0.001949 -0.757656 -0.652654 8.01254e-06 -0.895706 -0.444647 9.47276e-06 -0.917408 -0.397947 -0.000452074 -0.989087 -0.147328 0.00139463 -0.980418 -0.19693 -3.47766e-06 0.131968 -0.209025 0.968965 0.530327 -0.300762 0.792651 0.713045 -0.154212 0.683949 0.554124 -0.325725 0.766061 0.551092 -0.384182 0.740744 0.498304 -0.517016 0.69598 0.308131 -0.74963 0.585756 0.302569 -0.644094 0.702563 -0.251485 -0.938516 0.236521 -0.0205692 -0.953665 0.300166 0.169177 -0.875505 0.452626 0.241411 -0.789117 0.564815 -0.866825 -0.430417 0.251706 -0.734441 -0.632615 0.245754 -0.522629 -0.766845 0.37257 -0.966804 -0.194195 0.166069 -0.915605 -0.289196 0.279344 -0.906348 -0.253751 0.337853 -0.0943827 -0.273914 0.957112 -0.194046 -0.385399 0.902116 -0.193779 -0.443343 0.875155 -0.504037 -0.725499 0.468612 -0.522377 -0.767115 0.372367 0.343781 -0.168329 0.92384 0.195152 -0.980773 -1.15574e-06 0.195096 -0.980784 6.20657e-07 0.438707 -0.89863 -0.000101154 0.497075 -0.867707 0.000509104 0.562285 -0.826944 -0.000103719 0.637963 -0.770067 0.000342636 0.668396 -0.743805 5.01556e-06 0.760604 -0.649216 5.70748e-06 0.831629 -0.555329 -0.00145099 0.872359 -0.488866 -5.16626e-06 0.942377 -0.334552 -5.58099e-06 0.980765 -0.195187 -0.00116649 0.989403 -0.145194 -5.85953e-06 0.805518 -0.156381 0.571565 0.126437 -0.987674 0.0922701 0.12639 -0.987683 0.0922375 0.28479 -0.935788 0.207835 0.331335 -0.911878 0.24227 0.443448 -0.836431 0.322082 0.614171 -0.649529 0.448226 0.570853 -0.706822 0.417768 0.520903 -0.76434 0.380058 0.392083 -0.87428 0.286191 0.789903 -0.156409 0.59295 0.80145 0.124725 0.584912 0.719739 -0.453937 0.525278 0.740045 -0.403019 0.538432 0.679328 -0.541034 0.495778 0.938817 -0.333333 0.0866663 0.751417 -0.623468 0.216012 0.195321 -0.980739 -0.000569284 0.747286 -0.15604 0.645922 0.985206 -0.144546 0.0920584 0.865782 -0.485151 0.12268 0.690771 -0.453781 0.562955 0.733956 -0.599559 0.31912 0.784543 -0.587273 0.199003 0.732646 -0.625464 0.268375 -0.258551 0.964923 0.0455584 -0.708883 0.185494 -0.680497 -0.647478 0.548039 -0.529552 -0.507624 0.830895 -0.227886 -0.734704 0.667235 -0.122504 -0.691783 0.691868 -0.206773 -0.916825 0.39771 -0.0354801 -0.986956 0.146988 -0.0656665 -0.782477 0.187357 -0.593824 -0.142264 0.982274 -0.122063 -0.149319 0.982273 -0.113334 -0.198078 0.967054 -0.159909 -0.339215 0.899966 -0.27385 -0.42935 0.835469 -0.343002 -0.47418 0.792846 -0.382817 -0.627988 0.590417 -0.506989 -0.652206 0.548255 -0.523492 -0.706531 0.420022 -0.569558 -0.742142 0.208989 -0.636827 -0.25882 0.965926 -9.18061e-07 -0.25882 0.965926 -9.18061e-07 -0.562832 0.826572 -1.99642e-06 -0.707033 0.707178 -0.00194925 -0.989088 0.147327 -3.50841e-06 -0.980417 0.19693 0.0010424 -0.917412 0.39794 -0.000452013 -0.895713 0.444632 9.47284e-06 -0.757661 0.652648 8.01284e-06 -0.138488 0.982289 -0.126214 -0.187759 0.965912 -0.178214 -0.321731 0.900286 -0.293214 -0.449915 0.793377 -0.410036 -0.518236 0.707079 -0.481113 -0.713637 0.260218 -0.650392 -0.720684 0.194315 -0.665475 -0.583189 0.613696 -0.532229 0.819961 0.513016 -0.253926 0.551368 0.811036 -0.195482 0.656081 0.730421 -0.189851 0.810041 0.540793 -0.226662 -0.111811 0.959396 -0.258955 -0.294131 0.752392 -0.589401 -0.59538 0.18281 -0.78237 -0.242813 0.44075 -0.864165 0.459539 0.116806 -0.880443 0.148047 0.115104 -0.982259 -0.142633 0.266151 -0.95332 0.188582 0.948035 -0.256254 0.403094 0.825682 -0.39467 0.28945 0.911626 -0.291816 0.455608 0.644669 -0.613859 0.941456 0.187399 -0.280253 0.898772 0.413664 -0.145228 -0.098178 0.60245 -0.792096 0.293269 0.75654 -0.5845 0.784376 0.195108 0.588801 0.157648 0.980771 0.115046 0.157678 0.980763 0.11507 0.360274 0.895032 0.26291 0.449565 0.831463 0.326435 0.494302 0.790904 0.360744 0.642898 0.605429 0.469189 0.672465 0.555396 0.48921 0.725882 0.438693 0.529758 0.807383 -0.0305067 0.589238 0.799898 0.194987 0.567577 0.195096 0.980784 -1.15541e-06 0.195058 0.980792 -2.34795e-06 0.438707 0.89863 2.86809e-06 0.468583 0.883419 0.00032612 0.562264 0.826958 -0.000249862 0.668371 0.743828 0.000777019 0.631707 0.775207 4.7406e-06 0.760604 0.649216 5.70748e-06 0.831637 0.555317 -0.00145117 0.989404 0.145189 -5.85949e-06 0.980765 0.195187 -0.00116664 0.942366 0.334583 -5.58098e-06 0.872369 0.488848 -5.16638e-06 0.566246 0.694701 0.443572 0.732027 0.624938 0.271273 0.866103 0.485307 0.119764 0.939228 0.333511 0.081374 0.98577 0.144626 0.0856846 0.578031 0.786569 0.217234 0.756893 0.632309 0.165223 0.702746 0.55415 0.446168 0.724121 0.194293 0.66174 -0.850378 0 0.526172 -0.850393 0 0.526149 -0.850378 -5.3315e-05 0.526172 -0.850379 4.26223e-06 0.526171 -0.850379 0 0.52617 -0.850379 0 0.52617 -0.850374 -4.60553e-05 0.526179 -0.743188 0 0.669082 -0.698376 -0.0464879 0.714219 -0.603404 0 0.797435 -0.469579 0 0.882891 -0.383173 -0.0521894 0.922201 -0.232591 0.0351057 0.971941 -0.0133185 -0.0464874 0.99883 0.0503055 0 0.998734 0.177613 0 0.9841 0.177613 0 0.9841 0.965257 -3.82132e-06 -0.261303 0.965256 0 -0.261305 0 1 0 -0.005797 0.998564 0.0532529 -2.8438e-05 1 0.000261239 4.50044e-05 1 0.000249354 -0.0178828 0.999717 0.0157116 -0.0218714 0.999337 0.0291135 0.00503792 0.999982 0.00318606 0.00015204 1 9.61525e-05 0.000162665 1 4.87879e-05 0.965257 0 -0.261303 0.177613 0 0.9841 0.177613 0 0.9841 0.0503727 0 0.99873 -0.0133184 0.0465503 0.998827 -0.13944 0 0.990231 -0.29424 0 0.955732 -0.383172 0.0522412 0.922199 -0.524632 -0.0350531 0.850607 -0.698377 0.0464795 0.71422 -0.743185 0 0.669086 0.00461633 -0.999985 0.00291944 0.000339652 -1 -9.19624e-05 0.000181786 -1 0.000114964 -0.0302601 -0.998839 0.0374823 -4.66174e-05 -1 0.000449983 7.65649e-05 -1 0.00042425 -0.00504779 -0.998913 0.0463298 0.998354 0 -0.0573485 0.998471 -0.000858208 -0.0552646 0.936995 -0.000443826 0.349343 0.936647 -0.000821982 0.350275 0.717248 -0.000538854 0.696818 0.718241 0 0.695794 0.376132 0 0.926566 0.376132 0 0.926566 0.998354 0 -0.0573485 0.998354 0 -0.0573485 0.936497 0 0.350675 0.936995 0.000537615 0.349343 0.718641 0.000822711 0.695381 0.717248 0 0.696818 0.376132 0 0.926566 0.376132 0 0.926566 0.79226 0.000928509 0.610183 0.792207 0 0.610252 0.763163 0.0481825 0.644408 0.792183 -0.0114736 0.610175 0.920434 0 -0.390899 0.920492 1.48077e-05 -0.390763 0.920498 0 -0.390747 0 -1 0 0 -1 0 0 -1 0 -1.35615e-06 -1 -5.48553e-07 -2.14672e-07 -1 -7.67149e-07 1.76206e-07 -1 -3.61753e-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.324929 -0.632346 0.703249 -0.121919 -0.701182 -0.702481 -0.140952 -0.603928 -0.784477 -0.295969 -0.702391 0.64734 0.0247292 -0.379387 0.924908 0.0292755 -0.701071 0.712491 0.416695 -0.491441 0.764756 0.348947 -0.698072 0.625245 0.59174 -0.697252 0.404578 0.591977 -0.696946 0.404758 0.711508 -0.696729 0.0912408 0.711024 -0.697235 0.0911546 0.674703 -0.697217 -0.242207 0.674611 -0.697315 -0.242179 0.490644 -0.697356 -0.522459 0.606322 -0.482002 -0.632493 0.198907 -0.698821 -0.687085 0.272539 -0.357148 -0.893402 0.132785 -0.324093 -0.93666 0.927033 0 0.374979 0.927033 0 0.374979 0.994184 -0.00748835 -0.107431 0.991683 0 -0.128702 -0.169979 0.111654 -0.979102 -0.151508 0.346805 -0.92562 0.291708 -0.00385101 -0.9565 0.291429 0.256554 -0.921547 0.696298 -0.00265477 -0.717748 0.682992 0.160413 -0.712594 0.930644 -0.167181 -0.325503 0.939713 0.0560013 -0.337348 0.990371 -0.0551287 0.126986 0.9904 -0.0546438 0.126971 0.828853 0.0543984 0.556816 0.814703 -0.161126 0.557044 0.486563 0.157607 0.859311 0.487339 -0.00171252 0.873211 -0.40175 0.151815 0.903078 -0.386962 0.356789 0.850272 0.0511915 -0.00385696 0.998681 0.0396273 0.264056 0.963693 0.920497 -0.000923814 -0.390749 0.920458 0.000163587 -0.390843 0.901581 -0.0468268 -0.430069 0.920361 0.0112283 -0.390909 0.791982 0 0.610545 0.792235 -4.16333e-05 0.610215 0.792264 0 0.610179 0 1 0 0 1 0 0 1 0 -1.45172e-06 1 1.88407e-07 -4.01362e-07 1 6.88267e-07 7.92407e-08 1 3.94517e-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.106791 0.324269 0.939918 0.925125 0 0.379662 0.927032 0.00176465 0.374978 0.991683 0 -0.128702 0.991683 0 -0.128702 7.5433e-06 2.03505e-05 1 -1.62887e-05 0 1 0 0 -1 0 0 -1 0.000126003 5.42535e-05 -1 0.00123976 0 -0.999999 -7.4665e-06 -5.65407e-07 1 7.5433e-06 -1.34082e-05 1 0 0 -1 7.28089e-05 2.41162e-05 -1 0.00012325 0 -1 0.173142 0 -0.984897 0.0844161 -0.00360676 -0.996424 0.258815 0 -0.965927 0.402606 0 -0.915373 0.453473 0.000893348 -0.89127 0.613804 -0.00154805 -0.789457 0.643238 -0.000495024 -0.765666 0.807977 0.000508127 -0.589214 0.858058 -0.00211779 -0.513549 0.920351 0.000194329 -0.391094 0.986914 -0.000498444 -0.161246 0.992464 -0.00208311 -0.122521 0.971785 0.00231072 0.235857 0.959015 0 0.283356 0.998089 0 0.0617924 0.999973 -0.00531823 -0.00497872 0.855454 7.43641e-06 0.517878 0.855497 0 0.517808 0.156569 -0.984573 0.0781133 0.164989 -0.982926 0.0814579 0.170745 -0.982918 0.0686885 0.166398 -0.983758 0.0673172 0.181378 -0.981887 0.0547707 0.176116 -0.98291 0.0535829 0.180633 -0.982906 0.0355916 0.180604 -0.982912 0.0355882 0.183272 -0.982914 0.0170602 0.20833 -0.977903 0.0174456 0.168993 -0.985617 0.000261031 0.183982 -0.982929 -0.00129567 0.183454 -0.982923 -0.0144257 0.184231 -0.982775 -0.0145478 0.183003 -0.982919 -0.0194782 0.256969 -0.965646 -0.0386625 0.473161 -0.849756 0.232451 0.48759 -0.839024 0.241442 0.504833 -0.838987 0.203088 0.504888 -0.838947 0.203117 0.521036 -0.838908 0.157338 0.521096 -0.838866 0.157362 0.53411 -0.838839 0.10524 0.534113 -0.838837 0.105241 0.542039 -0.838838 0.0504564 0.541948 -0.838897 0.0504385 0.544224 -0.838939 0.000840622 0.543993 -0.839089 0.000816743 0.542246 -0.839137 -0.0426389 0.542386 -0.839047 -0.0426358 0.537574 -0.838959 -0.0846266 0.601636 -0.793651 -0.0902927 0.886357 -0.165559 0.432391 0.883768 -0.188072 0.428465 0.911194 -0.188021 0.366571 0.897602 -0.261754 0.354676 0.950728 -0.117074 0.287071 0.942039 -0.188396 0.277615 0.959769 -0.188511 0.208104 0.980469 -0.0366985 0.193218 0.969153 -0.188657 0.158593 0.977849 -0.188486 0.0910172 0.936215 -0.343471 0.0743578 0.996922 -0.0783817 0.00150276 0.981966 -0.188749 -0.010768 0.979008 -0.188716 -0.0770066 0.968429 -0.236098 -0.0800222 0.977822 -0.157445 -0.138112 0.953891 -0.261718 -0.146955 0.74936 -0.551767 0.366077 0.74939 -0.551712 0.366099 0.773848 -0.55158 0.311319 0.773839 -0.551595 0.311314 0.798531 -0.551541 0.241143 0.798374 -0.551801 0.241068 0.818307 -0.551703 0.161238 0.818446 -0.551481 0.161289 0.830568 -0.551526 0.0773002 0.83062 -0.551446 0.0773133 0.834146 -0.551543 0.00125237 0.834178 -0.551494 0.00125744 0.831583 -0.55154 -0.065369 0.831313 -0.551945 -0.0653893 0.824612 -0.551996 -0.123757 0.781812 -0.611149 -0.123557 0.984107 -0.166799 0.0609268 0.720488 -0.693045 0.0241965 0.72019 -0.591989 0.361768 0.721565 -0.588583 0.364574 0.84887 -0.314174 0.425104 0.827825 -0.252096 0.501152 -0.944202 0 0.329367 -0.916564 0.0042226 0.399866 0.563412 0 0.826176 0.539608 0.00213923 0.841914 0.136411 0.00147465 0.990651 -0.290393 0.00309829 0.956903 0.123588 0.000466682 0.992334 -0.736064 -0.00207455 0.676909 -0.664619 0.0041049 0.747171 -0.347158 -0.00108892 0.937806 -0.929879 0.108769 -0.351419 -0.175809 0.98293 -0.0542161 -0.509181 0.838951 -0.192084 -0.175779 0.982936 -0.0542044 -0.179612 0.982906 -0.0404274 -0.179584 0.982912 -0.0404191 -0.182394 0.982916 -0.0246871 -0.182383 0.982918 -0.024685 -0.183828 0.982918 -0.00892635 -0.166384 0.986037 -0.00689775 -0.200188 0.979735 0.00660056 -0.183828 0.982932 0.00727383 -0.182968 0.982927 0.0194133 -0.187785 0.982015 0.0195965 -0.170418 0.984692 0.0365942 -0.255291 0.965906 0.0430329 -0.892471 0.301634 -0.33543 -0.913929 0.222509 -0.339446 -0.950297 0.105035 -0.293092 -0.781685 0.610484 0.127585 -0.822243 0.551676 0.139892 -0.829418 0.551652 0.0880124 -0.829354 0.551751 0.0879969 -0.833588 0.551702 0.0274923 -0.833692 0.551545 0.0275095 -0.833141 0.551579 -0.0404586 -0.832916 0.551917 -0.0404773 -0.826375 0.551902 -0.111844 -0.826521 0.551683 -0.111844 -0.813737 0.551627 -0.183138 -0.813544 0.551917 -0.183121 -0.796817 0.551984 -0.245756 -0.796837 0.551954 -0.245759 -0.781007 0.552091 -0.291931 -0.765692 0.574823 -0.288607 -0.936986 0.188519 -0.294138 -0.954387 0.188616 -0.231449 -0.922346 0.325866 -0.207581 -0.963546 0.188168 -0.190189 -0.973289 0.188032 -0.131728 -0.992565 0.00303445 -0.121676 -0.949801 0.309437 -0.0461238 -0.981447 0.188431 -0.0354469 -0.981549 0.188451 0.0323722 -0.9833 0.17896 0.0330771 -0.974931 0.196994 0.103453 -0.976441 0.188967 0.104181 -0.966927 0.188965 0.171304 -0.952276 0.258683 0.162031 -0.598182 0.794872 0.101772 -0.53694 0.839045 0.087742 -0.541142 0.838969 0.0574168 -0.541135 0.838974 0.0574154 -0.543901 0.838958 0.0179472 -0.543742 0.839061 0.0179281 -0.543457 0.839022 -0.0264104 -0.543701 0.838864 -0.026401 -0.539402 0.838879 -0.0729915 -0.539209 0.839003 -0.0729825 -0.530854 0.838997 -0.11949 -0.530903 0.838965 -0.119497 -0.519977 0.83899 -0.16037 -0.52019 0.83885 -0.160416 -0.509242 0.838907 -0.192113 -0.171891 0.982936 -0.0655068 -0.175906 0.982145 -0.0666901 0.0181582 0.940824 0.338407 0.379296 0.697992 0.607406 -0.190159 0.928084 0.320157 -0.481027 0.739375 0.471103 -0.416518 0.814402 0.404058 -0.714499 0.595498 0.367251 -0.859334 0.24906 0.44667 0.522072 0.252874 0.814552 0.332618 0.384263 0.861224 0.130392 0.293785 0.946936 -0.277101 0.299094 0.913103 -0.33232 0.32836 0.884162 -0.652707 0.188525 0.733779 -0.869474 0.316432 0.379322 0.173142 0 -0.984897 0.237379 -0.00264716 -0.971414 0.416249 0.000245443 -0.909251 0.597012 -0.00122317 -0.802231 0.631213 7.24408e-05 -0.77561 0.766388 -1.66353e-05 -0.642378 0.772402 -0.000179559 -0.635134 0.892759 0.000290663 -0.450534 0.894571 0.000149226 -0.446927 0.974132 -0.000102077 -0.22598 0.999705 -0.0044301 -0.0238656 0.97599 0.0062376 -0.217726 0.99998 -0.000394938 0.00626952 0.971231 -0.000127164 0.238141 0.953176 0.00201329 0.302408 0.855454 2.60385e-05 0.517878 0.818605 0.00546461 0.574331 0.998089 -0.000167527 0.0617924 0.997974 0 0.0636256 0.255504 0.966259 -0.0325884 0.181868 0.982944 -0.0272989 0.183356 0.982941 -0.014418 0.183212 0.982968 -0.0144178 0.184236 0.982882 0.000284575 0.183958 0.982934 0.000262605 0.18319 0.98293 0.0170525 0.158576 0.987263 0.012829 0.216175 0.975543 0.0398054 0.18062 0.982909 0.0355891 0.176198 0.982916 0.0532042 0.176168 0.982922 0.0531976 0.170719 0.982923 0.0686778 0.170162 0.983039 0.0684026 0.164492 0.982796 0.0839901 0.524478 0.809697 0.263276 0.345964 0.922712 0.170033 0.176962 0.980175 0.0891135 0.788347 0.471029 0.395779 0.888005 0.148461 0.43521 0.956085 0.258687 -0.137775 0.978626 0.139861 -0.150765 0.967466 0.241286 -0.0760988 0.749606 0.551725 0.365637 0.773845 0.551586 0.311316 0.773835 0.551601 0.311314 0.798536 0.551546 0.241117 0.798364 0.551806 0.241092 0.818299 0.551709 0.161259 0.818447 0.551487 0.161266 0.830563 0.551532 0.077308 0.830617 0.551452 0.0773047 0.834142 0.551548 0.00125738 0.834174 0.551499 0.00125242 0.831577 0.551545 -0.06541 0.831313 0.55195 -0.0653477 0.824053 0.551936 -0.127687 0.783202 0.610556 -0.117542 0.978702 0.188684 -0.0808712 0.981967 0.188744 -0.0107681 0.996922 0.0783796 0.00150276 0.981569 0.188483 0.031569 0.977878 0.188337 0.0910199 0.911604 0.398148 0.102257 0.980469 0.0366975 0.193218 0.95977 0.188506 0.208104 0.94018 0.188333 0.283886 0.953917 0.104957 0.281116 0.892788 0.2719 0.359167 0.91345 0.187969 0.360938 0.883769 0.188067 0.428465 0.690432 0.639021 0.339051 0.488228 0.839043 0.240086 0.504839 0.838981 0.203097 0.504899 0.838941 0.203114 0.521043 0.838902 0.157346 0.521106 0.838861 0.157359 0.534119 0.838833 0.105242 0.534121 0.838832 0.105242 0.542048 0.838832 0.0504479 0.541956 0.838892 0.0504487 0.544234 0.838933 0.000817104 0.544002 0.839083 0.000840277 0.542255 0.839132 -0.0426255 0.542393 0.839042 -0.0426505 0.538068 0.839024 -0.0807525 0.590698 0.801369 -0.0942564 0.798257 0.589004 0.125941 0.798522 0.588674 0.125798 0.934215 0.324843 0.147374 0.965882 0.251986 0.0597984 0.843922 0.163644 0.510897 0.917358 0 -0.398062 -0.519692 0 -0.854354 -0.5633 -0.0043317 -0.826241 -0.131231 0.00411105 -0.991343 0.937563 0.00339496 -0.3478 0.773365 0.000301669 -0.633961 0.724018 -0.0030719 -0.689775 0.60347 0.00291042 -0.79738 0.437667 0.000583852 -0.899137 0.348438 -0.00271011 -0.937328 0.216484 0.00251608 -0.976283 0.10651 -8.61264e-05 -0.994312 -0.182978 -9.02993e-05 -0.983117 0.0424712 0.950022 -0.309281 0.944735 0.188223 -0.268417 0.488381 0.784335 -0.382495 0.326727 0.886234 -0.328388 0.115974 0.95131 -0.285585 -0.191327 0.753805 -0.628627 -0.112252 0.864326 -0.490245 -0.341665 0.413976 -0.843735 -0.297519 0.575311 -0.761905 -0.180038 0.178546 -0.96732 -0.344251 0.366822 -0.864253 -0.552809 0.19214 -0.810854 0.50646 0.249889 -0.82526 0.512297 0.524436 -0.680088 0.585539 0.626025 -0.515012 0.760687 0.543612 -0.35474 0.562771 0.361032 -0.743603 0.425491 0.234235 -0.874123 0.215067 0.114239 -0.969895 -0.194077 0.701908 -0.685317 -0.0706846 0 -0.997499 -0.23772 0.00288299 -0.971329 -0.223917 0.0034605 -0.974602 -0.510695 -0.00302315 -0.859757 -0.608544 0.00108055 -0.793519 -0.829937 -0.00294889 -0.557849 -0.86863 0 -0.495461 0.237231 8.08273e-05 0.971453 0.793327 -0.000995533 0.608795 0.660419 0.00352395 0.750889 0.608875 0.000840159 0.793266 0.258688 -0.00132684 0.96596 0.965878 0 0.258996 0.996236 -0.0121476 0.085832 0.965522 -0.00395629 0.260292 0.885911 0.000997689 0.463855 0.324254 -0.913743 0.244813 0.899712 -0.24123 0.363767 0.250442 -0.250467 0.935171 0.36718 -0.367216 0.854594 0.583955 -0.283163 0.760799 0.764544 -0.266921 0.586707 0.905448 -0.34816 0.242792 0.207773 -0.691672 0.69168 0.698814 -0.698714 0.15316 0.2441 -0.910992 0.332429 -0.985115 0 -0.171899 -0.970297 0.00486066 -0.241867 -0.989817 -0.00297147 0.142313 -0.973855 0.000642945 0.227171 -0.838545 -0.00326757 0.544823 -0.799608 0.000119366 0.600522 -0.529787 -0.000178507 0.848131 -0.607374 -0.00594028 0.794394 -0.285729 0.0039405 0.958302 -0.167922 -0.00101139 0.9858 7.28681e-06 -0.258688 0.965961 -5.08716e-06 -0.258836 0.965921 -5.50957e-05 -0.652321 0.757943 0.00431447 -0.707125 0.707076 4.5411e-06 -0.829165 0.559004 2.10234e-06 -0.965932 0.258796 2.10234e-06 -0.965932 0.258796 -0.81282 0 -0.582515 0.784676 -0.00145907 -0.619905 0.98306 0 -0.183283 0.97535 -0.00285984 -0.220644 0.786624 -0.00119644 -0.617431 0.0112017 0.00237658 -0.999934 -0.0665824 -0.00533401 -0.997767 0.441543 0.000331089 -0.89724 0.407319 -0.00313461 -0.91328 -0.770342 -0.0042915 -0.637616 -0.420291 0.00451814 -0.907378 -0.526704 -0.00763043 -0.850014 0.257454 -0.960925 -0.101688 -0.213011 -0.965177 -0.151853 0.943681 -0.25277 -0.213479 0.896216 -0.325286 -0.301639 0.770747 -0.187586 -0.608901 0.418989 -0.315515 -0.85141 0.296822 -0.423182 -0.856046 0.0109685 -0.202987 -0.97912 -0.414251 -0.168974 -0.89434 -0.701498 -0.413238 -0.580633 -0.649477 -0.242496 -0.720677 0.689578 -0.689685 -0.220948 0.496344 -0.796511 -0.345272 0.276658 -0.55658 -0.783377 -0.45627 -0.764867 -0.454747 -0.419227 -0.657003 -0.626574 -0.11414 -0.992051 -0.0529734 -0.114106 -0.992056 -0.052959 -0.108404 -0.992006 -0.0646039 -0.231647 -0.96592 -0.115488 -0.35711 -0.919241 -0.165737 -0.377549 -0.909027 -0.176425 -0.373607 -0.909041 -0.184561 -0.63175 -0.707062 -0.317734 -0.602393 -0.747642 -0.279561 -0.591649 -0.747647 -0.301621 -0.764135 -0.522197 -0.378692 -0.862747 -0.258843 -0.43436 -0.879561 -0.184639 -0.438498 -0.891424 -0.185202 -0.413598 -0.89109 -0.186932 -0.413539 -0.824242 -0.4175 -0.382516 -0.772798 -0.522167 -0.360728 -0.743593 -0.57269 -0.345102 -0.60221 -0.747818 -0.279486 -0.982422 -0.122046 0.14125 -0.834345 -0.100008 0.542094 -0.976457 -0.157529 0.147369 -0.804 -0.594629 -0.000717158 -0.152555 -0.707945 0.689595 -0.36469 -0.91488 0.173196 -0.22527 -0.950535 0.213863 -0.166499 -0.952449 0.255184 -0.165041 -0.184454 0.968885 -0.515011 -0.234529 0.824475 -0.869503 -0.443833 -0.216742 -0.977701 -0.198288 -0.0691618 -0.794533 -0.606252 -0.0343046 -0.604994 -0.761811 0.231573 -0.115186 -0.829411 0.546635 -0.56494 -0.484701 0.667763 -0.596873 -0.343311 0.725176 0.287758 0.925076 0.24785 0.247345 0.923101 0.294458 0.223456 0.739964 0.634445 0.702077 0.701966 0.119713 0.191573 0.190868 0.96274 0.529611 0.31109 0.789136 0.527728 0.312207 0.789955 0.798512 0.278781 0.533535 0.875474 0.353515 0.329504 0.948495 0.254346 0.188855 -0.167922 0 0.9858 -0.237301 -0.0033185 0.971431 -0.529785 0.00298926 0.848127 -0.586314 0.000124014 0.810084 -0.762863 -7.1753e-05 0.646561 -0.884914 0.00552582 0.465721 -0.839156 -3.02315e-06 0.543891 -0.989927 2.39058e-05 0.141581 -0.924664 0 -0.380783 -0.970308 0.000998562 -0.24187 -0.992524 -0.00407031 -0.121984 -0.97114 0.00606226 0.238432 2.10234e-06 0.965932 0.258796 -0.000133892 0.965494 0.260425 0.00459888 0.707441 0.706757 6.85451e-05 0.660898 0.750475 1.16887e-05 0.25906 0.965861 7.2859e-06 0.259006 0.965876 -0.925979 0.359867 -0.114271 -0.747768 0.663896 -0.00925519 -0.647372 0.759917 0.0586155 -0.774608 0.632194 0.0177193 -0.135662 0.954943 0.263969 -0.164349 0.205191 0.964824 -0.329373 0.850255 0.410585 -0.30787 0.717269 0.625094 -0.513281 0.297519 0.805 -0.504524 0.305117 0.807688 -0.6687 0.260091 0.696558 -0.886134 0.4074 -0.220888 -0.987766 0.128347 -0.0885761 -0.730142 0.683131 0.0149977 -0.855881 0.511312 -0.0776396 -0.631554 0.707063 -0.318122 -0.898489 0.137592 -0.416876 -0.89876 0.135121 -0.417101 -0.841495 0.37333 -0.390525 -0.86445 0.258836 -0.430964 -0.882964 0.13332 -0.450112 -0.807002 0.434084 -0.4004 -0.816335 0.434059 -0.381038 -0.768319 0.531547 -0.356572 -0.674458 0.668678 -0.313012 -0.662779 0.668694 -0.337004 -0.473112 0.849464 -0.233616 -0.229988 0.96592 -0.118765 -0.133653 0.988939 -0.0643163 -0.170198 0.982235 -0.0790393 -0.396809 0.899312 -0.183795 -0.477757 0.849445 -0.224034 -0.544166 0.800067 -0.252541 -0.674386 0.668768 -0.312975 -0.515118 0.689499 -0.509161 -0.287346 0.795171 -0.53398 0.904948 0.242364 -0.349756 0.612456 0.764889 -0.199606 0.656991 0.657135 -0.369508 0.258597 0.965189 -0.0392047 -0.745317 0.252851 -0.616902 -0.666936 0.322298 -0.671804 -0.422364 0.186245 -0.887086 -0.000360161 0.300961 -0.953636 0.432331 0.203203 -0.878521 0.122681 0.422685 -0.897934 0.106849 0.556458 -0.823977 -0.183767 0.96091 -0.207079 0.773377 0.169091 -0.610979 0.888048 0.413537 -0.200894 0.536857 0.830358 -0.149298 0.251008 0.965894 -0.0635927 0.0488115 0.998624 -0.0191535 0.642275 0.747025 -0.171569 0.824207 0.518531 -0.227616 0.93033 0.271392 -0.246644 0.950567 0.173795 -0.257327 0.174642 0.182125 0.967642 0.175257 0.200172 0.963959 0.142238 0.593541 0.792135 0.141684 0.60223 0.78565 0.108248 0.793264 0.599178 0.107831 0.794656 0.597406 0.0459803 0.965916 0.254741 0.0459696 0.965926 0.254702 -0.830231 0.217299 0.51332 -0.846696 0.0918508 0.524088 -0.849627 0.0419954 0.525709 -0.785409 0.38212 0.486946 -0.758696 0.451567 0.46954 -0.652354 0.641555 0.403537 -0.204544 0.970643 0.126549 -0.503602 0.805777 0.311623 -0.302958 0.934396 0.187406 -0.106402 0.99196 0.0685081 -0.229153 0.174773 0.957572 -0.229218 0.174353 0.957633 -0.693209 0.380304 0.612234 -0.462233 0.176181 0.86908 -0.466925 0.456642 0.757271 -0.593947 0.176355 0.784937 -0.727399 0.175428 0.663412 -0.740085 0.0912862 0.666289 -0.571657 0.639032 0.514633 -0.428095 0.802309 0.415976 -0.189016 0.970615 0.148929 -0.0837492 0.984922 0.151376 -0.046161 0.98488 0.166977 0.0407071 0.589896 0.806453 0.0307616 0.792249 0.609422 0.0495278 0.175163 0.983293 0.0504337 0.181701 0.98206 0.0330525 0.539582 0.841284 -0.196361 0.537252 0.820245 -0.196311 0.537414 0.820151 -0.442639 0.53739 0.717831 -0.442563 0.53755 0.717759 -0.619115 0.539879 0.570287 0.0264871 0.96574 0.258155 0.0097616 0.869377 0.494053 -0.119747 0.851316 0.510805 -0.125453 0.8424 0.524046 -0.284652 0.842253 0.457804 -0.277921 0.848307 0.450706 -0.378736 0.860412 0.340956 0.261431 0.952099 0.158625 0.614018 0.786714 0.0637494 0.602337 0.795608 0.0647942 0.853926 0.520131 -0.0165719 0.85779 0.513636 -0.0193353 0.976646 0.185055 -0.109162 0.979806 0.161515 -0.117872 0.9824 0.186088 0.0161679 0.98686 0.160974 0.0139958 0.853222 0.515183 0.0812326 0.861706 0.501029 0.0802055 0.603043 0.785765 0.137522 0.608792 0.781348 0.137363 0.329721 0.928629 0.170095 0.251002 0.953759 0.165354 0.195481 0.978295 0.0687441 0.974545 0.0601407 -0.215976 0.98201 0.178098 0.0627524 0.974342 -0.222162 -0.0360755 0.985101 0.171974 0.000655672 0.993965 -0.0388297 -0.102596 0.991259 0.120814 -0.0529975 0.983688 0.177233 -0.0307562 0.916332 0.35839 -0.178587 0.985254 0.00869708 -0.170877 0.985223 -0.0161835 -0.17051 0.968364 0.212425 -0.130945 0.988411 0.121844 -0.0905437 0.963353 0.192993 -0.186294 0.959837 0.190513 -0.205957 0.927318 0.290646 -0.235812 0.967138 0.108503 -0.229939 0.948016 0.192583 -0.253334 0.940271 0.219423 -0.260275 0.949219 0.176579 -0.26039 0.949889 0.17374 -0.259858 0.933502 0.251533 -0.25555 0.962298 0.118075 -0.245034 0.961094 0.129106 -0.244193 0.94695 0.229736 -0.224739 0.889111 0.422221 -0.176667 0.866098 0.467976 -0.175708 0.973374 0.189374 -0.129156 0.988508 0.146662 0.0366349 0.974231 0.223945 -0.0268949 0.821779 0.564392 -0.0783631 0.887956 0.452897 -0.0801118 0.976658 0.193025 -0.0942358 0.933791 0.283122 0.218806 0.976483 0.0784531 0.200813 0.943575 0.291616 0.156926 0.989729 0.0469278 0.135034 0.950025 0.298118 0.0926187 0.967886 0.236254 0.0859079 0.995522 0.0838017 0.0437454 0.920852 0.177956 0.346934 0.917328 0.22285 0.329919 0.808775 0.516388 0.281471 0.943283 0.171047 0.284534 0.952509 0.187004 0.240327 0.914388 0.176707 0.364237 0.829505 0.414057 0.374804 0.917277 0.0157997 0.397937 0.850356 0.299248 0.432834 0.899216 -0.0143496 0.437269 0.853766 0.245675 0.45905 0.854005 0.244369 0.459302 0.181814 0.96308 0.198544 0.206938 0.955235 0.211431 0.321858 0.91264 0.251983 0.316454 0.915248 0.249354 0.408242 0.879969 0.242886 0.345571 0.911023 0.224983 0.171472 0.96959 0.17462 0.202903 0.974952 0.0910968 0.320752 0.935621 0.147415 0.38589 0.906961 0.168851 0.24537 0.958389 0.145891 0.166007 0.976303 0.138828 0.229185 0.972891 -0.0309493 0.0932365 0.995486 -0.0177596 0.211643 0.977338 0.00419801 0.175454 0.984342 0.0169584 0.220272 0.9746 0.0404501 0.174905 0.983889 0.0370224 0.214406 0.973917 0.0742713 0.261735 0.953461 -0.149687 0.158213 0.978319 -0.133646 0.113461 0.98225 -0.149368 0.0900905 0.985539 -0.143516 0.16575 0.978497 -0.122761 0.051101 0.992616 -0.110007 -0.00283879 0.994957 -0.100263 0.166356 0.974053 -0.153448 0.105999 0.983221 -0.148462 0.088927 0.993022 -0.0774498 0.0757187 0.994422 -0.0734274 0.216685 0.97289 -0.0808198 0.055895 0.998055 -0.0275959 0.175535 0.983302 -0.0480097 0.190184 0.981104 -0.0355736 0.089281 0.996006 -0.00128973 0.193747 0.980887 -0.0179462 0.208166 0.978049 0.00932968 0.0726284 0.996524 0.0408082 0.199375 0.979055 0.0412372 0.27913 0.949548 0.142988 0.178799 0.976277 0.12212 -0.0360858 0.991109 0.128066 0.228652 0.970892 0.0713277 0.225297 0.973161 0.0468878 0.28248 0.941498 0.183809 0.149701 0.972403 0.178945 0.238562 0.957092 0.164507 0.694929 0.586377 0.416216 0.751255 0.499151 0.431816 0.760536 0.50128 0.412678 0.757741 0.505971 0.412095 0.779572 0.510842 0.362364 0.77321 0.521263 0.361153 0.802705 0.526739 0.279662 0.796559 0.536492 0.278695 0.818073 0.539771 0.198503 0.814777 0.544791 0.198345 0.826511 0.54567 0.13829 0.823346 0.550448 0.138233 0.831738 0.550016 0.0754649 0.828121 0.555441 0.0755029 0.83271 0.553569 0.0124542 0.82865 0.559626 0.0125954 0.828861 0.55394 -0.0783539 0.821201 0.565226 -0.078406 0.812373 0.55503 -0.17886 0.807559 0.562068 -0.178683 0.796621 0.554203 -0.241358 0.79455 0.557257 -0.241152 0.791002 0.555501 -0.256389 0.792904 0.552628 -0.256719 0.797263 0.553918 -0.239888 0.799224 0.550868 -0.240388 0.806763 0.551772 -0.211376 0.808682 0.54873 -0.211965 0.818271 0.548532 -0.171885 0.819935 0.54587 -0.172431 0.831492 0.543772 -0.113721 0.834021 0.539708 -0.114562 0.847185 0.531069 -0.0156158 0.850755 0.525288 -0.0169585 0.856853 0.506249 0.0975432 0.852945 0.512535 0.0989571 0.123806 0.986417 -0.107952 0.336676 0.936939 -0.0937825 0.44162 0.89268 -0.0899638 0.116833 0.991267 -0.061152 0.193363 0.980424 -0.0371558 0.451492 0.831412 0.323895 0.526641 0.774024 0.351476 0.534061 0.775707 0.336241 0.52439 0.783628 0.333079 0.543519 0.787848 0.289626 0.52401 0.802967 0.284003 0.549426 0.807548 0.214471 0.529991 0.821568 0.210084 0.547498 0.824359 0.143802 0.537893 0.830848 0.142699 0.547619 0.831536 0.0930645 0.538245 0.837705 0.0924293 0.545266 0.83729 0.0403792 0.536254 0.843099 0.0401927 0.540119 0.841494 -0.0126036 0.531628 0.846887 -0.0124015 0.532263 0.841813 -0.0897069 0.516889 0.8514 -0.0891235 0.509487 0.843285 -0.171152 0.501952 0.847963 -0.170301 0.494254 0.842768 -0.213203 0.494113 0.842857 -0.213177 0.494765 0.843169 -0.210413 0.500675 0.839322 -0.211808 0.509192 0.841788 -0.179209 0.515379 0.837646 -0.180923 0.525075 0.838813 -0.143835 0.530254 0.835287 -0.145352 0.540083 0.835107 -0.104437 0.544655 0.831968 -0.105735 0.555526 0.829955 -0.0506502 0.564156 0.823974 -0.0528636 0.577733 0.814864 0.0471319 0.59484 0.802686 0.043136 0.600665 0.785762 0.147578 0.602628 0.784322 0.147235 0.184766 0.960129 0.209794 0.214023 0.950368 0.225822 0.212803 0.950235 0.227526 0.17949 0.962607 0.202909 0.22761 0.945454 0.233047 0.490494 0.784467 0.37951 0.43557 0.827872 0.353422 0.706411 0.507981 0.492888 0.662 0.579043 0.475884 0.826471 0.175407 0.534956 0.811479 0.235475 0.534839 0.759798 0.177371 0.625497 0.761082 0.168321 0.626437 0.64946 0.517783 0.556868 0.65645 0.502605 0.56255 0.444631 0.797383 0.408024 0.460547 0.781243 0.421375 0.223812 0.945028 0.23839 0.206124 0.976858 0.0571092 0.18322 0.981872 0.0485633 0.603645 0.787083 0.126935 0.541912 0.835238 0.0933184 0.818691 0.546389 0.176645 0.948648 0.270705 0.163666 0.965605 0.187077 0.180581 0.906468 0.259662 0.333003 0.905328 0.266188 0.330947 0.572184 0.786388 0.232807 0.582605 0.776318 0.240629 0.192908 0.9754 0.106688 0.147722 0.979009 0.140427 0.196461 0.969354 0.147497 0.210353 0.970675 0.116365 0.466232 0.797409 0.383102 0.655347 0.517862 0.549855 0.639525 0.562632 0.523882 0.773557 0.177861 0.608256 0.773805 0.173904 0.609084 0.843056 0.252807 0.474705 0.849156 0.179974 0.496531 0.709342 0.586778 0.390547 0.528743 0.773616 0.349211 0.299254 0.934585 0.192348 0.24585 0.935365 0.254263 0.194183 0.960481 0.199421 0.981108 0.187497 0.0476568 0.183267 0.982075 -0.0440751 0.191236 0.980511 -0.0450171 0.535987 0.834175 -0.129886 0.542494 0.829869 -0.130453 0.814352 0.546335 -0.195827 0.809723 0.553171 -0.195831 0.955506 0.186201 -0.228773 0.95385 0.193766 -0.2294 0.188399 0.982091 -0.00202409 0.188464 0.982078 -0.002017 0.551358 0.834248 -0.00590081 0.55138 0.834233 -0.00589758 0.837546 0.546293 -0.00895841 0.83747 0.546409 -0.00897612 0.999239 -0.0374968 -0.01071 0.980367 0.187021 -0.0624805 0.525802 0.83281 -0.17309 0.780384 0.555458 -0.28717 0.590556 0.778431 -0.21281 0.520346 0.831525 -0.194439 0.275874 0.956542 -0.0944462 0.23897 0.966741 -0.091135 0.183377 0.980774 -0.0667511 0.521993 0.831516 -0.190011 0.521968 0.831534 -0.190004 0.781314 0.555571 -0.28441 0.781386 0.55546 -0.284427 0.921648 0.194978 -0.335483 0.921696 0.194746 -0.335485 -0.722305 0.175759 0.668868 -0.058535 0.946116 0.318494 -0.694818 0.175633 0.69741 -0.673534 0.260194 0.691846 -0.545237 0.521988 0.655931 -0.479092 0.629389 0.611833 -0.30541 0.799523 0.517192 -0.103979 0.992839 0.0588122 -0.471426 0.87344 -0.121902 -0.759476 0.58538 -0.283773 -0.898793 0.204333 -0.387838 -0.794333 0.203787 -0.572281 -0.813504 0.201368 -0.545584 -0.812817 0.207652 -0.544251 -0.843373 0.202996 -0.497509 -0.835952 0.314724 -0.449592 -0.861806 0.20497 -0.463981 -0.899719 0.196742 -0.389614 -0.0957091 0.993392 0.0633428 -0.0903901 0.994485 0.0531895 -0.0858824 0.994717 0.0562369 -0.0769976 0.996143 0.0420879 -0.0838509 0.995793 0.0369606 -0.0777594 0.996558 0.0287503 -0.0971403 0.995254 0.00570069 -0.0938547 0.995554 0.00800198 -0.0900378 0.995934 0.00290823 -0.112081 0.993521 -0.0188401 -0.116182 0.992995 -0.0215038 -0.114672 0.993119 -0.0237546 -0.122996 0.99192 -0.031093 -0.788444 0.212022 -0.577411 -0.790075 0.201218 -0.579045 -0.794281 0.200811 -0.573404 -0.813719 0.0171949 -0.581005 -0.808117 0.197482 -0.55493 -0.830541 0.19568 -0.52145 -0.830606 0.195097 -0.521565 -0.129015 0.991061 -0.0339592 -0.128503 0.991098 -0.0348042 -0.143537 0.988636 -0.0446819 -0.143316 0.988649 -0.0450993 -0.915316 0.18881 -0.355735 -0.899759 0.189633 -0.39303 -0.887125 0.179748 -0.425088 -0.885035 0.190878 -0.424592 -0.856379 0.192659 -0.479059 -0.865534 0.135371 -0.482209 -0.844374 0.194164 -0.499333 -0.964838 0.186139 -0.185578 -0.950984 0.185126 -0.247704 -0.960457 0.00590212 -0.278366 -0.938307 0.187265 -0.290708 -0.915546 0.187303 -0.355939 -0.160293 0.985695 -0.052066 -0.160103 0.985703 -0.0524953 -0.176864 0.982391 -0.0602309 -0.176897 0.982391 -0.0601359 -0.193814 0.978809 -0.0660931 -0.193478 0.97878 -0.0675011 -0.209908 0.975108 -0.0714305 -0.209581 0.974815 -0.07623 -0.225095 0.971342 -0.0763346 -0.224897 0.970913 -0.0821511 -0.243204 0.966302 -0.0843318 -0.982768 0.184617 -0.00917292 -0.980686 0.179649 -0.0773376 -0.996574 0.000256956 -0.0827106 -0.975242 0.183933 -0.122765 -0.965782 0.180841 -0.185908 -0.989637 0.123029 0.0740403 -0.982944 0.181041 0.0323294 -0.984223 0.176709 -0.00892814 -0.982228 0.176412 0.0640826 -0.974725 0.183958 0.126769 -0.975807 0.177726 0.127339 -0.970687 0.181676 0.157358 -0.968618 0.161382 0.189039 -0.966289 0.178904 0.185144 -0.95351 0.185514 0.237494 -0.0147797 0.996744 -0.079263 -0.237028 0.967745 -0.0853613 -0.237148 0.967499 -0.0877877 -0.243488 0.965953 -0.0874566 -0.243072 0.966364 -0.0839995 -0.245378 0.965806 -0.0837185 -0.243261 0.967258 -0.0723631 -0.242454 0.967449 -0.0725098 -0.237501 0.969977 -0.0523164 -0.23443 0.970685 -0.0530355 -0.229451 0.972642 -0.0363277 -0.138302 0.989434 -0.0435112 -0.943852 0.0239074 0.329504 -0.945445 0.183729 0.26903 -0.954392 0.180201 0.23804 -0.0728891 0.997333 0.00384525 -0.0594639 0.998226 -0.0029833 -0.195976 0.980095 0.0317473 -0.202974 0.97908 0.0143073 -0.907246 -0.089852 0.410891 -0.909489 0.187175 0.371209 -0.930258 0.184076 0.31739 -0.172393 0.982208 0.0744795 -0.163788 0.982225 0.091691 -0.0161053 0.999556 0.0250695 -0.150853 0.981987 0.113777 -0.13764 0.981105 0.135971 -0.138159 0.980994 0.136245 -0.121524 0.979284 0.16197 -0.0249545 0.99321 0.113626 -0.107703 0.976456 0.186906 -0.464587 0.877683 -0.117607 -0.44163 0.882526 -0.161591 -0.440428 0.883294 -0.160674 -0.414147 0.887426 -0.20238 -0.419399 0.88396 -0.206688 -0.401307 0.886277 -0.231226 -0.413458 0.877819 -0.24184 -0.4141 0.877753 -0.240978 -0.431051 0.865578 -0.254893 -0.441308 0.864778 -0.239595 -0.449838 0.85846 -0.24636 -0.460606 0.857667 -0.228583 -0.469596 0.851055 -0.234917 -0.481952 0.850296 -0.21147 -0.491214 0.843563 -0.217048 -0.503819 0.843043 -0.188269 -0.513704 0.835957 -0.193093 -0.525084 0.835914 -0.159799 -0.535672 0.828409 -0.163686 -0.544191 0.829144 -0.127966 -0.55491 0.821601 -0.130564 -0.559636 0.823222 -0.095469 -0.570343 0.815692 -0.0967242 -0.571416 0.817824 -0.0681722 -0.580275 0.811559 -0.0682227 -0.579001 0.814268 -0.041545 -0.584727 0.810191 -0.041047 -0.581288 0.813597 -0.0128051 -0.584608 0.811223 -0.012263 -0.578712 0.8153 0.0194777 -0.579605 0.81466 0.0196786 -0.570551 0.819307 0.0566332 -0.570377 0.819432 0.0565854 -0.550002 0.826081 0.122833 -0.546418 0.82865 0.121517 -0.512736 0.833533 0.205729 -0.511147 0.834674 0.205055 -0.476812 0.83516 0.274149 -0.47582 0.835883 0.273669 -0.447715 0.83446 0.321291 -0.447995 0.834258 0.321426 -0.419843 0.831092 0.364717 -0.420492 0.830621 0.365041 -0.75951 0.585321 -0.283801 -0.722754 0.593167 -0.354654 -0.723648 0.591563 -0.355508 -0.68428 0.597771 -0.41765 -0.687275 0.592273 -0.420554 -0.664 0.595292 -0.452473 -0.668381 0.586952 -0.456896 -0.675885 0.586175 -0.446741 -0.68134 0.575876 -0.451822 -0.702235 0.57428 -0.420795 -0.704757 0.569461 -0.423122 -0.724829 0.567995 -0.389879 -0.727576 0.562922 -0.392112 -0.750311 0.56148 -0.34896 -0.753312 0.556151 -0.351023 -0.776618 0.555136 -0.297806 -0.780141 0.549121 -0.299743 -0.801356 0.549078 -0.237365 -0.805544 0.542168 -0.239065 -0.821882 0.543551 -0.170478 -0.826606 0.535952 -0.171693 -0.836031 0.539184 -0.101646 -0.841396 0.530664 -0.102216 -0.843656 0.535298 -0.0412256 -0.848485 0.527623 -0.0410744 -0.845959 0.533099 0.0126103 -0.849891 0.526794 0.0131778 -0.843919 0.532775 0.0628566 -0.847055 0.527687 0.0635887 -0.838153 0.53388 0.111678 -0.839774 0.531224 0.112162 -0.827851 0.537421 0.160754 -0.828822 0.535823 0.161084 -0.805209 0.543772 0.236539 -0.805791 0.542802 0.236785 -0.768758 0.548138 0.329478 -0.768758 0.548139 0.329478 -0.729863 0.548622 0.407817 -0.729312 0.549535 0.407572 -0.697513 0.547846 0.461888 -0.696843 0.548917 0.461626 -0.668651 0.545889 0.504887 -0.668832 0.545605 0.504954 -0.792196 0.185721 0.58132 -0.805234 0.188149 0.562315 -0.806021 0.184867 0.562276 -0.829771 0.187416 0.525695 -0.829826 0.187162 0.525698 -0.847521 0.188279 0.496244 -0.875102 -0.0820232 0.476937 -0.867384 0.187717 0.460878 -0.891881 0.187378 0.411628 -0.776265 0.186475 0.602196 -0.780975 0.169213 0.601203 -0.631858 0.539486 0.556517 -0.632383 0.538697 0.556685 -0.382256 0.821755 0.422609 -0.380511 0.823012 0.421738 -0.084078 0.969601 0.229791 -0.0793976 0.970661 0.226965 -0.746647 0.183948 0.639282 -0.748337 0.178573 0.63883 -0.592884 0.532299 0.604274 -0.595107 0.529096 0.604901 -0.343657 0.809792 0.475538 -0.342457 0.810654 0.474935 -0.00345065 0.969471 0.24518 -0.0502161 0.960327 0.274318 -0.0920454 0.933437 0.346733 -0.0414709 0.955715 0.291358 -0.707138 0.179533 0.683903 -0.731895 0.13085 0.668736 -0.56258 0.527465 0.636619 -0.565536 0.523227 0.637498 -0.317449 0.803361 0.503822 -0.319513 0.801848 0.504927 -0.0328937 0.953084 0.300914 -0.97738 0.18736 -0.0981023 -0.942118 0.198452 -0.270242 -0.92291 0.198624 -0.329827 -0.941523 0.201589 -0.269992 -0.795157 0.575667 -0.190611 -0.798097 0.570992 -0.192379 -0.49148 0.86808 -0.0698896 -0.507348 0.858274 -0.0772224 -0.10939 0.99223 0.0592832 -0.111227 0.993364 0.0292541 -0.152565 0.9874 0.0420038 -0.0891214 0.995524 0.0314526 -0.546994 0.835709 -0.0488668 -0.515953 0.855661 -0.0404423 -0.829791 0.548418 -0.103366 -0.819635 0.564128 -0.0997866 -0.907835 0.401665 -0.120419 -0.967242 0.190875 -0.167362 -0.81608 0.188395 0.546371 -0.184382 0.982851 -0.00283011 -0.172177 0.985065 -0.00163472 -0.5448 0.838558 -0.00377389 -0.549835 0.835262 -0.00437784 -0.834225 0.551391 -0.00606218 -0.836323 0.548199 -0.00643678 -0.991406 0.130615 -0.0073572 -0.982349 0.187039 -0.00270294 -0.960032 0.246141 0.133238 -0.973666 0.187445 0.129768 -0.827066 0.55119 0.11023 -0.827303 0.550837 0.110221 -0.540275 0.838404 0.0719803 -0.540234 0.838431 0.0719796 -0.182798 0.982849 0.0243556 -0.223205 0.974422 0.0261207 -0.950233 0.187781 0.248589 -0.867004 0.419783 0.26849 -0.797474 0.550497 0.246958 -0.797054 0.551129 0.246902 -0.520923 0.838214 0.161361 -0.51306 0.843335 0.159862 -0.142835 0.988787 0.0435719 -0.172596 0.983721 0.0500311 -0.829234 0.350981 0.434953 -0.152762 0.984757 0.0831734 -0.733685 0.549667 0.399465 -0.862662 0.187633 0.469689 -0.923305 0.188421 0.334673 -0.482626 0.836534 0.25939 -0.215044 0.968629 0.124557 -0.379991 0.922347 -0.0698785 -0.0227284 0.999617 0.0157645 -0.0227555 0.999617 0.0157832 -0.104417 0.992311 0.0664504 -0.778748 0.471088 0.414279 -0.369792 0.901517 0.224767 -0.843976 0.157072 0.512868 -0.718335 0.0373691 -0.694693 -0.928481 0.217122 0.3013 -0.602404 0.430901 0.671889 0.893644 0.00685445 -0.448725 0.578802 0.75615 -0.305329 0.746595 0.524886 -0.408768 0.213166 0.965912 -0.146881 0.50312 0.796397 -0.335592 0.772351 0.352913 -0.528135 0.581921 0.707042 -0.40182 0.154092 0.982265 -0.106822 0.21576 0.965354 -0.146763 0.449995 0.835944 -0.314169 0.582775 0.70704 -0.400585 0.686023 0.548635 -0.477882 0.809021 0.187356 -0.557121 0.792966 0.26171 -0.550194 0.272894 0.953763 -0.125959 0.154179 0.982265 -0.106698 0.504499 0.831934 -0.231014 0.731564 0.557996 -0.391733 0.740812 0.545876 -0.391429 0.879319 0.185498 -0.438621 0.779086 0.609698 -0.145922 0.877951 0.468638 -0.0978789 0.124128 0.992127 -0.0165922 0.749738 0.653186 0.106024 0.184475 0.979424 0.0818414 0.832242 0.350973 0.429175 0.171447 0.984891 -0.0244074 0.375836 0.908128 0.184528 0.232273 0.913856 0.333043 0.67698 0.378271 0.631355 0.797204 0.0996796 0.595423 0.840364 0.536459 0.0774544 0.489471 0.861639 0.134152 0.5306 0.832856 0.157528 0.824526 0.495579 0.273055 0.434071 0.900476 0.0269518 0.506837 0.861064 0.0410384 0.851939 0.522199 0.0388294 0.95443 0.289833 0.0711299 0.916269 0.290407 0.27589 0.324773 0.928864 0.178139 0.518421 0.790226 0.326776 0.750818 0.485271 0.44809 0.748096 0.491832 0.445481 0.791901 0.283452 0.540877 0.675315 0.267085 0.68747 0.620366 0.42195 0.661139 0.450082 0.798315 0.40015 0.566211 0.812435 -0.139119 0.841961 0.527013 -0.115583 0.96635 0.195194 -0.167529 0.441398 0.893347 -0.0842548 0.95737 0.18738 -0.219846 0.892981 0.322694 -0.313772 -0.707641 -0.178405 0.683678 -0.746873 -0.183881 0.639037 -0.343454 -0.769207 0.538851 -0.311049 -0.802157 0.509698 -0.544771 -0.521804 0.656465 -0.566502 -0.489257 0.663102 -0.694 -0.174059 0.698618 -0.700596 -0.153587 0.696833 -0.898144 -0.204459 -0.389274 -0.759104 -0.585463 -0.284594 -0.471321 -0.87352 -0.121732 -0.899456 -0.196918 -0.390131 -0.861597 -0.205111 -0.464307 -0.834853 -0.317661 -0.44957 -0.076845 -0.99617 0.0417127 -0.0857089 -0.994756 0.0558043 -0.0902189 -0.994482 0.0535407 -0.0950826 -0.993486 0.0628156 -0.104665 -0.992751 0.059078 -0.0962371 -0.995338 0.00629935 -0.0778423 -0.996555 0.0285977 -0.0840764 -0.995772 0.0370029 -0.843174 -0.202865 -0.497899 -0.812456 -0.207571 -0.54482 -0.813351 -0.201476 -0.545772 -0.789583 -0.204429 -0.578591 -0.790045 -0.201305 -0.579056 -0.794311 -0.200898 -0.573332 -0.813885 -0.0172667 -0.580769 -0.111699 -0.993568 -0.0186189 -0.0901091 -0.995928 0.0028143 -0.0939274 -0.995548 0.00791763 -0.128187 -0.991098 -0.0359464 -0.129288 -0.99102 -0.0341283 -0.122991 -0.99192 -0.0311111 -0.114776 -0.993106 -0.0238209 -0.116271 -0.992983 -0.0215887 -0.808233 -0.197375 -0.5548 -0.830843 -0.19555 -0.521019 -0.830891 -0.195285 -0.521042 -0.844474 -0.194385 -0.499077 -0.862759 -0.147743 -0.483548 -0.858253 -0.193043 -0.475538 -0.885548 -0.191321 -0.42332 -0.887615 -0.175509 -0.425836 -0.14428 -0.988546 -0.0442678 -0.144473 -0.988534 -0.0439016 -0.899921 -0.189602 -0.392674 -0.915355 -0.188857 -0.355611 -0.915685 -0.18719 -0.355642 -0.938255 -0.187277 -0.29087 -0.96044 -0.00454336 -0.278451 -0.160038 -0.985678 -0.0531593 -0.159826 -0.985687 -0.053643 -0.177089 -0.982416 -0.0591545 -0.176397 -0.982416 -0.0611738 -0.194029 -0.978836 -0.0650574 -0.193223 -0.978765 -0.0684358 -0.95094 -0.185459 -0.247625 -0.964722 -0.186473 -0.185849 -0.965853 -0.180862 -0.185518 -0.975232 -0.183929 -0.122852 -0.996497 -0.00309519 -0.0835758 -0.209598 -0.974816 -0.0761708 -0.209932 -0.975183 -0.0703392 -0.980681 -0.179426 -0.077918 -0.982805 -0.184333 -0.0107643 -0.984169 -0.176969 -0.00964527 -0.982931 -0.181234 0.0316378 -0.99031 -0.119816 0.0702144 -0.981947 -0.176937 0.0668835 -0.974812 -0.184039 0.125984 -0.975888 -0.177204 0.127443 -0.97071 -0.181196 0.157765 -0.968944 -0.160601 0.188028 -0.229485 -0.972635 -0.0363087 -0.234503 -0.970661 -0.0531482 -0.237445 -0.970004 -0.0520702 -0.242469 -0.967441 -0.0725672 -0.243541 -0.967197 -0.0722352 -0.245653 -0.96575 -0.0835594 -0.243012 -0.966361 -0.084209 -0.243356 -0.96602 -0.0870752 -0.236764 -0.967554 -0.0882121 -0.236632 -0.967845 -0.0853363 -0.243054 -0.966348 -0.084245 -0.224727 -0.970956 -0.0821123 -0.224947 -0.971381 -0.0762737 -0.966147 -0.178493 0.18628 -0.953632 -0.184954 0.237442 -0.954182 -0.180916 0.238342 -0.945336 -0.184393 0.268958 -0.943806 -0.026576 0.329429 -0.13945 -0.989291 -0.04309 -0.014644 -0.99675 -0.0792146 -0.202991 -0.979075 0.014361 -0.19598 -0.980091 0.031828 -0.0601396 -0.998187 -0.00261251 -0.0722204 -0.997382 0.00353152 -0.875042 0.0823999 0.476982 -0.930236 -0.184093 0.317443 -0.909447 -0.187193 0.371303 -0.907296 0.0888642 0.410996 -0.891866 -0.187371 0.411663 -0.867366 -0.187708 0.460915 -0.137582 -0.981117 0.135941 -0.150818 -0.981991 0.113784 -0.0161225 -0.999555 0.0251155 -0.163777 -0.982225 0.0917127 -0.172372 -0.982209 0.0745214 -0.847684 -0.187385 0.496305 -0.829945 -0.186214 0.525848 -0.829762 -0.187414 0.525709 -0.805871 -0.18485 0.562497 -0.805318 -0.188135 0.5622 -0.792599 -0.185765 0.580757 -0.780964 -0.169215 0.601217 -0.776264 -0.18644 0.602207 -0.748123 -0.17848 0.639106 -0.759086 -0.58549 -0.284586 -0.722272 -0.593342 -0.355343 -0.723468 -0.591462 -0.356042 -0.683973 -0.597697 -0.418258 -0.68723 -0.592192 -0.420741 -0.663798 -0.595219 -0.452864 -0.668671 -0.586755 -0.456726 -0.675843 -0.586006 -0.447027 -0.681686 -0.57589 -0.451281 -0.702212 -0.574336 -0.420758 -0.705347 -0.569201 -0.422488 -0.725022 -0.567753 -0.389871 -0.728232 -0.56258 -0.391384 -0.75051 -0.561212 -0.348964 -0.753835 -0.555949 -0.350219 -0.776627 -0.55494 -0.29815 -0.780348 -0.54915 -0.299152 -0.801218 -0.549014 -0.237978 -0.805778 -0.542002 -0.238653 -0.821898 -0.543364 -0.170997 -0.82676 -0.535917 -0.171057 -0.835965 -0.539077 -0.102752 -0.841223 -0.530967 -0.102067 -0.843456 -0.535501 -0.0426625 -0.848491 -0.527595 -0.0413154 -0.84604 -0.532996 0.0114413 -0.849717 -0.527082 0.0128733 -0.843817 -0.533023 0.0621236 -0.846747 -0.528184 0.0635649 -0.837915 -0.534329 0.111311 -0.839782 -0.531168 0.112375 -0.827945 -0.537268 0.16078 -0.829157 -0.535169 0.161535 -0.805619 -0.543007 0.236898 -0.805729 -0.542817 0.236961 -0.768709 -0.548141 0.329587 -0.7687 -0.548157 0.329582 -0.729796 -0.548636 0.407917 -0.729241 -0.54962 0.407585 -0.6974 -0.547924 0.461966 -0.69687 -0.54891 0.461595 -0.668624 -0.545876 0.504936 -0.66877 -0.545608 0.505034 -0.632312 -0.538698 0.556764 -0.631398 -0.540331 0.556218 -0.594367 -0.529936 0.604893 -0.593564 -0.531326 0.604463 -0.464227 -0.877726 -0.118707 -0.441607 -0.882472 -0.161949 -0.440036 -0.88341 -0.161105 -0.413723 -0.887534 -0.202774 -0.419524 -0.883875 -0.206798 -0.401007 -0.886237 -0.2319 -0.413964 -0.877676 -0.24149 -0.413782 -0.877695 -0.241735 -0.431744 -0.865436 -0.254201 -0.441107 -0.864704 -0.240231 -0.450546 -0.858332 -0.24551 -0.46043 -0.857607 -0.22916 -0.470089 -0.851071 -0.233867 -0.481642 -0.850356 -0.211932 -0.491819 -0.843473 -0.216027 -0.503631 -0.842978 -0.18906 -0.514192 -0.835842 -0.192288 -0.524931 -0.835831 -0.160729 -0.535685 -0.828563 -0.162862 -0.543827 -0.829267 -0.12872 -0.55497 -0.821708 -0.12963 -0.559428 -0.82324 -0.0965212 -0.570371 -0.815745 -0.0961115 -0.571385 -0.817758 -0.0692151 -0.580089 -0.811715 -0.0679336 -0.57891 -0.814288 -0.0424029 -0.584935 -0.810047 -0.0409365 -0.581597 -0.81337 -0.0131805 -0.584493 -0.811307 -0.0122372 -0.578621 -0.815367 0.019366 -0.579636 -0.814635 0.0197658 -0.570515 -0.819323 0.056766 -0.569879 -0.819785 0.0564808 -0.549364 -0.826498 0.122885 -0.546416 -0.828649 0.121533 -0.512673 -0.833532 0.20589 -0.511132 -0.834675 0.205088 -0.476761 -0.835157 0.274248 -0.475813 -0.83588 0.273692 -0.447708 -0.834456 0.321313 -0.447952 -0.834259 0.321482 -0.419825 -0.831094 0.364733 -0.420252 -0.830744 0.365037 -0.380441 -0.823152 0.421528 -0.382626 -0.82134 0.423081 -0.342993 -0.810214 0.475298 -0.342967 -0.810237 0.47528 -0.0510669 -0.958442 0.280679 -0.0475731 -0.959463 0.277791 -0.0838804 -0.969537 0.230135 -0.0795964 -0.970691 0.226768 -0.107728 -0.976439 0.186982 -0.02485 -0.993212 0.113633 -0.121255 -0.979336 0.16186 -0.137919 -0.981037 0.136177 -0.0579676 -0.947635 0.314051 -0.0355171 -0.953897 0.298026 -0.72233 -0.175629 0.668875 -0.731959 -0.130496 0.668735 -0.565952 -0.522117 0.638037 -0.562844 -0.527515 0.636345 -0.318798 -0.802311 0.504642 -0.316872 -0.803976 0.503204 -0.0338153 -0.952833 0.301605 -0.0329683 -0.953099 0.300857 -0.967142 -0.191091 -0.16769 -0.921628 -0.198915 -0.333218 -0.94198 -0.198674 -0.270561 -0.939291 -0.212445 -0.269443 -0.798082 -0.570858 -0.192837 -0.794796 -0.575769 -0.191805 -0.507186 -0.858469 -0.0761135 -0.490741 -0.868364 -0.0715295 -0.109238 -0.992239 0.0594007 -0.141065 -0.988901 0.0466539 -0.170825 -0.968586 0.18072 -0.97738 -0.18736 -0.0981023 -0.907137 -0.403195 -0.120563 -0.829906 -0.548444 -0.102306 -0.819502 -0.564056 -0.101277 -0.547189 -0.835728 -0.0462863 -0.51498 -0.856128 -0.0429058 -0.0889286 -0.995536 0.0316133 0.00173953 -0.999177 0.0405154 -0.950119 -0.187506 0.24923 -0.869671 -0.18656 0.45702 -0.165347 -0.982102 0.0902031 -0.165155 -0.982146 0.0900743 -0.483966 -0.83433 0.263952 -0.484019 -0.834287 0.263989 -0.734715 -0.547372 0.400722 -0.735146 -0.546544 0.401062 -0.829239 -0.328179 0.452395 -0.816167 -0.187849 0.546429 -0.179563 -0.982161 0.0558222 -0.179702 -0.982133 0.0558793 -0.525635 -0.834861 0.163449 -0.526059 -0.834557 0.163636 -0.799298 -0.54709 0.248629 -0.798947 -0.547682 0.248451 -0.866299 -0.420656 0.269396 -0.923334 -0.187051 0.33536 -0.186097 -0.982215 0.0249248 -0.186221 -0.982191 0.024953 -0.545207 -0.835112 0.0730558 -0.545246 -0.835086 0.0730655 -0.829084 -0.547975 0.111101 -0.829412 -0.547458 0.111204 -0.96236 -0.239196 0.129029 -0.97294 -0.187167 0.135486 -0.174397 -0.984672 -0.0024766 -0.187657 -0.982234 -0.001381 -0.549852 -0.835252 -0.00404646 -0.549838 -0.835261 -0.00404793 -0.83633 -0.548191 -0.00615709 -0.836345 -0.548169 -0.00615466 -0.982316 -0.187093 -0.00722885 -0.990834 -0.135057 -0.00272629 -0.159272 -0.982297 0.0986104 -0.148022 -0.984758 0.091335 -0.453969 -0.845421 0.281382 -0.467396 -0.835395 0.289234 -0.659312 -0.631504 0.408058 -0.71176 -0.548194 0.439183 -0.759477 -0.449674 0.470094 -0.837096 -0.176746 0.517717 -0.835269 -0.187617 0.516842 0.976092 -0.185744 -0.11289 0.980103 -0.161486 -0.115413 0.853948 -0.520101 -0.0163935 0.795788 -0.60557 -0.00231409 0.604079 -0.792781 0.0811536 0.214722 -0.963006 0.16283 0.357146 -0.926201 0.120829 0.329721 -0.928629 0.170095 0.603012 -0.785656 0.13828 0.608743 -0.781513 0.136637 0.853208 -0.514935 0.0829398 0.861644 -0.501396 0.0785646 0.982434 -0.18568 0.0186082 0.986811 -0.161462 0.0116242 0.82654 -0.421118 0.373486 0.281642 -0.926599 0.249183 0.15012 -0.972336 0.178959 0.2825 -0.941493 0.183804 0.23029 -0.969616 0.082528 -0.0173629 -0.991817 0.12648 0.266921 -0.955065 0.128859 0.268531 -0.950008 0.159295 0.180747 -0.981115 -0.0688685 0.0560186 -0.998053 -0.0274411 0.159741 -0.984054 -0.0782344 0.0581916 -0.995944 -0.0686272 0.0985335 -0.991829 -0.0810388 -0.00298667 -0.994988 -0.0999487 0.107634 -0.986965 -0.119643 0.152792 -0.981507 -0.115324 0.110244 -0.982714 -0.148729 0.164082 -0.97457 -0.152614 0.185479 -0.972876 -0.138238 0.263073 -0.953007 -0.150232 0.138255 -0.979608 -0.145786 0.11191 -0.982464 -0.149131 0.396788 -0.901806 0.171189 0.376534 -0.911362 0.166255 0.408695 -0.879862 0.242511 0.203117 -0.966849 0.154749 0.225074 -0.963941 0.141984 0.227193 -0.948267 0.221749 0.280252 -0.930259 0.236806 0.321601 -0.912803 0.25172 0.185357 -0.965744 0.181609 0.315608 -0.924027 0.215789 0.87868 -0.142502 0.455648 0.912366 -0.0285358 0.40838 0.85048 -0.30125 0.431198 0.842945 -0.321289 0.431528 0.89667 -0.000267238 0.4427 0.871127 -0.39373 0.293451 0.920028 -0.197004 0.338729 0.921266 -0.124707 0.368397 0.968784 -0.189747 0.15954 0.959904 -0.184939 0.21067 0.934845 -0.280427 0.217773 0.957653 -0.144849 0.248835 0.884828 -0.361026 0.294517 0.95693 -0.288935 0.0283099 0.996168 -0.0580131 0.0654551 0.950111 -0.298156 0.0916055 0.958365 -0.26847 0.0972624 0.987993 -0.0334772 0.150828 0.974589 -0.189959 -0.118713 0.977488 -0.193579 -0.0839322 0.817309 -0.570659 -0.0797196 0.854139 -0.51504 -0.0719721 0.99766 -0.0682653 -0.00392769 0.9348 -0.31715 -0.159889 0.875953 -0.449271 -0.175677 0.955273 -0.229995 -0.185894 0.968906 -0.123846 -0.214206 0.923256 -0.302487 -0.236855 0.953575 -0.17164 -0.247458 0.940656 -0.217791 -0.260255 0.945026 -0.197851 -0.260349 0.944946 -0.198476 -0.260162 0.946811 -0.189784 -0.259867 0.951257 -0.185642 -0.246265 0.961612 -0.123962 -0.244816 0.95029 -0.211589 -0.228426 0.97204 -0.0954108 -0.214556 0.936093 -0.294142 -0.1929 0.981176 -0.089306 -0.171225 0.985244 0.0164711 -0.170359 0.976578 -0.163291 -0.140111 0.98369 -0.177246 -0.0306316 0.993955 -0.0880673 -0.0655538 0.990239 0.0877231 -0.108312 0.979111 -0.180973 -0.0926838 0.975371 -0.183509 -0.122372 0.984917 -0.172958 -0.0049511 0.984674 0.172334 -0.0267908 0.982183 -0.179149 0.0567595 0.190077 -0.980475 -0.0503995 0.179779 -0.983187 -0.0319923 0.089815 -0.995958 -0.00127297 0.227254 -0.973558 -0.0232473 0.146032 -0.988883 0.0280295 0.140264 -0.989695 0.0288093 0.225392 -0.973135 0.0469751 0.554515 -0.748677 0.363313 0.526656 -0.774216 0.35103 0.533775 -0.775831 0.336408 0.524474 -0.783843 0.332441 0.543201 -0.787973 0.289882 0.524293 -0.803283 0.282582 0.549166 -0.807737 0.214422 0.530347 -0.821771 0.208386 0.547289 -0.824511 0.143723 0.538253 -0.830908 0.140983 0.547623 -0.831536 0.0930401 0.538475 -0.837745 0.0907093 0.545169 -0.837354 0.0403717 0.536254 -0.843177 0.038533 0.53998 -0.841582 -0.0127164 0.531532 -0.846922 -0.0140682 0.532119 -0.841884 -0.0898918 0.516712 -0.851341 -0.0906988 0.509396 -0.843295 -0.171377 0.502033 -0.847731 -0.171216 0.49451 -0.842568 -0.213399 0.494525 -0.842559 -0.213401 0.495184 -0.842875 -0.210607 0.500917 -0.839277 -0.211415 0.509305 -0.841699 -0.179309 0.515697 -0.837551 -0.180458 0.525245 -0.838692 -0.143918 0.530292 -0.835341 -0.144902 0.540001 -0.835157 -0.104458 0.544668 -0.832011 -0.10533 0.55542 -0.830016 -0.0508135 0.564566 -0.823731 -0.0522812 0.577841 -0.814824 0.0464884 0.595255 -0.802328 0.0440565 0.600998 -0.785523 0.147496 0.602623 -0.784303 0.147357 0.205577 -0.974098 0.0941883 0.194091 -0.978312 0.0723436 0.240765 -0.967444 0.0779955 0.147088 -0.988515 0.0346962 0.222683 -0.97406 0.0402406 0.177688 -0.983922 0.0180065 0.200431 -0.979705 0.00246943 0.0846792 -0.996239 -0.0183731 0.229252 -0.972855 -0.0315844 0.193739 -0.980322 -0.0378689 0.105123 -0.992405 -0.0638892 0.458372 -0.884107 -0.0908247 0.310484 -0.945641 -0.0967675 0.109253 -0.988029 -0.108913 0.774959 -0.452988 0.440728 0.751249 -0.498944 0.432063 0.760651 -0.501104 0.41268 0.757848 -0.506136 0.411695 0.779563 -0.511014 0.362141 0.773656 -0.521279 0.360173 0.80294 -0.526687 0.279084 0.796873 -0.536765 0.277266 0.818106 -0.539974 0.197815 0.815233 -0.54465 0.196856 0.826736 -0.545478 0.137696 0.823563 -0.550497 0.136735 0.831767 -0.550038 0.0749742 0.828242 -0.555461 0.0740132 0.832706 -0.553586 0.0119758 0.828638 -0.559677 0.0109786 0.828769 -0.554006 -0.0788642 0.820908 -0.565431 -0.0799906 0.81201 -0.555422 -0.179297 0.807309 -0.562087 -0.179754 0.796437 -0.554392 -0.241532 0.794472 -0.557175 -0.241601 0.791008 -0.555459 -0.256459 0.792723 -0.552981 -0.25652 0.797053 -0.554236 -0.239854 0.799325 -0.550843 -0.240106 0.806823 -0.551694 -0.211352 0.808928 -0.548475 -0.211687 0.818459 -0.548271 -0.171827 0.819586 -0.546521 -0.172028 0.831132 -0.54435 -0.11359 0.833843 -0.540083 -0.114088 0.847014 -0.53134 -0.0156452 0.850569 -0.525606 -0.0164589 0.856622 -0.506568 0.0979159 0.85295 -0.512568 0.0987406 0.276331 -0.925469 0.259129 0.22184 -0.945976 0.236468 0.209656 -0.951678 0.224396 0.832557 -0.130024 0.538462 0.82395 -0.175156 0.538912 0.2565 -0.934757 0.245841 0.530521 -0.743311 0.407475 0.48918 -0.784272 0.381603 0.704874 -0.507948 0.495117 0.737138 -0.446754 0.50699 0.184371 -0.96011 0.210227 0.226236 -0.943967 0.2403 0.443935 -0.797368 0.40881 0.461276 -0.781243 0.420575 0.649009 -0.517775 0.557401 0.65685 -0.502744 0.561957 0.759582 -0.177363 0.625761 0.761299 -0.168345 0.626165 0.773215 -0.177849 0.608693 0.750356 -0.25232 0.610984 0.672769 -0.517836 0.52842 0.446384 -0.797417 0.406039 0.49385 -0.760477 0.421648 0.195345 -0.960512 0.198135 0.166294 -0.97713 0.132524 0.200245 -0.964588 0.171674 0.186132 -0.963343 0.193196 0.924036 -0.183564 0.335353 0.901349 -0.261441 0.34528 0.772723 -0.572077 0.275005 0.571131 -0.779132 0.258384 0.539106 -0.834341 0.115063 0.606008 -0.787528 0.112044 0.818497 -0.546333 0.177715 0.969132 -0.187361 0.160249 0.948705 -0.260835 0.17867 0.843607 -0.25163 0.474351 0.869052 -0.177797 0.461667 0.685659 -0.586484 0.431171 0.553589 -0.768544 0.32075 0.272084 -0.938104 0.214314 0.297296 -0.946183 0.127876 0.191922 -0.975266 0.109642 0.207002 -0.976902 0.0530421 0.182791 -0.981746 0.052556 0.980026 -0.188535 -0.0632816 0.184916 -0.982752 -0.00211554 0.188452 -0.982079 -0.00256878 0.54667 -0.837328 -0.00579193 0.551403 -0.834213 -0.00657306 0.835178 -0.549903 -0.00915113 0.837564 -0.546252 -0.00975466 0.999174 0.0390745 -0.0111191 0.981108 -0.187497 0.0476568 0.260863 -0.962582 -0.0733916 0.179742 -0.982757 -0.0433679 0.531284 -0.83744 -0.128187 0.531408 -0.837353 -0.128238 0.811881 -0.549967 -0.195922 0.811871 -0.549983 -0.195917 0.954993 -0.186762 -0.230454 0.954838 -0.187757 -0.230285 0.330784 -0.936113 -0.119478 0.123252 -0.991218 -0.0479094 0.126388 -0.990777 -0.0488586 0.510658 -0.83901 -0.18786 0.552326 -0.808974 -0.201239 0.526515 -0.829236 -0.187483 0.570737 -0.806519 -0.15423 0.922955 -0.187874 -0.335943 0.931894 -0.12198 -0.341607 0.890777 -0.318601 -0.324054 0.783166 -0.552407 -0.285479 -0.825402 -0.240578 0.510719 -0.834395 -0.176742 0.522061 -0.760045 -0.449673 0.469175 -0.677115 -0.603626 0.420893 -0.659337 -0.631502 0.408019 -0.456112 -0.845415 0.277911 -0.373128 -0.897863 0.233703 -0.148522 -0.984757 0.0905264 -0.12249 -0.989564 0.0758962 -0.28964 -0.176124 0.940792 -0.731696 -0.175157 0.658742 0.0494221 -0.193352 0.979884 0.0292485 -0.306358 0.951467 0.0549175 -0.552892 0.831442 0.0198267 -0.829777 0.557743 0.0195694 -0.828948 0.558984 0.0210521 -0.980692 0.194423 -0.110556 -0.989501 0.0930861 -0.727932 -0.239361 0.642512 -0.591343 -0.591829 0.54777 -0.627299 -0.539228 0.561897 -0.381664 -0.85175 0.358964 -0.33054 -0.898771 0.288018 -0.131831 -0.325824 0.936194 -0.20218 -0.47034 0.859013 -0.200777 -0.537769 0.818836 -0.124813 -0.816642 0.563487 -0.12355 -0.842497 0.524342 -0.0470904 -0.984876 0.166738 -0.51688 -0.174726 0.838037 -0.516877 -0.174335 0.83812 -0.442662 -0.537439 0.717781 -0.44264 -0.537557 0.717707 -0.282648 -0.842662 0.458291 -0.275901 -0.853818 0.441444 -0.0857444 -0.984857 0.150681 0.0459737 -0.965916 0.254742 0.0400915 -0.980764 0.191035 0.104039 -0.793256 0.599934 0.0986606 -0.83158 0.546573 0.140882 -0.609107 0.780475 0.14495 -0.55539 0.81886 0.175656 -0.258644 0.949868 0.174201 -0.195068 0.965196 0.801731 -0.597442 -0.0170577 0.961392 -0.255542 -0.102094 0.620762 -0.347941 0.702561 0.263738 -0.964476 -0.0151306 0.615852 -0.787069 -0.0353312 0.357716 -0.30907 0.881201 0.397719 -0.251462 0.882376 0.260636 -0.604401 0.75284 0.774837 -0.632157 0.0022836 0.730987 -0.629951 0.262336 0.636424 -0.711462 0.297968 0.565674 -0.697767 0.43947 0.197913 -0.789945 0.580359 0.213309 -0.976894 0.013307 0.173438 -0.93204 0.318153 0.112179 -0.96372 0.242197 0.962095 -0.0221777 -0.271811 0.933166 -0.258542 -0.249713 0.588224 -0.793456 -0.156268 0.765476 -0.608964 -0.207869 0.787589 -0.577146 -0.215883 0.251058 -0.965893 -0.0634081 0.137242 -0.98984 -0.037159 0.788291 0.017025 -0.615068 0.765137 -0.174709 -0.619711 0.720407 -0.493886 -0.48692 0.421149 -0.899558 -0.115886 0.7058 -0.512366 -0.489211 0.808843 -0.175177 -0.561325 0.807149 -0.187357 -0.559828 0.686674 -0.548636 -0.476946 0.451303 -0.835944 -0.312286 0.460957 -0.827944 -0.319417 0.153916 -0.982265 -0.107076 0.13797 -0.985818 -0.0955368 0.844235 -0.186921 -0.502323 0.905947 0.0403954 -0.421459 0.825245 -0.526306 -0.204873 0.718462 -0.68112 -0.141029 0.680507 -0.712542 0.170865 0.0731172 -0.972675 -0.220355 0.49369 -0.833432 -0.248316 0.784228 -0.538317 -0.308547 0.774333 -0.523804 0.355016 0.523145 -0.839572 0.14642 0.274355 -0.884057 0.378381 0.784307 -0.151659 0.60155 0.427719 -0.896278 0.117227 0.444984 -0.895118 0.027441 0.467755 -0.883485 0.025679 0.871299 -0.487871 0.0531023 0.870277 -0.489669 0.0533205 0.871325 -0.487799 0.0533479 0.836297 -0.336724 0.432695 0.736614 -0.494725 0.461136 0.752401 -0.465454 0.466096 0.897769 -0.321907 0.300644 0.833566 -0.490792 0.253555 0.530722 -0.830815 0.167575 0.35722 -0.910844 0.20678 0.461573 -0.850208 0.253175 0.383491 -0.857711 0.342442 0.583448 -0.559174 0.588993 0.620461 -0.483119 0.617758 0.689829 -0.0988662 0.71719 0.401651 -0.912094 -0.0822282 0.977703 -0.0882362 -0.190556 0.958695 -0.227102 -0.171257 0.900814 -0.285349 -0.327276 -0.880925 -0.318929 0.349649 0.868976 -0.439762 -0.226913 0.984624 -0.00349725 -0.17465 0.921131 -0.341968 -0.185943 -0.571083 -0.701765 0.425899 -0.476792 -0.64914 0.592694 -0.555329 -0.628491 0.544618 -0.328191 -0.546498 0.770474 -0.520205 -0.520087 0.677418 -0.128793 -0.408162 0.903779 -0.468607 -0.393349 0.791002 0.106829 -0.213357 0.971116 -0.382364 -0.218 0.897928 0.373228 0.000231705 0.92774 -0.834599 0.00156626 0.550856 -0.82069 -0.00181723 0.571371 -0.751227 0.00389786 0.660032 -0.703011 -0.00552134 0.711158 -0.612822 0.00562361 0.790201 -0.54523 -0.00565646 0.838268 -0.459448 0.00364434 0.888197 -0.364644 -0.00346854 0.93114 -0.336313 0.0014354 0.941749 -0.180071 -0.0014264 0.983653 -0.171413 0 0.985199 -0.0572438 0 0.99836 -0.0572438 0 0.99836 0.047498 0 0.998871 0.047498 0 0.998871 0.152357 0 0.988325 0.152357 0 0.988325 0.256269 0 0.966606 0.256269 0 0.966606 0.357215 0 0.934022 0.357215 0 0.934022 0.454483 0 0.890755 0.45425 -3.4178e-05 0.890874 0.566033 -0.00138874 0.824381 0.579692 0.00162742 0.814834 0.711303 -0.00182507 0.702883 0.72379 0.00187259 0.690018 0.838282 -0.00187145 0.545235 0.848019 0.00192724 0.529963 0.931309 -0.00188572 0.364226 0.937349 0.00166102 0.348389 0.983539 -0.00141744 0.180693 0.985079 0 0.172101 0.998348 0 0.0574645 0.998348 0 0.0574645 0.998868 0 -0.0475776 0.998868 0 -0.0475776 0.98831 0 -0.152461 0.98831 0 -0.152461 0.966597 0 -0.2563 0.966597 0 -0.2563 0.933898 0 -0.35754 0.933898 0 -0.35754 0.890974 0 -0.454054 0.890975 -2.54597e-07 -0.454052 0.977963 -0.207472 0.0233272 0.264458 0.930316 0.254114 0.240572 -0.922997 0.300335 -0.27823 0.924446 -0.260745 -0.258305 -0.927893 -0.268876 -0.272428 -0.926232 -0.260534 0.715219 0.0260046 -0.698416 0.713016 0.0919576 -0.695092 0.761709 0.00839313 -0.647865 0.725141 0.00420344 -0.688588 -0.681422 -0.689481 -0.245518 0.821305 0.522264 -0.229564 -0.309967 0.149469 -0.938925 0.210294 -0.973878 -0.0856602 0.71534 0.698148 -0.0296416 0.878496 0.455642 0.143648 0.702125 -0.0205463 -0.711757 0.698172 -0.0277314 -0.715392 0.693959 -0.297504 -0.655677 0.629424 -0.417592 -0.655318 0.646618 -0.455957 -0.611546 0.614293 -0.554132 -0.561766 0.571777 -0.610989 -0.547507 0.423178 -0.804777 -0.416237 0.807362 0.00492309 -0.590035 0.812813 0.00127286 -0.582523 0.743796 0.0377583 -0.66734 0.704492 -0.550773 -0.447593 0.614307 -0.673225 -0.411576 0.569337 -0.748512 -0.33998 0.58643 -0.735646 -0.339006 0.433375 -0.85069 -0.297512 0.358033 -0.910123 -0.208538 0.687988 -0.149479 -0.710161 0.697414 -0.164087 -0.697631 0.279619 -0.933164 -0.225871 0.308511 -0.912166 -0.269766 0.388795 -0.859467 -0.331897 0.505271 -0.744555 -0.436279 0.548992 -0.689937 -0.4718 0.699967 -0.396565 -0.593954 0.70952 -0.297454 -0.638829 0.754789 -0.172558 -0.632864 0.74769 -0.150216 -0.646834 0.754685 -0.000463944 -0.656087 0.748124 0.00592413 -0.663532 0.807049 -0.00915281 -0.590414 0.803573 -0.000501514 -0.595207 0.803146 -0.000965394 -0.595781 0.790067 -0.171679 -0.588491 0.780905 -0.150565 -0.606232 0.7778 -0.297251 -0.553776 0.723727 -0.41165 -0.553863 0.72226 -0.427384 -0.543768 0.668603 -0.546383 -0.504416 0.667784 -0.55062 -0.500881 0.608884 -0.648086 -0.457432 0.498043 -0.782421 -0.373859 0.432513 -0.840773 -0.325628 0.292084 -0.932637 -0.21184 0.846496 0.00011104 -0.532394 0.846786 -0.000205106 -0.531933 0.846438 -0.000502755 -0.532487 0.837087 -0.167936 -0.520657 0.848067 -0.150563 -0.508049 0.796378 -0.297276 -0.526697 0.771629 -0.427283 -0.471188 0.77235 -0.475754 -0.420872 0.552341 -0.12781 -0.823762 0.937369 -0.0015185 0.348335 0.952211 0.0148066 0.305083 -0.118983 -0.56423 -0.816999 0.871899 -0.327522 0.364036 0.875354 -0.242654 0.41818 0.791392 -0.441861 0.422442 0.878145 -0.244548 0.411166 0.875211 -0.331187 0.352592 -0.866749 -0.000471369 0.498745 -0.866327 -1.21479e-05 0.499477 -0.866551 -0.000826182 0.499087 -0.867234 -5.3852e-06 0.4979 0.499602 -8.52016e-05 0.866255 0.499582 0.000283922 0.866267 0.499435 -0.000178003 0.866352 0.499566 2.98323e-05 0.866276 0.499529 -5.4764e-05 0.866297 0.49958 0.000286279 0.866268 0.499515 1.33162e-05 0.866305 0.499545 -6.59576e-05 0.866288 0.499392 -9.07747e-06 0.866376 0.499549 -3.45006e-05 0.866286 0.499554 -6.42447e-05 0.866283 0.499445 0.000280049 0.866346 0.499548 0 0.866286 0.499565 2.47245e-05 0.866276 0.499464 -0.000152164 0.866335 0.499538 1.4178e-05 0.866292 0.499457 -0.000172531 0.866339 0.499503 3.52635e-05 0.866312 0.499572 4.06141e-05 0.866272 0.49935 -1.47865e-05 0.8664 0.499518 5.80111e-05 0.866303 0.49908 -0.000978846 0.866555 0.499563 -0.000194002 0.866278 0.499518 0.000211971 0.866304 0.499687 -0.000226774 0.866206 0.499542 4.22468e-06 0.866289 0.841842 0.480352 0.246097 0.751863 -0.00117367 0.659319 0.75529 0.00045672 0.655391 -0.0382467 -0.991454 0.124725 0.0342058 -0.989295 0.141861 -0.890223 -0.286116 0.354459 0.923981 -0.228028 -0.307021 0.256085 -0.771999 -0.581755 -0.473473 -0.0787576 -0.87728 0.750899 -0.0490362 -0.658595 0.698762 -0.0180442 -0.715127 -0.0357746 0.988949 -0.143872 0.0072887 0.990337 -0.138492 -0.570676 -0.695125 -0.437185 0.178667 -0.935668 -0.304308 0.833306 -0.544922 -0.0930685 0.611785 -0.751336 -0.247414 -0.497425 -0.773881 -0.392016 0.385065 -0.603829 -0.697937 0.601425 -0.633611 -0.486647 0.914222 -0.290809 -0.282185 -0.577826 -0.560287 -0.593462 -0.0519929 -0.673476 -0.737379 0.834848 0.393765 0.384679 0.349636 0.603534 0.71659 0.795446 0.0128402 0.605889 0.755535 -0.000673604 0.655108 0.755435 6.39633e-05 0.655223 0.755414 -4.36102e-05 0.655248 0.747752 0.00337393 0.66397 0.49958 5.31563e-05 0.866268 0.499487 -5.84559e-05 0.866321 0.49929 3.00718e-05 0.866435 0.491989 0.0013508 0.8706 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.499552 0 -0.866284 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.55115 0.00149211 0.834405 0.572675 -0.0017384 0.819781 0.659682 0.00391135 0.751534 0.711299 -0.00553652 0.702868 0.790167 0.00562038 0.612866 0.838271 -0.0056736 0.545225 0.888091 0.00364759 0.459652 0.931305 -0.00347549 0.364225 0.941914 0.00142659 0.335852 0.983539 -0.00141726 0.180691 0.98508 0 0.1721 0.998348 0 0.0574645 0.998348 0 0.0574645 0.998868 0 -0.0475776 0.998868 0 -0.0475776 0.98831 0 -0.152461 0.98831 0 -0.152461 0.966597 0 -0.2563 0.966597 0 -0.2563 0.933898 0 -0.35754 0.933898 0 -0.35754 0.890975 0 -0.454052 0.890972 7.75188e-07 -0.454058 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 7.21114e-05 1 2.23219e-05 0 1 0 0 1 0 0 1 0 -5.72847e-06 1 9.42912e-07 0 1 0 -6.82773e-05 1 -5.50322e-05 0.000100467 1 2.88188e-05 0 1 0 0 1 0 -5.50756e-06 1 1.20501e-07 1.40879e-05 1 -7.4553e-06 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.945485 0.272207 0.178777 -0.688277 0.713756 0.129723 -0.836057 0.478304 0.268764 -0.427006 0.902292 0.0594567 -0.749349 0.586606 0.307196 -0.246718 0.968858 0.0210923 -0.680611 0.652621 0.332949 -0.0868723 0.996209 -0.00456173 -0.612586 0.707094 0.353209 -0.629984 -0.649727 0.425411 -0.187873 -0.954352 0.2322 -0.640813 -0.587164 0.494569 -0.24133 -0.913331 0.328003 -0.6559 -0.502895 0.562932 -0.318682 -0.809716 0.49275 -0.50942 -0.619778 0.596964 -0.614631 -0.2319 0.753957 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 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.81494e-06 -1 -1.00849e-05 -7.09568e-06 -1 -3.52557e-06 0 -1 0 0.193481 -0.84216 -0.503321 -0.866327 9.23731e-05 0.499477 -0.866291 -4.33738e-05 0.49954 -0.866257 -1.21015e-06 0.499599 -0.869324 -0.0014415 0.494241 0.85103 0.223975 0.474957 0.834176 0.275003 0.478041 0.93673 0.333574 0.106136 0.930097 -2.43947e-05 0.367314 0.908503 0.0195116 0.417423 0.999386 -0.0314097 -0.0155385 -0.736664 -0.00198145 -0.676256 -0.70213 0.00931171 -0.711988 -0.164191 -0.0583809 -0.984699 -0.867455 -0.22333 -0.444574 0.723603 -0.435441 0.535528 0.835955 -0.329708 0.438716 0.0843113 0.0174732 -0.996286 -0.859436 -0.00290874 -0.511235 -0.806994 0.0291387 -0.58984 -0.945894 -0.265105 -0.187096 0.918598 -0.345328 0.192163 0.956733 0.0265745 -0.289752 0.91269 -0.0171682 -0.408292 -0.955776 -0.0340066 -0.292122 -0.808644 0.0591965 -0.585312 -0.692248 -0.661775 -0.287832 -0.949907 -0.297149 0.0968475 0.875726 -0.00710994 -0.482757 0.788026 0.0491718 -0.613675 -0.944218 0.000609062 0.329321 0.918563 -0.00688359 -0.395216 0.903432 0.00493115 -0.428703 0.75616 0.653396 0.0359901 -0.655691 -0.264948 -0.707016 -0.811846 0.0812189 -0.578196 -0.889798 -0.339593 -0.304853 -0.873841 -0.452902 -0.176865 -0.399323 -0.586868 -0.704363 0.895179 -0.187192 -0.404491 0.452016 -0.770212 -0.449951 -0.423346 -0.572743 -0.701957 0.530018 -0.508563 -0.67856 0.879454 -0.385382 -0.279358 0.344936 -0.525096 -0.778006 -0.0627991 -0.54776 -0.834275 -0.42986 -0.780933 -0.453171 -0.112534 -0.89999 -0.421134 -0.393342 -0.142767 -0.90824 -0.791823 -0.54895 -0.267715 0.360029 -0.823541 -0.43836 0.989745 -0.000817425 0.142845 0.989764 -0.000375746 0.142712 0.991799 0.0556681 0.11505 0.989912 -0.000931473 0.141682 -0.525247 -0.339298 -0.78038 -0.496437 -0.344938 -0.796597 0.423879 -0.652904 -0.627729 -0.673193 -0.48656 -0.55684 -0.365616 -0.708424 -0.603706 0.753196 -0.0100249 0.65772 0.995578 0 0.0939385 0.361732 0 0.932282 0.214857 0 0.976646 0.214857 0 0.976646 0.0594727 0 0.99823 0.0594727 0 0.99823 -0.252447 0 0.967611 -0.0998109 0.0888545 0.991031 -0.327492 0.0892543 0.940629 -0.253796 0.178468 0.950651 -0.397435 0.176714 0.900454 0.995578 0 0.0939385 0.972811 0 0.231603 0.972811 0 0.231603 0.92269 0 0.385543 0.92269 0 0.385543 0.84843 0 0.529308 0.84843 0 0.529308 0.750839 0 0.660485 0.750839 0 0.660485 0.631201 0 0.77562 0.631201 0 0.77562 0.532376 0 0.846508 0.499377 -0.00711311 0.866356 0.465655 0 0.884966 0.361732 0 0.932282 9.80475e-05 -1 -0.000407372 -3.53234e-05 -1 -0.000488821 0 1 0 0 1 0 4.64501e-05 -1 0.00022311 -4.22538e-05 -1 0.000190545 -2.42991e-05 -1 -0.000576957 -0.00168303 -0.999993 0.00341013 0.00208369 -0.999989 -0.00419464 0.00122785 -0.999999 -0.000309936 0.00232967 0.999977 -0.00643425 -7.78179e-05 -1 -0.000557847 -0.054477 -0.995385 -0.0790018 0.499435 -1.83031e-05 0.866352 0.499537 -6.77186e-07 0.866292 0.499528 -5.21309e-06 0.866297 0.499538 -1.66019e-05 0.866292 0.866276 -0.000316654 -0.499566 0.866369 1.77752e-05 -0.499404 0.867291 -0.00108301 -0.497801 0.86869 -3.02886e-05 -0.495356 -0.499533 2.59939e-05 -0.866295 -0.499527 0 -0.866298 -0.998165 0 0.0605457 -0.998779 -0.00564895 0.0490821 -0.991269 0.00637581 -0.131704 -0.988434 -0.00657823 -0.15151 -0.937295 0.00668035 -0.348473 -0.930171 -0.00668134 -0.367066 -0.834436 0.00669483 -0.551064 -0.823177 -0.00693769 -0.567743 -0.687792 0.00689886 -0.725875 -0.690448 0.00939026 -0.723321 -0.571681 -0.0132832 -0.820368 -0.50674 0.0199901 -0.861867 -0.389645 -0.0195663 -0.920757 -0.304035 0.0188251 -0.952475 -0.178753 -0.0190459 -0.98371 -0.0885219 0.0193712 -0.995886 0.0415974 -0.0195731 -0.998943 0.13377 0.0199338 -0.990812 0.263567 -0.0201223 -0.964431 0.351773 0.0201416 -0.935868 0.451896 -0.0128659 -0.891978 0.540453 0.0094669 -0.841321 0.56203 0 -0.827117 0.502635 -0.00432509 0.864488 0.499346 -0.000272751 0.866403 0.499677 0.000228125 0.866212 0.499557 -4.79906e-05 0.866281 0.499553 -9.10294e-05 0.866283 0.49954 9.35912e-06 0.866291 0.49951 -5.76193e-05 0.866308 0.499217 6.93017e-05 0.866477 0.499563 -1.11352e-05 0.866278 0.499582 -0.000200753 0.866267 0.499436 0.000309584 0.866351 0.499551 1.00803e-06 0.866285 0.499563 1.88425e-05 0.866278 0.499538 1.99307e-05 0.866292 0.499357 -0.00040554 0.866396 0.499483 -1.95557e-05 0.866324 0.499495 4.01599e-05 0.866317 0.499586 4.71668e-05 0.866264 0.49935 -1.1539e-05 0.8664 0.499514 5.92057e-05 0.866306 0.49954 4.36156e-07 0.866291 0.499859 0.000384166 0.866107 0.499551 -7.45518e-05 0.866284 0.499559 -0.000140135 0.86628 0.499418 0.000196211 0.866361 0.49956 -3.70795e-05 0.866279 -0.499541 4.09104e-05 -0.86629 -0.499532 -7.0421e-07 -0.866296 -0.499541 3.48925e-07 -0.86629 -0.499541 -2.40537e-07 -0.86629 0.55196 0.000488576 -0.833871 0.543127 0.00566591 -0.839631 0.382583 -0.00638999 -0.923899 0.364055 0.00658374 -0.931354 0.167499 -0.00669603 -0.985849 0.14785 0.00666033 -0.988987 -0.0589701 -0.00668251 -0.998237 -0.079053 0.0069422 -0.996846 -0.284185 -0.00692028 -0.958745 -0.280616 -0.00943425 -0.959774 -0.423328 0.0133086 -0.905879 -0.491773 -0.0199387 -0.870495 -0.602123 0.0194942 -0.798166 -0.671949 -0.0188316 -0.740358 -0.761618 0.0190815 -0.647745 -0.817586 -0.0193554 -0.575482 -0.885491 0.0195629 -0.464244 -0.924473 -0.0199277 -0.380725 -0.966715 0.0201271 -0.255064 -0.986211 -0.020138 -0.16426 -0.99837 0.0128541 -0.055604 -0.998896 -0.00944821 0.0460259 -0.997421 0 0.0717696 0.499404 -2.46756e-05 0.866369 0.499614 -0.000130737 0.866248 0.499421 0.000242602 0.86636 0.499433 0.000167306 0.866352 0.499773 -2.48366e-06 0.866156 0.499598 -0.000192573 0.866257 0.499755 5.78325e-05 0.866167 0.499635 -0.000390578 0.866236 0.500589 -6.76207e-05 0.865685 0.499661 0 0.866221 0.49984 -1.60959e-05 0.866118 0.499415 -1.20553e-05 0.866363 0.499494 0.000426211 0.866317 0.499565 -0.000280319 0.866276 0.499256 0.00016791 0.866455 0.499493 -0.000276801 0.866318 0.499517 -0.000241376 0.866304 0.499534 -8.46826e-05 0.866294 0.122935 0.992411 0.00264341 0.605236 0.780267 -0.157712 0.692243 0.709839 0.130109 0.837409 0.544551 0.047016 0.967583 0.245129 0.0607791 0.423407 0.905592 -0.0250967 0.989608 0.0431152 -0.137178 0.819432 0.564556 -0.099032 0.967378 0.184264 -0.173858 0.42333 -8.27687e-06 -0.905975 0.423376 -0.00117311 -0.905953 0.423327 0 -0.905977 0.423328 -1.79636e-06 -0.905976 -0.0874537 -5.34528e-05 0.996169 -0.0874503 -0.000645248 0.996169 -0.0875148 0.000227925 0.996163 -0.0874276 -3.61884e-08 0.996171 0.638988 0.722931 0.262804 0.628229 0.277177 0.726981 0.434476 0.597084 0.67433 0.465077 0.692702 0.551241 0.279677 0.929094 0.242003 0.689999 0.258601 0.676038 0.34321 0.901564 0.26342 0.555764 0.675954 0.483956 0.610174 0.613092 0.501803 0.758614 0.055033 0.649212 0.704668 0.544102 0.455406 0.827611 0.210442 0.52036 0.887766 0.0684335 0.455179 0.13956 0.98954 0.0365272 0.366568 0.901324 0.230743 0.700862 0.624265 0.345087 0.900828 0.204422 0.383041 0.939576 -9.35792e-05 -0.34234 0.939566 0.000353519 -0.342368 0.939567 -3.30169e-05 -0.342366 -0.76693 -0.000106125 0.64173 -0.767014 7.74976e-05 0.64163 -0.767011 5.0125e-05 0.641634 0.344306 0.619818 0.70518 -0.133596 0.0698957 0.988568 -0.00738813 0.988849 0.14874 -0.0912279 0.699268 0.709014 -0.0398932 0.521182 0.852513 0.0505875 0.450668 0.891257 0.0819589 0.221009 0.971822 0.0768104 0.199611 0.97686 0.0354027 0.956374 0.289992 0.0304397 0.844381 0.534878 0.125367 0.700801 0.702254 0.133138 0.609506 0.781522 0.184011 0.230155 0.955599 0.0680655 0.962433 0.262849 0.212233 0.466886 0.858472 0.18852 0.765301 0.615446 0.29606 -0.0389272 0.954376 0.0727898 0.976856 0.201134 0.302734 0.449225 0.840565 0.352176 0.172771 0.919849 0.905975 4.97499e-05 0.423331 0.905985 0.000193738 0.42331 0.905962 -1.96874e-06 0.423359 -0.996163 -2.15543e-05 -0.0875116 -0.996163 2.03022e-05 -0.0875151 -0.996164 4.49674e-06 -0.0875081 -0.996179 0.000391408 -0.0873318 -0.647807 0.20574 0.733497 -0.150468 0.91677 0.369991 -0.4408 0.656736 0.611877 -0.550005 0.359018 0.754056 -0.374442 0.709497 0.596998 -0.107774 0.982083 0.154587 -0.451601 0.18381 0.873081 -0.369659 0.312932 0.874886 0.499576 3.08761e-06 0.86627 0.499572 -5.2122e-06 0.866273 0.499422 0.000238562 0.866359 0.499553 0.000102972 0.866283 0.499539 -0.00017602 0.866291 0.499518 -0.000219032 0.866303 0.499567 5.26585e-06 0.866275 0.499567 4.98726e-06 0.866275 0.499343 -0.000365296 0.866405 0.499569 -5.99266e-07 0.866274 -0.499566 4.64985e-07 -0.866276 -0.499577 -5.26795e-06 -0.86627 0.8607 0.11363 -0.49627 0.862258 0.104719 -0.495526 0.746327 0.499908 -0.439417 0.72439 0.555214 -0.408653 0.394745 0.889147 -0.231504 0.429453 0.87101 -0.238561 0.0983719 0.992699 -0.0697947 -0.0661538 -0.98996 0.124911 -0.279478 -0.898946 0.337324 -0.357609 -0.763616 0.537593 -0.651803 -0.12402 0.748179 -0.569425 -0.314227 0.759616 -0.447883 -0.170582 0.877669 -0.522072 -0.550056 0.651828 -0.278974 -0.724204 0.630636 -0.383143 -0.285916 0.878324 -0.996163 -4.3295e-06 -0.0875118 -0.996164 -1.11058e-06 -0.0875098 -0.996163 -1.69476e-05 -0.0875116 0.905966 1.96874e-06 0.42335 0.905975 4.82587e-05 0.42333 0.33629 0.910757 0.239646 0.905985 -9.69909e-05 0.423311 0.0435964 -0.990364 0.131446 -0.302862 -0.581495 0.755075 0.308905 -0.699584 0.644329 -0.0234923 -0.162396 0.986446 -0.00331502 -0.215592 0.976478 0.0376872 -0.413756 0.909607 -0.0669041 -0.704829 0.706215 -0.000565018 -0.799181 0.60109 0.0201514 -0.960737 0.276727 0.0476007 -0.962015 0.268815 0.127056 -0.490366 0.862205 0.0882167 -0.76063 0.643164 0.243526 -0.334677 0.910322 0.241209 -0.349739 0.905263 0.136568 -0.837121 0.529696 -0.76698 0.000103002 0.641671 -0.214613 0.932135 0.291659 -0.766979 0.00010611 0.641673 0.939569 3.30152e-05 -0.342359 0.939579 -2.73474e-05 -0.342333 0.406519 0.911063 -0.0686035 0.93957 4.12421e-05 -0.342356 0.731449 -0.650224 0.205404 0.125597 -0.990277 0.059807 0.437798 -0.524375 0.730318 0.682374 0.0213315 0.730692 0.424612 -0.79131 0.439925 0.493588 -0.592352 0.636781 0.812853 -0.405651 0.417992 0.179848 -0.957305 0.226321 0.69349 -0.386726 0.607877 0.156541 -0.977167 0.143663 0.721704 -0.446797 0.528693 0.503225 -0.771355 0.389584 0.416936 -0.870954 0.260007 0.206049 -0.967991 0.143312 0.787164 -0.374656 0.489903 -0.0874743 -6.59736e-06 0.996167 -0.0873677 0.000112873 0.996176 -0.0874741 -0.000273747 0.996167 0.0221096 0.937472 0.347359 0.423417 0 -0.905935 0.423398 4.48329e-05 -0.905944 0.251096 0.892172 -0.375474 0.423352 -0.000167745 -0.905965 0.160978 -0.986701 -0.0225311 0.657008 -0.734158 0.171326 0.74644 -0.656662 0.107809 0.9594 -0.240912 -0.146672 0.942798 -0.330532 0.0433653 0.69296 -0.714708 -0.0948636 0.346156 -0.938164 -0.00494145 0.823711 -0.50391 -0.259951 0.863408 -0.0818367 -0.497825 0.858124 -0.11969 -0.499297 0.803972 -0.381896 -0.455835 0.759308 -0.471727 -0.448246 0.569344 -0.759333 -0.315057 0.490908 -0.819621 -0.295348 0.146114 -0.986282 -0.0767991 0.110237 -0.991871 -0.063561 0.716443 0.0131596 -0.697521 0.758407 -0.00820714 -0.65173 0.498856 -8.76785e-05 0.866685 0.499368 -6.90122e-06 0.86639 0.499527 6.95593e-05 0.866299 0.499524 7.32953e-05 0.8663 0.755106 0.000154803 0.655603 0.756128 -0.000815264 0.654423 0.755386 8.39692e-05 0.65528 0.75539 -3.44931e-05 0.655276 0.669291 -0.244614 0.70158 0.920471 0.325773 -0.215883 0.293268 0.851833 -0.434021 0.914261 0.405116 -0.00287878 0.303922 0.852269 -0.425757 -0.282954 0.562785 -0.776666 0.264014 0.589013 -0.763781 -0.559666 0.569939 -0.601618 0.617754 0.646998 -0.446961 -0.258932 0.895373 -0.362301 0.879325 0.396948 -0.263098 0.00364094 -0.989531 -0.144278 -0.0357649 -0.990815 -0.130412 -0.0282962 -0.992552 -0.118491 0.580703 -0.0566255 -0.812144 0.735843 0.00163192 -0.677151 0.789142 0.352518 -0.502977 -0.288779 0.851512 0.437647 -0.926923 0.295827 0.230869 -0.948429 0.0393459 -0.314537 -0.996397 -0.0301532 -0.0792701 -0.0108771 0.993305 0.115009 0.00761719 0.974528 0.224136 -0.0484951 0.991381 0.121707 0.680834 0.330254 0.653757 0.755562 -0.000762729 0.655076 0.756974 -0.000217061 0.653445 0.223272 -0.737913 0.636894 0.534789 0.00686278 -0.844958 0.516365 0.00282087 -0.856364 0.557542 -0.00176394 -0.830147 0.628859 0.00795228 -0.777479 0.617069 0.00052003 -0.786909 -0.872658 -0.00426782 -0.488314 -0.865721 1.26211e-06 -0.500527 0.992445 0.0555556 -0.109395 0.998591 -0.0026419 0.0529973 -0.971447 -0.000484519 -0.237256 -0.972463 0.000927631 -0.233057 0.277003 -0.00175272 -0.960868 0.281399 0.000259177 -0.959591 0.367359 -0.00185388 -0.930077 0.36504 -0.000341661 -0.930992 0.988077 -0.00369603 0.153919 0.990058 0.000484227 0.140656 -0.998251 -0.00366569 0.0590092 -0.998878 -0.000126967 0.0473666 -0.00402381 0.00829051 -0.999958 -0.067875 -0.00956885 -0.997648 0.0483848 -0.00588709 -0.998811 0.106062 0.000285028 -0.99436 0.100071 0.00215012 -0.994978 0.991827 -0.00440448 -0.127513 0.989888 -2.71616e-07 -0.141852 -0.27998 0.00563918 -0.959989 -0.304618 0.000572699 -0.952475 -0.253919 -0.0021712 -0.967223 -0.190743 0.000195489 -0.98164 -0.183426 -0.00343164 -0.983027 -0.96414 -0.00332887 -0.265373 -0.952912 -0.00780983 -0.303145 -0.765945 0.641633 -0.0404527 0.859457 0.374021 -0.348485 0.466707 -0.0380991 -0.883591 -0.0600605 -0.707081 -0.704578 -0.122369 -0.363239 -0.923625 -0.302264 -0.405473 -0.862686 -0.194596 -0.492172 -0.848469 -0.26909 -0.769842 -0.578734 0.0397541 -0.893763 0.446773 0.102808 -0.96428 0.244119 -0.0622546 -0.993076 -0.0996174 -0.165698 -0.805606 -0.568808 -0.225378 -0.285242 -0.93158 -0.223696 -0.486856 -0.844353 -0.0178983 -0.976712 -0.213809 -0.0989947 -0.606997 -0.788514 0.00866804 -0.676953 -0.735975 0.050303 -0.866582 -0.496493 -0.0347752 -0.955668 -0.292387 0.01565 -0.958455 0.284813 0.126824 -0.581335 -0.80372 0.0512877 -0.437322 -0.897841 0.139161 -0.347543 -0.92728 -0.0614951 -0.863219 0.50107 -0.0408722 -0.98988 0.135896 0.0508926 -0.43721 -0.897918 0.0558917 -0.284863 -0.956937 0.0212099 -0.3326 -0.94283 0.0382976 -0.991504 -0.124308 0.960583 -0.00445529 -0.277959 0.989902 -8.0882e-05 -0.141755 0.989922 0.000353742 -0.141614 0.989857 0.000215548 -0.142067 0.989937 0.000245812 -0.141509 0.970238 -0.0685632 0.232243 0.849277 -0.526184 0.0431206 0.849377 -0.494619 -0.184151 -0.0961793 -0.974862 0.20098 0.432711 -0.765785 -0.475746 0.550319 -0.49925 -0.669252 0.551473 -0.406298 -0.72856 0.587626 -0.345802 -0.731516 0.486327 -0.426338 -0.762707 0.467138 -0.40411 -0.786433 0.483824 -0.585822 -0.650175 0.267505 -0.712297 -0.648902 0.462756 -0.576732 -0.673229 0.335267 -0.827887 -0.449666 0.148747 -0.96383 -0.221146 -0.329701 -0.834887 0.44075 0.55327 -0.276222 -0.785871 0.16729 -0.959404 -0.227064 -0.101564 -0.989759 0.100307 -0.000145612 -1 -0.000491261 -0.000228144 -1 -0.0003755 -0.000620038 -1 -0.000339799 -0.000562358 -1 -0.000353049 -0.00126448 -0.999999 5.77858e-05 -0.000621364 -1 -0.000540211 -0.000769125 -0.999999 0.001413 -0.000941503 -1 -0.000154676 0.00901815 0.999957 0.00201668 0.00108469 0.999999 0.000593646 -0.00057006 -1 -0.000409291 -0.000421087 -1 -0.000450847 -0.000595974 -1 6.18568e-05 -0.000359451 -1 -0.000529705 -0.0938436 -0.960824 0.260789 -0.0172972 -0.933665 0.35773 0.0630463 -0.95488 0.290223 -0.380139 -0.326317 0.865454 -0.15914 -0.663338 0.731202 -0.411415 -0.805555 0.426402 -0.965667 -0.00266068 0.259769 -0.945485 -0.0149024 0.325325 -0.807703 -0.445812 0.385834 -0.714977 -0.662856 0.222331 -0.660589 -0.727482 0.185452 -0.778523 -0.594537 0.201065 -0.793086 -0.566211 0.224542 -0.854163 -0.444438 0.269965 -0.967515 -0.169719 0.187377 -0.98275 -0.177094 -0.0532899 -0.925222 -0.1958 -0.325002 -0.81185 -0.140011 -0.56683 -0.596879 -0.166242 -0.78492 -0.599409 -0.12159 -0.791154 -0.939045 -0.0907316 -0.331606 -0.994114 -0.0924662 -0.0564587 -0.951285 -0.00359674 0.308291 0.943751 0.105377 -0.313415 -0.777727 -0.443543 0.445432 -0.764345 -0.456914 0.45498 -0.732199 -0.572194 0.369431 -0.642046 -0.671164 0.370563 -0.615552 -0.728849 0.29979 -0.502975 -0.822208 0.266439 -0.476828 -0.836685 0.269431 -0.915129 -0.0214946 0.402588 -0.913056 -0.0965755 0.396236 -0.90954 -0.104904 0.40216 -0.863124 -0.330948 0.381432 -0.878396 -0.310015 0.363746 -0.812203 -0.444335 0.378013 -0.771839 -0.545644 0.326401 -0.75054 -0.572366 0.330284 -0.695441 -0.659114 0.286234 -0.636523 -0.718118 0.281327 -0.397532 -0.899157 0.182991 -0.321072 -0.934594 0.153123 -0.931225 -0.105298 0.348902 -0.931676 -0.183987 0.313254 -0.885292 -0.326513 0.331131 -0.882445 -0.331226 0.334035 -0.848725 -0.44439 0.286676 -0.797543 -0.526596 0.294316 -0.591423 -0.778903 0.208638 -0.531256 -0.823837 0.197635 -0.438824 -0.886088 0.149267 -0.456206 -0.877402 0.148467 -0.287054 -0.950976 0.115087 -0.962559 -0.0151699 0.270647 -0.953693 -0.159397 0.255072 -0.944381 -0.190206 0.268266 -0.911924 -0.32696 0.247977 -0.912133 -0.326586 0.247698 -0.85452 -0.310901 0.416096 -0.863971 -0.133776 0.485446 -0.878816 -0.103885 0.465714 -0.883417 0.000471153 0.468588 -0.883613 0.000367231 0.468218 -0.916337 -0.00091995 0.400407 -0.915003 0.000495 0.403447 0.866311 -1.47916e-06 -0.499506 0.866314 1.7481e-06 -0.4995 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.866759 4.13647e-07 -0.498727 0.86667 8.83613e-05 -0.498882 0.866281 -0.000521512 -0.499557 0.866405 0.000194596 -0.499342 0.108781 0.994048 0.00590172 0.107844 0.993788 -0.027486 0.107169 0.994042 -0.0198593 0.113181 0.993553 -0.00659787 0.109392 0.993845 -0.0174919 0.11182 0.993684 0.0094588 0.98994 0 0.141489 0.990727 0.00242365 0.135848 0.999205 -0.00319707 0.0397365 0.99927 -0.00207083 0.0381427 0.997441 0.00791448 -0.0710584 0.994301 -0.0111537 -0.106027 0.981973 0.0106194 -0.188722 0.9763 -0.00363319 -0.216389 0.108005 -0.993981 -0.0183641 0.109886 -0.993691 -0.0224419 0.112436 -0.993645 -0.00535818 0.110555 -0.993867 -0.00250581 0.111529 -0.993683 0.0124433 0.110703 -0.993791 0.0111192 0.108957 0.99399 0.0106173 0.112161 0.99369 -0.000442195 0.110156 0.993908 -0.00350917 0.109969 0.993845 -0.0133705 0.106702 0.994116 -0.0186503 0.108413 0.993775 -0.0256492 0.111068 0.993687 0.0158394 0.110224 -0.99375 0.0176764 0.108524 -0.994046 0.00980518 0.112331 -0.993665 0.00331616 0.107445 -0.99413 -0.0127107 0.10841 -0.994033 -0.0120547 0.109921 -0.993572 -0.0270548 0.978814 0.00590652 -0.204665 0.979379 0 -0.202032 0.99669 0 -0.0812908 0.99669 0 -0.0812908 0.999281 0 0.0379248 0.999281 0 0.0379248 0.9875 0 0.157621 0.9875 0 0.157621 0.965766 1.80147e-06 0.259414 0.965766 0 0.259414 0.965766 0 0.259414 0.966844 -7.26222e-07 0.255367 0.965766 0 0.259414 0.968257 -0.00523997 0.249902 0.96827 0 0.249905 0.966822 0.00682302 0.255361 0.505607 0 0.862764 0.926251 0.00718675 0.376838 0.924997 0 0.379974 0.866332 0 0.499469 0.866332 0 0.499469 0.79836 0 0.602181 0.79836 0 0.602181 0.717667 0 0.696387 0.71327 -0.010664 0.700808 0.625415 0.0094622 0.780235 0.601946 -0.0358448 0.797732 0.505606 -2.81224e-07 0.862765 0.505609 7.03031e-07 0.862763 0.505607 0 0.862764 0.468508 6.30662e-05 0.883459 0.469568 -4.05253e-05 0.882896 0.468509 0 0.883459 0.415386 0 0.909645 0.556436 0 0.83089 0.505607 0 0.862764 0.505607 0 0.862764 0.468508 0 0.883459 0.468508 0 0.883459 -0.253864 0.00334468 0.967234 0.415386 0 0.909645 0.31405 0 0.949406 0.31405 0 0.949406 0.200637 0 0.979666 0.200637 0 0.979666 0.0839544 0 0.99647 0.0839544 0 0.99647 -0.0352299 0 0.999379 -0.0352229 1.16516e-05 0.99938 -0.156311 -5.10311e-05 0.987708 -0.259312 -0.00208976 0.965792 -0.2557 -8.77888e-05 0.966756 -0.255693 -0.00627159 0.966738 -0.249202 0.00184283 0.96845 -0.254766 -0.000127121 0.967003 -0.25387 -0.00124062 0.967238 -0.378563 -0.000706107 0.925575 -0.375969 -0.00658903 0.926609 -0.498119 1.29714e-06 0.867109 -0.49812 0 0.867108 -0.600898 0 0.799326 -0.600898 0 0.799326 -0.69386 0 0.720109 -0.685497 0.0189567 0.727828 -0.377185 -0.001927 0.926136 -0.376342 0 0.926481 -0.49812 0 0.867108 -0.49812 0 0.867108 -0.600898 0 0.799326 -0.600898 0 0.799326 -0.693577 0 0.720383 -0.693147 0.000993576 0.720796 0.415291 -3.25969e-06 0.909688 0.31405 -2.48609e-06 0.949406 0.314051 0 0.949406 0.200637 0 0.979666 0.200637 0 0.979666 0.0839544 0 0.99647 0.0839544 0 0.99647 -0.0352229 0 0.99938 -0.0352451 -3.66535e-05 0.999379 -0.155912 4.24948e-05 0.987771 0.788164 -0.0411082 0.614091 0.71913 0.0323012 0.694125 0.73102 -0.0103702 0.682278 0.627627 0.0249838 0.778113 0.590317 -0.0343918 0.806439 0.558383 7.80021e-07 0.829583 0.846512 0.0442055 0.530531 0.858252 0.00193919 0.513225 0.927358 -0.0247043 0.373359 0.933009 0.00541466 0.359811 0.966842 0.00507003 0.255326 0.966855 -2.02356e-05 0.255328 0.9875 1.83936e-06 0.15762 0.9875 0 0.157621 0.999281 0 0.0379248 0.999281 0 0.0379248 0.99669 0 -0.0812908 0.99669 0 -0.0812908 0.979379 0 -0.202032 0.978814 0.00590652 -0.204664 0.103832 0.993753 0.0409137 0.0980326 0.994083 0.0467755 0.0986809 0.993837 0.0504901 0.0951873 0.993599 0.060826 0.0835926 0.994138 0.068569 0.0863056 0.993926 0.068277 0.0662873 0.993747 0.089853 0.0691121 0.993986 0.0849439 0.0759864 0.993657 0.0828912 -0.0103521 0.99414 0.107602 -0.0187213 0.99376 0.109957 0.000672436 0.99337 0.114963 0.0424345 0.993724 0.103498 0.037052 0.994075 0.102188 0.024897 0.99357 0.11045 0.0145952 0.994316 0.105461 -0.0464964 0.993809 0.100908 -0.0460843 0.993704 0.102123 -0.0572763 0.994187 0.0911676 -0.0671491 0.99358 0.0910441 -0.0754565 0.993946 0.0798614 -0.0752114 0.993641 0.0837906 -0.0753399 0.993593 0.0842395 -0.0687193 0.99409 0.0840453 -0.0445691 0.993545 0.104318 -0.0495629 0.994116 0.0963211 -0.0571275 0.993694 0.0964778 -0.0434528 -0.993817 0.102174 -0.0578989 -0.993571 0.0972867 -0.0620131 -0.994071 0.0893101 -0.0732191 -0.993651 0.0854154 -0.0736761 -0.993961 0.0813177 -0.0744534 -0.99402 0.0798765 -0.0742992 -0.993659 0.0843884 -0.0434432 -0.993648 0.10381 -0.0598957 -0.994064 0.0908297 -0.0591707 -0.993665 0.0955448 -0.0443922 -0.993803 0.101907 -0.386511 0.006675 0.922261 -0.41203 -0.0104863 0.91111 -0.501453 0.00705763 0.865156 -0.516225 -0.00272522 0.856449 -0.598311 0.00273027 0.801259 -0.605926 -0.00273913 0.795516 -0.676903 0.00222799 0.736069 -0.671842 0.00530148 0.740675 0.0374111 -0.994095 0.101864 0.0441493 -0.993725 0.102771 0.028616 -0.993532 0.109884 -0.00717922 -0.994024 0.108926 -0.0056542 -0.993862 0.110486 0.00996152 -0.993761 0.111081 0.0146313 -0.994159 0.10693 -0.0198711 -0.99372 0.110119 0.0697859 -0.994234 0.0814214 0.0674826 -0.993687 0.0896234 0.0840136 -0.993865 0.0719305 0.0841062 -0.993707 0.0739804 0.0925523 -0.994323 0.0524948 0.0971639 -0.993911 0.0519663 0.1054 -0.993507 0.0428386 0.0571878 0.996588 -0.0595184 -0.623738 -0.699711 -0.348361 -0.107491 -0.867398 -0.485866 -0.312094 0.925213 -0.215821 -0.303969 0.847356 -0.435419 -0.784157 0.365142 -0.501766 -0.756432 0.143284 -0.638185 -0.795309 0.0193736 -0.605895 -0.210151 -0.930937 -0.298653 -0.64708 0.531419 -0.546701 0.573378 0 0.819291 0.659851 0 0.751397 0.659851 0 0.751397 0.738829 0 0.673894 0.738829 0 0.673894 0.808364 0 0.588683 0.808364 0 0.588683 0.861103 0 0.508431 0.861103 0 0.508431 0.905816 0 0.42367 0.905816 0 0.42367 0.946352 0 0.323138 0.946352 0 0.323138 0.975735 0 0.218954 0.975735 0 0.218954 0.993709 0 0.11199 0.993793 0.000238471 0.111249 0.468854 0.00375194 0.883268 0.572878 -0.000163131 0.819641 0.481487 0 0.876453 0.386724 0 0.922195 0.386724 0 0.922195 0.288318 0 0.957535 0.288318 0 0.957535 0.186735 0 0.98241 0.186735 0 0.98241 0.082118 0 0.996623 0.082118 0 0.996623 -0.0201182 0 0.999798 -0.0201182 0 0.999798 -0.123731 0 0.992316 -0.123731 0 0.992316 -0.229845 0 0.973227 -0.229845 0 0.973227 -0.33351 0 0.942747 -0.33351 0 0.942747 -0.428137 0 0.903714 -0.428146 -2.43801e-06 0.903709 0.00192096 0.999991 0.00380868 -1.61388e-05 1 -2.70494e-05 7.01433e-06 1 0.000576261 2.58358e-05 1 0.000353629 0.00120856 -0.999993 -0.00363704 0.00131845 0.999999 0.00028706 0.000517548 -0.999997 -0.00219417 -0.000323488 1 -0.000496035 -0.000325848 1 -0.000498148 0.000139641 1 -0.000539086 -3.41741e-06 1 -0.000626591 -0.0001696 1 -0.000846452 -0.000179263 1 -0.000794691 -0.000275869 1 -0.000552884 -0.670991 0.34567 -0.65596 -0.517334 0.375013 -0.769241 0.98877 -0.00646375 0.149307 0.989754 2.1181e-05 0.142786 0.989757 1.32511e-05 0.142765 0.989757 0.000527927 0.14276 0.998213 -0.0137143 0.0581526 0.780278 -0.520454 0.346834 0.859387 -0.501577 0.0993699 0.156098 0.452968 -0.877755 0.520813 0.535751 -0.664623 0.71242 0.345713 -0.610689 0.0624323 0.933094 -0.354172 0.941963 0.27509 -0.192436 -0.844864 0.534295 -0.0270796 0.230935 0.751746 -0.617695 -0.346854 0.856237 -0.38282 -0.347941 0.490717 -0.798833 0.78921 0.517171 -0.331181 0.304368 0.928278 -0.213681 -0.816079 0.467826 -0.339343 -0.634072 0.539774 -0.553712 0.810818 0.484216 -0.328798 -0.766022 0.63022 -0.126621 0.911897 0.00139091 -0.410418 0.91184 0.0013519 -0.410543 -0.944784 -0.00368872 0.327674 0.445909 0.894803 0.0221965 0.932631 0.00253892 -0.360824 0.430689 0.0431377 -0.901469 0.824385 -0.0412677 -0.564523 -0.822856 0.370732 0.430657 0.921601 0.362625 -0.138399 -0.928166 -0.0433285 -0.369636 -0.969153 0.000104738 -0.246461 0.682323 0.0176327 -0.730838 0.70087 0.00788388 -0.713246 0.998161 -0.00874835 -0.0599783 -0.893094 0.449372 -0.0211842 -0.929465 0.327088 -0.170614 0.874595 0.282192 0.394272 0.33885 0.712405 0.61454 -0.730363 0.0337398 -0.682226 -0.742487 0.027793 -0.669283 -0.0788893 -0.0237569 -0.9966 -0.58521 0.803778 0.107098 -0.811035 0.275159 -0.516247 -0.653144 -6.70632e-05 -0.757234 -0.536764 -0.0470036 -0.842422 0.872387 -0.00632335 -0.488775 0.9386 0.00779362 0.34492 -0.592883 -0.0068479 -0.80526 -0.801384 0.354688 -0.481643 -0.813823 0.341033 -0.470519 0.572128 0.289866 -0.767233 -0.427422 0.00818108 -0.904015 -0.668313 -0.0158761 -0.743711 -0.855432 0.517556 -0.0193116 -0.909691 0.345892 -0.229829 0.992192 -0.0182528 -0.12338 0.746593 0.557095 0.363654 0.834084 -0.0323595 -0.550688 -0.831361 0.551757 -0.0663631 -0.877981 0.47702 0.0400162 0.915956 0.397573 -0.0544079 -0.726864 -0.361111 0.584182 -0.996255 -0.0389945 0.0771671 -0.985417 -0.00338732 0.170126 3.69072e-05 1 -0.000824403 -0.40442 0.0102636 -0.914516 -0.455596 -0.00323696 -0.890181 -0.48848 0.00448563 -0.872563 -0.534989 -0.00386092 -0.84485 -0.91339 -0.318224 -0.253875 0.212143 -0.955365 0.205605 0.188664 4.27997e-05 0.982042 0.218013 0.000554434 0.975946 0.188654 -3.89172e-05 0.982044 0.188036 0.000799972 0.982162 -0.482347 0.473847 0.736757 0.0791611 -0.114985 0.990208 -0.0252247 -0.0309153 0.999204 0.081983 -0.00139467 0.996633 0.268701 0.747012 0.608089 0.226986 0.805537 -0.547346 -0.15641 0.985934 -0.0589076 -0.761403 0.453831 -0.462929 -0.209631 0.174789 -0.962031 -0.412297 -0.00655632 -0.911026 -0.445113 -0.0717603 -0.892595 -0.942828 0.0906431 -0.320717 -0.817625 0.113827 -0.564387 -0.620073 0.107396 -0.777159 -0.611161 0.18931 -0.768533 -0.810773 0.167232 -0.560964 -0.927842 0.196048 -0.317292 -0.985891 0.161377 -0.0444661 -0.891758 0.401016 0.209651 -0.84683 0.465999 0.256367 -0.724403 0.656245 0.211148 -0.721798 0.660829 0.205701 -0.804213 0.532334 0.264316 -0.5892 0.78971 0.170885 -0.914842 -0.000654289 0.40381 -0.908465 0.000474162 0.41796 -0.918385 -0.00957243 0.395573 -0.906555 -0.00128472 0.422085 -0.915443 0.0197161 0.401964 -0.914822 -0.00163187 0.403854 -0.958212 0.0346003 0.28396 -0.43518 0.887171 0.153447 -0.422243 0.8928 0.156907 -0.552019 0.812638 0.186801 -0.882884 0.330518 0.333577 -0.901289 0.298636 0.313839 -0.932755 0.105188 0.344823 -0.915037 0.305571 0.263312 -0.955741 0.171611 0.238973 -0.957599 0.0331498 0.28619 -0.28593 0.949696 0.127756 -0.598128 0.751003 0.279709 -0.689266 0.667946 0.280645 -0.752961 0.564187 0.338736 -0.767257 0.547788 0.333536 -0.861594 0.341043 0.375959 -0.861651 0.34096 0.375905 -0.907155 0.110729 0.405967 -0.915001 0.0916878 0.392895 -0.914838 -0.0015958 0.403818 -0.883613 0.000379254 0.468218 -0.884379 -0.000164234 0.46677 -0.883564 -0.00185107 0.468306 -0.87831 0.0981018 0.467919 -0.88165 0.110936 0.458678 -0.83255 0.321267 0.451273 -0.835543 0.341237 0.430611 -0.725496 0.561081 0.398553 -0.725793 0.563952 0.393932 -0.598836 0.75072 0.278953 -0.514678 0.803841 0.298238 -0.418013 0.887672 0.193139 -0.317963 0.932039 0.17379 -0.566037 -0.824096 -0.0216402 -0.0861732 0.0118061 0.99621 -0.397777 -0.0824627 0.913769 0.499482 8.70229e-05 0.866324 0.499813 -6.01132e-05 0.866133 0.498113 0.000176845 0.867112 0.499532 -1.33841e-07 0.866295 0.423368 -3.15434e-07 -0.905958 0.423368 0 -0.905958 -0.000177619 -0.99354 0.113483 0.0148649 -0.994069 0.107732 0.0176249 -0.993804 0.109737 0.0369461 -0.993959 0.103351 0.0410144 -0.99361 0.105155 -0.0151546 -0.994261 0.105903 -0.0112636 -0.993625 0.112171 0.0662594 -0.993762 0.0897051 0.0688396 -0.993981 0.0852209 0.0762508 -0.993628 0.0829997 0.0976284 -0.993565 0.0574218 0.0890167 -0.993699 0.0681093 0.0837678 -0.994115 0.0686854 0.103914 -0.993645 0.0432623 0.0982396 -0.994065 0.0467325 -0.99616 -0.000348659 -0.0875499 -0.996132 -1.39158e-05 -0.087873 0.905974 -2.19376e-06 0.423334 0.905975 -6.38212e-07 0.423332 -0.0181932 0.993773 0.109925 -0.0123666 0.994092 0.107838 0.00150126 0.9935 0.113826 0.0126915 0.994262 0.106216 0.0199864 0.99367 0.110542 0.0472655 0.993793 0.100703 0.0375903 0.994092 0.101826 0.0346081 0.993758 0.106057 0.766914 0.000317636 -0.64175 -0.767024 -1.78586e-07 0.641619 -0.766942 -9.07458e-05 0.641716 0.93957 -1.06449e-05 -0.342356 0.939577 -3.1792e-05 -0.342337 0.105416 0.993506 0.0428274 0.0949398 0.994191 0.0507034 0.0963182 0.993716 0.0570195 0.0823252 0.994049 0.0713341 0.0695547 0.994081 0.0834596 0.0822857 0.993602 0.0773587 0.0668747 0.993678 0.0901723 -0.0874367 4.29541e-08 0.99617 -0.0874366 0 0.99617 0.122619 0.956123 0.266071 0.570415 0.55432 -0.6061 0.381984 0.290954 0.877174 0.887799 0.349789 -0.2991 -0.134666 0.909773 -0.392656 -0.27488 0.832512 -0.481003 -0.648007 0.543481 -0.533587 -0.285913 -0.915606 -0.282698 0.479852 0.867798 -0.12911 -0.00131279 0.999991 -0.00413262 -0.000439463 1 2.12706e-05 -0.000123107 1 -0.000770487 -0.000388783 1 -0.000439507 0.00313982 0.99999 0.00333906 -0.000336034 1 -0.000491921 -0.000469145 1 -0.000439756 -0.000122995 1 -8.58496e-05 -0.000119605 1 -6.00534e-05 -4.96755e-05 1 -0.000276804 -0.000720125 0.999999 0.00129317 -0.000448314 0.99999 0.00438037 0.000187444 0.999994 -0.00342906 -0.000934135 0.999999 0.000392661 0.540261 0.35945 -0.760864 0.516219 0.48418 -0.706461 0.404102 0.733531 -0.546475 0.0597725 0.996972 -0.0497416 -0.00185406 0.999515 -0.0310966 -0.240528 0.891138 0.384734 0.541361 0.362368 -0.758694 0.455569 0.562289 -0.690136 0.262486 0.869091 -0.419264 0.258621 0.895055 -0.363306 -0.273272 0.879827 0.38888 0.85981 0.484399 -0.161506 0.910601 0.407415 0.0694229 0.778387 0.615753 0.12232 0.821177 0.553173 0.140239 0.113416 0.354895 -0.928001 0.12347 0.600177 -0.79028 0.00555926 0.474617 -0.880175 -0.0291179 0.502627 -0.864013 -0.0147292 0.836161 0.548287 0.0350858 0.978382 -0.203809 0.0487288 0.476652 -0.87774 0.0554299 0.304691 -0.950837 -0.0519723 0.953495 0.296895 0.0231105 0.988119 0.15194 -0.0199557 0.999208 -0.0344272 -0.00221297 0.936069 -0.351808 0.0385021 0.859596 -0.509521 0.00716001 0.78084 -0.624691 0.0440491 0.676566 -0.735063 0.0167141 0.331634 -0.94326 -0.0745399 0.875209 -0.477968 -0.138519 0.567104 -0.811915 0.0153299 0.994187 -0.106572 0.184814 0.894527 0.40702 -0.240135 0.455478 -0.857249 -0.270122 0.319212 -0.908371 -0.237273 0.281172 -0.929862 -0.168879 0.337835 -0.92593 -0.191872 0.487921 -0.851539 -0.183307 0.743268 -0.64339 -0.00911518 0.984299 0.176276 -0.0859744 0.967493 -0.237834 0.989299 0.000777533 -0.145904 0.989898 0.000380668 -0.141781 0.98925 0.000421219 -0.146232 0.989876 -0.00041006 -0.141935 0.395875 -0.026917 -0.91791 0.67186 0.00468273 -0.740663 0.762251 -0.631922 -0.140171 0.818421 -0.352714 -0.453629 -0.648864 0.426361 -0.630232 -0.88337 -0.037768 0.467152 -0.0135356 -0.955089 0.296009 -0.99901 0.00368295 -0.0443391 -0.287388 -0.00907499 -0.957771 -0.308943 -0.00366127 -0.951073 -0.250562 0.0027136 -0.968097 -0.175238 0.000749163 -0.984526 -0.181219 0.00373614 -0.983436 0.990543 0.00036679 -0.137204 0.989712 0.00181811 -0.143065 0.105946 0.00149523 -0.994371 0.106307 0.00165064 -0.994332 0.0530462 -0.0048055 -0.998581 0.0196378 0.0031893 -0.999802 -0.0316321 -0.00444492 -0.99949 -0.0279002 -0.0031085 -0.999606 -0.999263 0.00137199 0.0383616 -0.999053 8.21321e-05 0.0435064 0.98796 -0.000891185 0.154707 0.988998 0.000607196 0.147929 0.38099 0.00327554 -0.924573 0.384906 0.00151928 -0.922955 0.311589 2.8597e-05 -0.950217 0.313395 0.000670705 -0.949623 0.271326 -0.000329144 -0.962488 0.270087 2.13854e-05 -0.962836 -0.974691 0.00192197 -0.22355 -0.972075 -0.00155985 -0.234667 0.966708 -0.000446798 0.255883 0.998238 0.0490098 0.0334423 0.846928 -0.0428516 -0.529978 -0.868674 -0.0015353 -0.495382 -0.865767 -2.43548e-05 -0.500448 0.532269 -0.00820578 -0.846536 0.52762 -0.0071391 -0.84945 0.560465 0.00226629 -0.828175 0.618228 0.000411802 -0.785998 0.615739 -0.000920409 -0.787949 -0.0026864 0.999996 0.00129765 -0.0074952 0.999959 0.00508094 0.906688 0.00116813 0.421801 0.907817 0.00028003 0.419367 -0.00450888 0.999977 0.00498726 0.00278937 0.999979 -0.00581134 0.850878 0.348973 0.392714 0.000308401 0.999958 -0.00916965 0.0025776 0.999996 0.00105914 0.00430936 0.998871 -0.0473187 0.000272714 0.999915 0.0130359 0.208827 -0.0258685 -0.97761 -0.812418 0.000107827 0.583076 -0.812563 3.43459e-05 0.582874 0.00254075 -0.999995 0.00179357 -0.00473116 -0.999974 -0.00542605 -0.944704 -0.00061825 0.327925 -0.945232 0.00769759 0.326309 -0.944984 0.00042383 0.327116 -0.945168 0.000215242 0.326586 -0.945237 0.000631623 0.326385 -0.94602 0.0114899 0.323905 -0.998899 8.19914e-06 0.0469186 -0.998881 0.000482749 0.0472825 -0.998881 -0.000182829 0.0472869 -0.998868 0.000362605 0.047564 -0.865734 -7.52157e-06 -0.500505 -0.873845 0.0243688 -0.485593 -0.865134 0.00169825 -0.501538 -0.865696 -2.27868e-05 -0.50057 -0.863296 -0.00302301 -0.504689 -0.86572 -0.00010015 -0.500529 -0.444543 -0.315491 0.83836 -0.138315 0.662956 0.73577 -0.972579 -0.00529449 0.232512 -0.946141 -0.197324 0.256672 -0.943992 0.00904521 0.329845 -0.927004 -0.0917253 0.363663 -0.901134 -0.00639566 0.433493 -0.893713 0.0169115 0.448321 -0.904585 -0.00193847 0.426289 -0.0060351 0.136837 0.990575 -0.147565 -0.255361 0.955518 -0.343301 -0.0521907 0.937774 -0.172507 0.00765419 0.984979 -0.414526 0.863682 -0.286743 0.0241601 0.315648 0.948569 -0.158323 0.659349 0.734979 -0.439917 0.814505 0.378226 -0.334101 0.389289 0.858388 -0.328788 0.381415 0.863956 -0.48274 -0.0382625 -0.874928 0.183331 0.352484 -0.917684 -0.67983 -0.0199605 -0.733098 -0.592212 -0.656644 -0.467016 0.105675 -0.194356 -0.975222 -0.146727 0.989078 0.0139696 -0.314241 0.779269 -0.542211 -0.539404 -0.283512 0.792884 -0.261156 -0.939492 0.221702 -0.782743 -0.621672 -0.0289382 -0.429199 -0.420588 -0.799309 -0.158751 -0.546843 -0.822047 -0.197132 -0.80285 -0.562646 -0.131195 -0.776972 -0.615712 -0.525851 -0.23931 0.816218 -0.679729 -0.722492 -0.126387 -0.611215 -0.7686 0.188864 -0.104551 0.990495 -0.0893838 0.54988 -0.834525 -0.0346344 0.703918 -0.293609 -0.646756 0.115476 -0.991344 0.0624643 -0.663798 -0.475704 -0.57713 0.132763 -0.990843 0.0245986 0.126275 -0.991755 0.021817 0.148704 -0.988796 -0.0129946 0.232122 -0.322269 0.917748 0.192584 0.00117511 0.98128 0.207012 0.00586572 0.978321 0.344539 0.590875 0.729493 0.163186 0.363016 0.917382 -0.131873 0.00516575 0.991253 -0.109107 -0.00634458 0.99401 -0.0347432 0.0091619 0.999354 0.0128821 -0.0114223 0.999852 0.0740853 0.00729469 0.997225 0.140714 -0.00711319 0.990025 0.160383 0.00327217 0.98705 0.266373 -0.00382062 0.963863 0.277341 0.00384873 0.960764 0.379502 -0.00330284 0.925185 0.385366 0 0.922764 0.607437 0.00549974 0.794349 0.629858 -0.00928096 0.776655 0.686976 0.00984952 0.726614 0.722109 -0.0108569 0.691694 0.770755 0.010956 0.637038 0.802739 -0.0109592 0.59623 0.844498 0.0110348 0.535445 0.871128 -0.0110629 0.490931 0.909026 0.0139403 0.416506 0.922849 -0.00572243 0.385119 0.758273 -0.00564174 -0.651913 0.758155 -0.00286496 -0.652068 0.615393 0.169709 -0.769734 0.900101 0.246594 -0.359179 -0.73373 -0.00465141 0.679426 0.762101 0.00818625 -0.647406 0.636609 -0.0435739 -0.769955 0.934665 0.23249 -0.268978 -0.730887 0.483754 0.481442 -0.455009 0.00572895 -0.890469 -0.466974 -0.00161853 -0.88427 -0.539922 0.000222212 -0.841715 -0.627889 0.76331 0.152033 -0.959896 0.00668677 0.280277 -0.996699 -0.055605 0.0591495 0.48728 -0.849136 -0.20378 0.802407 -0.592765 0.069089 0.898928 0.00212453 -0.438092 0.876063 0.00786701 -0.482132 -0.66575 -0.607526 0.433231 0.664363 -0.671835 -0.327504 0.999659 0.00405956 0.0258154 -0.574358 0.0317355 -0.817989 -0.787809 -0.615886 0.00644968 -0.532903 -0.822338 -0.199436 -0.869735 -0.365716 -0.331379 -0.330711 -0.804012 -0.49416 -0.324257 0.0302098 -0.945487 -0.00923939 -0.999935 0.00664984 0.111568 -0.990865 -0.0757549 -0.00515071 -0.999958 0.00761508 0.000905845 -1 -0.000306666 0.743353 0.00577856 -0.668874 0.756454 -0.000234951 -0.654047 -0.794066 0.00146204 -0.607829 -0.957983 -0.00361277 0.286803 -0.535138 0.599426 0.595244 0.511693 -0.697592 -0.501534 0.385798 -0.824968 -0.413022 -0.436079 -0.869612 -0.231541 -0.64673 -0.728097 -0.22719 -0.875956 -0.368631 0.311146 -0.883471 -0.424155 -0.198924 -0.121989 -0.688498 -0.714904 0.75499 -0.295224 -0.58552 -0.0303399 -0.644484 -0.764016 -0.882636 -0.469127 0.0295367 -0.945059 -0.322482 0.0535565 -0.95307 -0.288379 0.0921751 -0.930267 -0.337393 0.144115 -0.878243 -0.465987 0.107446 -0.488523 -0.869091 0.0776231 0.501264 -0.863377 -0.0575678 -0.16893 -0.98514 0.0310106 -0.865327 -0.496417 0.0691356 -0.738813 -0.668576 0.0846271 -0.629619 -0.776002 0.0374233 -0.269896 -0.962887 -0.0020374 0.123725 -0.991759 -0.033252 0.192768 -0.98124 -0.00287 0.476559 -0.878679 -0.0285394 -0.172631 -0.791443 0.586359 0.257853 0.689194 0.677144 0.593 -0.802332 0.0679293 -0.0645487 0.975947 -0.208233 0.0496045 -0.830256 -0.55517 -0.193612 -0.490513 -0.849654 -0.302771 0.886876 -0.34897 -0.945299 0.0273356 0.325058 -0.943672 -0.0253486 0.329911 -0.937882 -0.00224413 0.346948 -0.934556 -0.00676453 0.355751 0.295181 -0.476758 0.827991 0.171463 -0.348954 0.92132 0.0884881 -0.995911 0.0181738 0.200249 0.00435305 0.979735 0.183959 -0.0012903 0.982933 0.20068 0.303959 0.931309 0.53991 0.708507 0.454439 0.104515 0.989311 0.101693 0.494143 -0.0449801 -0.868216 0.0470562 0.0376445 -0.998183 -0.109602 -0.988629 -0.102956 -0.0574993 -0.998346 9.49531e-05 -0.356241 0.90608 -0.228278 -0.0881258 0.860292 -0.502128 -0.346693 0.935238 -0.0716507 -0.43649 0.372361 0.819038 -0.563613 0.810095 0.161512 -0.602046 0.521239 0.604856 -0.402653 0.361709 -0.840855 -0.816978 0.566311 -0.108808 -0.370135 0.673588 -0.63975 -0.243647 0.631658 -0.735965 -0.66197 0.707762 -0.246714 -0.619625 0.275192 0.735074 -0.376223 -0.611418 -0.69615 -0.131408 -0.991263 0.0113842 0.0627106 -0.731737 0.678696 0.188908 3.62197e-05 0.981995 0.193628 -0.0070041 0.98105 0.188643 -0.000105233 0.982046 0.188695 -0.000114208 0.982036 0.188057 -0.00124329 0.982157 0.216767 -0.0193683 0.976031 -0.644142 -0.4451 -0.622067 -0.48926 -0.732775 -0.472933 -0.505473 -0.461298 -0.729178 -0.07482 0.866899 0.492837 -0.370809 -0.000887875 0.928709 -0.372282 4.71557e-05 0.928119 -0.372323 -0.00054299 0.928103 -0.474244 0.00249016 0.88039 -0.0606472 0.683033 0.727865 0.606666 0.711258 -0.355061 -0.83965 -0.440607 -0.317575 -0.829091 -0.391474 0.399193 -0.815519 -0.53123 0.229614 0.401828 -0.191147 -0.895543 -0.846885 -0.517495 0.122413 -0.274927 -0.956579 -0.0968057 -0.634126 -0.408773 0.656345 -0.160438 -0.976649 -0.142885 0.224686 -0.734465 -0.640373 -0.301091 -0.593016 -0.746778 0.2275 -0.760267 -0.608471 -0.54307 -0.835153 -0.0871514 0.419057 -0.326928 -0.84706 -0.509958 -0.745926 -0.428412 -0.661746 -0.534501 0.525738 -0.514749 -0.805587 -0.293364 -0.753449 -0.291975 0.589123 -0.560045 -0.271304 0.782779 -0.860958 -0.00222121 0.508671 -0.860436 -0.00258628 0.509552 0.483371 -0.569138 -0.665158 -0.333695 -0.329535 0.883207 0.0460873 -0.60468 0.795134 -0.175477 0.00360636 -0.984477 -0.21037 0.0155243 -0.977499 -0.856801 0.055717 0.512628 -0.928835 -0.000753277 0.370493 0.278234 -0.346156 -0.89597 0.546861 -0.0825555 -0.833143 -0.139205 -0.329339 0.933894 0.298893 -0.692798 0.656273 -0.131404 -0.0480058 -0.990166 -0.123204 -0.691539 -0.711755 -0.739286 -0.0383027 -0.672302 -0.201288 7.13986e-06 -0.979532 -0.391285 0.0353625 -0.91959 -0.410204 -0.0217747 0.911734 -0.189096 0.0019728 0.981957 -0.848261 -0.00325953 -0.529569 -0.865906 -9.85091e-05 -0.500207 -0.865924 -3.6252e-05 -0.500176 -0.865698 -3.71595e-05 -0.500567 -0.86571 2.63652e-05 -0.500545 -0.867125 -0.000446343 -0.498091 -0.998957 2.10226e-08 0.0456523 -0.998898 -4.4335e-06 0.0469427 -0.998898 -4.46602e-06 0.0469427 -0.998903 -2.94181e-05 0.0468329 -0.9989 0.000220149 0.0468869 -0.945209 -1.43314e-05 0.326465 -0.94522 -5.98686e-06 0.326435 -0.945535 -0.00163945 0.325516 -0.945347 -0.00174152 0.326062 -0.945787 -0.00104376 0.324785 -0.80477 0.00483046 0.593567 -0.81462 -0.000299917 0.579996 -0.0132656 -0.999906 0.0033444 0.00877733 -0.999476 0.0311636 -0.0286514 -0.994693 -0.0988212 0.909398 -4.77377e-05 0.415928 0.909071 -0.000268796 0.41664 0.744786 -0.482171 0.461308 0.717491 -0.658436 0.227309 0.387438 0.567976 -0.726151 0.462674 -0.00375578 -0.886521 -0.747933 -0.461261 0.477321 -0.736982 -0.42604 0.524736 0.909807 2.31073e-05 -0.415033 0.911344 0.0013292 -0.411642 0.909473 9.55399e-05 -0.415764 0.909827 -4.30783e-05 -0.414989 0.909828 3.07182e-05 -0.414986 0.37855 -0.405414 0.832069 0.27714 -0.00438264 0.96082 0.551916 0.158474 0.818703 0.439832 -0.891063 0.112049 0.308631 0.171302 0.93563 0.0681547 0.117577 0.990722 -0.0997241 -0.994328 0.036978 0.396682 0.815348 -0.421724 -0.625052 0.0230177 0.780243 -0.56124 -0.69711 -0.446147 -0.299447 -0.122401 -0.946229 -0.0571234 0.20178 -0.977764 0.105953 0.0513024 0.993047 0.165328 -0.923834 0.34525 0.177944 0.921069 0.346364 -0.114755 -0.929363 -0.350879 -0.0862564 0.920995 -0.379906 -0.150287 0.927296 -0.342835 -0.149024 -0.695704 -0.702701 -0.507502 0.766211 -0.394159 -0.158956 -0.985864 -0.0529724 0.230015 -0.901375 0.3669 -0.120042 0.984495 0.127902 0.755024 -0.00510793 0.655677 -0.664621 0.03885 0.74617 -0.283449 0.0195833 -0.958787 -0.537555 -0.0528564 -0.84157 0.0639684 0.398126 -0.915098 -0.0529174 0.269417 0.961569 -0.20885 0.0407842 -0.977097 -0.377434 -0.0199321 -0.925822 0.32686 0.397917 -0.857219 -0.387388 0.388486 0.836068 -0.860859 -0.0227678 0.508334 -0.828119 -0.00172367 0.56055 -0.0958506 -0.0142289 -0.995294 -0.106978 -0.00985718 -0.994213 0.561187 0.294064 -0.773689 -0.614276 0.520313 0.593245 -0.868358 0.0199054 0.495539 -0.969483 -0.0632846 0.236849 0.755661 0.000150183 -0.654963 0.757892 -0.000938399 -0.652379 -0.292891 -0.729376 0.618243 -0.427105 -0.793296 -0.433892 0.647811 -0.260359 -0.715929 -0.228389 0.65746 -0.718043 -0.532516 0.781278 -0.325624 -0.884478 0.420505 -0.202173 -0.745833 0.292681 0.598391 -0.933776 0.324893 0.150022 -0.727081 0.378408 0.572852 -0.620791 0.440488 0.648528 -0.12073 0.843471 -0.523432 -0.19431 0.978424 -0.0702164 -0.626944 0.503456 0.594536 -0.57603 0.817429 8.27422e-05 0.163778 0.584155 -0.794946 0.147636 0.760448 -0.632394 -0.218197 0.629931 -0.745371 -0.370624 -0.000329527 0.928783 -0.372152 -0.00373311 0.928164 -0.550188 0.0247105 0.834675 -0.37325 -0.00310914 0.927725 -0.372138 -9.87313e-05 0.928177 -0.138644 -0.241177 0.960527 -0.145224 0.3695 -0.917813 -0.483075 0.431509 -0.761865 -0.419968 0.419665 -0.804679 -0.171171 0.55509 -0.813988 -0.372168 0.461573 0.805259 -0.320478 -0.649078 0.689921 -0.631292 -0.550376 0.546403 -0.635088 -0.567671 0.523844 -0.82568 -0.4983 0.26448 -0.861154 -0.368618 -0.35005 0.323958 -0.910059 0.258541 -0.749471 -0.600731 -0.278236 -0.712835 -0.523778 -0.466393 -0.153971 -0.987424 -0.0358681 -0.796494 -0.448407 -0.40562 0.240721 -0.963369 0.118208 -0.0227421 -0.999161 -0.0340547 -0.314788 -0.930062 -0.189458 -0.453466 -0.864797 -0.215625 -0.542602 -0.788571 -0.289375 -0.653944 -0.683299 -0.324746 -0.793172 -0.446921 -0.413691 -0.82507 -0.326974 -0.460812 -0.84686 -0.294613 -0.442754 -0.580672 -0.730194 -0.360051 -0.148886 -0.984896 -0.0883951 -0.399892 -0.792705 -0.460114 -0.596837 -0.412109 -0.688441 -0.72424 -0.365875 -0.584475 -0.602632 -0.496524 -0.624739 0.369422 -0.854855 0.364349 0.359355 -0.881179 0.307226 0.172278 -0.964934 0.198045 0.10732 -0.992134 0.0644423 -0.163424 -0.975633 -0.146403 -0.409991 -0.811274 -0.416824 -0.634037 -0.496965 -0.592471 -0.688501 -0.308922 -0.656151 -0.618694 2.1216e-05 0.785632 -0.624651 0.00210507 0.780902 -0.616585 0.0017607 0.787286 -0.618946 0.000319777 0.785434 -0.618694 2.7445e-05 0.785632 -0.68446 0.00894071 -0.728996 -0.66876 0.00375296 -0.743469 -0.712609 -0.00288298 -0.701555 -0.757051 -0.000819381 -0.653355 -0.757445 -0.000535089 -0.652899 -0.614222 0.000880025 0.789133 -0.618733 -0.000823295 0.785601 -0.910385 0.00148915 -0.41376 -0.900043 -0.00764225 -0.435735 -0.863887 0.00821403 -0.503619 -0.854042 0.00151713 -0.520201 0.529806 0.00422053 -0.848108 0.541078 0.000234743 -0.840972 -0.366117 -0.000254076 0.930569 -0.370793 -0.00197965 0.928713 -0.989769 0.00614748 -0.142544 -0.993596 -0.00154608 -0.112981 -0.98574 -0.00136458 -0.168273 -0.977683 -0.00300692 -0.210062 -0.968415 -0.0004499 -0.249345 -0.970856 0.00237488 -0.239653 0.281471 0.00013023 -0.95957 -0.470816 0.01702 0.882067 -0.423684 0.000203795 0.90581 0.00752617 0.00192201 -0.99997 -0.00013128 -3.85535e-05 -1 -0.999543 0.00687573 0.0294509 -0.999517 0.00703337 0.0302617 -0.997694 -0.000488488 0.0678745 -0.994895 0.00201053 0.100893 -0.99406 0.000251414 0.108834 -0.988976 0.000733162 0.148071 -0.987637 0.00335753 0.156723 -0.298563 0.933233 -0.199838 -0.544243 0.735717 -0.403137 -0.40899 0.886081 -0.218144 0.720549 0.554902 -0.415805 -0.473881 0.720359 -0.506478 -0.854523 0.441513 -0.2736 0.552972 0.477504 -0.682797 0.241688 0.616555 -0.749298 -0.0301985 0.493122 -0.869436 0.0910683 0.843829 -0.528828 -0.991545 0.0323787 -0.125655 0.0202346 0.0296197 -0.999356 -8.53933e-05 0.000224479 -1 0.000467157 -5.36773e-05 -1 0.000466985 3.14681e-05 -1 -0.0677901 0.0145154 -0.997594 -0.952683 0.00895819 0.303835 -0.942065 0.00461657 0.335399 -0.955948 -0.00951544 0.293383 -0.965834 -0.00633671 0.259086 -0.966513 -0.0596709 0.249583 -0.943166 -0.0216928 0.331614 -0.949768 0.00503565 0.312916 -0.0160745 -0.928349 0.371362 -0.89154 -0.37019 -0.260991 -0.213603 0.270753 -0.938652 -0.465236 -0.703691 -0.537005 -0.721717 0.371103 0.584301 0.543397 -0.37908 0.749011 0.256316 0.373482 0.891523 0.162461 0.267737 0.949696 -0.999703 -0.00485068 0.0238819 -0.999673 -0.00514058 0.0250516 -0.995636 -0.000177757 0.093318 -0.996297 -0.00319198 0.0859243 -0.983762 -0.0128354 0.179018 -0.990091 -4.05199e-05 0.140429 1.9306e-05 0.000451219 -1 0.0065246 -0.00207674 -0.999977 -0.542584 0.0364968 0.839208 -0.434621 -0.00460345 0.900602 0.300045 0.00326067 -0.953919 0.289069 -0.000378593 -0.957308 -0.972711 0.00166543 -0.232014 -0.970138 0.00717197 -0.242447 -0.981854 -0.00446127 -0.189584 -0.989496 0.0056497 -0.144452 -0.993695 -0.00381713 -0.112056 -0.345134 0.00970916 0.938503 -0.373781 -0.000238797 0.927517 0.552647 0.00455762 -0.833403 0.541469 0.000192568 -0.84072 -0.867755 -0.00590706 -0.496956 -0.855074 0.000229533 -0.518507 -0.890066 0.00666591 -0.455783 -0.91418 0.000219859 -0.405309 -0.910952 -0.0018294 -0.412508 -0.594851 0.00881916 0.803787 -0.617862 -0.000208528 0.786287 -0.672797 -0.000731232 -0.739827 -0.671626 -0.00107945 -0.74089 -0.710304 0.000229649 -0.703895 -0.713066 -0.000965394 -0.701097 -0.75443 0.00343956 -0.656371 -0.77214 -0.00662553 -0.635418 0.253025 0.00346253 -0.967454 0.21612 0.00778366 -0.976336 0.73016 -0.419906 -0.539022 0.706111 -0.354094 -0.613208 -0.0589117 0.99808 -0.0191224 -0.406009 0.860797 -0.306896 -0.64361 0.498968 -0.580342 -0.720181 0.318179 -0.616524 -0.701088 0.27652 -0.657277 -0.618336 0.360096 -0.698564 -0.492633 0.676005 -0.548024 0.367217 0.887519 0.278318 0.235105 0.939169 0.250376 0.014852 0.999889 0.00140852 -0.216687 0.94556 -0.242822 -0.648565 0.495968 -0.57739 -0.757845 0.466209 -0.45642 -0.574172 0.743075 -0.343753 -0.283074 0.943523 -0.172146 0.30742 0.919762 0.243989 -0.690376 0.67147 -0.269276 0.449604 0.869067 0.206344 0.0822881 0.996601 -0.00401939 -0.795753 0.43869 -0.417528 -0.843376 0.294783 -0.449244 -0.84176 0.324965 -0.43109 -0.796227 0.446071 -0.40871 -0.575738 0.755336 -0.313039 -0.395149 0.900012 -0.183944 -0.104206 0.99433 -0.0211889 -0.687713 -0.0118557 0.725886 -0.618501 0.000246601 0.785784 -0.618593 -3.99236e-05 0.785712 -0.618479 -0.000522666 0.785801 -0.618384 -8.42257e-06 0.785876 -0.28434 0.603771 0.744723 -0.26882 0.580825 0.768361 -0.640787 0.64609 0.41468 -0.510374 0.397048 0.762805 -0.222172 0.145184 0.964138 0.266189 0.963895 0.00705041 -0.0876891 0.99531 0.0408499 -0.943256 0.318649 0.0934364 -0.938418 0.330792 0.0997457 -0.861835 0.499126 0.0900734 -0.700864 0.70979 0.0706278 -0.457486 0.886698 0.0668817 0.543154 0.836715 -0.0699377 -0.879538 0.469773 0.0756696 -0.644952 0.763507 0.0330804 -0.273289 0.961914 -0.00581537 0.132227 0.990047 -0.0481877 -0.953475 -0.00253298 0.301463 -0.966111 -0.00771967 0.25801 -0.472558 0.68927 0.549177 -0.447275 0.633251 0.631616 -0.886168 0.0284669 0.46249 -0.677202 -0.000452684 0.735797 0.162965 0.0030056 -0.986627 0.189419 0.000193311 -0.981896 0.488218 0.365887 -0.792319 -0.389728 0.567156 0.725566 -0.316977 0.497099 0.807724 -0.478097 -0.0040051 0.878298 -0.0991487 -0.00310777 -0.995068 0.320472 0.711354 -0.625518 0.128396 0.824127 -0.551661 0.174013 0.431153 -0.88534 -0.2187 0.81238 -0.540564 -0.654961 -0.0300061 -0.755067 0.871753 0.0304809 -0.488997 0.909826 -1.82381e-06 -0.414991 0.909832 2.25994e-05 -0.414976 0.909834 -2.3479e-05 -0.414973 0.909877 -2.25591e-05 -0.414879 -0.0411055 0.994905 -0.0920595 -0.119721 -0.991384 -0.0531465 0.266415 -0.832636 0.485532 0.0480349 -0.964805 0.258541 0.139523 -0.98994 0.0235173 -0.206432 -0.869311 -0.449092 -0.17486 -0.847355 -0.501412 -0.39696 -0.65045 -0.647563 -0.361869 -0.522588 -0.77198 -0.420004 -0.346795 -0.838648 -0.457598 -0.40765 -0.790206 -0.884736 -0.00249575 0.466085 -0.95652 0.0826272 0.279717 -0.985241 0.0309667 0.168351 -0.942794 -0.00724921 0.333297 -0.677091 0.0313653 -0.735231 -0.00690087 -0.349867 -0.936774 2.03666e-05 -0.343947 -0.938989 -0.303033 0.00195936 -0.952978 -0.354875 0.00831581 -0.934877 0.301886 -0.43037 -0.850674 0.265517 -0.390709 -0.88139 -0.463589 0.00304136 0.886045 -0.351981 -0.346126 0.869659 -0.0690382 -0.570004 0.818736 -0.895226 -0.0029297 0.445604 -0.870829 0.00212047 0.491582 -0.305706 -0.00829233 -0.95209 -0.144869 0.00688618 -0.989427 0.441881 -0.54782 -0.710376 0.450458 -0.564342 -0.691813 -0.574395 -0.364521 0.732936 -0.687903 -0.559032 0.462896 -0.982383 0.0304182 0.184388 0.256164 0.364615 -0.895229 0.542102 0.000857891 -0.840312 0.541491 -0.000306128 -0.840707 0.541293 -1.54201e-05 -0.840834 0.541016 3.2806e-05 -0.841012 0.541034 -5.97105e-05 -0.841001 0.541091 -7.4633e-05 -0.840964 0.756027 -4.83405e-05 -0.654541 0.756364 0.00179148 -0.654148 0.756486 -0.00018013 -0.65401 0.710074 0.00717531 -0.70409 0.756077 -0.000437546 -0.654483 0.0107046 0.999802 0.0168035 0.00237035 0.999995 0.00202839 -0.0248962 0.999672 -0.00600444 0.0818047 0.996535 0.0150354 -0.0954697 0.000115598 0.995432 -0.0954814 0.000112551 0.995431 -0.294604 0.792878 0.533435 0.0440306 0.336613 0.940613 0.000332858 1 -0.000261806 0.0411455 0.998864 0.0240365 -0.0341501 0.99924 0.0188077 0.00384645 0.999992 0.00093944 0.838677 -0.33588 -0.428725 0.291547 -0.832596 0.470939 0.13787 -0.963411 0.229851 -0.0365419 -0.960109 -0.277227 -0.384323 -0.659455 -0.646076 -0.481072 -0.407461 -0.776238 -0.489479 -0.414931 -0.76697 -0.401395 -0.680286 -0.613265 -0.273948 -0.920483 -0.278682 -0.0124945 -0.974221 0.225248 -0.00178524 -0.999995 0.00270335 -0.0878777 -0.00175225 0.99613 -0.0952966 0.000608321 0.995449 0.0215668 -0.999759 -0.00405335 0.000812539 -0.999998 -0.00207839 -0.161689 -0.641378 0.749994 -0.0805149 -0.587934 0.804892 0.000188486 -1 0.000272457 -0.0347942 -0.999381 -0.0052365 0.0430754 -0.998823 0.0222908 0.00412643 -0.999991 0.00104332 0.756191 -0.00052098 -0.654351 0.755918 -0.000356552 -0.654666 0.75605 -1.69137e-06 -0.654513 0.75671 -7.42313e-05 -0.65375 0.753194 -0.0108286 -0.657709 0.575955 0.00480619 -0.817467 0.541525 6.7077e-05 -0.840685 0.541502 -0.000660407 -0.840699 0.541406 -0.000701745 -0.840761 0.334705 0.942017 -0.0240166 0.000508631 -6.15127e-05 -1 0.000409958 -4.43915e-05 -1 -0.00081152 -0.00231412 -0.999997 0.0147581 -0.00267294 -0.999888 0.000226158 0.000153185 -1 0.000453941 -2.70625e-06 -1 0.0781655 -0.608389 -0.789781 0.0543817 -0.949657 -0.308535 0.570523 -0.393906 -0.720654 0.510339 -0.427923 -0.745947 -0.856315 -0.37355 0.356629 -0.606495 -0.785926 -0.120349 -0.742046 -0.443717 0.502477 -0.368233 -0.929514 -0.020218 -0.513326 -0.85817 0.00637502 0.0158188 -0.736306 -0.676464 0.265613 -0.303057 -0.915208 0.579777 -0.497037 -0.64561 -0.8847 -0.233179 0.40365 -0.651438 -0.666755 -0.36203 -0.474564 -0.783074 -0.401976 0.298594 0.860936 0.411862 0.281796 0.851506 0.442187 -0.00886549 0.988714 0.149554 -0.322458 0.76956 -0.551179 -0.426862 0.490334 -0.759843 -0.462271 0.29986 -0.8345 -0.426738 0.331152 -0.841566 -0.302841 0.569206 -0.76439 -0.130285 0.907719 -0.398839 -0.190112 0.945802 -0.263279 0.0505155 0.998366 0.0267222 -0.054235 -0.995275 -0.0805405 -0.361047 0.896098 0.258174 0.957428 0.0620354 0.281927 -0.925366 -0.360282 -0.117879 0.593234 0.393265 -0.702436 -0.853374 0.484282 0.192935 -0.648795 0.760961 -0.00178528 -0.613125 0.678048 0.405374 0.0790666 0.716829 -0.692751 -0.137191 0.962677 -0.233306 -0.00599208 0.409928 -0.912098 0.303327 0.603306 -0.737574 0.546453 0.543949 -0.636796 0.259715 0.652302 -0.712075 -0.398631 0.750234 -0.527487 -0.74584 0.537363 -0.393655 -0.836049 0.00280607 0.548648 -0.814484 9.13122e-05 0.580186 -0.814829 0.00139476 0.5797 -0.814935 -3.92887e-05 0.579552 -0.815406 0.000755426 0.578889 -0.811698 0.00874938 0.584011 -0.141372 0.868119 -0.475797 0.161195 0.985543 0.0521741 -0.0159606 0.913393 0.406766 -0.238641 0.943726 -0.22898 -0.448745 0.706023 -0.547868 -0.5366 0.37131 -0.757753 -0.490478 0.299822 -0.818253 -0.408405 0.490061 -0.770095 -0.814907 1.98575e-05 0.579592 -0.814878 -2.02363e-05 0.579633 -0.845395 -0.0334942 0.533091 -0.814803 0.000323229 0.579738 -0.814467 -0.000625868 0.580209 -0.814959 2.40627e-05 0.579519 0.353363 -0.334283 -0.873721 0.251806 -0.323219 -0.912208 0.29351 -0.429606 -0.853985 0.181934 -0.549906 -0.815171 -0.0141647 -0.998904 -0.0446025 0.208634 -0.799214 -0.563674 0.343234 -0.496608 -0.797227 0.306804 -0.429823 -0.84919 0.240567 -0.613063 -0.752516 -0.00165079 -0.995734 0.0922556 -0.139329 -0.955236 0.260983 -0.164141 -0.826826 0.537974 0.305762 -0.266367 -0.914089 0.111785 -0.885629 -0.450739 0.122454 -0.955804 -0.267289 0.935551 -0.00190822 0.353186 0.909609 0.00142958 0.415463 0.909434 -3.60812e-05 0.415848 0.909429 -3.72633e-05 0.41586 0.909499 0.000405243 0.415706 0.950508 -0.0226952 0.309869 -0.971728 0.000382794 -0.236105 -0.971742 0.000318308 -0.236044 -0.971593 0.000200919 -0.236656 -0.97166 -1.66677e-05 -0.236382 -0.956451 0.00221326 -0.291886 0.0477428 0.989396 -0.13717 0.0463606 0.989635 -0.135913 -0.931139 0.307008 -0.196788 0.499194 -0.860174 0.104435 -0.860682 -0.482608 -0.162221 -0.737369 -0.661832 -0.13515 -0.475418 -0.874865 -0.0926809 -0.131253 -0.991152 -0.0197826 -0.124911 -0.991924 -0.0220182 0.53238 -0.842212 0.0851488 -0.931261 -0.310999 -0.189825 -0.928691 -0.32307 -0.182095 -0.867189 -0.466985 -0.172938 -0.704633 -0.694347 -0.146202 -0.46891 -0.878997 -0.0865291 0.209366 -0.977086 0.0383155 0.197105 -0.979413 0.0435753 -0.136464 0.990306 -0.0259207 -0.141623 0.989469 -0.0298909 0.282326 -6.03886e-05 -0.959319 0.282187 -5.62666e-05 -0.95936 0.282157 -1.67973e-05 -0.959368 0.282068 -2.4712e-05 -0.959394 0.281828 0.000424077 -0.959465 -0.097149 0.00497083 0.995257 -0.0923501 0.00420654 0.995718 -0.095802 0.000492986 0.9954 -0.0950129 3.69007e-05 0.995476 -0.0956651 5.84104e-05 0.995414 0.161458 0.326732 -0.931224 0.279901 0.309223 -0.908866 0.377322 0.359998 -0.853247 0.261837 0.489346 -0.831855 0.366594 0.685033 -0.629555 -0.00449071 0.967909 0.251262 -0.221222 0.833668 0.506022 0.166881 0.714844 -0.679079 0.114938 0.909238 -0.400094 0.269275 0.48864 -0.829893 0.236701 0.459414 -0.856102 0.135843 0.947747 -0.288656 0.3099 0.286453 -0.906591 0.204582 0.779312 -0.592299 -0.0725797 0.996029 0.0515671 0.0469915 -0.990045 -0.132679 0.0462161 -0.989399 -0.13767 -0.97166 -1.62094e-05 -0.236383 -0.971655 -0.000308485 -0.236404 -0.971695 -0.000254291 -0.236238 -0.971717 -2.22866e-06 -0.236147 0.914576 -0.00706995 0.404353 0.908889 -0.000575656 0.417037 0.909496 -0.000121395 0.415713 0.909429 -6.63661e-05 0.41586 0.909431 5.50011e-05 0.415854 -0.90956 -0.312816 -0.273582 -0.926936 -0.0171582 -0.374827 -0.937712 0.2634 -0.226532 -0.901719 0.397251 -0.17057 -0.826874 0.512259 -0.2321 -0.0516137 0.997364 -0.0510026 0.324922 0.94447 0.0490171 -0.928406 0.33903 -0.152055 -0.900636 0.397292 -0.176106 -0.814546 0.56266 -0.141165 -0.822603 0.547462 -0.153652 -0.656371 0.746418 -0.109714 0.0067404 0.999974 0.00266563 0.30409 0.950975 0.056361 0.539702 0.836349 0.0961378 -0.534017 0.834654 -0.134829 -0.39067 0.919634 -0.0406304 0.562325 0.818375 0.118546 -0.0963257 0.000767798 0.99535 -0.095618 0.000767805 0.995418 -0.0956921 3.72206e-05 0.995411 -0.0965109 -0.000510442 0.995332 0.28225 -7.04844e-05 -0.959341 0.281743 -0.000779959 -0.95949 0.282146 -5.72044e-05 -0.959371 0.282168 -2.72548e-05 -0.959365 0.282211 -2.50677e-05 -0.959352 -0.144273 -0.989147 -0.0278189 -0.76164 -0.000598561 0.648 -0.726283 0.00889215 0.687338 -0.285538 0.00351494 0.958361 -0.225572 -0.00946378 0.974181 0.285706 0.00373285 0.95831 0.329548 -0.00107228 0.944138 -0.155531 -0.0181855 0.987664 -0.750183 -0.0021365 0.661227 -0.692027 0.0141909 0.721732 -0.235101 0.000112144 0.971971 0.292386 0.0109232 0.956238 0.397082 -8.84022e-05 0.917783 0.670365 0.168962 0.722539 0.88626 0.0129361 0.463007 0.997686 0.00360887 -0.0678939 0.999086 -0.0196578 0.0379637 0.741256 -0.0131125 0.671094 0.631481 0.000780818 0.775391 0.897216 -0.00114353 -0.441591 0.749943 -0.280714 0.598987 0.838524 -0.05847 0.541718 0.810104 -0.283276 0.513309 0.751651 0.0114251 0.659462 0.987723 0.0427719 0.150243 0.989972 -0.139642 0.0213284 0.999278 -0.0376969 -0.00471202 0.89982 -0.133451 0.415349 0.96601 -0.0163998 -0.257986 0.964824 -0.0236085 -0.261835 0.929469 0.0139691 -0.368635 -0.478236 0.0408595 -0.877281 -0.817568 0.0304688 0.575026 -0.835315 -0.00515829 0.549747 -0.974853 0.0587718 0.214961 -0.977345 0.0474273 0.20627 -0.919347 -0.028065 -0.392444 -0.970795 0.0786407 -0.226654 -0.991499 -0.0033266 -0.13007 -0.520726 -0.00566029 -0.853705 -0.779775 0.0300675 -0.625338 -0.744573 0.0960696 -0.660592 -0.438095 0 -0.898929 -0.478143 -0.0453248 -0.877111 -0.817931 0.00646442 0.575281 -0.794052 -0.0434013 0.606298 -0.975224 -0.0519084 0.215043 -0.972675 -0.0638148 0.223229 -0.97378 0.00801321 -0.227351 -0.982093 -0.111854 -0.151596 -0.870202 0.0260056 -0.492009 -0.777643 -0.0797546 -0.623627 -0.721012 -0.00942416 -0.692858 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.965845 -2.32691e-07 -0.259121 0.965859 0 -0.259067 0.965856 7.11305e-06 -0.259078 0.965841 -5.47041e-05 -0.259135 0.965859 6.61029e-06 -0.259067 0.965841 0 -0.259135 0.965847 6.6347e-05 -0.259112 0.965864 0 -0.259051 -0.000729367 0.99999 0.00431615 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -7.51232e-05 1 0.000221131 0.000305169 1 -7.19928e-05 -3.5766e-05 1 0.000215222 0.0237164 0.999007 -0.037705 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.00642008 -0.999936 0.00930354 0 -1 0 0 -1 0 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.81957e-05 -1 9.5787e-06 4.43669e-06 -1 -4.25587e-06 3.66776e-06 -1 -4.6577e-06 -1.54646e-05 -1 -7.88796e-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.000227338 -0.999999 0.00134536 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.636187 -3.34273e-06 0.771535 -0.636221 -1.32983e-06 0.771506 -0.55162 1.4686e-05 0.834096 -0.55177 0 0.833996 0.571464 0 -0.820627 0.571464 0 -0.820627 -0.561744 0.705773 0.431658 -0.515749 0.70719 0.483616 -0.497859 0.715391 0.490258 -0.473596 0.708912 0.522638 -0.424343 0.715268 0.555271 -0.412606 0.721832 0.555621 -0.365922 0.705244 0.607233 -0.2935 0.727426 0.620249 -0.335855 0.692698 0.638256 -0.225074 0.715211 0.661676 -0.178032 0.755604 0.630371 -0.225942 0.697303 0.680234 -0.334998 -0.717189 0.611079 -0.308289 -0.734842 0.604124 -0.268112 -0.706679 0.654768 -0.209763 -0.718073 0.663605 -0.19435 -0.70244 0.684695 -0.383762 -0.706807 0.594265 -0.428383 -0.70718 0.562481 -0.433529 -0.713413 0.55054 -0.475853 -0.705466 0.525244 -0.507422 -0.711059 0.486742 -0.515754 -0.70719 0.483612 -0.561744 -0.705773 0.431658 -0.970068 0 -0.242836 -0.970068 0 -0.242836 -0.762226 0 -0.647311 -0.762226 0 -0.647311 -0.396719 0 -0.91794 -0.396719 0 -0.91794 -0.970068 0 -0.242836 -0.970068 0 -0.242836 -0.762226 0 -0.647311 -0.762226 0 -0.647311 -0.396719 0 -0.91794 -0.396719 0 -0.91794 -0.822027 0 0.569448 -0.822027 0 0.569448 -0.850348 0 0.526221 -0.850348 0 0.526221 -0.9994 0 -0.0346245 -0.9994 0 -0.0346245 -0.999838 0 0.0180275 -0.999838 0 0.0180275 -0.998529 0 0.0542249 -0.998529 0 0.0542249 -0.99618 0 0.08732 -0.99618 0 0.08732 -0.988566 0 0.150792 -0.988566 0 0.150792 -0.975083 0 0.221842 -0.975083 0 0.221842 -0.959298 0 0.282394 -0.959298 0 0.282394 -0.947167 0 0.320741 -0.936205 0.00127493 0.351451 -0.931435 0 0.363909 -0.905868 0 0.42356 -0.905868 0 0.42356 -0.865403 0 0.501076 -0.865403 0 0.501076 -0.946185 0 -0.323626 -0.931093 0 -0.364781 -0.994917 0 -0.100703 -0.994916 0 -0.100703 -0.987738 0 -0.156122 -0.987738 0 -0.156122 -0.980867 0 -0.194677 -0.980867 0 -0.194677 -0.968102 0 -0.250556 -0.968102 0 -0.250556 -0.958224 0 -0.28602 -0.958224 0 -0.28602 -0.946185 0 -0.323626 -0.931093 0 -0.364781 -0.915186 -3.82049e-07 -0.403032 -0.915187 0 -0.403029 -0.924959 0 -0.380067 -0.924959 0 -0.380067 0.935872 -0.00758382 0.352259 0.940437 0.00469337 0.339936 0.922608 -0.0024669 0.38573 0.915349 0.00676386 0.402604 0.896692 -0.00764947 0.442589 0.890432 0.00603251 0.455076 0.863485 -0.00213171 0.50437 0.861156 0.00212735 0.508337 0.843491 -0.00246661 0.537137 0.80912 0 0.587643 0.809767 -0.00112509 0.586751 0.817403 0.000799847 0.576066 0.822654 -0.00453647 0.568525 0.827175 0.00167914 0.561941 0.83245 -4.42838e-05 0.554101 0.84211 -6.73602e-05 0.539306 0.991859 0.00836583 0.127067 0.994545 -0.0107901 0.103751 0.985257 0.00767839 0.170908 0.987254 -0.00120745 0.159146 0.971644 0.00290226 0.236432 0.972137 0.00126838 0.23441 0.957712 -0.000553872 0.287727 0.954321 0.00598875 0.298722 0.99794 -0.00420063 0.0640119 0.997293 0 0.0735358 0.999919 0 0.0126903 0.999953 -0.00968093 -0.000840577 0.997944 0.00524353 -0.0638727 0.996685 -0.0015861 -0.0813475 0.988361 3.70895e-05 -0.152124 0.988229 -0.000601192 -0.152981 0.971218 -0.00567459 -0.238125 0.967 0.00211533 -0.254766 0.947096 -0.00297874 -0.320936 0.949052 0.000469991 -0.31512 0.909623 -0.0080023 -0.415358 0.911015 -0.00580016 -0.412333 0.863122 -0.00280629 -0.504988 0.851466 0.0077107 -0.524353 0.821683 0 -0.569945 0.821871 -0.000370024 -0.569674 0.314196 0.00934604 -0.949312 0.533447 0 -0.845834 0.378395 -0.0485851 -0.924368 0.405345 0 -0.914164 0.482247 0 -0.876036 0.503003 0.0376806 -0.863463 0.543077 -0.00488507 -0.839669 0.616573 0.00124009 -0.787297 0.626769 -0.0103109 -0.779137 0.7787 0 -0.627397 0.751386 -0.0206395 -0.65954 0.710039 0.000823952 -0.704162 0.149967 0 0.988691 -0.572329 0.0135913 0.819911 -0.525045 -0.0613517 0.84886 0.210442 -0.0704032 0.975068 -0.227424 0.010972 0.973734 -0.163385 -0.0853847 0.982861 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.00301985 -0.999982 -0.00523781 -0.0010227 -0.999999 -2.58396e-05 0.000359337 -1 0.000961098 3.07186e-05 -1 -0.000169266 -0.000124291 -1 7.90779e-06 2.85516e-05 -1 9.90636e-05 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.091237 -0.983175 -0.158248 -0.0918981 -0.982907 -0.159525 -0.0905153 -0.983309 -0.15783 -0.0862104 -0.984707 -0.151393 -0.0918921 -0.983143 -0.158066 -0.0872193 -0.984707 -0.150817 -0.0903829 -0.983491 -0.156772 -0.0895546 -0.983418 -0.157702 -0.0892969 -0.983419 -0.157839 -0.0836956 -0.986049 -0.143883 -0.0861944 -0.984766 -0.151019 -0.0837787 -0.984798 -0.152162 -0.053749 -0.994156 -0.0936214 -0.0513315 -0.993417 -0.102414 -0.0574609 -0.993855 -0.094603 -0.062701 -0.991841 -0.110997 -0.0631211 -0.992016 -0.109182 -0.0680159 -0.990705 -0.117806 -0.0688795 -0.99011 -0.122222 -0.0776856 -0.988301 -0.131248 -0.0767557 -0.9879 -0.134771 -0.0812077 -0.986732 -0.140587 -0.08351 -0.985961 -0.144593 -0.0459503 -0.995779 -0.0794559 -0.0382962 -0.996679 -0.0718621 -0.0381251 -0.997186 -0.0645496 -0.0253571 -0.998602 -0.0463774 -0.0228461 -0.998756 -0.0443334 -0.00882653 -0.999844 -0.0153093 -0.00828494 -0.999854 -0.0149164 -0.0191946 -0.999263 -0.0332453 0.851189 0 -0.52486 0.851189 0 -0.52486 0.945943 0 0.324333 0.982977 0.000479791 0.183727 0.98795 -0.000297102 0.154773 0.989262 0.000204348 0.146151 0.976357 0.00366963 0.216134 0.983836 -0.00362754 0.179035 0.970133 0.00264744 0.242561 0.977461 -0.00188671 0.211108 0.9714 -5.00651e-06 0.237451 0.965385 -5.07842e-06 0.260828 0.965391 -6.42715e-06 0.260807 0.959959 8.7671e-06 0.280139 0.959612 7.38794e-05 0.281328 0.945432 -0.000292102 0.32582 0.992241 -0.000229898 0.124332 0.993368 0.000308251 0.11498 0.994938 -4.37864e-05 0.100495 0.997239 0.000168569 0.0742655 0.99736 0 0.0726198 0.999681 0 0.0252581 0.999681 0 0.0252581 0.999391 0 -0.0348835 0.997974 -0.00409759 -0.0634945 0.995045 0 -0.0994294 0.985279 0 -0.170952 0.979869 -0.00454742 -0.199589 0.969658 0 -0.244467 0.947119 0 -0.320884 0.938086 -0.00409019 -0.346379 0.919326 0 -0.393497 0.882876 0 -0.469607 0.868292 -0.00458744 -0.496033 0.838614 0 -0.544727 0.813993 0 0.580875 0.81441 0.000223325 0.58029 0.833817 -0.000264217 0.552041 0.83261 0.000243668 0.55386 0.849192 -0.00013188 0.528084 0.890605 1.86277e-06 0.454777 0.880984 0.000239583 0.473147 0.880237 -2.98559e-06 0.474534 0.869025 3.08246e-06 0.494768 0.868098 -4.39592e-05 0.496393 0.86078 0.000146806 0.508978 0.86003 4.74046e-06 0.510243 0.848507 4.76766e-06 0.529185 0.930915 0 0.365235 0.930962 -5.02257e-06 0.365117 0.921412 -5.07651e-06 0.388587 0.921574 -5.09669e-05 0.388204 0.902416 0.000120415 0.430866 0.902738 -6.91205e-06 0.430191 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -7.62799e-05 1 0.000107961 -0.000121069 1 4.22589e-06 3.07186e-05 1 -0.000169266 8.05189e-05 1 2.0344e-06 3.41169e-05 1 5.91744e-05 -0.00983236 0.999823 -0.0160113 -0.0906512 0.983167 -0.158634 -0.09238 0.982935 -0.159074 -0.0918293 0.982928 -0.159436 -0.09184 0.983203 -0.157722 -0.0892331 0.983442 -0.157731 -0.089508 0.983446 -0.15755 -0.0926766 0.984651 -0.147898 -0.0929408 0.983722 -0.153797 -0.0825406 0.984816 -0.152726 -0.0683911 0.990564 -0.118768 -0.0688363 0.990117 -0.122191 -0.0823555 0.985372 -0.149199 -0.0833587 0.985972 -0.144602 -0.0780008 0.987729 -0.135305 -0.0758903 0.987514 -0.138044 -0.0776144 0.988271 -0.13152 -0.0475253 0.993128 -0.106954 -0.0656455 0.993148 -0.0966877 -0.0628741 0.992038 -0.10912 -0.0523307 0.993525 -0.100844 -0.0525506 0.994417 -0.0915066 -0.0417866 0.996532 -0.0719557 -0.0387046 0.996363 -0.0759108 -0.0326969 0.998448 -0.0450819 -0.0200823 0.998148 -0.05743 -0.023125 0.998881 -0.0412557 -0.00879781 0.999845 -0.0152595 -0.0919501 0.98313 -0.158119 -0.0861466 0.984703 -0.151458 0 -1 0 0 -1 0 0 -1 0 0 -1 0 6.11867e-06 -1 -2.32837e-05 -1.58175e-05 -1 1.00401e-05 -7.07017e-06 -1 1.90259e-05 -7.3585e-06 -1 2.54446e-05 -2.15416e-05 -1 1.61577e-05 -3.23143e-05 -1 -1.87936e-05 3.69513e-06 -1 -5.19887e-06 6.67942e-06 -1 9.96378e-07 -3.291e-07 -1 -5.099e-07 0 -1 0 6.15071e-05 -1 8.32213e-05 -0.00683097 -0.999842 -0.0164122 -0.000211086 -0.999998 -0.00209386 -4.22085e-05 -1 0.000194493 -0.000274618 -1 -0.000279629 0.00011553 -1 7.19385e-06 0.000116928 -1 1.48637e-05 0.00721439 -0.999961 -0.00504989 0.0042451 -0.999256 -0.038325 0.0130903 -0.998908 -0.0448512 0.0122039 -0.99777 -0.0656247 0.02466 -0.997146 -0.0713526 0.025705 -0.996256 -0.0825399 0.0333854 -0.995835 -0.0848406 0.0465957 -0.996189 -0.0737254 0.0361473 -0.995195 -0.0909965 0.0376361 -0.995456 -0.0874679 0.0421855 -0.995044 -0.0900419 0.0425008 -0.995234 -0.0877686 0.0458247 -0.995395 -0.0841946 0.0470413 -0.995623 -0.0807552 0.0482691 -0.99606 -0.0743903 0.0461653 -0.9957 -0.080316 0.0446454 -0.997098 -0.0616653 0.0472901 -0.997184 -0.0582016 0.0451207 -0.996934 -0.0639277 0.0468158 -0.996553 -0.0684847 0.0476968 -0.996601 -0.0671629 0.0160925 0.996482 -0.0822424 0.0324124 0.99721 -0.0672474 0.0270027 0.996276 -0.0818828 0.00950827 0.998611 -0.0518228 0.00875761 0.999759 -0.0201538 -0.00200755 0.99988 -0.0153626 0.0134024 0.998806 -0.0469793 -7.70628e-06 1 -4.81301e-06 -1.42712e-05 1 -3.38372e-05 -0.00210535 0.999995 0.0021812 -0.00275903 0.999996 0.00094618 -2.78546e-06 1 5.30657e-07 -1.06105e-06 1 -2.58145e-06 0 1 0 0 1 0 -1.12422e-06 1 3.34729e-06 -8.43752e-06 1 1.37842e-05 -8.51124e-06 1 -9.24922e-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.0449978 0.995867 -0.0788876 0.0443583 0.997135 -0.0612763 0.0452977 0.997107 -0.0610415 0.0456274 0.9967 -0.0671322 0.0493908 0.996452 -0.0681511 0.0481312 0.996506 -0.0682582 0.0474587 0.995408 -0.0831305 0.0467008 0.995648 -0.0806434 0.0489941 0.99604 -0.0741839 0.0457142 0.99555 -0.0824045 0.0452271 0.995362 -0.0849037 0.0411384 0.995138 -0.0894879 0.0315512 0.995705 -0.0870413 0.0371497 0.995364 -0.0887154 0.0366512 0.995472 -0.0877071 0.0409671 0.995071 -0.0903042 -0.816057 -6.60201e-05 -0.577971 -0.999027 0.0021989 -0.0440415 -0.999957 -0.00146337 0.00914409 -0.999848 0.00470811 0.0168022 -0.996842 -0.00665815 0.0791308 -0.996417 -0.000224841 0.0845712 -0.987615 0.0135216 0.156311 -0.99711 -0.017509 -0.0739242 -0.996601 -0.0112154 -0.0816115 -0.999404 0.0135094 -0.03176 -0.994359 0.0031719 -0.106024 -0.988407 -0.0052704 -0.151737 -0.987906 -0.00160777 -0.155045 -0.975897 0.0026597 -0.218214 -0.978169 -0.0180541 -0.207026 -0.967691 0.00801707 -0.252013 -0.955562 -0.00716091 -0.294704 -0.956051 -0.00978204 -0.293038 -0.942076 0.0143375 -0.335094 -0.905976 -0.00331202 -0.423317 -0.921945 0.00432775 -0.387296 -0.926753 -0.0115738 -0.375493 -0.854739 0.0152763 -0.518833 -0.885807 -0.0185568 -0.463682 -0.878947 0.027721 -0.476114 -0.90172 -0.0110611 -0.432179 -0.821544 6.85631e-05 0.570146 -0.821531 -5.29508e-05 0.570163 -0.823102 0.00466912 0.567875 -0.853665 -0.010828 0.52071 -0.867056 0.0121129 0.498063 -0.94797 0.00792952 0.31826 -0.913475 0.00637128 0.406846 -0.911233 0.000821283 0.411891 -0.9791 -0.0236164 0.202005 -0.972145 0.0025942 0.234367 -0.953887 -0.0107539 0.299974 -0.850618 0.0371847 -0.524467 -0.832049 -0.00904677 -0.554629 -0.81463 0.013201 -0.579831 -0.816057 6.74582e-05 -0.577971 -0.814371 -0.0154775 -0.580139 -0.837314 0.0199048 -0.54636 -0.836112 0.0112023 -0.548445 -0.860772 -0.0079763 -0.508928 -0.86337 0.00111969 -0.50457 -0.886923 -0.0018322 -0.461914 -0.8853 -0.00978521 -0.464918 -0.908864 0.00701189 -0.417034 -0.905302 0.0164878 -0.424447 -0.927606 -0.017424 -0.373152 -0.921729 0.00103805 -0.387832 -0.939727 0.00104226 -0.341923 -0.941865 -0.0044972 -0.335961 -0.956181 0.00493565 -0.292736 -0.956215 0.00483036 -0.292625 -0.971071 -0.00481866 -0.23874 -0.967193 0.0140418 -0.253655 -0.978927 -0.00833235 -0.20404 -0.983345 0.00788048 -0.18158 -0.98816 -0.00593237 -0.153315 -0.992786 0.00919759 -0.119551 -0.994367 -0.00233859 -0.105965 -0.998814 -0.00442153 -0.048489 -0.99892 -0.00209529 -0.0464229 -0.999856 0.00225608 0.0168012 -0.999806 0.00472051 0.0191323 -0.996413 -0.00298223 0.0845705 -0.995053 0.00954589 0.0988897 -0.987674 -0.00802779 0.15632 -0.982244 0.0134124 0.187127 -0.972104 -0.0101905 0.23433 -0.947471 0.0333881 0.318093 -0.958817 -0.0210967 0.28324 -0.913294 0.0201157 0.406805 -0.922149 -0.00841182 0.386744 -0.867096 0.00741551 0.498086 -0.869063 0.00304091 0.494692 -0.823111 -0.00202399 0.567876 -0.823204 -0.00233942 0.567741 -0.821531 -0.000149089 0.570163 -0.821513 0 0.570189 0.582202 0 0.813044 0.582202 0 0.813044 -0.034177 0 -0.999416 -0.034177 0 -0.999416 0.248537 0 -0.968622 0.248537 0 -0.968622 0.511009 0 -0.859575 0.511009 0 -0.859575 0.732314 0 -0.680967 0.732314 0 -0.680967 0.850386 0 -0.526159 0.850386 0 -0.526159 0.543083 0 -0.839679 0.315408 -0.0123821 -0.948875 0.404362 0.0736339 -0.91163 0.378927 0 -0.925426 0.469999 0 -0.882667 0.482199 0.0140061 -0.87595 0.535301 -0.0198714 -0.844428 0.544617 -0.00150518 -0.838683 0.626718 0.0164266 -0.779073 0.642517 0 -0.766272 0.711681 0 -0.702503 0.751386 0.0206395 -0.65954 0.7787 0 -0.627397 0.203493 0 0.979077 0.149777 0.0502709 0.987441 -0.571782 0.0457685 0.819128 -0.520312 -0.0217795 0.853698 -0.226941 0.0660073 0.971669 -0.151055 -0.0146645 0.988417 -0.58147 0 -0.813568 -0.58147 0 -0.813568 0.582202 0 0.813044 0.582202 -3.13355e-07 0.813044 -0.177609 0 -0.984101 -0.177613 -2.16475e-06 -0.9841 -0.177616 0 -0.9841 -0.177616 0 -0.9841 -0.177609 5.05997e-06 -0.984101 -0.177613 0 -0.9841 0.593805 -2.01852e-05 -0.804609 0.593788 0 -0.804621 0.593805 0 -0.804609 0.593788 1.30763e-05 -0.804622 0.593779 -0.000111596 -0.804628 0.593817 -4.85277e-05 -0.8046 0.593778 -4.68679e-05 -0.804629 0.593965 0.000281683 -0.804491 0.593171 0 -0.805076 0.593171 0 -0.805076 0.593739 -0.000201596 -0.804657 0.593937 -1.74665e-05 -0.804511 0.59359 -3.40399e-05 -0.804768 0.593821 6.81792e-05 -0.804597 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1.0029e-08 -1 1.38394e-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 -5.15633e-08 -1 2.20773e-07 2.20999e-08 -1 1.45699e-07 6.1532e-08 -1 1.2295e-07 -2.85161e-07 -1 2.16347e-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.272209 -0.00414019 -0.962229 0.271796 7.59471e-07 -0.962355 0.271797 0 -0.962355 0.271796 1.29112e-05 -0.962355 0.821739 -5.30728e-07 -0.569865 0.821669 6.31912e-05 -0.569965 0.821684 1.42829e-05 -0.569944 0.821669 0 -0.569965 0.821692 0 -0.569932 0.821667 -6.76677e-06 -0.569967 -0.865366 -6.13766e-06 -0.501141 -0.383777 0 -0.923426 -0.383777 0 -0.923426 -0.492338 0 -0.870404 -0.492438 -3.83149e-06 -0.870347 -0.550141 -3.89325e-06 -0.835072 -0.550034 0 -0.835142 -0.610359 0 -0.792125 -0.610358 0 -0.792125 -0.653467 0 -0.756955 -0.653352 2.98157e-06 -0.757055 -0.67833 2.52017e-06 -0.734758 -0.678375 0 -0.734715 -0.723275 0 -0.69056 -0.723275 0 -0.69056 -0.753236 0 -0.657751 -0.753236 0 -0.657751 -0.778802 0 -0.62727 -0.778802 0 -0.62727 -0.805681 0 -0.59235 -0.805681 0 -0.59235 -0.819923 0 -0.572474 -0.819923 0 -0.572474 -0.837904 0 -0.545817 -0.837904 0 -0.545817 -0.865379 0 -0.501119 -0.581233 0.707141 0.402641 -0.562758 0.707521 0.427456 -0.60126 0.707138 0.372078 -0.601262 0.707135 0.37208 -0.707137 0.706961 0.0127499 -0.706749 0.707341 0.0132266 -0.706197 0.706976 0.0383499 -0.702161 0.709693 0.0574895 -0.70448 0.707033 0.061751 -0.699202 0.706924 0.106654 -0.700979 0.705391 0.10513 -0.688421 0.708199 0.156623 -0.690093 0.706861 0.155304 -0.678443 0.706986 0.199717 -0.671127 0.71189 0.206885 -0.666384 0.696885 0.265113 -0.658706 0.710606 0.247278 -0.64167 0.705863 0.300028 -0.62047 0.714904 0.32238 -0.621697 0.69564 0.359968 -0.604788 0.707121 0.366349 -0.696512 0.716995 -0.0280769 -0.706984 0.707099 -0.0136318 -0.685823 0.725787 -0.0536672 -0.676118 0.733414 -0.0704849 -0.675287 0.734327 -0.0689325 -0.670888 0.735074 -0.0978584 -0.662445 0.742136 -0.10199 -0.660675 0.741643 -0.11608 -0.65635 0.743151 -0.13012 -0.658654 0.738786 -0.142725 -0.686103 0.725973 -0.0471772 -0.698995 0.714332 -0.0336959 -0.239749 0.765951 -0.596523 -0.602215 0.756848 -0.254004 -0.2315 0.769641 -0.595029 -0.319585 0.759324 -0.566827 -0.361175 0.763577 -0.535259 -0.385868 0.774159 -0.50178 -0.405321 0.766238 -0.498592 -0.438497 0.765309 -0.471192 -0.45137 0.767295 -0.455548 -0.457126 0.765334 -0.453101 -0.492547 0.762898 -0.41879 -0.492884 0.767627 -0.409651 -0.513749 0.763809 -0.390715 -0.535511 0.761507 -0.365151 -0.532104 0.763779 -0.365386 -0.559836 0.760551 -0.328857 -0.544427 0.770874 -0.330686 -0.562936 0.761525 -0.32122 -0.577738 0.759318 -0.299425 -0.575952 0.760558 -0.299719 -0.591507 0.758006 -0.274857 -0.605723 0.747754 -0.271964 -0.0839952 0.756645 -0.648408 -0.631027 0.750773 -0.195308 -0.630433 0.752034 -0.192353 -0.637305 0.750209 -0.176148 -0.638486 0.751866 -0.164419 -0.637281 0.754428 -0.157195 0.0913456 0.983059 0.158906 0.0913596 0.983029 0.159083 0.0915588 0.983081 0.158648 0.0916583 0.983081 0.158587 0.0917138 0.983204 0.157793 0.0920454 0.983241 0.157368 0.0900813 0.983329 0.157952 0.0905706 0.983656 0.155618 0.0894148 0.983677 0.156157 0.0904366 0.983634 0.155837 0.0881984 0.983847 0.155774 0.0888459 0.983743 0.156062 0.0848355 0.98553 0.146742 0.0854782 0.984555 0.152789 0.0871376 0.985341 0.146664 0.088873 0.983702 0.15631 0.0893768 0.984011 0.154062 0.0794074 0.987335 0.137349 0.0728742 0.989397 0.125627 0.0750267 0.987713 0.137092 0.0758781 0.988877 0.127927 0.0400052 0.996843 0.0685894 0.0387373 0.99733 0.0618977 0.0440459 0.99602 0.0774918 0.0578873 0.993439 0.0986281 0.0579071 0.993415 0.0988622 0.0651568 0.991334 0.114071 0.0247406 0.998779 0.0427528 0.0212008 0.999345 0.0293418 0.008623 0.999851 0.0149571 0.609406 0.682172 -0.40406 0.680264 0.697296 -0.225873 0.631481 0.715988 -0.297647 0.644814 0.706427 -0.291848 0.611025 0.706935 -0.356219 0.70018 0.713966 -0.000588583 0.708833 0.703995 -0.0441282 0.702806 0.709065 -0.0573617 0.704961 0.702306 -0.0989767 0.695927 0.709985 -0.107732 0.690704 0.704036 -0.165113 0.6871 0.706763 -0.168464 0.668255 0.70649 -0.23304 0.705285 0.707024 0.0518665 0.705352 0.706946 0.0520094 0.707265 0.706917 0.00673207 0.598372 0.64425 0.476332 0.590619 0.643226 0.487268 0.588843 0.644843 0.48728 0.699596 0.706613 0.106127 0.702378 0.704363 0.102652 0.688044 0.674551 0.267537 0.698095 0.682453 0.216615 0.691015 0.687994 0.221727 0.703835 0.684246 0.190852 0.706369 0.691168 0.152738 0.703729 0.693039 0.156406 0.691266 0.67219 0.265166 0.677255 0.669186 0.305805 0.673399 0.655466 0.341904 0.674806 0.670637 0.308032 0.666482 0.660133 0.346449 0.657547 0.65417 0.373756 0.63138 0.668457 0.393095 0.648619 0.653712 0.389813 0.635859 0.638662 0.433351 0.626192 0.647103 0.434904 0.612731 0.644809 0.456927 0.613936 0.641891 0.459411 0.60532 0.644003 0.467812 0.598901 0.643017 0.477333 0.580878 0.707177 -0.40309 0.221862 0.706758 -0.671766 0.228737 0.703093 -0.673305 0.287818 0.706315 -0.646746 0.278754 0.712171 -0.64429 0.333806 0.703972 -0.626894 0.327832 0.707312 -0.626288 0.378275 0.707083 -0.597446 0.363232 0.718655 -0.592957 0.412734 0.697628 -0.585633 0.453817 0.7084 -0.540574 0.444602 0.714298 -0.54047 0.508191 0.700072 -0.501638 0.496653 0.706617 -0.504013 0.551197 0.70637 -0.444099 0.551371 0.70627 -0.444041 0.192131 0.707098 -0.680514 0.19234 0.706865 -0.680696 0.192212 0.707036 -0.680555 0.192205 0.707047 -0.680545 0.192304 0.70823 -0.679286 0.1921 0.707138 -0.68048 -0.562758 -0.707521 0.427456 -0.581233 -0.707141 0.402641 -0.601262 -0.707135 0.37208 -0.60126 -0.707138 0.372078 -0.62047 -0.714904 0.32238 -0.621888 -0.686548 0.376707 -0.612038 -0.706985 0.354375 -0.64167 -0.705863 0.300028 -0.654665 -0.709633 0.260451 -0.658811 -0.706906 0.257396 -0.669785 -0.707068 0.226811 -0.671121 -0.711868 0.206982 -0.678487 -0.706939 0.19973 -0.689607 -0.706984 0.156893 -0.688757 -0.708224 0.155023 -0.70051 -0.705598 0.106853 -0.70179 -0.703988 0.109046 -0.70181 -0.709703 0.061517 -0.701412 -0.710149 0.0609029 -0.706197 -0.706976 0.0383499 -0.706755 -0.707344 0.0127431 -0.707136 -0.706954 0.0132339 -0.689593 -0.724085 -0.0127684 -0.706665 -0.706951 -0.0290581 -0.660675 -0.741643 -0.116082 -0.662445 -0.742135 -0.10199 -0.670888 -0.735074 -0.0978583 -0.67529 -0.734326 -0.0689107 -0.676131 -0.733403 -0.0704806 -0.685813 -0.725794 -0.0537031 -0.68664 -0.726301 -0.0318246 -0.70655 -0.705806 -0.0512427 -0.641672 -0.748796 -0.166017 -0.651642 -0.745576 -0.139568 -0.661052 -0.73382 -0.156585 -0.656351 -0.74315 -0.130121 -0.60849 -0.739847 -0.286996 -0.602212 -0.75686 -0.253977 -0.233219 -0.766042 -0.598989 -0.24405 -0.773083 -0.585476 -0.318389 -0.76151 -0.564562 -0.360975 -0.763873 -0.534972 -0.38765 -0.77344 -0.501516 -0.451363 -0.767304 -0.455539 -0.438436 -0.765312 -0.471245 -0.405294 -0.766238 -0.498614 -0.535511 -0.761507 -0.365151 -0.513633 -0.763818 -0.390848 -0.492898 -0.767611 -0.409664 -0.492561 -0.762896 -0.418775 -0.457147 -0.765333 -0.453081 -0.59694 -0.756935 -0.265916 -0.575962 -0.760556 -0.299704 -0.577723 -0.759334 -0.299413 -0.562922 -0.761541 -0.321208 -0.555317 -0.765448 -0.325135 -0.553114 -0.761495 -0.33792 -0.532104 -0.763779 -0.365386 -0.0629624 -0.751332 -0.656914 -0.637891 -0.75103 -0.170438 -0.637305 -0.75021 -0.176148 -0.630423 -0.752036 -0.192376 -0.631003 -0.750806 -0.195259 0.076681 -0.988539 0.13004 0.0769953 -0.987476 0.137708 0.0734348 -0.989337 0.125775 0.0794441 -0.987322 0.137418 0.0830438 -0.986139 0.143644 0.0851319 -0.985085 0.14953 0.0888791 -0.983696 0.156345 0.0871312 -0.985347 0.146629 0.085475 -0.984561 0.152753 0.0894859 -0.983671 0.156155 0.0885279 -0.983784 0.155987 0.0959362 -0.988938 0.113131 0.0900783 -0.983327 0.157968 0.0905708 -0.983656 0.155618 0.0904494 -0.983636 0.155817 0.0913308 -0.983066 0.15887 0.0893858 -0.984006 0.154084 0.0913471 -0.983031 0.159075 0.0915364 -0.983081 0.158662 0.0916725 -0.983081 0.158579 0.0917266 -0.983201 0.157803 0.0920572 -0.983238 0.15738 0.0659857 -0.99108 0.115786 0.0579125 -0.993416 0.098849 0.0578948 -0.993438 0.0986399 0.0440324 -0.996022 0.0774715 0.0387605 -0.997324 0.0619854 0.0400089 -0.996844 0.0685741 0.0167294 -0.999434 0.0291712 0.0167399 -0.999438 0.0290363 0.809717 0 0.58682 0.810946 -0.00290468 0.585113 0.823265 0.00349008 0.567646 0.824346 0.0011379 0.566086 0.830402 -0.00292964 0.557157 0.842801 0.00510292 0.538202 0.847707 -0.00360496 0.530452 0.862005 0.00298373 0.506892 0.864568 -0.000142107 0.502515 0.876245 -0.000141178 0.481866 0.877797 -0.00182983 0.479029 0.896994 0.00343834 0.442029 0.89686 0.00381343 0.442299 0.932805 0.0167808 0.359991 0.922694 -0.00295431 0.385523 0.980097 0.00780902 0.198366 0.942946 -0.00171817 0.332941 0.957818 0.00569611 0.287319 0.970935 -0.0192302 0.238571 0.965667 0.00726985 0.25968 0.985235 -0.00017754 0.171209 0.986379 -0.00461488 0.164424 0.991913 0.0043222 0.126844 0.994591 -0.00486839 0.103758 0.997262 0.00785866 0.0735335 0.999979 0.00636221 -0.000840599 0.999977 0.00678675 -0.000403103 0.996674 0.000132509 -0.0814885 0.996164 -0.00284163 -0.0874557 0.988202 0.00407898 -0.153103 0.987064 -0.000100361 -0.160329 0.971201 0.00350765 -0.238236 0.967641 -0.00328498 -0.252309 0.949021 0.00323298 -0.315195 0.945864 -0.000552325 -0.324564 0.910918 0.00761816 -0.412516 0.905691 -0.000205492 -0.423939 0.853232 -0.00838635 -0.521464 0.861049 -0.00178046 -0.50852 0.821683 0 -0.569945 0.821705 4.36023e-05 -0.569913 0.610531 -0.705373 -0.360139 0.609133 -0.682519 -0.403887 0.644387 -0.706723 -0.292074 0.63664 -0.712316 -0.295458 0.676342 -0.701501 -0.224631 0.669359 -0.706654 -0.229343 0.687026 -0.70682 -0.168527 0.690627 -0.704093 -0.165186 0.695974 -0.709925 -0.107828 0.699553 -0.706916 -0.104379 0.704822 -0.70704 -0.0576265 0.709752 -0.702684 -0.0498873 0.700214 -0.713933 -0.000588611 0.705273 -0.707026 0.0520036 0.723456 -0.689961 0.0237842 0.634624 -0.649829 0.418301 0.700055 -0.706709 0.102398 0.719094 -0.681745 0.134639 0.706899 -0.690795 0.151972 0.699673 -0.69142 0.179988 0.675535 -0.668775 0.310472 0.69031 -0.672038 0.268023 0.688665 -0.675064 0.26463 0.697793 -0.682237 0.218261 0.693386 -0.685467 0.222151 0.700632 -0.687653 0.19039 0.645203 -0.651874 0.398464 0.640739 -0.663597 0.386126 0.657567 -0.654122 0.373805 0.666777 -0.659646 0.346809 0.656784 -0.681735 0.322292 0.636079 -0.632898 0.441411 0.628935 -0.647526 0.430291 0.61221 -0.644714 0.457758 0.588823 -0.644862 0.48728 0.590638 -0.643208 0.487267 0.598464 -0.644241 0.47623 0.598162 -0.644524 0.476226 0.61277 -0.643435 0.458808 0.58098 -0.707177 -0.402943 0.551371 -0.70627 -0.444041 0.551197 -0.70637 -0.444099 0.496653 -0.706617 -0.504013 0.347967 -0.71988 -0.600577 0.369862 -0.706153 -0.60378 0.412088 -0.698782 -0.584711 0.431179 -0.716981 -0.547743 0.449755 -0.706264 -0.546728 0.506211 -0.701208 -0.502053 0.22133 -0.70677 -0.671929 0.228865 -0.702794 -0.673574 0.287479 -0.706521 -0.646672 0.278725 -0.712174 -0.644298 0.328984 -0.704794 -0.628518 0.192153 -0.707102 -0.680503 0.192199 -0.707067 -0.680526 0.192212 -0.707417 -0.680158 0.192206 -0.707057 -0.680535 0.191355 -0.708127 -0.679661 0.192413 -0.707098 -0.680434 -0.729472 6.53179e-07 0.684011 -0.729466 0 0.684017 -0.792933 0 0.609309 -0.792933 0 0.609309 -0.188074 0 -0.982155 -0.186663 0.00127931 -0.982423 0.150208 -0.0409384 -0.987806 0.1633 -0.0571474 -0.98492 0.501768 0.00687626 -0.864975 0.559859 -0.0758398 -0.82511 0.856299 0.0147701 -0.51627 0.79744 -0.132248 -0.588727 0.91943 0.0132318 -0.39303 0.991498 -0.0692926 -0.11014 0.999179 0.00962035 -0.0393612 0.926872 0.00338244 0.375362 0.946418 -0.0708559 0.315074 0.450418 0 0.892818 0.447541 0.00341025 0.894257 0.728231 -0.0577444 0.682895 0.738394 -0.0406769 0.673142 0.448775 -0.00122671 0.893644 0.447544 0 0.894262 -0.190706 -0.00632369 -0.981627 -0.188073 -0.00347528 -0.982149 0.163293 0.0578626 -0.984879 0.177582 0.0404468 -0.983274 0.560064 0.0708709 -0.825412 0.506636 -0.00302476 -0.862155 0.854006 0.0745928 -0.514888 0.793309 -0.0106705 -0.608725 0.993862 0.00697588 -0.110403 0.994178 0.0932009 -0.0540742 0.927496 -0.0270473 -0.372854 0.945991 0.0769294 0.314932 0.719107 0.0405118 0.693717 0.728237 0.0575971 0.682901 0.924657 -0.00741984 0.380729 0.144762 -0.704474 0.694809 -0.116621 -0.715149 0.689175 -0.292048 -0.70541 -0.645837 -0.311907 -0.714805 -0.625914 -0.419772 -0.692639 -0.586552 -0.511889 -0.71231 -0.480192 -0.507051 -0.704579 -0.496455 -0.601625 -0.705388 -0.374801 -0.608172 -0.716822 -0.341018 -0.673884 -0.693673 -0.254359 -0.694662 -0.710019 -0.115404 -0.690601 -0.716023 -0.101893 -0.72123 -0.692318 0.0228914 -0.683299 -0.71271 0.158577 -0.680538 -0.714621 0.161816 -0.660183 -0.689312 0.29834 -0.295783 -0.679055 0.671861 -0.36269 -0.724204 0.586502 -0.488677 -0.691825 0.531576 -0.556239 -0.71878 0.417077 -0.572432 -0.710627 0.409061 0.149861 -0.707681 0.690456 -0.0429299 -0.698588 0.714235 -0.13245 -0.725204 0.675674 0.292004 -0.705388 0.645881 0.318064 -0.717615 0.619568 0.419262 -0.693547 0.585843 0.514636 -0.708581 0.482766 0.517671 -0.712837 0.473159 0.610028 -0.695256 0.380111 0.647605 -0.721755 0.244291 0.65049 -0.711958 0.264533 0.714354 -0.689623 0.11882 0.698975 -0.714798 -0.0223163 0.695152 -0.718287 -0.0287688 0.701045 -0.694312 -0.162687 0.637802 -0.714309 -0.288047 -0.128788 -0.703415 -0.699014 -0.156401 -0.721474 -0.674547 -0.0225031 -0.695241 -0.718424 0.105627 -0.71272 -0.69345 0.115942 -0.708203 -0.696423 0.254641 -0.693723 -0.673726 0.351083 -0.720937 -0.597487 0.402202 -0.697156 -0.593471 0.565564 -0.705037 -0.427856 0.566686 -0.704447 -0.427342 0.654706 -0.704332 -0.274366 0.324022 0.700122 0.63627 0.311545 0.706847 0.635065 0.511811 0.70319 0.493532 0.501142 0.709177 0.495909 0.611359 0.693632 0.38094 0.642327 0.721383 0.258888 0.655952 0.713092 0.24744 0.716245 0.687605 0.119135 0.700743 0.694633 -0.162617 0.70029 0.713508 -0.0223582 0.703701 0.709872 -0.0297886 -0.159402 0.708482 -0.687491 -0.132926 0.719219 -0.681949 -0.0225538 0.693562 -0.720043 0.115876 0.708602 -0.696029 0.123797 0.712711 -0.690447 0.254096 0.695321 -0.672283 0.36622 0.721844 -0.587218 0.355141 0.710946 -0.606985 0.494577 0.691365 -0.526695 0.565668 0.71865 -0.404429 0.562067 0.703907 -0.434276 0.645962 0.705426 -0.291732 0.647846 0.715981 -0.260127 -0.295298 0.697393 -0.653025 -0.358594 0.719177 -0.595143 -0.414838 0.701359 -0.579659 -0.610554 0.694656 -0.380363 -0.510852 0.713707 -0.47922 -0.529984 0.704499 -0.472016 -0.490905 0.687752 0.534799 -0.359028 0.728422 0.583524 -0.574129 0.708556 0.410274 -0.577995 0.720405 0.383326 -0.656277 0.69379 0.296575 -0.688076 0.70785 0.159686 -0.684964 0.713907 0.145466 -0.718973 0.694664 0.0228197 -0.685628 0.718986 -0.113903 -0.704924 0.703731 -0.0885741 -0.663134 0.705409 -0.250302 -0.641925 0.716031 -0.274284 0.14114 0.709957 0.689956 0.104094 0.689085 0.717165 -0.107646 0.713404 0.692435 -0.0779755 0.729642 0.679369 -0.217379 0.690882 0.689514 -0.332157 0.709929 0.621026 -0.29288 0 -0.956149 -0.29288 0 -0.956149 -0.29288 0 -0.956149 -0.29288 0 -0.956149 0.259116 0 0.965846 0.259104 2.12067e-05 0.965849 0.259122 0 0.965845 0.259122 0 0.965845 0.259104 -2.12067e-05 0.965849 0.259116 0 0.965846 0.183212 0.707147 0.682918 0.183241 0.707079 0.68298 0.183264 0.707092 0.68296 0.183155 0.707009 0.683076 0.183359 0.707355 0.682663 0.866211 1.24197e-05 0.499678 0.866185 0 0.499724 0.183228 -0.707097 0.682965 0.183224 -0.707102 0.682961 0.183237 -0.70707 0.68299 0.183224 -0.707039 0.683026 0.1833 -0.707129 0.682913 0.866185 1.00091e-05 0.499724 0.86616 0 0.499767 0.0242681 0 0.999705 -0.106851 0 0.994275 -0.0657679 -0.00300169 0.99783 -0.24533 0.00470958 0.969428 -0.43423 0 0.900802 -0.163921 -0.00506375 0.98646 -0.302459 0.00133085 0.953162 -0.38092 -0.00131011 0.924607 -0.470774 0.00314238 0.882248 0.20083 0 0.979626 -0.000130661 0.00154098 0.999999 0.0900453 -0.000715143 0.995937 0.144818 0.000953667 0.989458 0.232005 -0.00203985 0.972713 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + + + + + + + + + + + +
diff --git a/descriptions/deep_robotics/x30_description/meshes/torso.dae b/descriptions/deep_robotics/x30_description/meshes/torso.dae new file mode 100755 index 0000000..ae032e6 --- /dev/null +++ b/descriptions/deep_robotics/x30_description/meshes/torso.dae @@ -0,0 +1,63 @@ + + + + + VCGLab + VCGLib | MeshLab + + Y_UP + 周四 11月 23 02:55:13 2023 + 周四 11月 23 02:55:13 2023 + + + + + + + + + 0.175495 0.0282167 0.0079859 0.177504 0.0284269 0.0111314 0.169495 0.0282167 0.0079859 0.164006 0.123193 0.0117679 0.160008 0.0270099 0.0454836 0.159991 0.0787873 -0.0279448 0.196995 0.0403689 -0.0153514 0.196996 0.0989426 -0.0380456 0.162534 0.0568934 -0.0357955 0.193431 0.0709432 0.0518322 0.193603 0.0367104 0.0304713 0.191004 0.0998736 0.0484095 0.193855 0.110486 0.0433058 0.197 0.119921 0.034096 0.191375 0.123554 0.0298983 0.196994 0.128081 0.0198677 0.169938 0.0585839 0.00599556 0.170425 0.0986183 0.0119494 0.162533 0.0824968 0.0295056 0.1692 0.0870527 0.0212036 0.162498 0.108538 -0.00583551 0.169169 0.0674873 0.0188834 0.162492 0.1027 -0.0358213 0.163025 0.115853 -0.0226956 0.162516 0.122147 -0.0047746 0.170858 0.10181 -0.0366157 0.170827 0.111319 -0.0286564 0.160916 0.103142 -0.0134008 0.160055 0.106584 -0.00543981 0.168155 0.0599481 -0.00220316 0.167412 0.0709505 -0.0187397 0.168124 0.0921453 -0.0165056 0.177401 0.0833536 -0.019751 0.182552 0.0910812 0.00263792 0.180406 0.0693863 -0.0047256 0.180414 0.0847351 -0.0105661 0.164039 0.0548841 0.0382661 0.1695 0.121551 0.0172245 0.190997 0.0392124 0.0203039 0.191 0.0769522 0.0444946 0.1775 0.0768978 0.0448725 0.1755 0.0787977 0.0453986 0.1755 0.124395 -0.00722923 0.169496 0.13347 -0.00309953 0.175496 0.13347 -0.00309953 0.1815 0.054995 0.0467772 0.183 0.0548178 0.0464747 0.183 0.0835354 0.053282 0.1815 0.0974735 0.0515857 0.181508 0.0512196 -0.0441684 0.1815 0.121452 0.0332807 0.181969 0.038375 0.0325035 0.182994 0.103436 -0.0380712 0.1815 0.0748001 -0.0522308 0.182994 0.126196 0.0278076 0.182539 0.0946513 -0.0512611 0.164 0.0480893 0.0486067 0.17551 0.0512159 -0.0441992 0.177229 0.121639 0.0328181 0.1715 0.105298 0.0466156 0.1695 0.105323 0.0463979 0.1695 0.0320579 -0.0232227 0.1755 0.11394 -0.0295173 0.175502 0.0777166 -0.0450189 0.1815 0.124395 -0.00722923 0.1815 0.0608975 -0.0407218 0.1775 0.0430466 -0.0263993 0.1815 0.0398967 -0.0213122 0.182998 0.0829369 -0.0448959 0.191 0.0423215 -0.0245662 0.160004 0.0801198 -0.0561903 0.16 0.0335 0 0.16 0.133098 -0.00113098 0.159997 0.136458 0.0454992 0.160007 0.134335 0.0601017 0.16 0.0415 0.0535 0.16 0.0799782 0.0592905 0.1695 0.0359915 -0.00929621 0.184079 0.0695528 0.00392393 0.177425 0.0807832 -0.0088635 0.182364 0.0734025 -0.0080189 0.177603 0.0742778 0.0074794 0.177602 0.0888149 0.00281524 0.1774 0.066918 -0.0150594 0.177399 0.0972693 -0.0101217 0.177399 0.0686752 0.0160831 0.177398 0.098239 0.0088893 0.177401 0.0825214 0.0198542 0.167814 0.0679549 0.0167507 0.177402 0.0597281 0.00229915 0.168167 0.100037 0.00221998 0.167896 0.0885525 0.0184038 0.160143 0.0535115 0.00899183 0.16 0.0483893 0.051 0.160005 0.108192 0.0324973 0.160002 0.0651099 0.020765 0.16 0.0493754 -0.00650312 0.160552 0.0670229 -0.0352587 0.160009 0.124014 0.0345498 0.160083 0.0914416 -0.0248112 0.159974 0.120357 -0.0185453 0.160207 0.0804904 0.0269089 0.160587 0.0565794 -0.0254046 0.196996 0.109257 -0.0310518 0.196996 0.0581401 -0.0366378 0.197004 0.035725 0.0160821 0.196997 0.0463813 -0.0262672 0.170733 0.122361 -0.00466609 0.196959 0.121776 -0.00781091 0.196994 0.118498 -0.0183882 0.197153 0.132354 -0.00594968 0.197006 0.0327785 0.0248351 0.197002 0.0582394 0.0479727 0.197 0.0771459 0.052527 0.196981 0.0885294 -0.0418023 0.196981 0.0728503 -0.0420603 0.197 0.082854 -0.052527 0.196993 0.0321403 -0.0198388 0.1965 0.0375 0 0.197 0.0382215 -0.00780176 0.196997 0.113619 0.0262672 0.196981 0.0871497 0.0420603 0.170743 0.072857 0.0420156 0.162551 0.0580319 0.0365203 0.170618 0.0421695 0.0196384 0.170675 0.0388286 -0.0110144 0.162512 0.0424092 -0.0198368 0.170673 0.0485476 -0.0285167 0.162533 0.0679588 -0.0406695 0.162518 0.0795631 -0.0426287 0.170698 0.0914492 -0.0408822 0.170696 0.119543 -0.0154546 0.163139 0.121137 0.0111555 0.170693 0.109229 0.0310202 0.162548 0.115014 0.0242135 0.162545 0.0961164 0.0394443 0.170579 0.0487255 0.0287123 0.163061 0.0376392 0.0046112 0.162512 0.10548 0.0142258 0.162517 0.051958 0.0102784 0.162501 0.0952225 -0.0246768 0.169161 0.0729146 -0.0211923 0.162514 0.0546947 -0.0145242 0.162528 0.0755315 -0.0289949 0.169262 0.101024 -0.00859508 0.169175 0.0881566 -0.0205304 0.177807 0.069145 -0.0193493 0.169556 0.0605339 -0.0105085 0.179508 0.058895 -0.00614623 0.180401 0.0976331 -0.00859807 0.177787 0.0956805 -0.0159058 0.179655 0.10192 0.000333716 0.179315 0.0831264 -0.0215031 0.180136 0.0688672 0.0187032 0.180405 0.0716499 0.00788551 0.180125 0.0849763 0.0213949 0.180475 0.0807723 0.0121052 0.193431 0.0890568 -0.0518322 0.196707 0.0287505 -0.0092974 0.196919 0.0277016 0.00761878 0.196542 0.12272 -0.031312 0.193675 0.131872 -0.00910922 0.196922 0.109921 -0.0438044 0.197 0.0369846 -0.0309326 0.191 0.121175 -0.0191597 0.191003 0.064406 -0.0426991 0.191012 0.0601386 0.048138 0.191022 0.0878894 0.0522271 0.191003 0.0332233 0.024509 0.191001 0.0607532 0.0404731 0.191 0.0958524 0.0419336 0.191002 0.10998 0.0332722 0.191 0.124406 0.00485427 0.191 0.119607 0.0206817 0.190986 0.12767 0.0195676 0.191 0.0889309 -0.043769 0.191 0.104139 -0.0375872 0.191029 0.0719819 -0.0521986 0.191 0.0355937 -0.00485429 0.191395 0.0364463 -0.0299026 0.18041 0.0703579 -0.0180404 0.16103 0.0802787 0.0317709 0.16 0.0693421 0.0379277 0.161862 0.081541 0.0425428 0.160067 0.0930218 0.0369242 0.160492 0.103837 0.0131029 0.160628 0.117347 0.0150023 0.161002 0.039668 0.012819 0.16087 0.0564081 0.016973 0.160944 0.0399925 -0.0113262 0.160756 0.0907491 -0.0331177 0.161043 0.113726 -0.0227556 0.160327 0.0561194 -0.0127341 0.162514 0.043131 0.0206291 0.197 0.121779 0.00780173 0.196995 0.119631 0.0153514 0.196996 0.10186 0.0366378 0.196981 0.0714705 0.0418023 0.196996 0.0610574 0.0380456 0.196996 0.050743 0.0310518 0.196993 0.0415024 0.0183881 0.196959 0.0382235 0.00781092 0.196998 0.100028 -0.0479946 0.197002 0.0585793 -0.0482245 0.190988 0.0323525 -0.0195457 0.197002 0.101357 0.0482795 0.160124 0.0930315 0.0234034 0.162507 0.0709744 0.0276149 0.164 0.1365 0 0.164 0.136515 0.0450842 0.16 0.0283881 0.06349 0.16 0.1265 0.0635 0.16 0.0235 0.0535 0.16 0.0976113 -0.0538685 0.16 0.0608111 -0.0533268 0.16 0.0295176 -0.0268668 0.16 0.127584 -0.0322512 0.164 0.134251 -0.0174378 0.16 0.136473 -0.00559456 0.16404 0.113838 0.0297864 0.163999 0.126589 0.044052 0.164 0.0335 0.0635 0.164015 0.048467 -0.0457653 0.163998 0.0739988 -0.0571005 0.164001 0.0804406 -0.0519826 0.163992 0.109053 -0.0493176 0.164 0.122211 -0.0378266 0.164012 0.124141 -0.00913087 0.164 0.0235135 -0.00551592 0.164 0.0326962 -0.0325578 0.164 0.0263446 0.00907289 0.164016 0.038257 0.0169788 0.164 0.040009 0.0593235 0.164003 0.0927379 0.0433073 0.164 0.110136 0.0445366 0.163999 0.131097 0.0634881 0.164 0.0235299 0.0586291 0.157258 0.0339787 0.0120742 0.157 0.0388769 0.0509925 0.157008 0.0336125 0.0534309 0.159944 0.0428564 -0.0289012 0.160001 0.0798288 -0.0479881 0.157 0.036 0.045 0.15697 0.123746 0.0509514 0.159128 0.11293 -0.0318111 0.160005 0.101238 -0.039324 0.159988 0.0527272 -0.0354253 0.159998 0.0756215 -0.0441805 0.16 0.0360507 -0.00907125 0.16 0.033551 0.0489861 0.16 0.122319 0.0534889 0.16 0.1265 0.0455 0.158485 0.0573457 -0.0402345 0.158497 0.035549 -0.0109078 0.157224 0.093209 -0.0439085 0.159968 0.125311 -0.0142329 0.158874 0.124011 -0.00275107 0.158565 0.126622 0.00808937 0.156895 0.0682691 -0.0439055 0.157019 0.126467 0.0492777 0.157015 0.118468 0.0534948 0.160004 0.0475746 -0.0457009 0.160003 0.0278162 0.00901813 0.160006 0.110905 -0.0460744 0.159999 0.132443 0.00891458 0.164 0.132536 0.00887563 0.164 0.0801516 0.0587439 0.16 0.0399482 0.0592951 0.16 0.119926 0.059323 0.164 0.119854 0.0596382 0.164016 0.0355943 -0.00804161 0.164019 0.0584207 -0.0406859 0.164008 0.0927324 -0.0439276 0.164005 0.107328 -0.0385309 0.159996 0.0235304 -0.00107436 0.181498 0.0281507 0.00850888 0.181505 0.0489208 0.0331007 0.181503 0.112831 -0.0419363 0.1815 0.0356051 0.00722924 0.1815 0.0320579 -0.0232227 0.1815 0.11394 -0.0295173 0.1815 0.0787977 0.0453986 0.181519 0.133407 0.0020037 0.181498 0.0878431 -0.0448358 0.1815 0.121551 0.0172244 0.1755 0.057113 -0.0383624 0.1755 0.0356051 0.00722924 0.1755 0.0320579 -0.0232227 0.1755 0.0398967 -0.0213122 0.175496 0.104093 -0.0395173 0.1755 0.0766518 0.0532715 0.175502 0.0490065 0.0331504 0.1755 0.0547325 0.0460589 0.1755 0.0748001 -0.0522308 0.1755 0.121551 0.0172244 0.1755 0.130721 0.0152659 0.177501 0.108744 0.0358556 0.1775 0.115504 -0.0283182 0.177499 0.12075 -0.0359185 0.177497 0.132999 0.00264182 0.177499 0.0564981 0.0479155 0.176019 0.0384163 0.0329343 0.177501 0.0731287 -0.0450887 0.177499 0.0958761 -0.0510186 0.1775 0.0350658 0.00971233 0.1775 0.0296526 -0.0173882 0.177514 0.049534 -0.0426699 0.1695 0.0368388 0.0115149 0.169496 0.107207 0.0358091 0.169476 0.113116 -0.0305593 0.169424 0.0960942 -0.0415444 0.169485 0.078901 0.0451631 0.1695 0.0766518 0.0532715 0.169502 0.0489312 0.0330894 0.1695 0.0547325 0.0460589 0.169477 0.0489394 -0.0333957 0.169498 0.0774549 -0.0456012 0.16951 0.0512159 -0.0441992 0.169499 0.113134 -0.041781 0.171229 0.121639 0.0328181 0.1695 0.130721 0.015266 0.1695 0.124395 -0.00722925 0.171505 0.125638 0.00606596 0.1715 0.115504 -0.0283182 0.171499 0.12075 -0.0359185 0.171497 0.132999 0.00264182 0.171501 0.108744 0.0358555 0.171499 0.052725 0.0357734 0.1715 0.0430466 -0.0263993 0.171504 0.0284269 0.0111314 0.171499 0.0958761 -0.0510186 0.171501 0.0731288 -0.0450887 0.171501 0.0726811 -0.0524512 0.1715 0.0768978 0.0448725 0.171498 0.0639828 0.0518434 0.1715 0.0350658 0.00971233 0.1715 0.0296526 -0.0173882 0.171514 0.049534 -0.0426699 0.170019 0.0384163 0.0329343 0.1715 0.100515 -0.0402145 0.177499 0.052725 0.0357734 0.177505 0.125638 0.00606594 0.175501 0.117418 -0.0379683 0.1775 0.100515 -0.0402145 0.177501 0.0726811 -0.0524512 0.1755 0.105323 0.0463979 0.177501 0.101858 0.0498831 0.175496 0.107327 0.0357135 0.175499 0.0872594 -0.052449 0.169499 0.0872594 -0.052449 0.191019 0.124545 -0.0293354 0.191003 0.0997172 -0.0479912 0.191005 0.0596873 -0.0482944 0.193843 0.0495119 -0.0433081 0.194123 0.0890585 0.0517476 0.191167 0.132164 0.00893512 0.194123 0.0709415 -0.0517476 0.191043 0.0276523 -0.00767119 0.193666 0.0496617 0.0433449 0.159993 0.0478822 0.030877 0.160027 0.0359975 0.0423229 0.161038 0.0504475 0.0381293 0.163983 0.0361071 0.047514 0.160897 0.108716 0.0447017 0.16 0.111611 0.051 0.161087 0.122785 0.048602 0.163979 0.115804 0.0356559 0.191366 0.0347148 0.0187962 0.197 0.127704 -0.0198858 0.183 0.132846 0.00275803 0.183 0.124542 0.00338801 0.18299 0.118797 0.0227396 0.182999 0.122 -0.0335233 0.183 0.120103 -0.0213122 0.183 0.0631786 -0.0413827 0.183 0.0460604 -0.0295173 0.182998 0.0284285 0.0109455 0.182995 0.039435 0.0200436 0.18301 0.0496138 -0.0426833 0.183001 0.0727406 -0.052449 0.181688 0.105832 0.0365732 0.182993 0.0554857 0.0374497 0.183003 0.0811663 0.0454584 0.183 0.0297503 -0.0175979 0.183 0.0356051 -0.00722924 0.183002 0.105318 0.045373 0.198114 0.0294958 0.015857 0.208975 0.0641356 -0.0503242 0.211868 0.1241 -0.0149067 0.222345 0.119288 0.0132393 0.222494 0.0504077 -0.0282821 0.222494 0.110892 -0.0268565 0.222498 0.0519112 -0.0193976 0.209014 0.0510235 -0.0252195 0.207647 0.0318056 -0.000330432 0.21995 0.102632 -0.027565 0.220626 0.0471917 -0.0128056 0.217 0.10386 -0.0300993 0.209014 0.110071 -0.0234775 0.217212 0.1144 -0.0164054 0.217123 0.0418316 -0.00259807 0.219058 0.0882343 -0.0331468 0.222525 0.0486679 0.026629 0.212 0.0973875 -0.0370605 0.212 0.05212 -0.0295903 0.205289 0.0465906 0.0279553 0.198111 0.0620762 -0.0392035 0.209004 0.0959775 -0.0397083 0.197639 0.122343 0.0310046 0.197933 0.079143 0.0527387 0.216499 0.0445333 0.0387494 0.197949 0.0332948 0.0248262 0.197079 0.0535288 -0.0456224 0.197069 0.121385 -0.0322932 0.212 0.119012 -0.0353368 0.212 0.0417682 -0.0362209 0.219378 0.120399 0.0238128 0.198037 0.0567697 0.0469867 0.206449 0.063993 0.0503603 0.211998 0.121801 0.0326654 0.206333 0.104144 0.0468102 0.209005 0.120479 0.0134131 0.209 0.0623325 0.0388636 0.208999 0.0412252 0.0179077 0.19807 0.0649222 0.0449951 0.199563 0.0962117 0.0501307 0.197716 0.131457 0.0112587 0.19806 0.126774 -0.0239973 0.1976 0.102261 -0.0472914 0.196915 0.113738 -0.0402611 0.197906 0.0367452 -0.0298292 0.197975 0.0433654 -0.0373291 0.197775 0.0458464 0.0399479 0.205517 0.0793173 0.0494147 0.208282 0.107673 -0.0332397 0.198002 0.0468491 -0.027141 0.208893 0.0373383 0.00438778 0.208767 0.0530366 0.0331983 0.198415 0.0755343 0.0426701 0.208857 0.113627 0.026677 0.197996 0.113887 0.0276487 0.212 0.0275221 -0.00347578 0.212001 0.0427741 0.0168978 0.212 0.0372969 0.0151887 0.211996 0.0292642 0.0157895 0.211999 0.0958016 -0.0503378 0.212 0.0805809 -0.0527054 0.212 0.0490734 0.0264023 0.212 0.0793315 -0.0406501 0.212 0.064692 -0.0376635 0.212 0.0300753 -0.0160811 0.212 0.0395067 0.00361937 0.212 0.112036 -0.0250308 0.212 0.104824 -0.0467092 0.212 0.121097 -0.0201466 0.212 0.120588 -0.00673258 0.212 0.13256 -0.0020261 0.212133 0.120052 0.0128588 0.212 0.130653 0.0155918 0.219453 0.0459372 0.00613354 0.220423 0.11547 -0.00252456 0.218381 0.110301 -0.0161957 0.217646 0.0515936 0.0199474 0.217544 0.11327 -0.00526911 0.217302 0.0882389 -0.0372337 0.217956 0.0616948 -0.0296011 0.2172 0.0478484 -0.0209738 0.217333 0.0727597 0.0376976 0.217224 0.0940119 0.0357803 0.21727 0.0669751 -0.0365079 0.20901 0.117662 -0.00768716 0.217009 0.118118 -0.0022001 0.217123 0.115695 0.0139994 0.216993 0.10846 0.0253892 0.217001 0.0565683 0.030125 0.217001 0.0470149 0.0191948 0.209744 0.043374 0.0107426 0.208999 0.0980019 0.038741 0.208999 0.118741 -0.0180015 0.209013 0.0930606 -0.0365207 0.209014 0.0686401 -0.0366962 0.208999 0.0619984 -0.0387412 0.209005 0.0395213 -0.0134131 0.208984 0.0800139 0.0437041 0.211995 0.0799757 0.0525709 0.212 0.055248 0.0322688 0.212001 0.0949745 0.0433087 0.222557 0.0551213 0.0326415 0.212 0.0821896 0.040601 0.212 0.100977 0.0352136 0.222476 0.0394834 0.00548108 0.222472 0.101943 -0.0268898 0.222489 0.120015 -0.00803651 0.222494 0.0410891 -0.0117734 0.222494 0.0659491 -0.0381474 0.222262 0.0732745 -0.0336498 0.222494 0.0886748 -0.040409 0.219724 0.0980393 0.0306862 0.222446 0.113516 0.00236893 0.220016 0.0577256 -0.0271469 0.222428 0.0473258 0.00766267 0.219472 0.0575176 0.027147 0.221178 0.0824631 0.0342231 0.217997 0.111516 0.0139816 0.22113 0.108814 0.0184214 0.212 0.112265 0.024768 0.205605 0.0452037 -0.0352815 0.208825 0.0464017 -0.0267254 0.198196 0.0497223 0.0348545 0.205622 0.115323 0.0353667 0.208753 0.123327 -0.00170013 0.205515 0.127949 0.000497507 0.198216 0.116171 -0.0328696 0.198328 0.0844647 -0.0426711 0.205706 0.0798188 -0.0491597 0.208758 0.0754956 -0.0426191 0.20901 0.116741 0.01105 0.209004 0.107858 0.0265617 0.209007 0.0928349 0.0360087 0.209007 0.0763566 0.0382853 0.209007 0.054176 0.0291002 0.209014 0.0421334 -0.00625114 0.222369 0.0662633 0.0318891 0.222403 0.0994889 0.0276405 0.218168 0.097096 0.0285779 0.218047 0.0782733 0.0338852 0.217531 0.0462699 -0.00396506 0.222505 0.11261 0.0252041 0.222494 0.0918815 0.0391844 0.222494 0.0732357 0.0400905 0.21668 0.123529 0.0292415 0.211998 0.048036 0.0416535 0.212597 0.0398739 0.0341769 0.198097 0.0399313 0.0158203 0.196922 0.0991989 0.0487788 0.197879 0.113204 0.0407355 0.198006 0.121585 -0.0108136 0.19812 0.040597 -0.0172174 0.198182 0.0952786 -0.0434756 0.19804 0.120391 0.0149086 0.198003 0.122714 0.00426941 0.198 0.130027 -0.000899661 0.198321 0.107329 0.0336487 0.197943 0.0965874 0.0397436 0.198944 0.113261 -0.0269192 0.197993 0.0784173 0.0496756 0.198587 0.0847988 0.0427049 0.198138 0.114525 -0.0371573 0.198 0.107007 -0.0332581 0.198148 0.0981736 -0.0390974 0.197914 0.0802805 -0.0526295 0.198003 0.0751379 -0.0425823 0.197998 0.046331 0.0270497 0.198003 0.037411 0.00484043 0.198416 0.0530783 -0.0332631 0.198001 0.0299244 -0.000824687 0.198799 0.0370441 -0.00361847 0.212003 0.100805 0.0419362 0.212001 0.0648615 0.045349 0.198032 0.0618774 0.0390322 0.211999 0.0642647 0.0378548 0.211904 0.0561025 0.0468897 0.212339 0.12112 0.0179819 0.200986 0.129812 0.0166617 0.212 0.0418338 -0.0154545 0.212 0.033663 -0.0245472 0.201024 0.0332734 -0.0239721 0.198232 0.0293027 -0.0154523 0.198036 0.0353054 -0.0157678 0.212 0.0588872 -0.0425266 0.212 0.0650998 -0.0437368 0.19824 0.0644851 -0.0455415 0.211999 0.0950216 -0.0431143 0.198033 0.0961678 -0.0502661 0.198089 0.122697 -0.020156 0.211997 0.0962329 0.0503716 0.203468 0.130044 -0.0159926 0.212 0.12666 -0.0241589 0.20656 0.0556315 -0.046868 0.198167 0.125811 0.0224252 -0.0724758 0.1315 0.063898 -0.156923 -0.1369 0.0143547 -0.157124 -0.136874 0.0575724 -0.153508 -0.125 -0.0264894 -0.0549529 4.13283e-05 -0.0885895 -0.158 -0.0815659 -0.0868471 0.158 0.0784167 -0.0890612 0.0502651 0.104119 -0.0826 -0.141 0.0045 -0.0906 -0.0742595 -0.0349404 -0.0885993 0.114328 -0.0287016 -0.0851 0.105347 -0.0350984 -0.0885994 0.128398 -0.00569519 -0.0851 0.155 -0.0859118 0.0638983 0.16 -0.0866015 0.0638994 0.160011 -0.0468468 -0.0390976 -0.155 -0.114606 0.0638983 0.159662 0.14273 0.0689001 -0.0324083 0.137181 0.0688992 -0.160052 -0.139857 0.0688606 0.0965143 -0.137238 0.0688983 0.160753 -0.137358 0.068893 0.161074 -0.068829 0.0639008 0.162082 -0.0695185 0.0689 0.158584 0.0199236 -0.0521544 -0.156195 0.00180197 -0.053193 -0.0135712 0.137418 0.0284285 0.00940475 0.136585 0.0193816 0.1096 -0.1495 0.01538 -0.102737 -0.1495 0.01388 -0.1024 -0.1495 0.01538 0.124737 -0.154 0.02488 -0.1244 -0.154 0.02638 -0.124737 -0.1315 0.02488 -0.13051 -0.130666 0.0248819 -0.131263 -0.154 0.02488 0.1096 -0.151216 0.05938 0.102732 -0.1315 0.0578799 0.1024 -0.151216 0.05938 -0.0663656 -0.132011 0.0585935 -0.0375646 0.13162 0.0138539 -0.0331808 0.131498 0.0153981 -0.0279149 0.131071 0.0582937 0.103294 0.13121 0.0578816 0.109238 0.131501 0.0578798 0.1244 0.1315 0.02638 0.102737 0.1495 0.01388 0.102734 0.1315 0.0138799 0.109263 0.1495 0.01388 -0.102728 0.1315 0.0138799 -0.1024 0.1495 0.01538 -0.131265 0.1315 0.0248799 -0.124737 0.154 0.02488 -0.102732 0.1315 0.0578799 -0.109203 0.131498 0.0578797 -0.156014 0.132857 0.000591171 -0.158715 -0.132135 0.000733683 0.09 0.0316 -0.0886 0.106843 0.0273608 -0.0885801 0.105112 0.0282236 -0.0826 0.12112 0.00548728 -0.0826 0.115171 -0.019783 -0.0826 0.106137 -0.0277878 -0.0885848 -0.0732663 0.0273687 -0.0885802 -0.0748884 0.0282236 -0.0826 -0.0588801 -0.00548728 -0.0826 -0.0626336 -0.0158 -0.0826 0.159325 0.0524464 -0.0444644 0.160006 0.0797353 -0.0520973 0.160008 0.111425 -0.0405762 0.16 0.133264 0.0441221 0.158797 -0.0828135 -0.05328 0.159997 -0.111194 -0.0474947 0.16 -0.129376 0.0437896 0.159896 -0.132945 0.0453734 0.16001 -0.0842435 0.0602944 0.16 -0.0392574 0.0561265 0.160004 -0.0278053 0.0454926 -0.16 0.0800058 0.057846 -0.160006 -0.0797353 -0.0520973 -0.159999 -0.132549 0.0449263 -0.159217 -0.0791471 0.0599504 -0.158337 -0.0469932 -0.0418716 -0.159994 0.131665 0.00866623 -0.153 -0.1315 0.00838 -0.159677 -0.0270989 0.00871474 0.156 0.109698 -0.043143 0.0245274 0.134532 0.0555577 0.1585 0.1049 0.0089 0.149206 0.128464 0.0089 0.147 0.1049 0.0089 -0.147 0.129 0.0089 -0.1585 0.1049 0.0089 0.0215 0.1315 0.03738 -0.0169325 0.130701 0.0655 -0.0215 0.1315 0.03738 -0.0214857 0.129 0.0654563 -0.0215 0.1315 0.04288 -0.0215 0.1315 0.04138 -0.0215 0.133 0.04213 -0.0214413 0.129 0.0338768 0.0215 -0.1315 0.04688 0.0215 -0.1315 0.04138 0.0225681 -0.132046 0.0572615 -0.0195 -0.1315 0.0339 -0.0215 -0.1315 0.04288 -0.021478 -0.129 0.0339063 -0.0215 -0.133 0.03738 -0.1567 -0.124 0.0669 -0.147 0.1302 0.0669 0.023639 0.1337 0.0669 0.1567 0.124 0.0669 0.1567 -0.124 0.0669 0.1532 -0.124 0.0669 0.023639 -0.1337 0.0669 0.158505 -0.12232 0.0536981 0.1585 -0.0413 0.0537 0.1585 -0.0309 2.22921e-09 0.1585 -0.0351917 -0.0131569 0.1585 -0.0407135 -0.0252479 0.1585 -0.0993999 -0.0424798 0.1585 -0.124808 -0.0131569 0.1585 -0.1267 2.22921e-09 -0.1476 -0.1315 0.0639 -0.102337 -0.131498 0.0593811 -0.102737 -0.152347 0.05788 -0.0863333 -0.133 0.05938 -0.0848589 -0.13154 0.0578788 -0.103208 -0.131231 0.0578836 -0.0661647 -0.1315 0.0538802 0.0366907 -0.13162 0.0586553 0.0863333 -0.133 0.05938 0.0714369 -0.131588 0.0586841 0.1476 -0.1315 0.05388 0.109202 -0.131501 0.0578797 0.102376 -0.131497 0.0593839 0.108782 -0.131341 0.0593796 0.0724758 -0.1315 0.063898 0.0854242 -0.133 0.05788 -0.153 0.1369 0.0639 -0.16 0.1369 2.86613e-08 -0.15575 0.1369 0.0144 -0.150067 0.1369 0.01938 -0.153 0.1369 0.04288 -0.153 0.1369 0.03038 -0.155205 0.137394 0.00852829 -0.0661439 0.131685 0.05788 -0.0276915 0.1315 0.05388 -0.0366711 0.131503 0.0589455 0.102737 0.152347 0.05788 0.0851184 0.131584 0.0578788 -0.025 0.144043 0.0689 -0.025 0.14781 0.0639 -0.1024 0.151216 0.05938 -0.0215147 0.1315 0.0639001 -0.164 0.0331 0.0639 -0.0317292 0.137866 0.0639001 -0.137016 0.14781 0.0639 -0.0965151 0.138007 0.0639 -0.155 0.0453923 0.0638965 -0.160954 0.143123 0.0639429 -0.1476 0.1315 0.0639 0.0863333 0.133 0.05938 0.0663335 0.132011 0.0587558 0.1476 0.1315 0.0639 0.0653064 0.131506 0.063899 0.163996 0.139562 0.0638993 0.161657 0.0678823 0.0639002 0.0962972 0.137456 0.0639 0.0724676 0.1315 0.0638971 0.025 0.14781 0.0639 0.16 0.0872553 0.0639 0.153 0.1369 0.0639 0.147134 -0.1369 0.04838 0.147134 -0.154 0.04838 0.0796667 -0.154 0.04838 -0.0796667 -0.133 0.04838 -0.147134 -0.154 0.04838 -0.147134 -0.1369 0.04838 0.0787576 -0.133 0.04688 -0.0799269 -0.154 0.04688 0.146403 -0.131511 0.0153811 -0.143959 -0.1495 0.01388 0.144627 -0.131501 0.0593765 0.140783 -0.151216 0.05938 -0.109231 -0.131501 0.0578797 0.075 -0.1495 0.00988 0.075 -0.1495 0.00838 -0.140783 -0.1369 0.00838 -0.1476 -0.1315 0.00988 -0.076 -0.1495 0.00988 0.143959 -0.1495 0.01388 0.109263 -0.1495 0.01388 -0.0787576 -0.133 0.02088 -0.0799269 -0.154 0.02088 -0.148 -0.1369 0.02088 -0.021 -0.133 0.02088 0.0209942 -0.149998 0.02088 0.021 -0.133 0.02088 0.0787576 -0.154 0.02088 -0.147134 -0.1369 0.01938 0.147134 -0.154 0.01938 0.0796667 -0.154 0.01938 0.1476 -0.1315 0.01938 0.021 -0.133 0.01938 -0.021 -0.133 0.01938 -0.1476 -0.1315 0.01938 -0.0796667 -0.133 0.01938 -0.147134 -0.154 0.01938 -0.148 -0.154 0.02088 0.0787576 -0.154 0.04688 -0.148 -0.154 0.04688 -0.080836 -0.154 0.04838 0.143959 -0.1369 0.05388 0.0716353 -0.1315 0.05388 0.144825 -0.1369 0.05238 0.1476 -0.1315 0.05238 0.0820226 -0.131503 0.05238 0.144825 -0.154 0.05238 0.083 -0.154 0.05388 0.0820909 -0.154 0.05238 -0.143959 -0.154 0.05388 -0.083 -0.133 0.05388 -0.1476 -0.1315 0.05388 -0.1096 -0.151216 0.05938 0.141649 -0.152347 0.05788 0.141649 -0.1369 0.05788 0.109337 -0.152347 0.05788 0.147698 -0.131598 0.05788 -0.109322 -0.152347 0.05788 -0.141649 -0.152347 0.05788 0.141649 -0.1495 0.00988 0.140783 -0.1495 0.00838 0.144825 -0.1495 0.01538 -0.109263 -0.1495 0.01388 -0.1096 -0.1495 0.01538 -0.153 -0.135857 -0.0108463 0.160007 -0.13485 -0.0150662 0.153 -0.13621 -0.00924027 0.131 0.125 -0.0846 0.0733815 0.125 -0.0877118 0.0768703 0.125 -0.0865885 -0.0739713 0.125 -0.0875982 -0.0743249 0.125 -0.0849316 -0.154 0.125 -0.0906 -0.070481 0.0326038 -0.0851 -0.105958 0.0344869 -0.0851 -0.0818866 0.0371237 -0.0851 -0.0505034 0.0138941 -0.0850992 -0.0645898 -0.0276896 -0.0851 -0.0505144 -0.00974038 -0.0851003 -0.12008 -0.0253444 -0.0850999 -0.100547 -0.036507 -0.0851 -0.132996 -0.0899932 -0.0851 -0.132994 0.0899967 -0.0851 0.137008 -0.00532474 -0.0851004 0.137004 -0.0892351 -0.0851001 0.043262 -0.114994 -0.0851 -0.0448044 -0.0940023 -0.0851014 0.137 -0.115 -0.0851 0.053382 -0.114869 -0.0851015 -0.141061 -0.0940112 -0.0851 -0.0545 -0.094 -0.0851 -0.147996 0.00531851 -0.0851001 -0.137014 0.00579196 -0.0851004 -0.0464932 0.0899967 -0.0851 0.0464963 0.0899939 -0.0851 0.119832 0.0227251 -0.0851 0.094138 0.037774 -0.0851 0.105958 0.0344869 -0.0851 0.132996 0.0899932 -0.0851 0.0818866 0.0371237 -0.0851 0.147993 0.0895386 -0.0906 0.0465 0.086 -0.0906 0.0451401 0.104041 -0.0851 0.0844396 -0.0371682 -0.0851 0.0657955 0.0286445 -0.0851 -0.0611099 0.0246853 -0.0851 -0.094138 0.037774 -0.0851 -0.0868285 0.0383029 -0.0886 -0.108032 0.0338082 -0.0885982 -0.119832 0.0227251 -0.0851 -0.128376 0.00388342 -0.0871155 0.0545 0.094 -0.0851 -0.0483699 0.104496 -0.0906002 -0.154 -0.125 -0.0906 -0.043453 -0.114997 -0.0906 0.0435336 -0.114994 -0.0906 -0.0425 -0.0015 -0.0906 -0.0464922 0.0015037 -0.0905999 0.0464922 -0.0015037 -0.0905999 -0.0451492 0.0940011 -0.0906 0.0452611 0.0940024 -0.0906 0.0452461 0.0940019 -0.0850995 -0.0440957 0.103824 -0.0906 0.0434677 0.112994 -0.0906 0.04 0.115 -0.0906 -0.0436392 0.114994 -0.0906 0.0505777 -0.0940094 -0.0906 0.132996 0.0899957 -0.0906 0.0489685 0.105533 -0.0906001 0.154 0.125 -0.0906 0.147993 -0.00489143 -0.0906 0.137 -0.0085 -0.0906 -0.0523521 0.0899991 -0.0906 -0.147996 0.0057083 -0.0906 -0.0505 0.086 -0.0906 -0.0545 0.094 -0.0906 -0.133 0.086 -0.0906 0.0505 -0.086 -0.0906 0.133 -0.086 -0.0906 0.13299 -0.0899944 -0.0851 0.137008 -0.0899841 -0.0906 -0.158 0.121 -0.0906 -0.0486122 -0.104661 -0.0906 -0.0465 0.086 -0.0906 0.145617 -0.105286 -0.0905995 0.145323 0.105275 -0.0906003 -0.158 0.079149 -0.0891424 -0.158 -0.0786168 -0.0893952 -0.158 -0.121 -0.0906 -0.158 -0.0815 -0.0826 -0.163405 0.00151854 -0.080721 -0.158 -0.0276 -0.0826 -0.158 -0.02421 -0.0812496 -0.158 0.0166 -0.0826 -0.163693 -0.00152003 -0.0807657 -0.158 -0.0055 -0.0826 -0.158029 0.0247888 -0.0825968 -0.158 0.0745 -0.0826 -0.158 0.0817018 -0.0825815 0.163546 0.0784734 -0.0807129 0.163693 0.00152003 -0.0807657 0.158 0.105396 -0.0825874 0.163405 -0.00151854 -0.080721 0.163405 0.0205815 -0.080721 0.158 0.0276 -0.0826 0.158 -0.0788536 -0.0862954 0.158 -0.0745 -0.0826 0.158 -0.0828583 -0.0825888 0.158 0.0815659 -0.0868471 0.158 0.121 -0.0906 0.158 -0.0796374 -0.089386 -0.152 0.0132698 0.0596237 -0.152001 -0.0156372 0.0566488 0.16 -0.0309 0.0457 0.159998 -0.0288658 0.0133003 0.16 -0.1369 0.0638991 0.158399 -0.02332 -0.00389435 -0.16 0.1291 0.0457 -0.160028 0.0748671 -0.0508201 -0.16 0.0635452 -0.0482631 -0.159967 0.0418091 -0.033261 -0.15924 0.0332702 -0.0203553 -0.16 0.0309 0.02285 -0.16 0.12176 0.0581562 -0.16 0.0866013 0.0638992 -0.16 0.0725811 0.0581 -0.160001 0.112856 -0.0460449 -0.15501 0.0852233 0.0581104 -0.16 0.0235222 0.0589782 -0.16 -0.1187 0.0561 -0.16 -0.0307132 0.00909619 -0.16 -0.0391046 0.0608924 -0.159642 -0.0850204 -0.0563996 -0.159523 -0.107282 -0.0413865 -0.16 -0.12924 0.0111278 -0.160002 -0.125537 -0.0202965 -0.157513 -0.0271674 0.000665457 -0.159999 -0.0291785 -0.00548243 -0.159024 -0.0414259 0.0634677 -0.155014 -0.0747761 0.0581104 -0.16 -0.085043 0.0581303 -0.16 -0.113917 0.0638991 -0.155027 -0.11558 0.0581305 -0.16001 -0.135061 -0.0147765 -0.16 -0.136888 -0.00134878 -0.16 -0.1369 0.0639001 -0.161928 -0.0691793 0.0639004 0.163226 0.0146981 -0.051006 0.164 0.0236011 -0.0352062 0.164 0.0206 -0.0058711 0.164 0.0231 1.88724e-08 0.162642 0.0183833 0.00184181 0.158422 0.000327019 0.000617635 0.164004 0.00598892 0.0029303 0.164 -0.0288684 -0.0317285 0.164 -0.0306704 -0.0283584 0.164 -0.0500149 -0.0516235 0.164 -0.0396536 -0.0401221 0.163241 -0.0522026 -0.0498519 0.164 -0.020599 -0.0453564 0.164 -0.0236013 -0.0350385 0.160207 -0.018225 -0.0525902 0.164043 -0.0143895 -0.0509975 0.164001 -0.00150474 -0.00422946 0.164001 -0.0185103 0.00690665 0.164 -0.0250252 -0.0146757 0.164 0.0231121 0.0565324 0.164 0.0203653 0.0638002 0.164 -0.0209877 0.0537732 0.164 -0.0205922 0.0390318 0.159759 -0.0166644 0.0474972 0.164001 0.0205254 0.00691628 0.163997 0.020516 0.0454398 0.164 -0.00155242 -0.0563241 0.164 -0.0236 -0.0796 0.164 -0.065018 -0.0548922 0.164 -0.0619967 -0.0569207 0.164 -0.106233 -0.0536277 0.164 -0.095964 -0.057526 0.163676 0.0408982 -0.041673 0.164 0.039477 -0.0438403 0.163265 0.0741988 -0.0566868 0.164 0.122 -0.0796 0.156316 -0.124996 -0.0840841 -0.164076 0.0185155 0.00191277 -0.164 0.0250252 -0.0146757 -0.164 0.0288684 -0.0317285 -0.164 0.039477 -0.0438403 -0.164 0.0500149 -0.0516235 -0.163165 0.0424692 -0.0435748 -0.164 0.0236013 -0.0350385 -0.164001 0.00276392 -0.0561225 -0.163999 0.018168 -0.0561061 -0.160207 0.018225 -0.0525902 -0.164079 -0.0141824 -0.0511884 -0.164006 0.00151583 -0.0578775 -0.163997 -0.020516 0.0454398 -0.164 0.0178342 0.0638896 -0.164 -0.137396 0.0689 -0.164 0.02114 0.0597314 -0.164 0.0231 3.29143e-10 -0.164001 0.0205309 0.00691657 -0.164 -0.0250252 -0.0146757 -0.162642 -0.0183833 0.00184181 -0.164001 -0.0205259 0.00693226 -0.164 -0.0306704 -0.0283584 -0.164 -0.039477 -0.0438403 -0.163533 -0.0408609 -0.0416083 -0.164 -0.0500149 -0.0516235 -0.164 -0.0619967 -0.0569207 -0.164 -0.0815481 -0.0602015 -0.164031 -0.101473 -0.053303 -0.164 -0.106233 -0.0536277 -0.164 -0.117856 -0.0466164 -0.164 -0.0176618 -0.0561098 -0.163698 -0.0189444 -0.0534017 -0.164 0.0236 -0.0796 -0.164 0.065018 -0.0548922 -0.164 -0.121999 -0.0500988 -0.163996 -0.124997 -0.0375736 -0.164 -0.122 -0.0796 -0.163425 0.0205797 -0.0807777 -0.163546 -0.0784734 -0.0807129 -0.155 -0.0203377 0.0277779 -0.155 -0.0204164 0.00691851 0.025 -0.144043 0.0689 0.137016 -0.14781 0.0639 0.025 -0.14781 0.0639 0.0185 0.1315 0.02638 0.0754242 0.133 0.02638 0.153 0.1369 0.03038 0.1476 0.1315 0.03038 -0.074 0.154 0.03038 -0.010248 0.131593 0.0295182 0.076337 0.153999 0.0248804 -0.124737 0.1315 0.02488 0.124737 0.154 0.02488 0.153 0.1369 0.03188 -0.073 0.133 0.03188 0.1476 0.1315 0.03188 0.074 0.154 0.03188 -0.074 0.154 0.03188 -0.074969 -0.131503 0.00988001 -0.102734 -0.1315 0.01388 -0.109191 -0.131501 0.0138798 -0.0335807 -0.131319 0.0099484 -0.0351662 -0.131313 0.0140124 -0.0830143 -0.149494 0.01388 -0.0667769 -0.132043 0.0138789 -0.0189938 -0.149498 0.01388 0.036706 -0.131643 0.0138316 0.083 -0.1495 0.01388 0.103685 -0.131188 0.0138813 0.1476 -0.1315 0.00988 0.109223 -0.131501 0.0138797 0.0822477 -0.131509 0.0138821 -0.028637 0.131527 0.0100421 -0.0681789 0.132091 0.0138739 -0.00264824 0.136726 0.0138802 0.0190004 0.1315 0.01388 0.0354532 0.131471 0.0138409 0.0785616 0.131497 0.0138835 0.109193 0.1315 0.0138798 0.0215 0.1315 0.04688 0.1476 0.1315 0.04688 0.148 0.154 0.04688 -0.0215 0.1315 0.04688 0.080836 0.154 0.04838 0.147134 0.154 0.04838 0.0796667 0.133 0.04838 0.147134 0.1369 0.04838 -0.147134 0.1369 0.04838 -0.153 0.1369 0.0477488 -0.1476 0.1315 0.04838 -0.0215 0.1315 0.04838 -0.0796667 0.133 0.04838 0.1476 0.1315 0.04138 0.0215 0.1315 0.04138 0.0754242 0.133 0.04138 -0.0754242 0.133 0.04138 -0.1476 0.1315 0.04138 -0.0765936 0.154 0.04138 -0.153 0.1369 0.04138 -0.153 0.154 0.04138 0.0215 0.1315 0.04288 0.0775027 0.154 0.04288 -0.0775027 0.154 0.04288 -0.083 0.1495 0.01388 -0.102737 0.1495 0.01388 -0.019 0.133 0.01538 -0.0244022 0.133782 0.0120173 0.019 0.133 0.01538 -0.00310317 0.135681 0.0153819 0.0820909 0.133 0.01538 0.102305 0.131499 0.0153807 0.0820909 0.1495 0.01538 0.1024 0.1495 0.01538 -0.1244 0.154 0.02638 0.144825 0.1369 0.05238 0.143959 0.1369 0.05388 0.083 0.133 0.05388 0.0830047 0.153999 0.0538797 0.143959 0.154 0.05388 0.0765936 0.154 0.02638 0.1244 0.154 0.02638 -0.147134 0.154 0.01938 -0.1476 0.1315 0.01938 -0.0796667 0.133 0.01938 0.147134 0.1369 0.01938 0.0796667 0.133 0.01938 0.080836 0.154 0.01938 0.147134 0.154 0.01938 -0.1476 0.1315 0.02088 0.1476 0.1315 0.02088 0.148 0.1369 0.02088 0.148 0.154 0.02088 -0.0799269 0.154 0.02088 0.021 0.133 0.02088 -0.021 0.133 0.02088 -0.148 0.1369 0.02088 -0.00328788 0.135982 0.0208796 -0.00456586 0.149993 0.02088 0.140783 0.1495 0.00838 0.141649 0.1369 0.00988 0.141649 0.1495 0.00988 -0.1476 0.1315 0.00988 -0.141649 0.1495 0.00988 -0.15305 0.1315 0.00838011 -0.075 0.133 0.00838 -0.140783 0.1369 0.00838 -0.075 0.1495 0.00838 -0.148 0.154 0.02088 -0.153 0.154 0.04288 -0.080836 0.154 0.04838 -0.147134 0.154 0.04838 -0.148 0.154 0.04688 -0.083 0.133 0.05388 -0.147616 0.131516 0.05238 -0.0832602 0.154 0.05238 -0.0820909 0.133 0.05238 -0.144825 0.154 0.05238 -0.143959 0.154 0.05388 -0.00516762 0.148836 0.00837858 -0.00283937 0.135253 0.00988097 0.0147367 0.148914 0.00940865 0.0854242 0.152347 0.05788 0.102328 0.151216 0.0593799 -0.0863333 0.151216 0.05938 -0.102678 0.152347 0.05788 -0.0787576 0.133 0.02088 -0.021 0.133 0.01938 -0.02035 -0.1315 0.01388 0.0211878 -0.131558 0.00988535 0.0763333 -0.133 0.02488 0.073 -0.133 0.03188 0.021 -0.133 0.03188 -0.0217129 -0.13204 0.0583641 0.0215 -0.1315 0.03738 0.153 -0.1369 0.03738 0.073 -0.154 0.03738 -0.153 -0.154 0.03738 -0.073 -0.133 0.03738 0.153 -0.1369 0.03588 -0.073 -0.133 0.03588 -0.1476 -0.1315 0.03588 0.0763333 -0.133 0.04288 0.0215 -0.1315 0.04288 0.1476 -0.1315 0.04288 0.153 -0.1369 0.04288 0.0763333 -0.154 0.04288 -0.0763333 -0.133 0.04288 -0.0775027 -0.154 0.04288 -0.153 -0.1369 0.04288 0.153 -0.1369 0.04138 0.153 -0.154 0.04138 -0.0215 -0.1315 0.04138 -0.1476 -0.1315 0.04138 -0.0754242 -0.133 0.04138 0.0215 -0.133 0.04763 -0.0215 -0.133 0.04763 0.0215 -0.133 0.04213 -0.0215 -0.133 0.04213 0.073 -0.133 0.03588 0.0215 -0.133 0.03738 0.0380999 -0.133 0.01538 0.1024 -0.1495 0.01538 0.0380999 -0.1315 0.01538 0.019 -0.133 0.01538 -0.0194249 -0.131512 0.0153793 -0.0379495 -0.133 0.014881 -0.0820909 -0.133 0.01538 0.1316 -0.154 0.02638 -0.0754242 -0.133 0.02638 0.0754242 -0.154 0.02638 0.0754242 -0.133 0.02638 0.1244 -0.154 0.02638 0.021 -0.133 0.02638 0.124737 -0.1315 0.02488 0.021 -0.133 0.02488 -0.153 -0.154 0.02488 0.0763333 -0.154 0.02488 -0.076337 -0.153999 0.0248804 -0.124737 -0.154 0.02488 -0.1405 -0.1315 -0.0011 -0.1312 -0.1315 0.000900003 0.1405 -0.1315 -0.0011 0.148534 -0.1315 -0.0237819 -0.061 -0.1315 0.0069 -0.059 -0.1315 0.0069 -0.101 -0.1315 0.0069 -0.095 -0.1315 0.0069 0.035 -0.1315 0.0069 0.041 -0.1315 0.0069 -0.017 -0.1315 0.0069 -0.013 -0.1315 0.0069 -0.049 -0.1315 0.0069 0.085 -0.1315 0.0069 0.047 -0.1315 0.00838 -0.043 -0.1315 0.0069 -0.071 -0.1315 0.0069 -0.065 -0.1315 0.0069 -0.005 -0.1315 0.0069 -0.0251 -0.1315 0.00838 -0.001 -0.1315 0.0069 0.1312 -0.1315 0.0069 0.153 -0.1315 0.00838 0.101 -0.1315 0.0069 -0.035 -0.1315 0.0069 -0.025 -0.1315 0.0069 0.065 -0.1315 0.0069 0.013 -0.1315 0.0069 0.017 -0.1315 0.0069 -0.0215 -0.1315 0.04838 -0.1476 -0.1315 0.04838 -0.1476 -0.1315 0.05238 0.0215 -0.1315 0.04838 0.0309 -0.1315 0.01538 -0.0381431 -0.1315 0.0153814 0.109519 -0.131497 0.0153807 0.1476 -0.1315 0.02088 0.131265 -0.1315 0.0248799 0.130386 -0.130817 0.0263806 0.1476 -0.1315 0.03038 0.1476 -0.1315 0.03588 0.1476 -0.1315 0.03188 0.0214999 -0.1315 0.03588 -0.0214999 -0.1315 0.03588 0.0195 -0.1315 0.0339 -0.0215 -0.1315 0.03738 -0.1476 -0.1315 0.03738 0.1476 -0.1315 0.03738 0.1476 -0.1315 0.04138 -0.0215 -0.1315 0.04688 -0.0689 -0.1315 0.05238 -0.0716362 -0.1315 0.0538801 -0.0689 -0.1315 0.00838 0.0697355 -0.1315 0.00838 0.0661638 -0.1315 0.0538801 0.0277732 -0.133 0.0538791 0.0234561 -0.131747 0.0523414 0.0236175 -0.133065 0.00835708 -0.073 -0.133 0.03188 -0.153002 -0.13694 0.0089625 0.073 0.133 0.03588 0.153 0.1369 0.03588 0.074 0.154 0.03588 0.1476 0.1315 0.03588 -0.153 0.154 0.03588 -0.074 0.154 0.03588 0.074 0.154 0.03738 0.153 0.1369 0.03738 0.1476 0.1315 0.03738 -0.153 0.1369 0.03738 -0.1476 0.1315 0.03738 0.0215222 0.132095 0.0587039 -0.0380999 0.133 0.01538 -0.0820909 0.133 0.01538 0.0215 0.133 0.04763 0.0787576 0.133 0.04688 -0.0215 0.133 0.04763 0.0763333 0.133 0.04288 0.0215 0.133 0.04213 0.0215 0.133 0.03663 -0.0214995 0.133 0.03663 0.037 0.1315 0.0069 -0.029 0.1315 0.0069 -0.031 0.1315 0.0069 -0.035 0.1315 0.0069 -0.037 0.1315 0.0069 -0.153 0.1315 0.0069 -0.107 0.1315 0.0069 -0.097 0.1315 0.0069 -0.071 0.1315 0.0069 -0.073 0.1315 0.0069 -0.053 0.1315 0.0069 -0.017 0.1315 0.0069 -0.0259355 0.1315 0.00838 -0.025 0.1315 0.0069 -0.0190178 0.131514 0.00838034 -0.023 0.1315 0.0069 0.001 0.1315 0.0069 -0.005 0.1315 0.0069 -0.007 0.1315 0.0069 0.0189737 0.131528 0.00838019 0.029 0.1315 0.0069 0.019 0.1315 0.0069 0.013 0.1315 0.0069 0.055 0.1315 0.0069 0.077 0.1315 0.0069 0.0697355 0.1315 0.00838 0.065 0.1315 0.0069 0.091 0.1315 0.0069 0.1168 0.1315 0.0069 0.152999 0.1315 0.00837998 -0.109223 0.1315 0.0138797 -0.1476 0.1315 0.04288 -0.1476 0.1315 0.05388 0.0661647 0.1315 0.0538801 -0.0689 0.1315 0.05238 -0.109525 0.131497 0.0153807 -0.145922 0.131501 0.0153816 0.1476 0.1315 0.01938 -0.102392 0.1315 0.0153802 0.124757 0.1315 0.0248799 -0.1476 0.1315 0.03038 -0.124389 0.1315 0.0263801 -0.0185 0.1315 0.03038 -0.0185 0.1315 0.02638 0.0195 0.1315 0.0339 0.0019418 0.1315 0.0336 -0.0215 0.1315 0.03588 -0.1476 0.1315 0.03188 -0.102376 0.131497 0.0593835 0.0214983 0.1315 0.04838 0.1476 0.1315 0.05238 0.0184602 0.130998 0.0640141 -0.0678197 0.133 0.00838098 -0.0275722 0.133 0.0528389 0.0246319 0.133588 0.0118207 0.0233817 0.131744 0.0523733 0.0276915 0.1315 0.05388 0.0689 0.1315 0.05238 0.0662322 0.133044 0.052847 0.0716362 0.1315 0.05388 0.130316 0.130695 0.024884 0.153 0.154 0.02638 0.131263 0.154 0.02488 -0.130504 0.130894 0.0263805 -0.149638 0.131958 0.02638 -0.143326 0.131482 0.059375 0.140783 0.1369 0.00838 0.1405 0.105 -0.0806 0.1405 -0.1315 -0.0241942 0.1385 0.11 0.000900003 0.1312 -0.1315 0.000900003 -0.1405 0.105 -0.0011 -0.1405 0.105 -0.0806 -0.1385 0.105 -0.0826 0.140232 -0.125 -0.0816 -0.1385 -0.1315 0.000900003 -0.1395 -0.1315 0.00063205 -0.140375 0.105 -0.000403789 -0.140232 -0.1315 -9.99995e-05 0.140375 0.105314 -0.000402761 0.140376 -0.1315 -0.000407768 0.139914 -0.1315 0.000314216 0.139914 0.106464 0.000314216 0.139145 0.108387 0.000793087 0.138956 -0.1315 0.000898559 0.159996 0.134347 -0.0183666 0.156003 0.133917 -0.018815 -0.1585 -0.0333 2.22921e-09 -0.143 -0.0351917 -0.0131569 -0.143 -0.0407135 -0.0252479 -0.143 -0.049418 -0.0352935 -0.143 -0.0733539 -0.0462247 -0.143 -0.0993999 -0.0424798 -0.143 -0.110582 -0.0352935 -0.143 -0.119287 -0.0252479 -0.1585 0.1267 0.0089 -0.151993 0.124892 0.0515259 -0.151208 0.126701 0.0089003 -0.149169 0.128515 0.0089 -0.147 0.1049 0.0089 -0.147 0.0333 0.0089 -0.147 -0.0333 0.0089 -0.147 -0.129 0.0689 -0.147 0.1049 -0.039508 -0.147 0.0918987 -0.0451587 0.1585 -0.126699 0.047376 0.147 -0.1267 0.0089 0.152 0.124 0.0689 0.149833 0.128216 0.0687467 0.147 0.129 0.0089 0.151208 0.1267 0.0089 0.158783 0.0352623 -0.0137396 0.147 0.0778009 -0.0466482 0.147 0.0918987 -0.0451587 0.1585 0.0918987 -0.0451587 0.1585 0.1267 0.0089 0.147 0.0417084 -0.0267328 0.147 0.0514937 -0.0369903 0.147 0.0639057 -0.0438391 -0.09 -0.0316 -0.0826 0.156 0.108 -0.0826 0.0588801 0.00548728 -0.0826 0.100808 -0.0296943 -0.0826 0.117366 0.0158 -0.0826 0.0696879 -0.024207 -0.0826 0.0626336 -0.0158 -0.0826 0.12112 -0.00548728 -0.0826 -0.0626336 0.0158 -0.0826 -0.117366 0.0158 -0.0826 -0.106887 0.0271989 -0.0826 -0.0731134 -0.0271989 -0.0826 -0.156 0.119766 -0.082601 -0.09 0.0316 -0.0826 -0.1385 -0.125 -0.0826 -0.0481843 -0.105324 -0.0826 -0.0588801 0.00548728 -0.0826 -0.0492571 0.106103 -0.0825999 -0.0478334 0.104052 -0.0826 0.131 0.121 -0.0826 -0.163255 0.0743894 -0.0567327 -0.147 0.065018 -0.0548922 -0.1631 0.0520568 -0.0494396 -0.147 0.0868609 -0.0567801 -0.163647 0.0894855 -0.0562686 -0.163208 0.10316 -0.0519175 -0.164 0.0306704 -0.0283584 -0.147018 0.0238964 -0.0114447 -0.147 0.0306704 -0.0283584 0.146999 0.0716343 -0.0568984 0.164 0.065018 -0.0548922 0.164 0.094369 -0.0550558 0.164 0.0306704 -0.0283584 0.147 0.0306704 -0.0283584 0.164 0.0250252 -0.0146757 -0.0653064 -0.131506 0.063899 -0.155014 -0.0456554 0.0638466 -0.16 -0.0872553 0.0639 -0.025 -0.14781 0.0639 -0.153 -0.1369 0.0639 0.164 -0.137396 0.0639 0.0215147 -0.1315 0.0639001 0.065382 -0.131506 0.0638991 0.152 -0.0413 0.0537 0.152001 -0.013423 0.0481768 0.152039 0.0051385 0.0477285 0.152036 -0.0129026 0.0298153 0.152 0.0136628 0.0402526 0.152 -0.0333 0.0089 0.152001 0.00812485 0.0286582 0.152 0.0333 0.0089 0.152 0.1187 0.0537 0.152 0.0413 0.0537 0.151625 -0.126644 0.0501599 0.149169 -0.128515 0.0089 0.147 -0.129 0.0089 0.158523 0.0333201 0.050013 0.147 0.0333 0.0089 0.147 0.0354517 -0.014012 0.152 0.0333167 0.0481625 0.1585 0.0413 0.0537 0.151753 0.12601 0.0503811 0.143 -0.124808 -0.0131569 0.143 -0.110582 -0.0352935 0.143 -0.0993999 -0.0424798 0.1585 -0.0866461 -0.0462247 0.143 -0.0733539 -0.0462247 0.158944 -0.0735037 -0.0463094 0.143 -0.049418 -0.0352935 0.1585 -0.049418 -0.0352935 0.143 -0.0351917 -0.0131569 0.1585 -0.0333 2.22921e-09 0.143 -0.0333 0.0089 0.1585 -0.0333357 0.0501932 0.152 -0.0333173 0.0494584 0.152 -0.1187 0.0537 0.16 0.0235908 0.0596472 0.159221 0.0473828 -0.0394131 0.159642 0.0850204 -0.0563996 0.159508 0.0860998 -0.0506105 0.159134 0.131719 0.000453698 0.16 0.13048 -0.00239785 0.160094 0.103806 -0.0513022 0.15903 0.0445491 -0.0430587 0.163918 0.0532502 -0.0502737 0.160013 0.0288248 -0.00505768 0.155645 0.0723374 0.0639129 0.159998 0.114433 0.0581015 0.159999 0.044341 0.0639249 -0.1585 0.0918987 -0.0451587 -0.147 0.0778009 -0.0466482 -0.147 0.0639057 -0.0438391 -0.1585 0.0778009 -0.0466482 -0.1585 0.0639057 -0.0438391 -0.147 0.0514937 -0.0369903 -0.147 0.0417084 -0.0267328 -0.147 0.0348391 -0.0123533 -0.1585 0.0354517 -0.014012 -0.1585 0.0333 2.22921e-09 -0.158596 0.0333372 0.0504129 -0.152 -0.0333553 0.0500377 -0.152 -0.0333 0.0089 -0.143 -0.0333 2.22921e-09 -0.152 -0.0413 0.0537 -0.1585 -0.1267 2.22921e-09 -0.147 -0.1267 0.0089 -0.158572 -0.122442 0.0536979 -0.152 0.0333173 0.0494584 -0.152 0.0413 0.0537 -0.152 0.0333 0.0089 -0.152 0.0070441 0.0609596 -0.152 0.124 0.0689 -0.152 0.1187 0.0537 -0.152002 -0.123794 0.0536868 0.1168 -0.1195 0.000900003 0.101 -0.1195 0.000900003 0.103 0.1195 0.000900003 0.097 -0.1195 0.000900003 0.095 -0.1195 0.000900003 0.089 -0.1195 0.000900003 0.083 0.1195 0.000900003 0.079 0.1195 0.000900003 0.073 0.1195 0.000900003 0.067 0.1195 0.000900003 0.067 -0.1195 0.000900003 0.061 0.1195 0.000900003 0.059 0.1195 0.000900003 0.053 0.1195 0.000900003 0.053 -0.1195 0.000900003 0.049 0.1195 0.000900003 0.047 -0.1195 0.000900003 0.043 -0.1195 0.000900003 0.043 0.1195 0.000900003 0.041 0.1195 0.000900003 0.037 0.1195 0.000900003 0.031 -0.1195 0.000900003 0.031 0.1195 0.000900003 0.029 -0.1195 0.000900003 0.029 0.1195 0.000900003 0.023 -0.1195 0.000900003 0.013 -0.1195 0.000900003 0.013 0.1195 0.000900003 0.011 -0.1195 0.000900003 0.007 -0.1195 0.000900003 0.007 0.1195 0.000900003 0.001 -0.1195 0.000900003 -0.001 -0.1195 0.000900003 0.001 0.1195 0.000900003 -0.007 -0.1195 0.000900003 -0.005 0.1195 0.000900003 -0.007 0.1195 0.000900003 -0.017 0.1195 0.000900003 -0.019 -0.1195 0.000900003 -0.019 0.1195 0.000900003 -0.025 -0.1195 0.000900003 -0.025 0.1195 0.000900003 -0.035 0.1195 0.000900003 -0.041 0.1195 0.000900003 -0.049 -0.1195 0.000900003 -0.049 0.1195 0.000900003 -0.061 0.1195 0.000900003 -0.065 -0.1195 0.000900003 -0.067 -0.1195 0.000900003 -0.073 0.1195 0.000900003 -0.073 -0.1195 0.000900003 -0.083 -0.1195 0.000900003 -0.085 -0.1195 0.000900003 -0.085 0.1195 0.000900003 -0.089 -0.1195 0.000900003 -0.097 -0.1195 0.000900003 -0.101 -0.1195 0.000900003 -0.101 0.1195 0.000900003 -0.103 0.1195 0.000900003 -0.107 0.1195 0.000900003 -0.1385 0.105 0.000900003 0.03928 0.1429 0.0689 0.151078 -0.144043 0.0689 0.151078 0.144043 0.0689 -0.100332 -0.142892 0.0688996 -0.151078 -0.144043 0.0689 -0.160459 0.142903 0.0689582 0.150109 -0.127982 0.0686692 0.152 -0.124 0.0689 -0.149977 0.128054 0.0686549 -0.152 -0.124 0.0689 0.0233431 -0.129 0.0689 0.147 0.129 0.0689 0.147 -0.129 0.0689 -0.03928 0.1359 0.0689 -0.10356 0.1359 0.0689 -0.08928 0.1359 0.0689 0.0177158 -0.130685 0.0685242 -0.0219647 0.137122 0.0688399 0.147 0.1339 0.0689 0.021941 0.135732 0.0688999 0.0219638 -0.137221 0.0688226 -0.03928 -0.1359 0.0689 -0.16037 -0.0700822 0.0689 0.164 0.137396 0.0689 -0.164 0.137396 0.0689 0.16077 0.0698218 0.0689 -0.151078 0.144043 0.0689 -0.151208 -0.1267 0.0273 -0.149838 -0.128206 0.0687693 -0.147 -0.129 0.0089 -0.149312 -0.128413 0.0089 -0.0245532 0.135922 0.0553866 -0.0250164 -0.135099 0.0554016 0.0696571 -0.136444 0.011066 0.0663648 -0.133123 0.053029 -0.0246327 -0.133616 0.0118783 -0.0693226 -0.137018 0.0107571 0.1168 -0.1315 0.0069 0.153 0.1315 0.0069 -0.1312 -0.1315 0.0069 -0.103 -0.1315 0.0069 -0.107 -0.1315 0.0069 -0.103 0.1315 0.0069 -0.101 0.1315 0.0069 -0.091 -0.1315 0.0069 -0.085 -0.1315 0.0069 -0.085 0.1315 0.0069 -0.089 0.1315 0.0069 -0.089 0.1195 0.000900003 -0.079 -0.1315 0.0069 -0.083 -0.1315 0.0069 -0.083 0.1315 0.0069 -0.083 0.1195 0.000900003 -0.073 -0.1315 0.0069 -0.077 -0.1315 0.0069 -0.077 -0.1195 0.000900003 -0.067 -0.1315 0.0069 -0.067 0.1195 0.000900003 -0.061 0.1315 0.0069 -0.065 0.1315 0.0069 -0.065 0.1195 0.000900003 -0.055 0.1315 0.0069 -0.055 -0.1315 0.0069 -0.059 0.1315 0.0069 -0.059 0.1195 0.000900003 -0.053 -0.1315 0.0069 -0.043 0.1195 0.000900003 -0.047 -0.1315 0.0069 -0.047 0.1195 0.000900003 -0.037 -0.1195 0.000900003 -0.037 0.1195 0.000900003 -0.037 -0.1315 0.0069 -0.041 0.1315 0.0069 -0.041 -0.1195 0.000900003 -0.031 0.1195 0.000900003 -0.029 0.1195 0.000900003 -0.019 -0.1315 0.0069 -0.019 0.1315 0.0069 -0.023 0.1195 0.000900003 -0.013 0.1195 0.000900003 -0.013 0.1315 0.0069 -0.007 -0.1315 0.0069 -0.011 -0.1195 0.000900003 -0.001 0.1195 0.000900003 -0.001 0.1315 0.0069 0.005 -0.1195 0.000900003 0.005 0.1315 0.0069 0.005 -0.1315 0.0069 0.001 -0.1315 0.0069 0.011 0.1315 0.0069 0.007 -0.1315 0.0069 0.007 0.1315 0.0069 0.017 -0.1195 0.000900003 0.017 0.1195 0.000900003 0.023 0.1195 0.000900003 0.023 -0.1315 0.0069 0.023 0.1315 0.0069 0.019 -0.1315 0.0069 0.019 -0.1195 0.000900003 0.019 0.1195 0.000900003 0.029 -0.1315 0.0069 0.025 -0.1315 0.0069 0.025 -0.1195 0.000900003 0.025 0.1315 0.0069 0.035 -0.1195 0.000900003 0.035 0.1195 0.000900003 0.035 0.1315 0.0069 0.031 0.1315 0.0069 0.041 -0.1195 0.000900003 0.047 0.1195 0.000900003 0.043 0.1315 0.0069 0.053 0.1315 0.0069 0.053 -0.1315 0.0069 0.049 0.1315 0.0069 0.049 -0.1315 0.0069 0.059 0.1315 0.0069 0.059 -0.1195 0.000900003 0.059 -0.1315 0.0069 0.055 0.1195 0.000900003 0.061 0.1315 0.0069 0.061 -0.1195 0.000900003 0.071 0.1195 0.000900003 0.071 -0.1315 0.0069 0.071 0.1315 0.0069 0.067 0.1315 0.0069 0.077 -0.1315 0.0069 0.077 0.1195 0.000900003 0.083 0.1315 0.0069 0.079 -0.1315 0.0069 0.079 0.1315 0.0069 0.079 -0.1195 0.000900003 0.089 0.1195 0.000900003 0.089 -0.1315 0.0069 0.089 0.1315 0.0069 0.085 -0.1195 0.000900003 0.085 0.1195 0.000900003 0.095 0.1195 0.000900003 0.095 -0.1315 0.0069 0.095 0.1315 0.0069 0.091 -0.1315 0.0069 0.091 0.1195 0.000900003 0.101 0.1195 0.000900003 0.101 0.1315 0.0069 0.097 -0.1315 0.0069 0.097 0.1315 0.0069 0.107 0.1195 0.000900003 0.107 -0.1315 0.0069 0.107 0.1315 0.0069 0.103 -0.1195 0.000900003 -0.164 0.0231142 0.0569684 -0.159991 0.0240126 -0.00324082 -0.160017 -0.111595 -0.0465545 -0.146999 -0.0716343 -0.0568984 -0.164 -0.065018 -0.0548922 -0.163378 -0.0741872 -0.0566831 -0.147 -0.0306704 -0.0283584 -0.164 -0.0231 1.88724e-08 -0.160019 -0.0233828 -0.00482121 -0.16 -0.023646 0.0596897 -0.164 -0.0300355 0.0638885 -0.164 -0.0231122 0.0565326 -0.1585 -0.1291 0.0457 -0.1585 -0.1291 2.22921e-09 -0.158452 -0.119234 -0.0253917 -0.1585 -0.110582 -0.0352935 -0.158456 -0.0993693 -0.0425139 -0.1585 -0.0606001 -0.0424798 -0.158813 -0.0350931 -0.0130103 -0.1585 -0.0333191 0.0498409 -0.1585 -0.0413 0.0537 -0.1585 -0.1187 0.0561 -0.1585 -0.126697 0.0480164 -0.1585 -0.0309 2.22921e-09 -0.158449 -0.0406753 -0.0252226 -0.158503 -0.0492823 -0.0352207 -0.158448 -0.0732553 -0.0462377 -0.158448 -0.0865399 -0.0462771 -0.158447 -0.124808 -0.0132532 -0.1585 -0.0309 0.0457 -0.16 -0.0311566 0.0560545 -0.1585 -0.0413 0.0561 -0.1585 0.124208 -0.0201893 -0.159919 0.115919 -0.0341507 -0.15855 0.067398 -0.0480394 -0.16 0.129204 -0.00141312 -0.16 0.1187 0.0561 -0.1585 0.0309 0.0457 -0.16 0.0413 0.0561 -0.1585 0.1291 2.22921e-09 -0.159266 0.0979613 -0.04748 -0.1585 0.0514937 -0.0369903 -0.1585 0.0417084 -0.0267328 -0.158465 0.0434938 -0.0334271 -0.1585 0.0309 2.22921e-09 -0.1585 0.0413 0.0537 -0.1585 0.0413 0.0561 -0.1585 0.121777 0.0536973 -0.1585 0.1187 0.0561 -0.1585 0.129088 0.0488871 -0.1585 0.126697 0.0475288 -0.159995 0.134049 -0.0185178 -0.146413 -0.131529 0.015381 -0.153 -0.1369 0.0200112 -0.156516 -0.1369 0.0592197 -0.153 -0.1369 0.03738 0.155 0.0231027 0.0394364 0.164 0.0300372 0.0638897 0.164 -0.0304727 0.0638908 0.16 -0.0235222 0.0589782 0.164 -0.0231142 0.0569684 0.164 -0.0231 3.29143e-10 0.16311 -0.103127 -0.051907 0.147 -0.0868609 -0.0567801 0.163647 -0.0894855 -0.0562686 0.163243 -0.074389 -0.0567331 0.147001 -0.0238476 -0.0115246 0.1585 -0.129088 0.0488871 0.1585 -0.1187 0.0561 0.16 -0.1187 0.0561 0.1585 -0.0413 0.0561 0.160001 -0.129132 8.5863e-06 0.158455 -0.119361 -0.0251823 0.160002 -0.125045 -0.0212525 0.1585 -0.110697 -0.0352338 0.158445 -0.060672 -0.0425421 0.158492 -0.12892 -0.0074773 0.1585 0.1291 0.0457 0.158838 0.126658 0.0505592 0.1585 0.0778009 -0.0466482 0.158499 0.104904 -0.0396304 0.1585 0.1187 0.0537 0.1585 0.1187 0.0561 0.1585 0.0309 2.22921e-09 0.1585 0.0333 2.22921e-09 0.1585 0.0514937 -0.0369903 0.158787 0.0632578 -0.043726 0.160003 0.0307238 0.00784579 0.158455 0.0415363 -0.0265715 0.1585 0.124208 -0.0201893 0.1585 0.1291 2.22921e-09 0.1585 0.0309 0.0457 0.16 0.0413 0.0561 0.16 0.0309 0.0457 0.16 0.120279 0.0561284 0.1585 0.0413 0.0561 0.16 0.1291 0.02285 0.155834 0.1369 0.0575875 0.153 0.1369 0.00988 0.150667 0.132375 0.02488 0.153 0.1369 0.0516467 0.143959 0.1369 0.01388 0.153 0.1369 0.058685 0.153 0.1369 0.04288 0.15999 0.136934 0.0139799 0.153 -0.1369 0.0532053 0.153 -0.1369 0.0477488 0.141649 -0.1369 0.00988 0.147134 -0.1369 0.01938 0.1505 -0.1369 0.02088 0.16 -0.1369 5.58801e-09 0.153 -0.1369 0.0639 -0.156047 0.0277502 0.00946883 -0.159983 -0.132865 0.00882925 -0.159997 -0.0286059 0.0433769 -0.158484 -0.0403227 0.0588465 -0.16 -0.0782498 0.0587774 -0.159998 -0.117881 0.0583108 -0.16 0.132492 0.0448672 -0.158797 0.0828135 -0.05328 -0.159985 0.0816153 -0.0516951 -0.160002 0.0518659 -0.0410682 -0.16 0.0401868 0.0638659 -0.159496 0.0402052 0.0582534 -0.159444 0.0809987 0.0600609 -0.159995 0.118548 0.0619943 0.159655 0.0240883 0.010289 0.16 -0.132443 0.00898309 0.159996 0.132681 0.00911316 0.159412 -0.0454557 -0.0434641 0.159426 -0.0520604 -0.040817 0.15747 -0.0399489 0.0596205 0.159998 -0.0415903 0.0639058 0.159997 -0.11834 0.0581797 0.159944 -0.109218 -0.0416651 0.160001 0.028785 0.0455498 0.152563 0.079868 0.0595976 0.159999 0.12068 0.0638331 -0.105112 -0.0282236 -0.0826 -0.119718 -0.011907 -0.0826 -0.12112 0.00548728 -0.0826 -0.100808 0.0296943 -0.0886 0.09 -0.0316 -0.0826 0.0791922 -0.0296943 -0.0826 0.0735845 -0.0276513 -0.0886118 0.0588801 -0.00548728 -0.0826 0.0648293 0.019783 -0.0826 0.0791922 0.0296943 -0.0826 0.09 0.0316 -0.0826 0.159998 -0.0279821 -0.000858663 0.159262 -0.132906 0.000474507 -0.0182071 -0.13088 0.0640025 0.0767957 -0.125 -0.0867568 -0.1405 -0.125 -0.0806 0.163985 -0.124997 -0.0371051 0.1405 -0.125 -0.0806 -0.1395 -0.125 -0.0823321 0.164 -0.125 -0.0796 0.1395 -0.125 -0.0823321 0.1385 -0.125 -0.0826 0.158 -0.125 -0.0906 -0.0731463 -0.125 -0.0858067 -0.140232 -0.125 -0.0816 -0.164 -0.125 -0.0796 0.147 0.1049 -0.039508 -0.1585 0.1049 -0.039508 0.155932 0.108 -0.0328224 0.14681 0.108 -0.027335 0.155999 0.124999 -0.0885342 0.156007 0.134765 -0.000206994 0.156 0.108009 0.000883019 -0.156 0.108 -0.0826 -0.155912 0.108 -0.0327158 -0.147518 0.108 -0.0322399 -0.148527 0.108 -0.0266717 -0.156 0.108 0.000900003 -0.156001 0.134412 -0.0179454 -0.156 0.109957 -0.0429231 -0.131 0.12 -0.0836 -0.156763 0.120989 -0.0885965 0.131 0.119 -0.0826 0.132039 0.120002 -0.0886142 -0.155998 0.119761 0.000919553 0.1312 0.119684 0.000900372 0.156004 0.119588 0.000921098 0.1312 0.12 0.0069 -0.1312 0.12 0.0069 -0.1312 0.119 0.000900003 0.1168 0.1195 0.000900003 -0.1168 0.1195 0.000900003 -0.1168 0.1315 0.0069 0.107 -0.1195 0.000900003 0.103 -0.1315 0.0069 0.091 -0.1195 0.000900003 0.083 -0.1195 0.000900003 0.083 -0.1315 0.0069 0.077 -0.1195 0.000900003 0.073 -0.1195 0.000900003 0.071 -0.1195 0.000900003 0.073 -0.1315 0.0069 0.067 -0.1315 0.0069 0.065 -0.1195 0.000900003 0.061 -0.1315 0.0069 0.055 -0.1195 0.000900003 0.055 -0.1315 0.0069 0.049 -0.1195 0.000900003 0.047 -0.1315 0.0069 0.043 -0.1315 0.0069 0.037 -0.1195 0.000900003 0.037 -0.1315 0.0069 0.031 -0.1315 0.0069 0.011 -0.1315 0.0069 -0.005 -0.1195 0.000900003 -0.013 -0.1195 0.000900003 -0.011 -0.1315 0.0069 -0.017 -0.1195 0.000900003 -0.023 -0.1195 0.000900003 -0.023 -0.1315 0.0069 -0.029 -0.1195 0.000900003 -0.031 -0.1195 0.000900003 -0.029 -0.1315 0.0069 -0.031 -0.1315 0.0069 -0.035 -0.1195 0.000900003 -0.043 -0.1195 0.000900003 -0.041 -0.1315 0.0069 -0.047 -0.1195 0.000900003 -0.053 -0.1195 0.000900003 -0.055 -0.1195 0.000900003 -0.059 -0.1195 0.000900003 -0.061 -0.1195 0.000900003 -0.071 -0.1195 0.000900003 -0.079 -0.1195 0.000900003 -0.089 -0.1315 0.0069 -0.091 -0.1195 0.000900003 -0.095 -0.1195 0.000900003 -0.097 -0.1315 0.0069 -0.103 -0.1195 0.000900003 -0.107 -0.1195 0.000900003 -0.1168 -0.1195 0.000900003 -0.1168 -0.1315 0.0069 -0.097 0.1195 0.000900003 -0.095 0.1195 0.000900003 -0.095 0.1315 0.0069 -0.091 0.1195 0.000900003 -0.091 0.1315 0.0069 -0.079 0.1195 0.000900003 -0.079 0.1315 0.0069 -0.077 0.1195 0.000900003 -0.077 0.1315 0.0069 -0.071 0.1195 0.000900003 -0.067 0.1315 0.0069 -0.055 0.1195 0.000900003 -0.053 0.1195 0.000900003 -0.049 0.1315 0.0069 -0.047 0.1315 0.0069 -0.043 0.1315 0.0069 -0.011 0.1195 0.000900003 -0.011 0.1315 0.0069 0.005 0.1195 0.000900003 0.011 0.1195 0.000900003 0.017 0.1315 0.0069 0.025 0.1195 0.000900003 0.041 0.1315 0.0069 0.047 0.1315 0.0069 0.065 0.1195 0.000900003 0.073 0.1315 0.0069 0.085 0.1315 0.0069 0.097 0.1195 0.000900003 0.103 0.1315 0.0069 -0.131 0.125 -0.0846 -0.131 0.121 -0.0826 0.156 0.119454 -0.0826087 0.1096 0.151216 0.05938 0.145724 0.131537 0.059378 0.153 0.154 0.04138 0.153 0.154 0.04288 0.153 0.1369 0.04138 0.153 0.154 0.03738 0.073 0.133 0.03738 0.153 0.154 0.03588 0.153 0.154 0.03038 0.073 0.133 0.03038 0.153 0.154 0.03188 0.153 0.154 0.02488 0.1316 0.154 0.02638 0.147123 0.131609 0.0153807 -0.153 0.1369 0.0145547 -0.109263 0.1495 0.01388 -0.146618 0.131536 0.0138808 -0.150663 0.132367 0.02488 -0.131263 0.154 0.02488 -0.153 0.154 0.02638 -0.1316 0.154 0.02638 -0.153 0.154 0.02488 -0.153 0.154 0.03188 -0.073 0.133 0.03038 -0.153 0.154 0.03038 -0.153 0.154 0.03738 -0.073 0.133 0.03738 -0.141649 0.152347 0.05788 -0.145462 0.131555 0.0578785 -0.108989 0.131363 0.05938 -0.105632 0.129357 0.0152964 0.108935 0.131348 0.015381 0.131641 0.13149 0.0263819 0.102351 0.1315 0.0593808 0.109624 0.1315 0.0593805 -0.0344009 0.129782 0.0154188 0.0308038 0.1315 0.0153819 0.0382187 0.131499 0.0154003 0.0337291 0.129389 0.0148316 0.0343001 0.131492 0.0584518 -0.0709576 0.134404 0.0538822 -0.0692755 0.135029 0.0110442 0.075 0.133 0.00838 0.071392 0.133989 0.0527851 0.0379495 0.133 0.014881 0.073 0.133 0.03188 -0.0164201 0.13299 0.0303194 0.0147332 0.132998 0.0304478 0.0763333 0.133 0.02488 -0.0754242 0.133 0.02638 0.021 0.133 0.01938 0.0277407 0.133 0.0538796 0.0274435 0.133003 0.00929078 0.0667371 0.133004 0.00881083 -0.0222869 0.131503 0.0524396 -0.0662695 0.131759 0.0538046 -0.067572 0.133 0.0523802 -0.1316 -0.154 0.02638 0.150667 -0.132374 0.02488 0.131263 -0.154 0.02488 0.153 -0.154 0.02638 0.153 -0.154 0.02488 -0.150664 -0.132367 0.02488 -0.149786 -0.132175 0.02638 -0.153 -0.154 0.02638 -0.153 -0.1369 0.03188 -0.021 -0.133 0.03188 -0.1476 -0.1315 0.03188 -0.074 -0.154 0.03188 0.0209942 -0.149998 0.03188 0.153 -0.1369 0.03038 0.153 -0.154 0.03038 0.073 -0.154 0.03038 0.073 -0.133 0.03038 -0.021 -0.133 0.03038 -0.073 -0.133 0.03038 0.021 -0.133 0.03038 -0.153 -0.154 0.03038 -0.1476 -0.1315 0.03038 0.153 -0.154 0.03188 0.073 -0.154 0.03188 -0.153 -0.154 0.03188 0.153 -0.154 0.03738 0.153 -0.154 0.03588 0.073 -0.133 0.03738 0.073 -0.154 0.03588 -0.153 -0.1369 0.03588 -0.153 -0.154 0.03588 0.153 -0.154 0.04288 0.0754242 -0.154 0.04138 -0.153 -0.154 0.04138 -0.0765936 -0.154 0.04138 -0.153 -0.154 0.04288 -0.0713927 -0.133988 0.0527866 0.083 -0.133 0.05388 0.0709576 -0.134404 0.0538822 -0.075 -0.133 0.00838 0.0735678 -0.1315 0.00988 0.0820909 -0.133 0.01538 0.0190217 -0.131516 0.00837988 0.0276915 -0.1315 0.05388 -0.0678288 -0.133 0.00838033 -0.0273473 -0.133002 0.00907653 -0.0651383 -0.131708 0.00989115 -0.0277881 -0.131559 0.0538788 -0.0662312 -0.133039 0.0530843 -0.0246921 -0.131822 0.0523569 0.034401 -0.129512 0.0152304 -0.0343331 -0.131493 0.0588727 0.0277627 -0.131156 0.0563079 -0.109595 -0.1315 0.0593805 -0.1244 -0.1315 0.02638 -0.131606 -0.131502 0.0263803 0.126771 -0.1315 0.0294294 0.1244 -0.1315 0.02638 -0.102343 -0.1315 0.0153806 -0.109078 -0.13138 0.0153785 0.102392 -0.1315 0.0153802 -0.137016 -0.14781 0.0639 0.0854242 -0.152347 0.05788 0.102678 -0.152347 0.05788 -0.102328 -0.151216 0.0593799 -0.0854242 -0.152347 0.05788 0.109322 0.152347 0.05788 -0.140783 0.151216 0.05938 -0.1096 0.151216 0.05938 -0.109337 0.152347 0.05788 -0.02 -0.15 0.03188 -0.0209942 -0.149998 0.03038 -0.021 -0.133 0.02638 -0.021 -0.133 0.02488 0.0209942 -0.149998 0.02638 -0.02 -0.15 0.02638 0.02 -0.15 0.01938 0.0157205 0.149654 0.0207887 -0.0209943 0.149986 0.02088 -0.019 -0.133 0.00838 -0.018 -0.1495 0.01538 -0.0863333 -0.151216 0.05938 0.0863333 -0.151216 0.05938 0.0723198 -0.132992 0.0083679 -0.0820909 -0.133 0.05238 -0.0787576 -0.133 0.04688 0.0796667 -0.133 0.04838 0.0754242 -0.133 0.04138 -0.0763333 -0.133 0.02488 0.0796667 -0.133 0.01938 0.0787576 -0.133 0.02088 -0.0802957 -0.13149 0.0138896 -0.0190002 0.1315 0.00988 -0.0854242 0.152347 0.05788 -0.0863333 0.133 0.05938 -0.0854242 0.133 0.05788 0.0863333 0.151216 0.05938 0.0787576 0.133 0.02088 0.0820909 0.133 0.05238 0.0735678 0.1315 0.00988 0.075 0.1495 0.00838 0.075 0.1495 0.00988 -0.0787576 0.133 0.04688 -0.0763333 0.133 0.04288 -0.0763333 0.133 0.02488 -0.0820909 0.1495 0.01538 -0.0826094 0.131509 0.0138822 0.00329574 0.134576 0.00837921 0.154833 -0.136944 0.0591261 0.1476 -0.1315 0.0639 0.1476 -0.1315 0.04838 0.153 -0.1369 0.03188 0.149642 -0.131964 0.02638 0.153 -0.1369 0.0154621 0.153 -0.1369 0.00907495 -0.147157 -0.131668 0.0138925 -0.1476 -0.1315 0.02088 -0.153 -0.1369 0.03038 -0.153 -0.1369 0.04138 -0.1476 -0.1315 0.04288 -0.153 -0.1369 0.0516467 -0.1476 -0.1315 0.04688 -0.153 -0.1369 0.058685 -0.1476 -0.1315 0.05938 -0.153 0.1369 0.03188 -0.1476 0.1315 0.03588 -0.153 0.1369 0.03588 -0.15388 0.13691 0.0540499 0.1476 0.1315 0.00988 0.147708 0.131608 0.01388 0.153 0.1369 0.0200112 0.149792 0.132184 0.02638 0.1476 0.1315 0.04288 0.1476 0.1315 0.04838 0.1476 0.1315 0.05388 0.143542 0.131486 0.0578768 0.0709996 -0.132339 0.0137145 0.0662572 -0.131791 0.0100475 0.0190228 -0.131515 0.0138798 0.0278437 -0.132346 0.00988076 0.0269747 -0.133727 0.0123021 -0.0190002 -0.1315 0.00988 -0.0735678 0.1315 0.00988 -0.0660333 0.131712 0.00988649 -0.0190223 0.131517 0.0138791 -0.0242706 0.133012 0.00899748 0.0190002 0.1315 0.00987998 0.0690027 0.133001 0.0138702 0.0689883 0.13622 0.0110698 0.0436034 0.131451 0.00985419 -0.0189878 0.149492 0.01388 -0.00459396 0.149499 0.0151144 0.0172913 0.146422 0.013882 -0.0170785 0.14952 0.00987997 -0.0189878 0.149492 0.00838 -0.075 0.1495 0.00988 0.083 0.1495 0.01388 0.143959 0.1495 0.01388 0.1096 0.1495 0.01538 -0.144825 0.1495 0.01538 -0.1096 0.1495 0.01538 -0.143959 0.1495 0.01388 0.102737 -0.1495 0.01388 0.0820909 -0.1495 0.01538 0.0189938 -0.149498 0.00988 -0.0189938 -0.149498 0.00838 -0.0189939 0.149484 0.01538 0.0189941 0.14945 0.00838 0.0148067 0.148671 0.0152337 0.0189938 -0.149498 0.01538 0.018 -0.1495 0.01388 0.018 -0.1495 0.00838 -0.018 -0.1495 0.00988 -0.076 -0.1495 0.00838 -0.0820981 -0.149489 0.01538 0.02 -0.15 0.02488 0.02 -0.15 0.03038 -0.0209942 -0.149998 0.02488 -0.0209942 -0.149998 0.01938 -0.02 -0.15 0.02088 -0.080836 -0.154 0.01938 -0.0765936 -0.154 0.02638 -0.074 -0.154 0.03038 -0.074 -0.154 0.03738 -0.074 -0.154 0.03588 -0.0830047 -0.153999 0.0538797 0.144825 0.154 0.05238 0.0799269 0.154 0.04688 0.0765936 0.154 0.04138 0.074 0.154 0.03038 0.0799269 0.154 0.02088 -0.0830037 0.153998 0.0538797 -0.0799269 0.154 0.04688 -0.073 0.133 0.03588 -0.074 0.154 0.03738 -0.0763379 0.153997 0.0248804 -0.080836 0.154 0.01938 -0.0209885 0.149993 0.01938 -0.00562071 0.148663 0.0193794 0.0209944 0.14996 0.01938 -0.0120185 0.133 0.0262845 0.018284 0.133001 0.0263724 0.0185 0.1315 0.03038 0.0109899 0.131627 0.0263705 0.0108869 0.131894 0.0297423 0.0151976 0.135096 0.0278679 -0.162952 -0.0158797 0.0458551 -0.161345 0.0181582 0.0461957 -0.157617 -0.0199578 -0.0513496 -0.158451 -0.000274442 0.000705502 -0.164 -0.00143994 0.00491688 -0.164022 0.00569032 0.00295331 0.162452 -0.0182324 0.00182675 0.162952 0.0158797 0.0458551 0.164029 -0.00576424 0.00301316 0.15682 -9.75179e-05 -0.0513035 -0.154059 -0.131379 0.068884 -0.147 -0.1337 0.0669 -0.147 0.1337 0.0669 -0.1567 0.124 0.0669 0.150313 -0.133689 0.0669023 0.154575 -0.130819 0.0688971 -0.023639 -0.1337 0.0669 -0.153124 -0.1302 0.0669007 -0.1532 0.124 0.0687 -0.1532 -0.124 0.0669 -0.1532 0.124 0.0669 -0.0192281 0.130192 0.0669017 0.0250887 0.1302 0.0669 0.152775 0.130198 0.0669008 0.1532 0.124 0.0669 0.147 -0.1302 0.0669 0.0178917 0.12865 0.0669238 0.0250887 -0.1302 0.0669 0.16027 0.000448187 0.0688999 0.155034 -0.0716039 0.0639043 0.0321328 -0.137677 0.0639 -0.0227956 -0.140565 0.0639023 -0.164 -0.137396 0.0639 -0.160924 0.0679998 0.0688999 -0.161692 0.0679981 0.0639004 -0.161065 0.000500298 0.0688984 -0.16 0.136899 0.0638988 -0.162938 0.139178 0.0688993 -0.0965143 0.137238 0.0688983 0.0226322 0.14108 0.0639035 0.159999 0.1369 0.063886 -0.147 0.129 0.0689 -0.147 0.13015 0.0687866 -0.0157395 -0.1307 0.0689 -0.153068 0 0.0688683 -0.0250887 0.1302 0.0687 -0.0250887 -0.1302 0.0669 0.0250887 0.1302 0.0687 0.0179784 0.129007 0.0688998 0.153 0.124 0.0689 0.0250887 -0.1302 0.0687 0.1532 -0.124 0.0687 0.147 -0.13015 0.0687866 -0.152824 0.131046 0.0676144 -0.15356 0.1359 0.0689 -0.1567 0.124 0.0687 -0.023639 0.1337 0.0669 -0.147 -0.1339 0.0689 -0.1567 -0.124 0.0687 -0.1569 -0.124 0.0689 -0.0229246 0.133799 0.0688886 0.0228191 0.133702 0.0688465 0.151596 0.133693 0.0669034 0.1567 0.124 0.0687 0.1569 0.124 0.0689 0.156862 -0.124 0.0688924 0.1567 -0.124 0.0687 0.0228884 -0.133705 0.0688997 0.159369 -0.143703 0.0643169 0.164 -0.137396 0.0689 -0.161096 -0.143152 0.0639905 -0.164 0.137396 0.0639 0.137016 0.14781 0.0639 0.160367 0.143499 0.0640017 -0.0169244 0.130704 0.0689 -0.0219882 -0.135788 0.0688996 0.0222258 -0.146428 0.0639009 -0.0229786 -0.144042 0.0689002 -0.0222258 0.146428 0.0639009 0.0222223 0.144043 0.0688987 0.0169323 -0.130701 0.0655 0.08928 -0.1359 0.0689 0.0338833 -0.138136 0.06889 0.0916679 -0.142909 0.0688996 0.03928 -0.1359 0.0689 0.0364681 -0.142891 0.0654001 0.0373846 -0.135903 0.0653998 0.0914032 -0.13591 0.0654018 0.0918856 -0.142887 0.0653998 -0.0373846 0.135903 0.0653998 -0.0925083 0.142892 0.0688998 -0.0364681 0.142891 0.0654001 -0.03593 0.14286 0.0688965 -0.0914032 0.13591 0.0654018 -0.0918856 0.142887 0.0653998 0.15356 0.1359 0.0689 0.155533 0.135902 0.0654 0.100332 0.142892 0.0688996 0.15356 0.1429 0.0689 0.100954 0.142887 0.0653998 0.101437 0.13591 0.0654018 0.156563 0.142889 0.0654002 0.0926699 0.14287 0.0689001 0.03928 0.1359 0.0689 0.0956575 0.135915 0.0689004 0.0342252 0.138029 0.0688976 0.0362746 0.135922 0.0654002 0.0373057 0.142895 0.0654 0.0918832 0.135906 0.0653998 0.0915053 0.142897 0.0654 -0.10073 0.14289 0.0689 -0.156584 0.142875 0.0654039 -0.155757 0.135906 0.0654 -0.10104 0.135908 0.0654058 -0.101335 0.142897 0.0654 -0.101437 -0.13591 0.0654018 -0.160312 -0.142905 0.0689365 -0.15356 -0.1359 0.0689 -0.100954 -0.142887 0.0653998 -0.15356 -0.1429 0.0654 -0.156725 -0.135916 0.0654001 -0.0342907 -0.138325 0.0688985 -0.0373057 -0.142895 0.0654 -0.03928 -0.1429 0.0689 -0.0956575 -0.135915 0.0689004 -0.0926699 -0.14287 0.0689001 -0.0918832 -0.135906 0.0653998 -0.0362746 -0.135922 0.0654002 -0.0915053 -0.142897 0.0654 0.155457 -0.142895 0.0653998 0.156372 -0.142891 0.0688956 0.10356 -0.1359 0.0689 0.10073 -0.14289 0.0689 0.155455 -0.135903 0.0689019 0.156375 -0.135918 0.0654001 0.10104 -0.135908 0.0654058 0.101335 -0.142897 0.0654 -0.164 -0.0203604 0.0638483 -0.155 0.0203712 0.00693904 -0.155 0.0205542 0.0277579 -0.159091 0.00353587 0.0638043 -0.157822 -0.0130604 0.0619129 -0.158019 0.0171019 0.0549117 -0.159 -0.00490234 0.0298026 -0.158998 0.0205116 0.0277803 -0.159006 0.0205875 0.0398591 -0.159 0.0130984 0.0298013 -0.156901 0.0130642 0.0619359 -0.159 0.00490082 0.0298027 -0.159 -0.0130984 0.0298013 -0.157058 -0.0153369 0.0420291 -0.158992 -0.0205599 0.0277467 -0.159001 -0.0205883 0.0402102 -0.15906 0.0214345 0.0543864 -0.164002 0.0204644 0.0494575 -0.159 -0.0166 0.0639 0.155 0.0204176 0.00693663 0.163995 -0.0205713 0.00283272 0.159 0.00490082 0.0619973 0.159 0.00490234 0.0298026 0.158988 0.0210384 0.0550489 0.157467 0.00495233 0.0439239 0.157818 0.0123046 0.0459017 0.159001 0.0205883 0.0402102 0.156869 -0.0130554 0.0619257 0.158025 -0.0171069 0.0548971 0.15202 -0.0170897 0.0367307 0.158855 0.000635437 0.0527677 0.159063 -0.00388162 0.0636696 0.159 0.000133526 0.0366687 0.155 0.0203377 0.0277779 0.158992 0.0205599 0.0277467 0.158998 -0.0205116 0.0277803 0.155 -0.0205628 0.0277577 0.159061 -0.0213906 0.0544864 0.159002 -0.0205891 0.0401896 0.164 -0.0166 0.0639 0.158403 0.0125291 0.0630608 0.155 -0.0203977 0.00691757 0.158127 0.0170904 0.0548813 0.158482 0.0167009 0.0333125 0.159 -0.00490159 0.0298013 0.159 -0.0130977 0.0298026 -0.159 -0.00490159 0.0619987 -0.159 3.36382e-10 0.0549 -0.158538 -0.0190289 0.0547808 -0.152069 0.00872041 0.0289522 -0.152021 0.0170797 0.0367136 -0.164 -0.0156258 -0.00107971 -0.164 -0.0206 -0.0443289 -0.164 -0.0206 -0.0058711 -0.143 -0.00150481 -0.00423749 -0.143 -0.0156038 -0.00103828 -0.142999 -0.00642027 -0.0526774 -0.163893 -0.0198166 -0.00326622 -0.143 -0.016409 -0.048819 -0.164 0.00150474 -0.00422946 -0.143 0.00660176 0.00358832 -0.143 0.00150251 -0.0460535 -0.164009 0.0135449 0.00197958 -0.143 0.0205979 -0.0464733 -0.143 0.0131251 -0.0524464 -0.143 0.0015007 -0.00393738 -0.164 0.020599 -0.0453564 -0.164043 0.0143895 -0.0509975 -0.142999 0.00619211 -0.0527387 -0.163979 0.00150126 -0.0472728 -0.143 -0.00150058 -0.046134 -0.164 -0.00150121 -0.0461945 -0.164 -0.0065121 -0.0529661 -0.143 -0.020599 -0.0453553 -0.143002 -0.013085 -0.0529232 -0.143 -0.0205988 -0.00361042 -0.164001 -0.0130099 0.00354638 -0.143 -0.012937 0.00377458 -0.164004 -0.00625979 0.00309796 -0.143 -0.00593644 0.00297887 -0.164 -0.00150072 -0.00393262 -0.143 0.0134965 0.0030444 -0.143 0.0160134 -0.00121386 -0.143 0.020599 -0.00483633 -0.164001 0.0197913 -0.00322415 -0.164 0.0206 -0.0058711 -0.158015 -0.121988 -0.0825667 -0.158 -0.0855 -0.0826 -0.143006 -0.10518 -0.0826033 -0.143 -0.106233 -0.0536277 -0.164 -0.095964 -0.057526 -0.143 -0.121998 -0.0807004 -0.143 -0.095964 -0.057526 -0.143 -0.0842682 -0.0825913 -0.158 -0.0745 -0.0826 -0.143 -0.0619967 -0.0569207 -0.143 -0.039477 -0.0438403 -0.164 -0.0236 -0.0796 -0.143 -0.0236092 -0.0825926 -0.143 -0.0500149 -0.0516235 -0.143 0.0500149 -0.0516235 -0.164 0.0619967 -0.0569207 -0.163125 0.0784699 -0.0807979 -0.143 0.0619967 -0.0569207 -0.143 0.0236092 -0.0825853 -0.143 0.039477 -0.0438403 -0.143 0.0299058 -0.0328206 -0.163991 0.099319 -0.0568709 -0.163888 0.0815223 -0.0805756 -0.143 0.10543 -0.0556238 -0.163405 -0.0205815 -0.080721 -0.143 -0.00158599 -0.0562186 -0.143 -0.00153008 -0.0824787 -0.158 0.0055 -0.0826 -0.157873 0.122 -0.0826 -0.164 0.121999 -0.0502599 -0.16283 0.117861 -0.0465945 -0.158 0.105455 -0.0825397 -0.143 0.105415 -0.0824855 -0.143 -0.121989 -0.0487981 -0.143 -0.116718 -0.0472473 -0.157998 0.105316 -0.0547505 -0.143 -0.0815731 -0.0602598 -0.163831 -0.0815277 -0.080724 -0.143 -0.0815036 -0.0796508 -0.143 -0.0755463 -0.0825989 -0.143 -0.0784958 -0.0798252 -0.143 -0.0784274 -0.060239 -0.164 -0.0784548 -0.0602906 -0.143 0.078429 -0.0602842 -0.164 0.0784537 -0.0602449 -0.143 0.0784534 -0.0825927 -0.143 0.0815456 -0.0825397 -0.143 0.0815754 -0.0601955 -0.164 0.0815466 -0.0602663 -0.143 -0.0288684 -0.0317285 -0.164 -0.0286994 -0.031497 -0.143 -0.0236007 -0.0350395 -0.164 -0.0236011 -0.0352062 -0.143 -0.0205712 -0.0823737 -0.158 -0.0166 -0.0826 -0.143 -0.0205177 -0.0563214 -0.164 -0.0205948 -0.0588733 -0.164 -0.00155242 -0.0563241 -0.143 0.00152877 -0.0823737 -0.143 0.00158599 -0.0562186 -0.143 0.0205699 -0.0824787 -0.164 0.0205956 -0.0590477 -0.143 0.0205177 -0.0563214 -0.143 0.0236046 -0.0335273 0.164009 -0.0135449 0.00197958 0.143 -0.0131251 -0.0524464 0.143 -0.0205979 -0.0464733 0.164 -0.0206 -0.0058711 0.143 -0.00150251 -0.0460535 0.142999 -0.00619211 -0.0527387 0.143 -0.00660176 0.00358832 0.143 -0.0134965 0.0030444 0.143 0.00150481 -0.00423749 0.143 0.012937 0.00377458 0.164003 0.0168691 -0.0017017 0.143 0.0156038 -0.00103828 0.143 0.0131064 -0.0521322 0.143 0.0205981 -0.0463324 0.164 0.0205992 -0.0452103 0.164 0.00582687 -0.0525463 0.142999 0.00642027 -0.0526774 0.143 0.00150058 -0.046134 0.164 0.00150121 -0.0461945 0.164 -0.00150059 -0.0461296 0.164013 -0.0066347 -0.0529376 0.143 -0.0160134 -0.00121386 0.164001 -0.0197913 -0.00322415 0.143 -0.020599 -0.00483633 0.143 -0.0015007 -0.00393738 0.164 0.00150072 -0.00393262 0.143 0.00593644 0.00297887 0.164001 0.0130099 0.00354638 0.143 0.0205955 -0.00370532 0.164 -0.0815466 -0.0602663 0.163931 -0.0815137 -0.0802417 0.143 -0.095964 -0.057526 0.143 -0.0815042 -0.0798252 0.143 -0.106233 -0.0536277 0.143 -0.121998 -0.0500969 0.164 -0.039477 -0.0438403 0.143 -0.039477 -0.0438403 0.143 -0.0619967 -0.0569207 0.143 -0.0500149 -0.0516235 0.143 -0.0299058 -0.0328206 0.143 -0.078429 -0.0602842 0.164 0.0619967 -0.0569207 0.164 0.0500149 -0.0516235 0.143 0.0619967 -0.0569207 0.143 0.039477 -0.0438403 0.158 0.02421 -0.0812496 0.143 0.0500149 -0.0516235 0.143 0.0288684 -0.0317285 0.163989 0.10425 -0.0536609 0.164 0.095964 -0.057526 0.158 0.0815 -0.0826 0.143 0.105359 -0.0556816 0.143 0.105456 -0.0824836 0.143 0.0815456 -0.0825397 0.158 -0.0166 -0.0826 0.158 -0.0055 -0.0826 0.163425 -0.0205797 -0.0807777 0.158 0.0166 -0.0826 0.143 0.00153008 -0.0824787 0.158004 -0.12058 -0.0825822 0.143005 -0.108316 -0.0826414 0.143 -0.121999 -0.0799893 0.164002 -0.121999 -0.0792222 0.157873 0.122 -0.0511243 0.158002 0.118791 -0.046065 0.143 -0.117856 -0.0466164 0.164 -0.118043 -0.0464794 0.164 -0.121999 -0.0502392 0.158 0.105414 -0.054986 0.143 -0.0815754 -0.0601955 0.143 -0.0844426 -0.0825927 0.163125 -0.0784699 -0.0807979 0.143 -0.0784534 -0.0825927 0.164 -0.0784537 -0.0602449 0.143 0.0784274 -0.060239 0.143 0.0784958 -0.0798252 0.143 0.0755463 -0.0825989 0.158 0.0745 -0.0826 0.163831 0.0815277 -0.080724 0.164 0.0785541 -0.0605832 0.143 0.0815731 -0.0602598 0.164 0.0815053 -0.0624647 0.143 -0.0236092 -0.0825853 0.158029 -0.0247888 -0.0825968 0.143 -0.0236046 -0.0335273 0.143 -0.0205699 -0.0824787 0.164 -0.0205956 -0.0590477 0.163999 -0.018168 -0.0561061 0.143 -0.0205177 -0.0563214 0.143 -0.00158599 -0.0562186 0.143 -0.00152877 -0.0823737 0.158 0.0055 -0.0826 0.164001 0.00154963 -0.0562964 0.143 0.00158599 -0.0562186 0.143 0.0205712 -0.0823737 0.164 0.0176618 -0.0561098 0.143 0.0205177 -0.0563214 0.164 0.0205948 -0.0588733 0.164 0.0286994 -0.031497 0.143 0.0236007 -0.0350395 0.143 0.0236092 -0.0825926 -0.159349 -0.0594943 -0.0468233 -0.147011 -0.0559199 -0.0454217 -0.160145 -0.0346968 -0.0243549 -0.147004 -0.0288765 -0.00457925 -0.147 -0.0459794 -0.03803 -0.147 -0.0234166 -0.00990222 -0.147028 -0.0341229 -0.0230002 -0.147016 0.0346065 -0.0240836 -0.158987 0.0515361 -0.0436734 -0.146978 0.0735923 -0.0509066 -0.147054 0.0532775 -0.0503513 -0.147 0.0537481 -0.0442727 -0.147002 -0.100627 -0.0469247 -0.160049 -0.101619 -0.0468061 -0.14734 -0.10135 -0.0530335 -0.147013 0.0286438 -0.00398161 -0.159081 0.0276687 -0.000566648 -0.146998 0.101226 -0.0468258 -0.146997 0.101634 -0.0526884 -0.147 -0.0871641 -0.0564875 -0.159997 -0.0867189 -0.050441 -0.146999 -0.0851125 -0.0509438 -0.147372 -0.0756065 -0.0511915 -0.163467 -0.051872 -0.0495112 -0.147002 -0.0524133 -0.0499682 -0.147 -0.0408461 -0.0416634 -0.159998 -0.0489856 -0.0413813 -0.146999 0.0466449 -0.038861 -0.147 0.0410427 -0.0418944 -0.147006 0.0740531 -0.0566617 -0.147001 0.084726 -0.0510421 -0.155 0.0739122 0.0581026 -0.155407 -0.0724745 0.0639032 -0.155 -0.028897 0.0147131 -0.155004 -0.028879 0.0399717 -0.155 0.0859118 0.0638983 -0.154999 -0.0450658 0.0581281 -0.155 -0.084821 0.0638803 -0.160013 0.0700177 0.0639271 -0.155115 0.0753692 0.0638574 -0.155 -0.0860878 0.0581026 -0.16 -0.045646 0.0581014 -0.155 -0.0231027 0.0394364 -0.16 -0.0231005 0.03929 -0.155456 -0.0231085 0.0134058 -0.16 -0.0288937 0.0140438 -0.159966 0.0235409 0.0109928 -0.155 0.0231008 0.0145654 -0.155001 0.0288502 0.0133351 -0.160001 0.0288872 0.0139302 -0.155 0.0231021 0.0400467 -0.159996 0.0231036 0.0404448 -0.155 0.0288887 0.0400421 -0.159998 0.0286506 0.0443575 -0.155019 0.0446999 0.0581237 -0.155 0.113771 0.0581007 -0.15501 0.115489 0.0639032 0.146998 -0.101226 -0.0468258 0.160051 -0.0563942 -0.0456694 0.146978 -0.0735923 -0.0509066 0.146996 -0.0569399 -0.052046 0.159286 -0.0329051 -0.0196536 0.159265 -0.038268 -0.0288753 0.147022 -0.034844 -0.0244041 0.147 -0.0306704 -0.0283584 0.147003 -0.0288099 -0.00427896 0.160058 0.0352386 -0.0251044 0.147018 0.0343244 -0.0233102 0.147 0.0234085 -0.00985553 0.14701 0.0288902 -0.0046007 0.147011 0.0559199 -0.0454217 0.160001 0.0635785 -0.0482823 0.159503 -0.0982937 -0.0474152 0.146997 -0.101634 -0.0526884 0.159778 0.0235134 -0.0039818 0.147002 0.100627 -0.0469247 0.159257 0.0959501 -0.0479533 0.14734 0.10135 -0.0530335 0.159357 -0.0894699 -0.0496373 0.147001 -0.084726 -0.0510421 0.159966 -0.0761678 -0.0512222 0.147006 -0.0740531 -0.0566617 0.147 -0.0537481 -0.0442727 0.146999 -0.046574 -0.0387813 0.147 -0.0410845 -0.0419432 0.147 0.0459794 -0.03803 0.147 0.0408964 -0.0417328 0.147002 0.0524133 -0.0499682 0.147372 0.0756065 -0.0511915 0.146999 0.0851125 -0.0509438 0.147 0.0871641 -0.0564875 0.154999 -0.0455678 0.0638943 0.155 -0.0451426 0.0581107 0.16 0.0765683 0.058181 0.154999 0.0747954 0.0581131 0.155 -0.0288976 0.0392864 0.155 0.028897 0.0147131 0.155 0.114606 0.0638983 0.155109 0.118684 0.0583117 0.155001 -0.115048 0.0638602 0.155 -0.113771 0.0581007 0.16 -0.113932 0.0638997 0.154999 -0.0852036 0.0581136 0.159536 -0.0784913 0.0610116 0.155 -0.0739122 0.0581026 0.159997 -0.0758934 0.0581515 0.16 -0.0454262 0.058102 0.155385 -0.0231061 0.0399882 0.160005 -0.0288232 0.0401564 0.160018 -0.0235071 0.0108076 0.155 -0.0231008 0.0145654 0.155001 -0.0288543 0.0137497 0.155005 0.0231071 0.0133148 0.16 0.0288937 0.0140427 0.159994 0.0231021 0.0400089 0.155081 0.0287129 0.0429769 0.155002 0.0442368 0.0638678 0.159991 0.0413184 0.0581821 0.155 0.0462288 0.0581007 0.155 0.0848861 0.0638808 0.155 0.0860878 0.0581026 0.159997 0.0826295 0.0620069 0.16 0.0868134 0.0581067 -0.16398 0.124978 -0.037194 -0.159998 -0.124982 -0.036688 0.163999 0.12499 -0.037428 -0.152013 0.0060457 0.0471956 -0.153945 0.00497347 0.0619472 -0.157973 0.0135579 0.0477463 -0.158766 0.0059965 0.0454852 -0.152057 0.000698725 0.0375302 -0.158439 0.0137894 0.0439104 -0.152006 -0.0159992 0.0331278 -0.158566 -0.000361785 0.0367052 -0.152001 -0.00519926 0.0298195 -0.158778 -0.00579796 0.0450331 -0.15826 -0.0126119 0.0467373 -0.152015 -0.00537433 0.0477403 -0.152426 -0.000611302 0.0574131 0.152022 -0.00539869 0.044064 0.152606 -0.000736487 0.0343485 0.158411 -0.0137879 0.0438221 0.152001 0.00608175 0.0621995 0.152009 -0.00109542 0.0542995 0.15201 -0.00515009 0.0619764 0.158764 -0.00593877 0.0462917 0.131265 0.125 -0.0885907 0.0645898 -0.0276896 -0.0851 0.0726029 -0.034095 -0.0886001 -0.106484 -0.0344878 -0.0886018 -0.0830184 -0.0376903 -0.0851 -0.137005 -0.00570101 -0.0851001 -0.147996 -0.0892534 -0.0851001 -0.0714916 0.0332019 -0.0885944 -0.059581 0.00998107 -0.0886 -0.0553213 -0.0169845 -0.088601 -0.0739883 -0.027949 -0.0885703 -0.106537 -0.0276478 -0.088585 -0.09 -0.0316 -0.0886 -0.12112 0.0054873 -0.0886 -0.113853 0.021353 -0.0886 -0.09 0.0316 -0.0886 -0.060282 -0.011907 -0.0886 -0.120419 -0.0099811 -0.0886 -0.123302 0.0185663 -0.0886001 -0.122866 -0.0198311 -0.0885986 0.120419 0.00998108 -0.0886 0.09 -0.0316 -0.0886 0.0564274 0.0186771 -0.0886021 0.0748528 0.028331 -0.0885822 0.071741 0.0331783 -0.088608 0.089099 0.0384234 -0.0886 0.0580645 0.00228119 -0.0885958 0.0626336 0.0158 -0.0886 0.0505 0.0161342 -0.0886 0.0551697 -0.0162477 -0.0886021 0.059581 -0.00998107 -0.0886 0.119718 -0.011907 -0.0886 0.127368 0.00920913 -0.088603 0.110927 0.0322756 -0.088604 0.121746 -0.0216171 -0.0886 -0.145015 0.000196888 -0.0822455 -0.147181 0.000144384 -0.0906001 0.0488688 -0.105438 -0.0826 0.0474683 -0.105438 -0.0906 0.144979 -0.00161263 -0.0906 0.145678 0.000451586 -0.0901938 0.0472467 0.105753 -0.0826 -0.145345 -0.105023 -0.0905998 -0.145388 0.105159 -0.0905992 0.14904 0.0801536 -0.0876703 0.148807 -0.0800399 -0.0876792 -0.158 0.0795875 -0.0860605 -0.148807 0.0800399 -0.0876792 -0.14904 -0.0801536 -0.0876703 -0.158 -0.078873 -0.086473 0.0763334 0.115 -0.0851062 0.0532985 0.109262 -0.0851023 -0.0436369 0.114997 -0.0851 -0.0463536 0.098671 -0.0851009 -0.137 0.115 -0.0851 -0.0533924 0.114882 -0.0851018 -0.07505 0.115 -0.0850999 -0.147995 -0.0890554 -0.0906 -0.147995 -0.00497781 -0.0851 -0.0535264 -0.114895 -0.0851004 -0.138959 -0.114993 -0.0851 -0.0518856 -0.102173 -0.0906 -0.0514908 -0.0976075 -0.0851023 -0.0440184 -0.103846 -0.0906 -0.0452596 -0.101819 -0.0851 0.0522323 -0.103576 -0.0905828 0.057 -0.115 -0.0906 0.147997 -0.0897116 -0.0906 0.0505 0.086 -0.0906 0.0505 -0.0161342 -0.0886 -0.0505 -0.086 -0.0906 -0.0505 0.0161342 -0.0886 -0.0464922 -0.0015037 -0.0851 0.0505077 0.0899967 -0.0851 0.0446545 0.0899993 -0.0906 -0.0545 0.094 -0.0851 -0.140476 0.0942894 -0.0905994 -0.0545 -0.094 -0.0906 0.0445971 -0.0899972 -0.0905977 0.0464969 -0.089998 -0.0851 0.0452067 -0.0940034 -0.0905993 0.0474376 -0.0940092 -0.0851 0.132999 0.00671317 -0.0851 0.133 -0.0085 -0.0851 0.137006 0.00540539 -0.0851001 0.137005 0.0895162 -0.0851 -0.137 0.0085 -0.0906 -0.132999 -0.00595743 -0.0851042 -0.133 0.0085 -0.0851 -0.137002 -0.00476814 -0.0906 0.0418937 0.114998 -0.0851 0.0538457 0.115007 -0.0906001 0.138936 0.114993 -0.0851001 0.14035 0.114684 -0.0906001 0.141313 0.0940104 -0.0851 -0.0435998 -0.114994 -0.0851001 -0.0466741 -0.0990943 -0.0906 -0.057 -0.115 -0.0906 -0.140786 -0.11468 -0.0906 -0.148 -0.0085 -0.0906 -0.140896 0.114696 -0.0905998 -0.0538532 0.115006 -0.0906001 -0.0525043 0.101864 -0.090642 0.0447497 0.10122 -0.0906709 0.0440345 -0.103833 -0.0906 0.148 0.0085 -0.0906 0.147989 0.00557152 -0.0851003 0.147996 -0.00531851 -0.0851001 0.140971 -0.114695 -0.0905998 0.0530606 -0.112152 -0.0906 0.0510801 0.0983911 -0.0885707 -0.0505 -0.0161342 -0.0886 0.0505131 0.00943983 -0.0851003 0.128734 -0.00154462 -0.0885819 0.139021 -0.0940011 -0.0905998 0.141014 -0.0940078 -0.0851 -0.156769 -0.123969 -0.0906004 0.163994 0.121908 -0.0454029 0.15789 0.122001 -0.0825997 -0.157999 0.12199 -0.0493835 -0.156 0.125 -0.0826 0.142924 0.00455546 -0.0906102 0.137 0.0085 -0.0906 0.140911 0.0943028 -0.0906007 -0.140974 0.0940107 -0.0851 -0.140921 -0.0942979 -0.0906001 -0.0464986 -0.00341908 -0.0905999 0.0464959 -0.00150696 -0.0851 0.0465 -0.086 -0.0906 -0.0464887 -0.0899942 -0.0905991 -0.0464977 -0.0899972 -0.0851 0.0464922 0.0015037 -0.0851 0.0464959 0.00150696 -0.0905999 -0.0464959 0.00150696 -0.0851 -0.0446201 0.0899982 -0.0905998 -0.0443933 0.0940015 -0.0851 0.147996 0.0890341 -0.0851 0.137 0.086 -0.0906 0.0545 0.094 -0.0906 0.147995 -0.0893411 -0.0851 -0.137004 -0.0895372 -0.0906005 -0.13701 -0.0889583 -0.0851003 -0.0507907 0.0975773 -0.0851138 -0.147995 0.0893411 -0.0851 -0.147997 0.0895977 -0.0906 -0.137 0.086 -0.0906 -0.137004 0.089246 -0.0851001 0.0526063 0.089998 -0.0906 0.0505054 -0.0899932 -0.0851 0.0524792 -0.0899986 -0.0905998 -0.130894 0.089998 -0.0906 -0.0505047 0.0899942 -0.0851 -0.0526063 -0.089998 -0.0906 -0.0505077 -0.0899967 -0.0851 -0.132996 -0.0899957 -0.0906 0.0504582 -0.0940092 -0.0851 -0.127226 -0.00209059 -0.0885922 -0.0552152 0.0164299 -0.0886036 0.0505082 -0.0132151 -0.0850997 0.124743 -0.000133879 -0.0885906 -0.1435 0.108 -0.0825999 -0.140303 0.105 -0.0814481 -0.139704 0.105 -0.0821765 -0.139623 0.105 0.000513791 -0.1435 0.108 0.000899948 0.143502 0.108002 -6.12592e-06 0.1405 0.105 -0.0011 0.1395 0.105 -0.0823321 0.1385 0.105 -0.0826 0.143499 0.108 -0.0825999 0.140375 0.105 -0.0812962 0.149169 0.108 -0.0325742 0.148527 0.124994 -0.0266717 0.155996 0.125053 -0.0329869 -0.155997 0.125033 -0.0331062 -0.147824 0.124996 -0.0324294 0.147867 0.124969 -0.032074 0.144866 -0.131423 -0.0253268 0.150261 -0.124987 -0.0241605 0.1405 -0.125 -0.0380869 0.153157 -0.131594 -0.0242842 -0.1405 -0.1315 -0.0241942 -0.153278 -0.131503 -0.0244297 -0.143722 -0.126701 -0.028029 0.07505 -0.115 -0.0850999 0.0733823 -0.125 -0.0854445 -0.0768951 -0.125 -0.0866857 -0.075014 -0.115 -0.0850999 -0.0768349 0.125 -0.086663 0.0745875 0.125 -0.0850605 0.0737509 0.114996 -0.0868685 0.154855 0.124991 -0.0265499 0.155997 0.108 -0.0264767 -0.150418 0.124865 -0.0268894 -0.155994 0.108 -0.0262923 0.155898 0.137221 0.00606643 0.155667 0.119995 0.00688224 -0.155663 0.119996 0.0068799 -0.131382 0.119999 -0.0885917 -0.131302 0.125 -0.0885811 0.155887 0.12 -0.0885971 0.159999 0.123746 -0.0380201 0.156032 -0.125 -0.0357041 0.16 -0.124972 -0.0369895 -0.1405 -0.125 -0.0380869 -0.156 -0.125 -0.0380869 -0.160002 0.123655 -0.0383168 -0.144825 -0.1495 0.01538 0.146029 -0.131514 0.0138813 0.140783 -0.1369 0.00838 -0.140783 -0.1495 0.00838 -0.141649 -0.1369 0.00988 -0.141649 -0.1495 0.00988 -0.140783 -0.151216 0.05938 -0.140783 -0.1369 0.05938 -0.144418 -0.131503 0.0578775 -0.143959 -0.1369 0.05388 -0.144825 -0.154 0.05238 -0.144825 -0.1369 0.05238 0.143959 -0.154 0.05388 0.148 -0.154 0.04688 0.1476 -0.1315 0.04688 0.148 -0.154 0.02088 0.15712 -0.136882 0.0143612 0.155834 -0.1369 0.0147125 0.070581 0.137785 0.0576696 0.0683489 0.146904 0.0594873 -0.0703216 0.141394 0.0585119 -0.0667941 0.147628 0.0610141 0.0715556 0.131686 0.0592372 -0.0662258 0.133061 0.0588318 -0.0654003 0.131504 0.0638872 -0.0714369 0.131591 0.0586841 -0.0716353 0.1315 0.05388 0.144825 0.1495 0.01538 -0.140783 0.1495 0.00838 -0.141649 0.1369 0.00988 0.140783 0.151216 0.05938 0.141649 0.152347 0.05788 -0.144825 0.1369 0.05238 -0.143959 0.1369 0.05388 -0.1476 0.1315 0.04688 0.157215 0.136875 0.0579452 -0.15559 0.137563 0.0586128 -0.157241 0.136887 0.0144286 0.0965151 -0.138007 0.0639 -0.0962972 -0.137456 0.0639 -0.070581 -0.137785 0.0576696 0.0687531 -0.144624 0.0586346 0.0663555 -0.131816 0.0586623 -0.0715556 -0.131692 0.0592372 -0.0724676 -0.1315 0.0638971 -0.0683489 -0.146904 0.0594873 0.143 -0.0333 2.22921e-09 0.143 -0.1267 2.22921e-09 0.143 -0.119287 -0.0252479 0.143 -0.0866461 -0.0462247 0.143 -0.0606001 -0.0424798 0.143 -0.0407135 -0.0252479 -0.143 -0.124808 -0.0131569 -0.143 -0.1267 0.0089 -0.143 -0.1267 2.22921e-09 -0.143 -0.0866461 -0.0462247 -0.143 -0.0606001 -0.0424798 0.164 0.0236 -0.0796 0.163975 0.124997 -0.0808841 -0.163975 0.124997 -0.0812116 -0.164 0.122 -0.0796 -0.143 -0.0333 0.0089 0.143 -0.1267 0.0089 0.147 -0.0333 0.0089 -0.0233431 0.129 0.0689 0.0214925 -0.129 0.0339062 -0.0214808 -0.129 0.0654764 0.0214598 -0.129 0.0654485 0.0214989 0.129 0.0654939 0.0215 0.1315 0.03588 0.0214997 0.129 0.0339016 -0.142324 -0.0680318 0.0827921 -0.139275 -0.0694784 0.0709429 -0.100022 -0.0688749 0.0713643 -0.0599587 -0.0689649 0.0706531 0.0178913 -0.0685475 0.0829 0.0594331 -0.0712912 0.0829 0.09822 -0.0705385 0.0829 -0.139981 0.0690004 0.0712567 -0.102359 0.0696356 0.0828998 -0.0600102 0.0690933 0.0708079 -0.0606625 0.0710524 0.0829 -0.0621087 0.0694525 0.0829 -0.0200102 0.0690933 0.0708079 -0.0206625 0.0710524 0.0829 -0.0221087 0.0694525 0.0829 -0.0322502 -0.137829 0.0689071 -0.159229 -0.0655375 0.0724835 -0.161362 -0.0684791 0.0689 0.0354086 0.135387 0.077927 0.0997088 0.135359 0.0779457 0.163746 0.00516875 0.0808875 -0.159505 0.143502 0.0693224 0.125 0.143802 0.0692195 0.153881 0.13738 0.0778616 0.0157574 0.131 0.0779 -0.1377 0.132261 0.0779 -0.03214 0.1341 0.0779 -0.154016 0.137167 0.0779275 -0.035264 0.135664 0.0779115 -0.0255898 0.138916 0.076705 -0.0999315 -0.135832 0.0779469 0.0928919 -0.135876 0.0779324 0.150235 -0.13228 0.0778969 0.1377 -0.132261 0.0779 0.15464 -0.136609 0.0781229 -0.1357 -0.141014 0.0729263 -0.0359298 -0.137267 0.0778884 0.135685 -0.140566 0.0733436 0.157502 -0.143929 0.069053 0.12737 -0.143161 0.0699969 0.1507 -0.141028 0.0729 0.162204 0.00380513 0.0721578 0.16375 -0.130999 0.0778999 0.16375 0.131 0.0779 0.163749 0.07592 0.0809 -0.16375 0.137567 0.0691856 -0.16375 -0.137567 0.0691856 -0.163748 -0.07592 0.0809 0.163687 -0.0731 0.0859 -0.163687 -0.0731 0.0829 -0.16351 -0.0649 0.0829 -0.102109 -0.0685475 0.0829 -0.0604719 -0.0666048 0.0829 -0.0221087 -0.0685475 0.0829 0.0203536 -0.0665812 0.0829 0.0208952 -0.0711842 0.0829 0.0593375 -0.0669476 0.0829 0.0578913 -0.0685475 0.0829 0.16351 -0.0649 0.0829 0.163687 -0.0731 0.0829 0.163708 -0.0648992 0.0859095 -0.16351 -0.0649 0.0859 -0.163755 0.0639611 0.0858991 0.16351 0.0649 0.0859 0.163687 0.0731 0.0829 -0.16351 0.0649 0.0829 -0.140193 0.0712767 0.0829002 -0.0982225 0.0695737 0.0829 -0.0603799 0.0664109 0.0829 -0.0203799 0.0664109 0.0829 0.0178913 0.0694525 0.0829 0.0203919 0.0708262 0.0829 0.0598565 0.0693251 0.0829 0.0999574 0.0692096 0.0829 0.139229 0.0695029 0.0828992 0.156846 0.0677248 0.0829015 -0.163687 0.0731 0.0829 -0.163775 0.0740042 0.0858992 -0.163687 0.0731 0.0859 0.14675 0.064 0.0784 0.150745 -0.063213 0.0783998 -0.150725 -0.0634118 0.0784005 -0.14675 -0.064 0.0784 0.14675 -0.064 0.0784 0.14675 0.128 0.0784 -0.14675 0.074 0.0784 0.14675 0.074 0.0784 -0.14675 0.128 0.0784 0.163749 -0.0620802 0.0809 -0.163707 0.130045 0.0807873 0.16325 0.129 0.0809 -0.16325 0.0759199 0.0809 0.0595224 0.137226 0.0778659 -0.16175 -0.1305 0.0809 -0.16375 -0.134041 0.0719689 0.156836 -0.0698957 0.0829014 -0.0323366 -0.133924 0.0778993 0.10057 -0.137205 0.0779522 0.158968 0.0656661 0.0721259 -0.156595 0.0681861 0.0829006 -0.159477 0.0721413 0.0753349 0.14675 -0.129 0.0689 -0.14675 -0.073 0.0689 -0.151741 -0.0753389 0.0689 0.14675 -0.073 0.0689 0.151746 0.126394 0.0689 0.14675 0.073 0.0689 0.15175 0.0649998 0.0689 -0.151749 0.0649999 0.0689 0.14675 -0.065 0.0689 -0.15175 -0.06 0.0689 0.135 -0.143757 0.0689 0.096892 -0.136662 0.0689 0.0961628 0.137305 0.0689 0.0315465 0.137683 0.0689 -0.15175 0.124 0.0689 -0.125 0.143757 0.0689 -0.13 0.138757 0.0689 -0.159855 -0.135388 0.0726838 0.0238538 -0.143757 0.0689 0.163694 0.137567 0.0689 0.161031 -0.0689758 0.0689 0.163694 -0.137567 0.0689 0.151749 -0.0626548 0.0689 -0.160262 -0.000117228 0.0689 -0.1507 0.141028 0.0729 -0.135721 0.140987 0.0729647 -0.100247 0.137526 0.0775411 -0.0233903 0.144022 0.0689011 -0.151746 -0.126394 0.0689 -0.14675 -0.129 0.0774 0.151704 -0.0753237 0.0783273 0.151729 -0.126292 0.0782423 0.151746 -0.0756063 0.0689 0.14675 0.129 0.0689 -0.14675 -0.074 0.0784 -0.14675 -0.128 0.0784 0.14675 -0.128 0.0784 0.14675 -0.074 0.0784 -0.14675 0.129 0.0689 -0.150232 0.127783 0.0689008 0.151741 -0.126661 0.0689 -0.14675 -0.129 0.0689 0.158994 -0.0719908 0.0721215 0.15829 -0.0658102 0.0725603 0.16375 0 0.0719 0.161074 -0.000363767 0.0689 0.158771 0.0719012 0.0689072 0.162827 0.138748 0.0689022 0.15742 0.144053 0.0689207 0.0930294 0.135895 0.0779112 0.096089 0.13445 0.0716869 0.0330085 0.136843 0.0730511 -0.0319786 0.137539 0.0688996 -0.0312843 0.134704 0.0714627 -0.03674 0.141782 0.0719 -0.0932165 0.135179 0.0779441 -0.0965829 0.137236 0.0689 -0.158259 0.0657529 0.0718608 -0.159993 0.06856 0.0689 -0.16375 -0.06425 0.0719 -0.162314 -0.143687 0.0689015 -0.156931 -0.13716 0.0776117 -0.0961621 -0.137461 0.0689 -0.0965543 -0.134176 0.071789 0.033623 -0.137316 0.0689 0.0312953 -0.137249 0.0731573 0.0958169 -0.138811 0.0689005 0.0953446 -0.137118 0.0731267 0.161039 -0.134942 0.0719469 -0.0963731 0.134525 0.0718573 -0.15638 -0.0698514 0.0829019 -0.158139 -0.000495859 0.0733402 -0.16375 -0.131 0.0803995 0.0170096 -0.131001 0.0779006 -0.16175 0.131 0.0804 0.0357925 -0.141213 0.0726603 0.0357511 -0.136254 0.0779323 0.0288501 -0.13575 0.0779669 -0.02754 -0.141782 0.0719 -0.0329791 -0.136908 0.07339 -0.163748 0.133797 0.0774666 -0.157726 0.135604 0.0689048 -0.0927185 0.141779 0.0719031 -0.066769 0.137311 0.0777775 0.0246827 0.138268 0.0775331 0.123852 0.137311 0.0778296 0.0999023 0.141025 0.0728613 0.160128 0.135348 0.0727373 0.163264 -0.0724676 0.0719001 -0.158513 -0.0720588 0.0719273 -0.163687 -0.0731 0.0859 -0.16375 0.0036766 0.0739009 -0.163745 0.00419874 0.0808866 -0.163573 0.0649 0.0859 -0.16375 0.06425 0.0719 0.163687 0.0731 0.0859 0.16351 0.0649 0.0829 0.16375 0.06425 0.0719 -0.0157574 0.131 0.0779 -0.0271061 -0.138 0.0777797 -0.0157574 -0.131 0.0779 -0.021915 -0.136128 0.0779072 -0.125 0.143802 0.0692195 -0.163693 0.138986 0.0689 -0.163694 -0.137567 0.0689 -0.0216829 0.135674 0.0689001 -0.125 -0.143757 0.0689 -0.0239562 -0.144033 0.0689013 -0.0166542 0.131 0.0689 0.0157574 0.131 0.0691856 0.021206 0.134582 0.0688999 -0.0215321 -0.135777 0.0689001 0.0165968 -0.131 0.0689001 -0.0163315 -0.131086 0.0689 0.0284332 0.142979 0.0703135 0.0228018 0.143553 0.0689004 0.0217166 -0.135729 0.0689 0.16375 -0.137567 0.0691856 0.16375 0.137567 0.0691856 0.162635 -0.138853 0.0689059 0.0236596 -0.141848 0.0699368 0.163749 -0.0759198 0.0809 -0.16375 0.0618982 0.0804 -0.16325 0.0620801 0.0809 -0.16375 0.0638521 0.0857684 -0.16375 0.0761018 0.0804 -0.14675 0.073 0.0689 0.14675 -0.073 0.0774 -0.14675 -0.065 0.0774 -0.151746 0.0756063 0.0689 0.15175 0.06 0.0774 0.151741 0.0753389 0.0689 -0.14675 -0.065 0.0689 0.0198301 0.069132 0.0708603 0.0210283 0.0667345 0.0829001 -0.0182225 0.0695737 0.0829 -0.0581181 0.0698863 0.0829 -0.099475 0.0670407 0.0829 -0.100106 0.0691584 0.0708887 -0.139605 0.0667737 0.0828996 0.139507 -0.0684053 0.0829002 0.10005 -0.0689303 0.0708842 0.102055 -0.069785 0.0829 0.100226 -0.0667248 0.0829001 0.0599586 -0.0688536 0.07085 0.0621799 -0.0681731 0.0829 0.0199586 -0.0688536 0.07085 -0.0198753 -0.0689119 0.0708781 -0.0189696 -0.0712879 0.0829 -0.0197742 -0.0667248 0.0829 -0.05957 -0.0714663 0.0829002 -0.0989198 -0.071131 0.0829001 -0.0996081 -0.0671738 0.0829 -0.138761 -0.0710209 0.0829028 -0.139539 -0.0672204 0.0829 -0.16375 -0.131 0.0779 -0.16175 0.131 0.0779 0.16375 -0.0741479 0.0857684 0.163775 -0.0740042 0.0858992 -0.16375 -0.0740258 0.0858995 0.16375 -0.0638521 0.0857684 -0.16375 -0.0638521 0.0857684 0.16375 0.0740258 0.0858995 -0.16375 0.0741479 0.0857684 -0.15075 0.06 0.0784 -0.15175 0.06 0.0774 -0.150399 0.0636826 0.0746183 -0.14675 0.065 0.0774 -0.15175 -0.06 0.0774 0.14675 0.065 0.0774 -0.14675 0.064 0.0784 0.15075 0.06 0.0784 0.150535 0.0636519 0.069551 0.15175 -0.06 0.0774 0.14675 -0.065 0.0774 -0.151729 0.126292 0.0782423 -0.14675 0.129 0.0774 -0.14675 0.073 0.0774 -0.151704 0.0753237 0.0783273 0.14675 0.129 0.0774 0.14675 0.073 0.0774 0.151729 0.0757078 0.0782423 0.151704 0.126676 0.0783273 -0.151729 -0.0757078 0.0782423 -0.14675 -0.073 0.0774 -0.151704 -0.126676 0.0783273 0.14675 -0.129 0.0774 -0.163747 -0.0620801 0.0809 -0.163741 -0.00367826 0.0808812 -0.1566 -5.57622e-17 0.0809 0.163707 -0.130045 0.0807873 0.16175 -0.131 0.0804 -0.16325 -0.129 0.0809 0.16325 0.0620801 0.0809 0.156777 -0.00104306 0.0719253 0.1566 -2.70024e-17 0.0809 0.163747 -0.00400006 0.0808851 0.16375 0.131 0.0803995 0.16175 0.1305 0.0809 -0.0643008 0.135194 0.0737979 0.128502 0.136177 0.0739318 0.0679391 0.133251 0.0779131 0.0642948 0.135186 0.0737941 -0.0693192 0.134515 0.0779006 -0.133452 0.134173 0.0732061 -0.124074 0.133278 0.0778989 -0.150377 0.132277 0.0728993 0.1507 0.141028 0.0729 0.135155 0.132487 0.0731077 0.13496 0.132639 0.0779006 -0.150235 0.13228 0.0778964 0.150477 0.132293 0.0728997 0.149778 0.132266 0.0779 0.124943 -0.133266 0.0779 0.131011 -0.135192 0.074053 0.0644224 -0.135258 0.0738071 0.0684929 -0.133291 0.0779 0.0598114 -0.133281 0.0778992 -0.0643794 -0.135273 0.0737995 -0.0593451 -0.137165 0.0778629 -0.0695806 -0.136899 0.0778822 -0.05995 -0.133308 0.0778992 -0.124626 -0.133279 0.0778997 -0.130654 -0.135111 0.0741558 0.135805 -0.132313 0.0729 -0.150918 -0.140606 0.0734874 -0.15059 -0.1323 0.0729003 -0.135719 -0.132266 0.0729 -0.149778 -0.132266 0.0779 -0.135999 -0.13228 0.0778897 0.150615 -0.132276 0.0729 -0.123674 -0.137196 0.0778263 -0.100012 -0.141308 0.0725223 0.123404 -0.137132 0.0778824 -0.092768 -0.140807 0.0731982 -0.0929055 -0.135912 0.0779465 0.100785 -0.141119 0.0727849 0.060556 -0.137258 0.0778178 0.0692412 -0.136461 0.0779036 0.135717 0.141027 0.0729087 -0.124326 0.137277 0.077848 -0.0596029 0.133377 0.0779037 0.125 -0.138757 0.0689 0.125 -0.143757 0.0689 0.025 -0.143802 0.0692195 0.1275 0.141257 0.0689 0.131098 0.143217 0.0699789 -0.13 -0.143296 0.0698939 -0.13 -0.140757 0.0689 -0.130837 0.143293 0.069895 0.127958 0.000465346 -0.088616 0.0523193 -0.00489683 -0.0920933 0.0903022 0.0292456 -0.0845036 0.0703518 -0.0252716 -0.0845687 0.0756679 0.0282041 -0.084566 0.063434 -0.0181561 -0.0885961 0.0759335 -0.02811 -0.0887751 0.103994 0.0249508 -0.0920362 0.108875 0.0211862 -0.084821 0.118164 -0.00880697 -0.0842144 0.0719566 0.0340504 -0.088651 0.0571219 -0.0205413 -0.0886153 0.0725885 -0.034391 -0.0886098 0.128016 -0.00708683 -0.092072 0.106016 0.0352156 -0.0885946 0.0505938 0.00700182 -0.0920966 0.0797384 0.0268044 -0.0917147 0.0868244 0.038074 -0.0920844 0.113022 0.0303282 -0.0920852 0.118919 -0.00172966 -0.092044 0.071864 -0.0338035 -0.0919019 0.0617798 -0.000688584 -0.0920037 0.105672 -0.0244468 -0.0844274 0.115292 0.013267 -0.0919138 0.115377 -0.0195979 -0.0885429 0.10905 0.0261369 -0.0847185 0.108144 -0.0335707 -0.0886381 0.09 -0.038 -0.0886 0.122096 0.00752205 -0.088521 0.106301 0.0277914 -0.0886132 0.0756206 0.027787 -0.0890495 0.103286 -0.0283067 -0.0888232 0.0899938 0.0360685 -0.0884843 0.123193 0.0200371 -0.0885984 0.121034 -0.0223995 -0.0885999 0.0600429 0.0126327 -0.0886004 0.0589393 0.0223544 -0.0885999 0.0883286 -0.029515 -0.084579 0.0575708 0.00389117 -0.0846352 0.128381 0.00674449 -0.0921128 0.0928922 -0.0381063 -0.0920871 0.0742785 -0.0252268 -0.0920574 0.0651801 0.0137628 -0.0919256 0.104075 0.0345062 -0.0920915 0.0718254 0.0320029 -0.0919953 0.103975 -0.0255245 -0.0920166 0.11042 -0.0319209 -0.0919944 0.0517441 0.000291236 -0.0887065 -0.108136 -0.0338035 -0.0919019 -0.0711985 -0.0325305 -0.0919643 -0.0718557 -0.0335707 -0.0886381 -0.129406 0.00700183 -0.0920966 -0.0782629 0.0272925 -0.0845536 -0.104276 0.0282386 -0.084546 -0.118638 -0.00674042 -0.0845977 -0.0761996 -0.025964 -0.0844943 -0.121061 0.0223544 -0.0885999 -0.0568075 0.0200371 -0.0885984 -0.0704245 0.0227331 -0.0921007 -0.0931755 0.038074 -0.0920844 -0.0669778 0.0303282 -0.0920852 -0.127681 -0.00489682 -0.0920934 -0.104867 -0.0247037 -0.0920933 -0.0580418 -0.00194922 -0.0845691 -0.0901876 -0.0310993 -0.084776 -0.0646233 -0.0195979 -0.0885429 -0.057494 0.00776331 -0.0886062 -0.0736995 0.0277914 -0.0886132 -0.0899313 0.0349048 -0.0883439 -0.108043 0.0340504 -0.088651 -0.116566 -0.0181562 -0.0885961 -0.119957 0.0126326 -0.0886004 -0.122878 -0.0205413 -0.0886153 -0.0767144 -0.0283067 -0.0888232 -0.0739835 0.0352156 -0.0885946 -0.107411 -0.034391 -0.0886098 -0.09 -0.038 -0.0886 -0.0520417 0.000465339 -0.088616 -0.0589655 -0.0223995 -0.0885999 -0.0684949 0.0234218 -0.0846725 -0.115014 0.0146133 -0.0919612 -0.117638 0.0115718 -0.0842188 -0.112221 -0.0195872 -0.0844581 -0.0516187 0.00674448 -0.0921128 -0.0519835 -0.00708684 -0.092072 -0.0871077 -0.0381063 -0.0920871 -0.0908152 -0.0288417 -0.0920318 -0.118521 -0.000587555 -0.0920854 -0.102772 0.0262189 -0.0911812 -0.0759253 0.0345062 -0.0920915 -0.104004 -0.028478 -0.0887282 -0.108175 0.0320029 -0.0919953 -0.061488 -0.00253638 -0.0919495 -0.0734714 -0.0233332 -0.0920411 -0.128256 0.00029124 -0.0887065 0.212316 -0.012539 -0.0551002 0.164003 -0.0174483 0.00708379 0.196405 -0.0167065 0.0648994 0.307137 -1.28441e-05 -0.0170815 0.354001 -0.00493977 0.0459264 0.350961 -0.00877201 0.0516604 0.346003 -0.00951708 0.0170653 0.164 -0.00329035 -0.0533019 0.163998 -0.0182211 -0.0514046 0.23393 0.0204992 0.0679 0.199 0.0125981 0.0684 0.333 0.0125981 0.0684 0.199 -0.01 0.0669 0.333 -0.0115 0.0673019 0.333 -0.013 0.0699 0.199 -0.0125981 0.0684 0.328 -0.005 0.0549 0.179033 -0.005 -0.0414204 0.33599 -0.005 0.0107957 0.280951 -0.005 -0.0521 0.172 -0.005 -0.0521 0.335972 0.00500027 0.0506682 0.17905 0.005 -0.0408899 0.331 0.005 0.0619 0.170926 0.00500647 -0.0527624 0.278126 0.005 -0.0450851 0.354006 -0.00305662 0.0511531 0.354 -0.0129348 0.0239888 0.354011 0.0150916 0.0616722 0.354 0.0190053 0.0527446 0.354 -0.0190023 0.0526078 0.354 0.0101195 0.0172654 0.354002 -0.0103854 0.0179072 0.23393 -0.0145008 0.0679 0.236363 -0.0204036 0.0679516 0.2338 -0.0145013 0.0729 0.202461 -0.0145533 0.0679003 0.204099 -0.0204992 0.0679 0.235912 0.0145652 0.0679517 0.204099 0.0204992 0.0729 0.20201 0.0203794 0.067948 0.204099 0.0145008 0.0679 0.261232 -0.0119506 -0.0571008 0.216931 -0.00159668 -0.0571003 0.214526 -0.00869695 -0.0631004 0.234548 0.0204955 0.0728998 0.333 0.0225 0.0729 0.279616 0.0204945 0.0728998 0.3238 0.0204987 0.0729 0.334016 0.0177282 0.0729373 0.164001 0.0225 0.0728995 0.204229 0.0145013 0.0729 0.241499 0.0168661 0.0729007 0.234451 0.014503 0.0728996 0.249229 0.0145013 0.0729 0.21529 -0.000444007 0.0548999 0.328 0.005 0.0549 0.209002 -0.005 0.0549001 0.264068 1.48222e-06 0.0548999 0.314119 9.14842e-05 0.0549 0.335692 -0.00641386 0.0644255 0.199339 0.0065714 0.0645603 0.200287 0.00549141 0.063635 0.170441 -0.0053388 -0.0535495 0.169004 -0.00721008 0.00689923 0.16901 0.00688509 0.00689719 0.287824 0.015632 0.0649002 0.199 0.00777784 0.0649 0.184 0.0225 0.0649 0.287033 -0.0160587 0.0649 0.334593 -0.0225 0.0648962 0.240231 -0.0184878 0.0649 0.169 -0.0207092 -0.0506444 0.169004 -0.00719436 -0.0550858 0.169 -0.0174988 0.040552 0.234649 -0.0204958 0.0729 0.20338 -0.0145042 0.0729004 0.164 -0.0225 0.0728996 0.3238 -0.0145013 0.0729 0.203123 -0.02048 0.0729018 0.195919 -0.0175851 0.0729 0.241387 -0.0169022 0.0729005 0.2788 -0.0145013 0.0729 0.333 -0.0225 0.0729 0.168996 -0.0224955 0.0435724 0.184 -0.0225 0.0649 0.260553 -0.00152986 -0.0631022 0.21608 0.00930931 -0.0630996 0.171561 -0.0119928 -0.0631 0.16927 0.00154239 -0.0631001 0.212672 0.00153024 -0.0631 0.221 -0.012 -0.0631 0.211704 0.0119725 -0.0631015 0.169 -0.015 -0.0631 0.212323 -0.0120111 -0.063101 0.264064 -0.000180007 -0.0631001 0.169 0.0225 0.0499 0.169 0.015 -0.0550997 0.169 0.0171002 0.000938112 0.169 0.015 -0.0631 0.169 0.0203546 -0.050691 0.164 -0.0224986 -0.0630996 0.164 0.0175156 0.0437154 0.17684 0.0130358 0.0644516 0.163999 -0.0176144 0.0484114 0.164 -0.0174894 0.0420828 0.164 0.0224991 -0.0630874 0.164 -0.0200884 0.00032667 0.164 -0.00301244 0.00125359 0.212322 0.00959055 -0.0550999 0.285398 0.015 -0.0630972 0.215714 -0.00932648 -0.0551 0.164001 0.0171054 0.0491003 0.168998 -0.0179781 -0.053631 0.164 0.0181907 -0.0525317 0.168998 0.0174427 -0.0533623 0.179 0.005 -0.00310254 0.213942 3.7927e-05 -0.0451 0.264133 -0.000169947 -0.0451 0.187 -0.005 -0.0451 0.278123 -0.005 -0.0450882 0.187 0.005 -0.0451 0.318988 -0.00106996 -0.0306605 0.352992 -0.0157758 0.00217659 0.294574 0.00409989 -0.0542371 0.285397 -0.015 -0.0630976 0.33598 0.005 0.0107862 0.346014 0.00983714 0.0173163 0.28216 -0.00734368 -0.0550864 0.282164 -0.015 -0.0550994 0.281583 -0.00547446 -0.0537985 0.345891 -0.00692926 0.00645067 0.343566 -0.00501226 0.00742149 0.345949 -0.00661425 0.0526513 0.282163 0.015 -0.0550993 0.28217 0.00731046 -0.055084 0.34569 0.00659088 0.00662124 0.344059 0.00500955 0.00783388 0.344744 0.00503323 0.0542257 0.28051 0.00500281 -0.052722 0.281771 0.00579446 -0.0541284 0.170586 0.00587868 -0.0542213 0.169 0.00724819 -0.0550596 0.168999 -0.0224992 -0.0625798 0.169 0.0224977 -0.0627182 0.335931 -0.005 0.0512486 0.170751 -3.92339e-05 -0.0522343 0.170521 -0.00016678 0.00229524 0.347562 7.89331e-05 0.0522671 0.354002 0.00190345 0.0550546 0.353997 -0.00029214 0.0175495 0.345768 0.0100787 0.0536035 0.353999 0.0102827 0.0520436 0.345591 -0.0111473 0.0537797 0.346068 -0.0149996 0.00663187 0.346014 0.0150027 0.00655425 0.347155 0.0140585 0.0081532 0.354001 -0.0150025 0.0615048 0.293241 -0.00275297 -0.0631106 0.296463 0.00116421 -0.0631184 0.295312 -0.0036008 -0.0535239 0.286965 0.00106897 -0.0630365 0.290975 7.11273e-05 -0.0497741 0.320105 0.000739597 -0.0295811 0.286397 -0.0169819 0.0729004 0.285531 -0.0185532 0.0649 0.242756 -0.0154328 0.0649 0.196524 0.0168531 0.0729004 0.241551 0.0169687 0.0649001 0.286259 0.0175306 0.0729018 0.285155 0.0184495 0.0649 0.169003 0.017492 0.0419673 0.164001 -0.0139876 0.0640988 0.196646 0.0140042 0.0648995 0.199 0.0115 0.0673019 0.199 -0.013 0.0649 0.199 -0.0115 0.0673019 0.336615 -0.0222121 0.0669034 0.333 -0.01 0.0669 0.213515 9.26347e-05 0.0669 0.199 0.01 0.0669 0.333 0.01 0.0669 0.164011 0.013 0.0728995 0.199 0.013 0.0699 0.199 -0.013 0.0699 0.164012 -0.013 0.0728995 0.169 -0.0192346 0.000471149 0.164 0.0184576 0.00206446 0.168999 0.0174899 0.00695327 0.212786 0.000401663 0.054912 0.314247 -0.000925562 0.0669 0.313981 0.00114562 0.0669 0.264089 3.19581e-05 0.0669 0.219448 0.0119974 -0.0631001 0.261049 0.00154938 -0.0571003 0.21653 0.0119205 -0.0571004 0.218637 0.00152042 -0.0571004 0.169814 0.0119524 -0.0570997 0.211301 0.00154477 -0.0571 0.217618 0.00150894 -0.0631001 0.260873 0.00151692 -0.0630999 0.215492 -0.00149974 -0.0630999 0.25943 -0.00150864 -0.0570999 0.209686 -0.00151656 -0.0630983 0.17156 0.00152038 -0.0570999 0.169759 -0.00155102 -0.0630998 0.170696 -0.00152242 -0.0570996 0.171671 0.0119774 -0.0631023 0.170158 -0.0119628 -0.0570994 0.208748 -0.0119967 -0.0570999 0.210671 -0.0015691 -0.0570991 0.20944 0.0119796 -0.0570999 0.218563 -0.0119828 -0.0570999 0.259882 0.011982 -0.0630992 0.25943 0.0119914 -0.0570999 0.260888 -0.0119881 -0.0631015 0.29355 -0.0204919 0.0729029 0.324627 -0.0145026 0.0679 0.292823 -0.0145099 0.0729001 0.32551 -0.0204701 0.0678986 0.32621 -0.0204697 0.0728957 0.292412 -0.0204786 0.0678997 0.293608 -0.014504 0.0679 0.293464 0.020494 0.0729019 0.292681 0.0145192 0.0728962 0.32621 0.0145277 0.0728949 0.293402 0.0145026 0.0679 0.325509 0.0145266 0.0678987 0.324627 0.0204974 0.0679 0.29252 0.0204734 0.0678987 0.24838 0.0204957 0.0729002 0.280718 0.0145797 0.0679955 0.27893 0.0145008 0.0729 0.27893 0.0204992 0.0679 0.249099 0.0145008 0.0679 0.246666 0.0204036 0.0679635 0.249099 -0.0145008 0.0729 0.279649 -0.0204957 0.0729003 0.248414 -0.0204945 0.0728998 0.249099 -0.0204992 0.0679 0.27893 -0.0145008 0.0679 0.247312 -0.0145797 0.0679719 0.281363 -0.0204036 0.0679516 0.173947 0.0224972 0.0623664 0.173035 -0.0224937 0.061554 0.167544 -0.0152579 0.0460824 0.168984 -0.0174916 0.00691342 0.164001 0.00394917 0.00668843 0.164 0.0174846 0.00965844 0.167926 0.0169553 0.0487265 0.172581 -0.0174565 0.0602999 0.180507 -0.0129966 0.0647505 0.164 0.0173022 0.0614275 0.333 0.013 0.0729 0.333 0.013 0.0699 0.333 -0.013 0.0729 0.333881 -0.0168752 0.0729418 0.333 0.0115 0.0673019 0.335871 -0.0126122 0.0684124 0.202 0.005 0.0619 0.200299 -0.00546771 0.0635995 0.199 -0.008 0.0649 0.17096 -0.00501055 0.00494072 0.171464 0.00500197 0.00443599 0.179 -0.005 -0.00310503 0.209005 0.005 0.0549001 0.340661 0.0151161 0.0617029 0.345999 0.0170013 0.0512635 0.344238 0.0224427 0.0571866 0.331606 0.0168959 0.0649 0.335045 0.0224996 0.064894 0.331 0.008 0.0649 0.337439 0.00629957 0.063581 0.344134 -0.0223966 0.0573186 0.340656 -0.0150341 0.0616809 0.346 -0.0170024 0.0515083 0.331528 -0.0170377 0.0649012 0.331 -0.008 0.0649 0.343574 -0.00516227 0.0575206 0.201863 -0.00499986 0.062037 0.331 -0.00540192 0.0634 0.354032 -0.0189365 0.00825394 0.354003 0.0230517 0.0625634 0.346234 0.015 -0.00434947 0.353997 0.0189596 0.00329512 0.347968 0.0189954 0.00527018 0.348032 0.0193044 0.0535048 0.347914 -0.0189747 0.00522556 0.347998 -0.0190015 0.0531238 0.354 -0.022472 0.057466 0.353998 0.0127809 0.023973 0.348 0.0127963 0.045822 0.348 -0.0128904 0.0457781 0.354 0.0129073 0.0456329 0.348 0.012879 0.0240369 0.348 -0.0127674 0.0239729 0.354 -0.0129579 0.0437759 0.16904 -0.015 -0.0550996 0.354 0.0205 0.0669 0.337183 0.0203486 0.0670595 0.353999 -0.0223482 0.0668917 0.216156 0.0123252 -0.0551 -0.324627 -0.0204974 0.0679 -0.3238 -0.0204987 0.0729 -0.324627 0.0145026 0.0679 -0.264133 0.000169947 -0.0451 -0.354001 0.00493977 0.0459264 -0.345768 -0.0100787 0.0536035 -0.23393 -0.0204992 0.0679 -0.333 -0.0125981 0.0684 -0.333 0.0115 0.0673019 -0.199 0.0115 0.0673019 -0.199 0.0125981 0.0684 -0.328 0.005 0.0549 -0.179033 0.005 -0.0414204 -0.172 0.005 -0.0521 -0.179 0.005 -0.00310503 -0.354 0.0129348 0.0239888 -0.354 -0.0205 0.0669 -0.354032 0.0189365 0.00825394 -0.354001 0.0150025 0.0615048 -0.354002 0.0103854 0.0179072 -0.346003 0.00951708 0.0170653 -0.236363 0.0204036 0.0679516 -0.23393 0.0145008 0.0679 -0.2338 0.0145013 0.0729 -0.202461 0.0145533 0.0679003 -0.204099 0.0204992 0.0679 -0.235912 -0.0145652 0.0679517 -0.20201 -0.0203794 0.067948 -0.204099 -0.0145008 0.0679 -0.218563 0.0119828 -0.0570999 -0.216931 0.00159668 -0.0571003 -0.214526 0.00869695 -0.0631004 -0.210671 0.0015691 -0.0570991 -0.170696 0.00152242 -0.0570996 -0.234548 -0.0204955 0.0728998 -0.32621 -0.0145277 0.0728949 -0.333 -0.0225 0.0729 -0.279616 -0.0204945 0.0728998 -0.333 -0.013 0.0729 -0.334016 -0.0177282 0.0729373 -0.164001 -0.0225 0.0728995 -0.204099 -0.0204992 0.0729 -0.204229 -0.0145013 0.0729 -0.241499 -0.0168661 0.0729007 -0.234451 -0.014503 0.0728996 -0.27893 -0.0145008 0.0729 -0.209005 -0.005 0.0549001 -0.21529 0.000444007 0.0548999 -0.314119 -9.14842e-05 0.0549 -0.264068 -1.48222e-06 0.0548999 -0.328 -0.005 0.0549 -0.200287 -0.00549141 0.063635 -0.202 -0.005 0.0619 -0.170441 0.0053388 -0.0535495 -0.17096 0.00501055 0.00494072 -0.170926 -0.00500647 -0.0527624 -0.331 -0.008 0.0649 -0.335045 -0.0224996 0.064894 -0.287824 -0.015632 0.0649002 -0.196646 -0.0140042 0.0648995 -0.285155 -0.0184495 0.0649 -0.199 0.013 0.0649 -0.199 0.008 0.0649 -0.240231 0.0184878 0.0649 -0.285531 0.0185532 0.0649 -0.287033 0.0160587 0.0649 -0.334593 0.0225 0.0648962 -0.196405 0.0167065 0.0648994 -0.184 0.0225 0.0649 -0.168999 0.0224992 -0.0625798 -0.168998 0.0179781 -0.053631 -0.234649 0.0204958 0.0729 -0.3238 0.0145013 0.0729 -0.2788 0.0145013 0.0729 -0.20338 0.0145042 0.0729004 -0.195919 0.0175851 0.0729 -0.164 0.0225 0.0728996 -0.203123 0.02048 0.0729018 -0.241387 0.0169022 0.0729005 -0.286397 0.0169819 0.0729004 -0.333 0.0225 0.0729 -0.354 0.022472 0.057466 -0.260553 0.00152986 -0.0631022 -0.219448 -0.0119974 -0.0631001 -0.164 0.0224986 -0.0630889 -0.212323 0.0120111 -0.063101 -0.264064 0.000180007 -0.0631001 -0.260873 -0.00151692 -0.0630999 -0.184 -0.0225 0.0649 -0.169 -0.0171002 0.000938112 -0.169 -0.0203546 -0.050691 -0.164001 -0.0171054 0.0491003 -0.163999 0.0176144 0.0484114 -0.164 -0.0224991 -0.0630996 -0.164 -0.0181907 -0.0525317 -0.163998 0.0182211 -0.0514046 -0.164 -0.0184576 0.00206446 -0.164 0.00612388 -0.0526881 -0.164 0.0015 -0.000698076 -0.163998 -0.0035348 -0.0511537 -0.216156 -0.0123252 -0.0551 -0.212322 -0.00959055 -0.0550999 -0.169 -0.00724819 -0.0550596 -0.169 -0.015 -0.0631 -0.169 0.015 -0.0631 -0.212316 0.012539 -0.0551002 -0.215714 0.00932648 -0.0551 -0.169 0.0207092 -0.0506444 -0.168998 -0.0174427 -0.0533623 -0.179 -0.005 -0.00310254 -0.17905 -0.005 -0.0408899 -0.213942 -3.7927e-05 -0.0451 -0.187 0.005 -0.0451 -0.278123 0.005 -0.0450882 -0.187 -0.005 -0.0451 -0.318988 0.00106996 -0.0306605 -0.352992 0.0157758 0.00217659 -0.346234 -0.015 -0.00434947 -0.294574 -0.00409989 -0.0542371 -0.285398 -0.015 -0.0630972 -0.307137 1.28441e-05 -0.0170815 -0.33598 -0.005 0.0107862 -0.278126 -0.005 -0.0450851 -0.282164 0.015 -0.0550994 -0.280951 0.005 -0.0521 -0.281583 0.00547446 -0.0537985 -0.28216 0.00734368 -0.0550864 -0.345891 0.00692926 0.00645067 -0.343566 0.00501226 0.00742149 -0.345949 0.00661425 0.0526513 -0.28217 -0.00731046 -0.055084 -0.282163 -0.015 -0.0550993 -0.34569 -0.00659088 0.00662124 -0.344059 -0.00500955 0.00783388 -0.344744 -0.00503323 0.0542257 -0.28051 -0.00500281 -0.052722 -0.281771 -0.00579446 -0.0541284 -0.169 -0.0224977 -0.0627182 -0.33599 0.005 0.0107957 -0.335972 -0.00500027 0.0506682 -0.335931 0.005 0.0512486 -0.170744 5.64416e-05 -0.0522846 -0.170521 0.00016678 0.00229524 -0.164023 -0.00320879 0.00364856 -0.354002 -0.00190345 0.0550546 -0.354006 0.00305662 0.0511531 -0.347562 -7.89331e-05 0.0522671 -0.353997 0.00029214 0.0175495 -0.354 -0.0101195 0.0172654 -0.346014 -0.00983714 0.0173163 -0.353999 -0.0102827 0.0520436 -0.345591 0.0111473 0.0537797 -0.354011 -0.0150916 0.0616722 -0.340661 -0.0151161 0.0617029 -0.346068 0.0149996 0.00663187 -0.346014 -0.0150027 0.00655425 -0.347155 -0.0140585 0.0081532 -0.293241 0.00275297 -0.0631106 -0.286965 -0.00106897 -0.0630365 -0.296463 -0.00116421 -0.0631184 -0.295312 0.0036008 -0.0535239 -0.290975 -7.11273e-05 -0.0497741 -0.320105 -0.000739597 -0.0295811 -0.331606 -0.0168959 0.0649 -0.242756 0.0154328 0.0649 -0.196524 -0.0168531 0.0729004 -0.241551 -0.0169687 0.0649001 -0.286259 -0.0175306 0.0729018 -0.199 -0.0125981 0.0684 -0.199 -0.0115 0.0673019 -0.314247 0.000925562 0.0669 -0.333 0.01 0.0669 -0.199 0.01 0.0669 -0.199 -0.01 0.0669 -0.313981 -0.00114562 0.0669 -0.213515 -9.26347e-05 0.0669 -0.333 -0.013 0.0699 -0.17684 -0.0130358 0.0644516 -0.199 -0.013 0.0699 -0.199 0.013 0.0699 -0.333 0.013 0.0729 -0.164 0.01891 0.00162445 -0.169 0.0192346 0.000471149 -0.168995 0.0174699 0.00692357 -0.168999 -0.0174876 0.00702665 -0.164012 0.013 0.0728995 -0.164011 -0.013 0.0728995 -0.212786 -0.000401663 0.054912 -0.264089 -3.19581e-05 0.0669 -0.261232 0.0119506 -0.0571008 -0.21653 -0.0119205 -0.0571004 -0.218637 -0.00152042 -0.0571004 -0.168948 0.0119574 -0.0630995 -0.211301 -0.00154477 -0.0571 -0.20944 -0.0119796 -0.0570999 -0.169814 -0.0119524 -0.0570997 -0.261049 -0.00154938 -0.0571003 -0.25943 0.00150864 -0.0570999 -0.217618 -0.00150894 -0.0631001 -0.215492 0.00149974 -0.0630999 -0.212672 -0.00153024 -0.0631 -0.209686 0.00151656 -0.0630983 -0.17156 -0.00152038 -0.0570999 -0.174 0.0015 -0.0631 -0.171671 -0.0119774 -0.0631023 -0.16927 -0.00154239 -0.0631002 -0.170158 0.0119628 -0.0570994 -0.208748 0.0119967 -0.0570999 -0.221 0.012 -0.0631 -0.259882 -0.011982 -0.0630992 -0.25943 -0.0119914 -0.0570999 -0.260888 0.0119881 -0.0631015 -0.292823 0.0145099 0.0729001 -0.29355 0.0204919 0.0729029 -0.292412 0.0204786 0.0678997 -0.32621 0.0204697 0.0728957 -0.293608 0.014504 0.0679 -0.32551 0.0204701 0.0678986 -0.293464 -0.020494 0.0729019 -0.293402 -0.0145026 0.0679 -0.292681 -0.0145192 0.0728962 -0.325509 -0.0145266 0.0678987 -0.29252 -0.0204734 0.0678987 -0.24838 -0.0204957 0.0729002 -0.249229 -0.0145013 0.0729 -0.280718 -0.0145797 0.0679955 -0.249099 -0.0145008 0.0679 -0.27893 -0.0204992 0.0679 -0.246666 -0.0204036 0.0679635 -0.249099 0.0145008 0.0729 -0.248414 0.0204945 0.0728998 -0.27893 0.0145008 0.0679 -0.279649 0.0204957 0.0729003 -0.249099 0.0204992 0.0679 -0.247312 0.0145797 0.0679719 -0.281363 0.0204036 0.0679516 -0.169 -0.0225 0.0499 -0.173947 -0.0224972 0.0623664 -0.167557 0.0153009 0.0461173 -0.168996 0.0224955 0.0435724 -0.173035 0.0224937 0.061554 -0.180507 0.0129966 0.0647505 -0.169 0.0174988 0.040552 -0.164 0.0174888 0.0420834 -0.163996 0.0174864 0.00918761 -0.163996 0.002114 0.00679856 -0.164 -0.0174279 0.00702128 -0.169003 -0.017492 0.0419673 -0.164 -0.0175156 0.0437154 -0.164001 0.0139876 0.0640988 -0.172581 0.0174565 0.0602999 -0.167926 -0.0169553 0.0487265 -0.164 -0.0173022 0.0614275 -0.333881 0.0168752 0.0729418 -0.333 -0.0115 0.0673019 -0.333 -0.01 0.0669 -0.333 0.013 0.0699 -0.335871 0.0126122 0.0684124 -0.336615 0.0222121 0.0669034 -0.285397 0.015 -0.0630976 -0.199339 -0.0065714 0.0645603 -0.200299 0.00546771 0.0635995 -0.199 -0.00777784 0.0649 -0.169004 0.00721012 0.00689796 -0.209002 0.005 0.0549001 -0.345999 -0.0170013 0.0512635 -0.337439 -0.00629957 0.063581 -0.331 -0.005 0.0619 -0.340656 0.0150341 0.0616809 -0.350961 0.00877201 0.0516604 -0.344134 0.0223966 0.0573186 -0.331528 0.0170377 0.0649012 -0.331 0.008 0.0649 -0.331 0.00540192 0.0634 -0.335692 0.00641386 0.0644255 -0.343574 0.00516227 0.0575206 -0.201863 0.00499986 0.062037 -0.347968 -0.0189954 0.00527018 -0.353997 -0.0189596 0.00329512 -0.347914 0.0189747 0.00522556 -0.346 0.0170024 0.0515083 -0.344238 -0.0224427 0.0571866 -0.354003 -0.0230517 0.0625634 -0.348032 -0.0193044 0.0535048 -0.354 -0.0190053 0.0527446 -0.354 0.0190023 0.0526078 -0.347998 0.0190015 0.0531238 -0.353998 -0.0127809 0.023973 -0.348 0.0128904 0.0457781 -0.348 -0.0127963 0.045822 -0.354 -0.0129073 0.0456329 -0.348 -0.012879 0.0240369 -0.348 0.0127674 0.0239729 -0.354 0.0129579 0.0437759 -0.169 -0.015 -0.0550997 -0.170586 -0.00587868 -0.0542213 -0.16901 -0.00688509 0.00689773 -0.171464 -0.00500197 0.00443599 -0.16904 0.015 -0.0550996 -0.169004 0.00719436 -0.0550858 -0.337183 -0.0203486 0.0670595 -0.353999 0.0223482 0.0668917 -0.211704 -0.0119725 -0.0631015 -0.21608 -0.00930931 -0.0630996 0.16856 0.080186 -0.0864696 0.161779 -0.0859997 -0.0831 -0.143764 0.00197991 -0.0905999 -0.158 -0.0777499 -0.0888041 -0.158 0.0825832 -0.087743 0.158 -0.0780364 -0.0855987 0.158 0.0826498 -0.0873559 0.158 0.0782928 -0.0858925 0.07298 0.1286 -0.0860587 -0.150956 -0.108225 -0.113502 0.139069 -0.104536 -0.113502 0.145036 -0.0985686 -0.0966 0.144207 -0.0989751 -0.113502 0.140406 0.10342 -0.0967057 0.161779 -0.1286 -0.0906 0.161779 0.0964422 -0.108587 0.161779 0.090607 -0.103714 0.161779 0.0755596 -0.0928627 0.161779 0.0740003 -0.0831 0.161779 -0.090607 -0.103714 0.161782 -0.0866997 -0.0928464 -0.161779 0.133686 -0.0933502 -0.161779 -0.130434 -0.0905999 -0.161779 0.090607 -0.103714 -0.161782 -0.0864308 -0.0930913 -0.161779 -0.0759741 -0.0936541 -0.161779 0.0759932 -0.0936704 -0.15266 0.00224274 -0.111106 -0.157027 -0.0103633 -0.106865 -0.157027 0.0103633 -0.106865 -0.151187 0.0119887 -0.110738 -0.140377 -0.0124959 -0.110738 -0.151187 -0.0119887 -0.110738 -0.155011 -0.00855092 -0.110738 -0.140377 0.0942048 -0.110738 -0.140477 0.00485721 -0.110754 -0.137171 0.000858654 -0.111313 -0.1275 0.0905 -0.103505 -0.134176 0.0101811 -0.107255 -0.134176 -0.0101811 -0.107255 -0.161779 -0.090607 -0.103714 -0.151187 -0.0942048 -0.110738 -0.140377 -0.0942048 -0.110738 -0.161779 -0.096489 -0.108586 -0.112551 -0.0956199 -0.113502 -0.149194 -0.0956199 -0.113502 -0.157634 -0.127947 -0.111463 -0.161779 -0.128856 -0.108595 -0.154687 -0.118493 -0.113502 -0.154687 -0.0991317 -0.113502 -0.151187 0.0942048 -0.110738 -0.161779 0.0962223 -0.108571 -0.143607 0.110864 -0.113502 -0.150838 0.108617 -0.113502 -0.154687 0.0991317 -0.113502 -0.149194 0.0956199 -0.113502 -0.112551 0.0956199 -0.113502 -0.144207 0.0989751 -0.113502 -0.154687 0.118493 -0.113502 -0.112551 0.118493 -0.113502 -0.118326 0.127947 -0.111463 -0.161779 0.128856 -0.108595 -0.157634 0.127947 -0.111463 -0.111244 0.129267 -0.107297 -0.0970103 0.124125 -0.102949 0.112239 0.130434 -0.0906 0.161779 0.130434 -0.0905999 0.121241 0.133686 -0.0933502 0.161779 0.133686 -0.0933502 0.161779 0.128856 -0.108595 0.140377 0.0942048 -0.110738 0.0922309 0.0905 -0.103505 0.151187 -0.0942048 -0.110738 0.157027 0.0103633 -0.106865 0.151187 0.0942048 -0.110738 0.151187 0.0119887 -0.110738 0.157027 -0.0103633 -0.106865 0.140377 0.0124959 -0.110738 0.140377 -0.0124959 -0.110738 0.151187 -0.0119887 -0.110738 0.153391 -0.0014483 -0.111532 0.137439 0.000415654 -0.111323 0.155011 0.00855092 -0.110738 0.144281 0.00669493 -0.110738 0.140377 -0.0942048 -0.110738 0.1275 0.0905 -0.103505 0.134176 0.0101811 -0.107255 0.134176 -0.0101811 -0.107255 0.1275 -0.0905 -0.103505 0.1275 -0.0905 -0.0906 0.0506503 0.104923 -0.0906 0.0459896 0.105539 -0.0906 -0.0470212 0.106479 -0.0906 -0.1275 -0.0905 -0.0906 0.0463738 -0.10302 -0.0906 0.0508325 -0.104375 -0.0906 -0.147214 -0.000583272 -0.0906 -0.146007 -0.105298 -0.0906009 -0.143 0.105 -0.0906 0.1275 0.0905 -0.0906 -0.0491197 0.103398 -0.0906 0.145935 0.00200195 -0.0906 -0.158 -0.125 -0.0906 -0.0753795 -0.125 -0.0875023 0.075 -0.125 -0.0841 0.158 -0.125 -0.0906 -0.158 0.123 -0.0831 0.161779 -0.0739997 -0.0831 0.168784 -0.0801628 -0.0867035 -0.161779 0.0740003 -0.0831 -0.161779 0.1286 -0.0831 -0.156 0.125 -0.0831 0.161779 0.1286 -0.0831 0.112239 -0.130434 -0.0906 0.161779 -0.130434 -0.0905999 0.157634 -0.127947 -0.111463 0.161779 -0.133686 -0.0933502 0.118326 -0.127947 -0.111463 0.161779 -0.128856 -0.108595 0.161779 -0.0963201 -0.108571 0.149194 -0.0956199 -0.113502 0.112551 -0.0956199 -0.113502 0.112551 -0.118493 -0.113502 0.154687 -0.118493 -0.113502 0.151486 -0.101874 -0.11525 0.101117 -0.118493 -0.107877 -0.101117 -0.0956199 -0.107877 -0.0426359 -0.106893 -0.107877 0.0431622 -0.101383 -0.107877 0.101117 -0.0956199 -0.107877 -0.0433038 -0.102 -0.107877 0.0485 -0.099 -0.107877 -0.0922309 -0.0905 -0.103505 -0.101117 -0.118493 -0.107877 -0.112551 -0.118493 -0.113502 -0.118326 -0.127947 -0.111463 -0.111244 -0.129267 -0.107297 -0.121241 -0.133686 -0.0933502 -0.161779 -0.133686 -0.0933502 -0.0970103 -0.124125 -0.102949 -0.112239 -0.130434 -0.0906 0.121241 -0.133686 -0.0933502 0.111244 -0.129267 -0.107297 0.0970103 -0.124125 -0.102949 -0.0530713 -0.109132 -0.107877 -0.0545587 -0.107044 -0.0965969 -0.0472072 -0.111025 -0.107877 -0.0466072 -0.0991359 -0.107877 -0.0538378 -0.101383 -0.107877 0.0433115 -0.100597 -0.0966 0.0543017 -0.102186 -0.107877 0.0526321 -0.109571 -0.107877 0.0448825 -0.110338 -0.107877 0.0456861 -0.110802 -0.0966 0.0922309 -0.0905 -0.103505 -0.1275 -0.0905 -0.103505 -0.1275 0.0905 -0.0906 0.112551 0.0956199 -0.113502 0.149194 0.0956199 -0.113502 0.140929 0.100868 -0.113502 0.154687 0.0991317 -0.113502 0.150692 0.108652 -0.113502 0.118326 0.127947 -0.111463 0.157634 0.127947 -0.111463 0.154687 0.118493 -0.113502 0.112551 0.118493 -0.113502 0.0970103 0.124125 -0.102949 0.111244 0.129267 -0.107297 -0.101117 0.0956199 -0.107877 0.101117 0.0956199 -0.107877 0.101117 0.118493 -0.107877 -0.101117 0.118493 -0.107877 -0.0526321 0.109571 -0.107877 0.0472072 0.111025 -0.107877 -0.0922309 0.0905 -0.103505 -0.0433038 0.102 -0.107877 -0.0434918 0.100895 -0.0965617 -0.0472072 0.0989751 -0.107877 -0.0543017 0.102186 -0.107877 -0.047 0.110598 -0.107877 -0.0424751 0.106293 -0.107877 0.0530713 0.109132 -0.107877 0.0455528 0.109219 -0.096682 0.0420686 0.105464 -0.107877 0.0454809 0.0985382 -0.0966 0.0466072 0.0991359 -0.107877 0.0538378 0.101383 -0.107877 0.140901 0.109914 -0.113502 0.149066 0.0993038 -0.113502 0.151592 0.106782 -0.0966 0.142806 0.111146 -0.0966 0.150838 -0.108617 -0.113502 0.143607 -0.110864 -0.113502 0.139093 -0.107292 -0.0966 -0.112239 0.130434 -0.0906 -0.161779 0.130434 -0.0905999 -0.121241 0.133686 -0.0933502 0.157999 0.124999 -0.0831 0.0741462 0.125 -0.0844962 0.157999 0.124999 -0.0906 -0.157998 0.125 -0.0906 -0.0764262 0.125 -0.0876425 -0.157507 0.124414 -0.0832655 -0.158 -0.0801335 -0.0902252 -0.158 -0.0794672 -0.0849849 -0.158 0.0783501 -0.0893921 -0.157999 -0.124999 -0.0831 0.157999 -0.125 -0.0831 -0.149117 0.0053378 -0.0966 -0.145964 -0.00643142 -0.110738 -0.145036 -0.00643142 -0.0966 -0.139069 0.104536 -0.113502 -0.150071 0.100868 -0.113502 -0.148418 -0.0990375 -0.113502 -0.141097 -0.110188 -0.113502 -0.140929 -0.100868 -0.113502 0.146719 -0.00669493 -0.110738 0.149117 -0.0053378 -0.0966 0.139698 0.00281395 -0.0966 0.161779 -0.1286 -0.0831 -0.161779 -0.1286 -0.0831 -0.0735212 -0.1286 -0.0851212 0.0735631 -0.1286 -0.08761 -0.161779 -0.1286 -0.0906 0.074375 -0.1286 -0.0842675 -0.07702 -0.1286 -0.0871413 -0.161779 0.1286 -0.0906 0.07702 0.1286 -0.0871413 0.161779 0.1286 -0.0906 -0.0735212 0.1286 -0.0880788 -0.0770271 0.1286 -0.0859601 0.0751492 0.125 -0.0872817 -0.07298 0.125 -0.0860587 0.0771186 -0.125 -0.0860517 0.0770271 -0.1286 -0.0859601 0.0742113 -0.125 -0.0881967 -0.0738337 -0.125 -0.0850375 0.158 0.0781135 -0.0897757 0.158 -0.0824329 -0.086328 0.158002 -0.080685 -0.090516 -0.158 0.07843 -0.0849409 -0.158 -0.0826548 -0.0871443 -0.152131 -0.104957 -0.0966 -0.145135 -0.0986857 -0.0966 -0.140457 -0.103369 -0.0965498 -0.143208 -0.111408 -0.0966 -0.0489639 -0.0985686 -0.0966 -0.04325 -0.104056 -0.0965986 -0.0448825 -0.110338 -0.0966 0.0526321 -0.100429 -0.0966 0.0531538 -0.107198 -0.0966721 0.147393 -0.110864 -0.0966 0.151275 -0.104523 -0.096572 0.14262 -0.00459332 -0.0962924 0.149742 0.00506694 -0.0965618 0.147011 0.098454 -0.0966 0.0549075 0.107292 -0.0966 -0.0535663 0.102459 -0.0965876 -0.0521175 0.110338 -0.0966 -0.0443679 0.109571 -0.0966 -0.145036 0.0985686 -0.0966 -0.151931 0.104536 -0.0966 -0.147393 0.110864 -0.0966 -0.141368 0.109571 -0.0966 -0.140196 0.104256 -0.0965326 -0.151364 -0.00189284 -0.0966 -0.141368 0.00457128 -0.0966 -0.14056 -0.000697563 -0.0965847 -0.147138 0.10478 -0.0906 0.0480366 0.102436 -0.0905999 0.146189 0.105037 -0.0906002 0.143862 -0.10522 -0.0906 0.148041 -0.106104 -0.0905987 0.0483353 -0.107972 -0.0906 -0.0478 -0.104416 -0.0906 -0.16844 -0.0800056 -0.0865216 -0.168379 0.0800243 -0.0864159 -0.161779 -0.074001 -0.0831 -0.161779 0.085999 -0.0831 -0.161782 0.0878133 -0.091773 0.161779 -0.0759735 -0.0936532 0.161779 0.085885 -0.0830999 0.161781 0.0865707 -0.0930171 0.409907 0.026618 -0.0473916 0.430191 -0.00898139 -0.0278093 0.398225 -0.00703419 -0.0671509 0.433272 0.01007 -0.0330633 0.426002 0.0194919 -0.0402397 0.407411 0.0201071 -0.0590695 0.397355 -0.0159636 -0.0595287 0.407967 -0.0233773 -0.057585 0.430406 -0.0171091 -0.0362035 0.421059 -0.0249481 -0.0449812 0.41149 -0.0210102 -0.0553597 0.402828 -0.0120073 -0.0633152 0.40033 0.00267103 -0.0653991 0.416426 0.0245003 -0.0495593 0.433635 -0.00204598 -0.0333179 0.410597 -0.00103049 -0.0719261 0.413224 -0.0144683 -0.0671769 0.436949 -0.0099738 -0.0477469 0.426193 -0.00957136 -0.0680216 0.438396 -0.000782086 -0.0580082 0.429449 -0.0162254 -0.0407945 0.4298 -0.0177683 -0.0540497 0.420095 -0.0224463 -0.0469744 0.421045 -0.0189356 -0.061493 0.431837 0.00809463 -0.0354034 0.434845 0.0126818 -0.0469212 0.410551 0.00326483 -0.0717714 0.424508 0.0211766 -0.0550341 0.421257 0.0124618 -0.0684697 0.425192 -2.29558e-05 -0.070406 0.438385 0.00203149 -0.0437856 0.434028 -0.00749809 -0.0618731 0.432431 0.0107308 -0.0625145 0.425034 0.0188111 -0.0327831 0.414753 -0.0264855 -0.0427994 0.394277 0.00883434 -0.0625692 0.444319 0.0215239 0.0571468 0.451934 0.0202833 0.0267195 0.445549 0.0256433 0.0431268 0.443342 0.00572524 0.0685002 0.445681 -0.025423 0.0416359 0.453488 -0.0119604 0.02344 0.451526 0.024021 0.0464064 0.449979 0.0185345 0.0618451 0.450946 -0.0249356 0.0499092 0.449284 -0.0106407 0.0667349 0.450307 0.0125515 0.0624621 0.451189 -0.0184421 0.056492 0.449504 0.000714441 0.0687627 0.452641 -0.0223983 0.0335419 0.453956 -0.000638331 0.0178052 0.453486 0.0183634 0.0296885 0.452441 -0.000232335 0.0660776 0.458507 -0.000676584 0.0216889 0.461276 -0.0120219 0.0607116 0.466222 -0.00894774 0.0284334 0.470673 -0.0140368 0.044034 0.462061 -0.0181216 0.0527675 0.459921 -0.0190544 0.034435 0.461257 0.0202938 0.0382983 0.463134 0.0153016 0.0564056 0.466767 0.0171471 0.045581 0.464117 0.0037891 0.0624608 0.46839 0.0078972 0.0291961 0.473359 -4.62303e-05 0.0355374 0.471586 -0.000279308 0.0553738 0.472559 0.0081375 0.0472544 0.447769 0.00715566 0.0176807 0.444014 -0.019264 0.0606918 0.447416 -0.0163921 0.0224549 0.414345 0.03605 0.0666001 0.44334 -0.035561 0.0689112 0.465983 -0.0257361 0.0627794 0.447836 -0.0356559 0.0168303 0.467725 -0.0281133 0.0248271 0.476364 0.0219985 0.0669756 0.486557 0.00792565 0.0357337 0.485256 0.010989 0.051687 0.409689 0.0390036 0.0749599 0.410212 -0.0333247 0.0695082 0.416925 0.0408664 0.0206564 0.447362 -0.0423785 0.0121861 0.48636 -0.00170897 0.0493699 0.447874 0.0355687 0.0168793 0.478524 6.73117e-05 0.0491264 0.442912 0.0326424 0.0719831 0.478144 0.0106106 0.0400058 0.486052 -0.0115915 0.0407936 0.4787 -1.31204e-05 0.0334958 0.419407 -0.0421384 0.00992288 0.416714 -0.0406444 0.0197527 0.486832 0.00162871 0.0438729 0.478864 -0.000655794 0.041591 0.412083 -0.0463897 0.0635482 0.412615 0.0404785 0.0599848 0.410176 0.0332176 0.0695912 0.464752 0.0279984 0.0644553 0.477099 0.0254718 0.062755 0.469131 -0.0198803 0.0639312 0.465548 -0.0336441 0.0137471 0.4781 -0.0105836 0.0399772 0.41904 0.0359272 0.0141557 0.416227 0.042531 0.00927616 0.463958 0.0343975 0.0129466 0.443333 0.034136 0.0700136 0.452142 0.04 0.0143917 0.443212 0.0400673 0.0719148 0.448312 0.0341879 0.0682738 0.448964 -0.034 0.0162888 0.448227 -0.0342238 0.0682374 0.448222 0.0397638 0.0141142 0.444293 -0.034 0.0696837 0.448207 -0.0397885 0.0140813 0.452998 -0.0397835 0.0145951 0.415946 -0.0463025 0.0155348 0.412656 -0.0403412 0.0597525 0.413788 0.0466804 0.063874 0.416464 0.0443175 0.0157311 0.476864 0.0115568 0.0519381 0.478318 0.00785321 0.036532 0.453053 0.0389956 0.0154573 0.448263 -0.039 0.0701978 0.416174 -0.0392324 0.00524116 0.415108 -0.039004 0.0755442 0.410389 -0.0424621 0.0707798 0.414273 -0.0378511 0.0678571 0.443161 -0.0390007 0.0711435 0.419034 -0.0359271 0.0141515 0.452728 -0.0341123 0.0182872 0.477116 -0.0113711 0.0519666 0.472669 0.0196599 0.0264898 0.451448 0.0329378 0.0138357 0.446473 -0.033031 0.0133053 0.465079 -0.0266904 0.0201287 0.47865 -0.00807946 0.0363806 0.41535 -0.0332165 0.0104544 0.449477 0.0339364 0.0161956 0.452819 0.0348308 0.0180409 0.472494 0.022769 0.0295519 0.439992 0.0358574 0.0687989 0.462109 0.0261654 0.0684231 0.476616 0.00877557 0.0563275 0.476725 -0.00783309 0.0548368 0.446153 -0.0329102 0.0724937 0.45917 0.0338923 0.0752892 0.44046 0.0388712 0.0777128 0.484837 0.00813909 0.0566609 0.484937 -0.0086166 0.0568972 0.467748 -0.0294432 0.0719072 0.444786 -0.0386035 0.0778993 0.438801 -0.0421405 0.0737315 0.447138 -0.0400197 0.0726549 0.485182 -0.0109664 0.0516799 0.477951 -0.0243787 0.0619269 0.462451 -0.0362068 0.0701644 0.480107 -0.0254489 0.0288255 0.465853 -0.0366586 0.0184573 0.445671 -0.0389253 0.0076559 0.486871 -0.00776325 0.0366454 0.481832 -0.0192838 0.0267773 0.481279 0.0213148 0.0250477 0.415089 0.0335927 0.0100162 0.44427 0.0389519 0.00748768 0.446545 0.0421104 0.011681 0.461121 0.0386016 0.016477 0.478553 0.0279185 0.0267176 0.486131 0.0111541 0.0409944 0.458924 0.0377622 0.0712108 0.448175 0.0387127 0.0712913 0.444401 0.0416044 0.0739458 0.414059 0.0424902 0.0710809 0.372799 0.0457152 -0.0383233 0.373088 -0.0471024 -0.0383162 0.432176 -0.034 -0.0273834 0.430932 -0.0355734 -0.0271455 0.433396 -0.0341744 -0.0311645 0.394815 -0.0338996 -0.0654572 0.436198 0.0388657 -0.0196665 0.420927 0.0212145 -0.0842653 0.447326 -0.0244236 -0.0583656 0.443732 -0.0367018 -0.0403596 0.414637 0.0389309 0.00250086 0.384746 0.0389179 -0.0673656 0.364484 -0.0390694 -0.0461198 0.364297 0.0389031 -0.0460842 0.385899 -0.0388582 -0.0684868 0.377309 0.0400851 -0.0376859 0.393424 0.0355703 -0.0633668 0.438323 0.0307063 -0.0406261 0.432176 0.034 -0.0273834 0.441888 0.00884678 -0.061169 0.437546 0.00160518 -0.0669913 0.427897 0.00781809 -0.074711 0.425689 -0.000587188 -0.077082 0.429956 0.011746 -0.0726049 0.410991 0.0359275 -0.00613368 0.439997 -0.00334745 -0.0756375 0.433005 -0.00151527 -0.0712725 0.441576 0.00337918 -0.0740957 0.405195 -0.0406746 -0.00764892 0.406161 0.0401392 -0.00804556 0.370026 -0.0421538 -0.0455913 0.369956 0.0422357 -0.0456395 0.443242 -0.0247748 -0.0446209 0.414086 -0.0423079 -0.00308713 0.417979 -0.0185159 -0.076897 0.373131 0.0359262 -0.0427022 0.43329 0.00738267 -0.0808949 0.430985 0.0356481 -0.0270906 0.393363 -0.0356442 -0.0634218 0.39362 0.034 -0.0646164 0.435504 0.0397872 -0.0295486 0.39159 -0.0397856 -0.0653613 0.375562 -0.0401085 -0.036724 0.405697 -0.0474482 -0.00568869 0.406654 0.0472308 -0.00617684 0.439988 0.0130609 -0.0628375 0.433639 0.0342073 -0.0314343 0.394898 0.039868 -0.0688518 0.433217 0.0400004 -0.0252759 0.394816 -0.0398762 -0.0688268 0.397379 -0.0349976 -0.0665471 0.436374 -0.0397537 -0.0288396 0.410615 -0.0332231 -0.000942563 0.433083 -0.0398764 -0.0252312 0.373122 -0.0359274 -0.0427009 0.41233 -0.0275223 -0.0734581 0.43007 -0.0113057 -0.0728411 0.441238 -0.0226962 -0.0529232 0.440349 -0.00996288 -0.0623969 0.36793 0.0332265 -0.0421596 0.410281 0.0247755 -0.0761513 0.388137 0.0331563 -0.0630057 0.427851 -0.00778399 -0.0747668 0.367936 -0.0332159 -0.0421544 0.421427 0.0202295 -0.0743617 0.397597 0.034084 -0.0659815 0.410618 0.0332229 -0.000936637 0.442125 0.025953 -0.0419945 0.431889 0.0330988 -0.0230789 0.430721 -0.0331592 -0.0218058 0.449894 0.0293314 -0.0449658 0.447648 0.00807396 -0.0670297 0.447479 -0.00808268 -0.0670804 0.450218 -0.0236225 -0.0519442 0.445973 -0.0341011 -0.0360292 0.435896 -0.0388586 -0.0193345 0.414717 -0.0389638 0.00258597 0.433376 -0.0420963 -0.0222477 0.444116 -0.0117288 -0.0700172 0.436348 -0.0108834 -0.0778307 0.402473 -0.0383461 -0.0747973 0.423578 -0.0247053 -0.0806661 0.387224 -0.0423971 -0.0637053 0.406888 -0.0314034 -0.0812809 0.393336 -0.0327749 -0.0679676 0.432789 -0.0086407 -0.0817741 0.431256 -0.00021952 -0.0827897 0.400719 0.0342047 -0.0784473 0.39119 0.0402631 -0.065585 0.435868 0.0118381 -0.0784794 0.415629 0.030793 -0.0799079 0.392866 0.0420743 -0.0690613 0.407325 0.030123 -0.0713363 0.443953 0.0108736 -0.0706093 0.447692 0.0287129 -0.053808 0.436682 0.04202 -0.026499 0.414227 0.0424716 -0.00300835 0.392845 0.0348404 0.1353 0.386909 0.0364015 0.135095 0.383134 0.0342326 0.093852 0.384783 0.0292642 0.0961054 0.388497 0.0273598 0.0952592 0.392342 0.0287753 0.133913 0.385443 0.0281923 0.135104 0.386129 0.0360515 0.0951455 0.393287 0.0293939 0.0967248 0.391793 0.0312522 0.0854199 0.39062 0.0291784 0.0753833 0.383365 0.0312231 0.0768794 0.39097 0.0371218 0.0766961 0.388762 0.0248268 0.0778605 0.395599 0.0297874 0.0760637 0.392959 0.03525 0.0978839 0.387155 0.0385321 0.0764091 0.438219 0.0509206 0.0471484 0.435503 0.057715 0.0524701 0.433434 -0.000519621 -0.0288387 0.426152 -0.0183513 -0.032885 0.41405 -0.026654 -0.0475602 0.400762 -0.0185606 -0.0603927 0.448825 0.0268699 0.0400261 0.446471 -0.0111955 0.0668895 0.447969 -0.0259061 0.0488714 0.450791 -0.00680642 0.0175653 0.416992 0.046514 0.0617561 0.353993 -0.0895644 -0.00979825 0.353993 0.0791467 -0.0135394 0.363993 0.082579 -0.0142255 0.38452 -0.0369522 0.0838936 0.394617 -0.0367701 0.0838936 0.395523 -0.0305995 0.0738936 0.393436 -0.0275604 0.0838936 0.385948 0.0257148 0.0838936 0.390317 0.0247472 0.0738936 0.389499 0.0389674 0.0738936 0.437488 0.0606145 0.0235856 0.438111 0.0713659 0.0254729 0.438335 0.0784807 0.0356882 0.438373 0.0721817 0.0511436 0.433179 0.0486227 0.0351376 0.437927 0.0474205 0.0205587 0.414739 0.0509138 -0.0357212 0.432035 0.0182107 -0.0301917 0.437661 0.0509142 0.0241589 0.441995 0.0320146 0.012514 0.442827 0.0392042 0.0234814 0.399501 -0.0325645 -0.0116692 0.394672 -0.0325523 -0.0163326 0.40527 -0.0810995 -0.0061055 0.363994 -0.0865642 0.00893519 0.363993 -0.0859267 -0.0118527 0.363993 -0.0773855 -0.0128324 0.363993 -0.0931665 -0.00261293 0.353993 -0.0623806 -0.00610628 0.413403 -0.0464276 0.0326249 0.424639 0.028569 -0.0121459 0.415481 0.0392063 0.00377178 0.412606 0.0348999 0.000986575 0.432989 0.0485351 0.0645789 0.434736 -0.0465314 0.0633347 0.439416 -0.0399487 0.061075 0.41093 -0.0457839 0.0608764 0.416986 -0.0466827 0.047996 0.432099 -0.0476186 0.0668518 0.414016 0.03257 0.0256228 0.410401 -0.0344059 0.0724241 0.400993 -0.0805 0.0738936 0.416991 -0.0404141 0.00515204 0.436067 -0.0438353 0.0113 0.437014 -0.0485365 0.019534 0.427282 -0.0399829 0.0231151 0.39605 0.0400792 -0.0548562 0.374974 -0.0349053 -0.0534264 0.377514 -0.0396541 -0.0622011 0.363993 -0.0865 -0.00610634 0.400993 0.0775 0.0778936 0.398493 0.0574725 0.0778936 0.388966 -0.0768926 0.0808867 0.400993 -0.0798842 0.07789 0.388489 0.0811389 0.0739606 0.363996 -0.0803139 0.0808936 0.389179 0.059256 0.0808825 0.409607 -0.0802394 0.0809041 0.412065 0.0781243 0.0808933 0.366996 -0.0395326 0.0808936 0.43905 0.0798703 0.0288742 0.38707 0.0509103 -0.0530049 0.375048 0.0406544 -0.0617387 0.386808 0.0319814 -0.0616657 0.396044 -0.0400137 -0.0548839 0.386918 -0.0319173 -0.0616577 0.38707 -0.0509103 -0.0530049 0.436007 -0.0390057 0.00525554 0.422203 -0.0402319 -0.0296404 0.417352 -0.0509103 -0.0295434 0.442193 -0.0317717 0.0127281 0.442729 -0.0401439 0.0243278 0.42955 -0.0389825 0.0784239 0.439577 0.0399369 0.0607801 0.439413 0.0127641 0.0838934 0.432048 0.0673995 0.0177726 0.3905 0.0673052 -0.0486633 0.389444 0.0509171 -0.0486708 0.412589 0.0670264 -0.0335834 0.392533 0.0945085 -0.0102656 0.40324 0.0673884 -0.0433096 0.42627 0.0800814 0.0244023 0.428223 0.0851487 0.0430381 0.411756 0.0848257 0.0743365 0.421871 0.0899864 0.0292489 0.404872 0.0936625 -0.00289315 0.419773 0.0674892 0.0787908 0.425114 0.0878099 0.0482945 0.415093 0.0509111 0.0808357 0.43619 -0.0677474 0.0287534 0.435946 -0.0672716 0.0516806 0.436273 -0.0509103 0.0289506 0.438318 -0.0509209 0.0395403 0.413101 -0.0509136 -0.0322772 0.389444 -0.0509138 -0.0486708 0.353993 -0.0673 -0.0486928 0.390522 -0.0673071 -0.0486625 0.401182 -0.0672955 -0.0444695 0.40661 -0.09337 -0.000393767 0.412222 -0.0672309 -0.0344147 0.419984 -0.0797624 0.00799597 0.438239 -0.0673968 0.0394381 0.411773 -0.0848328 0.0743444 0.419554 -0.0674702 0.0791297 0.414367 -0.0509055 -0.0360694 0.392476 -0.0126446 -0.0683925 0.380401 -0.0129171 -0.0724451 0.380608 0.012729 -0.0725 0.436066 -0.0125893 -0.0263046 0.43584 0.0115102 -0.0265206 0.40338 0.0223483 -0.0578594 0.392555 0.0127925 -0.0683161 0.405325 0.0301823 -0.0559852 0.395041 0.000295876 -0.0659111 0.416755 0.0258984 -0.0449222 0.427509 0.0188478 -0.0345614 0.423109 0.0300789 -0.0388062 0.450627 0.0111441 0.0193929 0.446935 0.0188803 0.0615037 0.449618 0.0301484 0.0308014 0.450954 0.0152647 0.0156385 0.449523 -0.023813 0.0319535 0.447415 -0.0300287 0.0559061 0.446276 0.00379374 0.0690409 0.451182 -0.0124458 0.0130512 0.451188 0.00957766 0.0129303 0.44963 -0.0301277 0.0307726 0.445903 0.0125927 0.073232 0.445913 -0.0118856 0.073236 0.423184 -0.0301106 -0.0387391 0.402386 -0.050908 -0.0474504 0.40531 -0.0301849 -0.0559897 0.447446 0.0300875 0.055664 0.441015 -0.050911 0.0333446 0.403343 0.0509484 -0.0433118 0.401559 0.0509119 -0.0478716 0.413104 0.0509144 -0.0322577 0.353993 -0.0127862 -0.0724844 0.353993 -0.0406573 -0.0617361 0.387228 0.0938971 -0.00498185 0.397112 0.0930837 0.00212112 0.407695 0.0858582 0.06538 0.40125 0.0852282 0.0708972 0.418903 0.0886573 0.040851 0.35459 0.0960456 -0.00293828 0.416301 -0.0892271 0.0358876 0.356288 -0.0978637 -0.00116178 0.412507 -0.0967221 0.0402428 0.404479 -0.0852397 0.0708608 0.392952 -0.0938641 -0.0046156 0.390312 -0.094502 -0.0102873 0.424328 -0.0876305 0.0498628 0.39918 -0.0941894 -0.00747156 0.425472 -0.0891948 0.036233 0.430558 0.0689367 0.0591211 0.353993 0.0848215 0.0744561 0.399819 0.0950882 0.0636089 0.391491 0.0994703 0.000962083 0.355617 0.0928915 0.0652691 0.391512 -0.0994924 0.000653368 0.361829 -0.0995052 0.000442059 0.394018 -0.0950848 0.0636556 0.375453 0.0508435 0.083893 0.376429 0.0509074 0.0808936 0.367004 0.0437628 0.0808942 0.372675 -0.050757 0.0808936 0.420308 -0.0509103 0.0838928 0.375346 -0.0508222 0.0838933 0.369996 0.0395326 0.0838936 0.382711 0.0350484 0.0838936 0.393767 0.0376208 0.0838938 0.420313 0.0509103 0.0838948 0.393436 0.0275604 0.0838936 0.383376 -0.0272299 0.0838936 0.369996 -0.0395326 0.0838936 0.439497 -0.0126279 0.083894 0.41521 -0.050911 0.0808391 0.353993 -0.0509103 -0.0530049 0.403296 -0.0509394 -0.0433358 0.421098 -0.0509106 0.076683 0.435661 -0.0509073 0.0521286 0.439764 -0.0509126 0.0509197 0.432959 0.05165 0.0567606 0.421042 0.0509106 0.0767546 0.360754 0.0950835 0.0636566 0.360158 0.0995023 0.000439717 0.356288 0.0978637 -0.00116178 0.353792 -0.0830387 0.0695922 0.354238 -0.0904964 0.0624583 0.355645 -0.0928648 0.0652889 0.35459 -0.0960456 -0.00293828 0.36162 -0.0950846 0.0636557 0.35883 -0.0990786 2.5229e-05 0.353915 -0.0852272 0.0709063 0.357849 -0.0821387 0.0762248 0.353993 -0.0848215 0.0744561 0.363996 0.0803139 0.0808936 0.414993 0.0825 0.0175085 0.408536 0.0822574 -0.00245626 0.416877 0.0771065 0.00534892 0.416446 -0.0820482 0.0166096 0.408272 -0.0824971 -0.00275535 0.417019 -0.067479 0.0333641 0.373531 0.0864014 -0.00609005 0.374493 -0.079348 0.0776367 0.374411 -0.0829095 -0.00478401 0.374193 -0.0865 0.00748731 0.398493 0.0825 0.0658936 0.404409 0.0824959 0.0738857 0.416976 -0.069916 0.0738536 0.398493 0.0825 -0.00410637 0.398493 0.0864989 -0.0030697 0.398493 0.0865 0.0628936 0.400993 0.0825 0.0658936 0.400993 0.0805 0.0738936 0.402311 -0.0497659 -0.00867317 0.401996 0.0500205 -0.0084658 0.404453 0.0545 -0.00610637 0.353993 0.0526661 -0.00611595 0.417028 0.0498968 0.0456757 0.405265 0.0816679 -0.00610527 0.37451 -0.0819155 0.0756984 0.405958 -0.0824532 0.0728373 0.374455 -0.0862741 -0.00610108 0.376493 -0.0825 -0.00410637 0.400993 -0.0824999 -0.00470056 0.405258 -0.0535067 -0.0061066 0.416833 -0.0770347 0.00531978 0.400993 0.0865 0.0628936 0.400993 0.0864955 -0.00287578 0.398493 -0.0864982 -0.00284216 0.400993 -0.0865 -0.00110637 0.398493 -0.0865 0.0628936 0.400993 -0.0864979 0.0647501 0.416863 0.042325 0.0740719 0.416982 0.0698838 0.0738671 0.376493 -0.0825 0.0718936 0.375471 -0.0813013 0.0741222 0.398493 -0.0825 -0.00410637 0.398493 -0.0825 0.0658936 0.400993 -0.0825 0.0658936 0.374494 0.0794854 0.0774915 0.429433 0.0447865 0.0121477 0.416994 0.0478215 0.0163342 0.416898 0.082478 0.065058 0.400993 0.0825 -0.00410637 0.416995 0.0756149 0.0475452 0.416996 0.0678745 0.0533344 0.417016 0.07703 0.0311101 0.417104 0.0785689 0.039777 0.416996 0.0612741 0.0236353 0.417036 0.0533351 0.027268 0.41698 -0.0824847 0.0649883 0.417012 -0.0478919 0.0160678 0.388493 0.0635 0.0738936 0.376493 -0.0805 0.0738936 0.382029 0.0325026 0.0738936 0.392211 0.0579459 0.0738938 0.388494 -0.0806275 0.0738942 0.395523 0.0334005 0.0738936 0.384044 -0.0364764 0.0738936 0.388821 -0.0589654 0.0738988 0.391047 -0.0256472 0.0738936 0.383214 -0.0280811 0.0738936 0.398493 -0.058714 0.0738936 0.392045 -0.0382852 0.0738936 0.354223 0.0904964 0.0633717 0.374193 0.0775 0.0778936 0.363992 0.0824086 0.0778935 0.36398 0.0866623 0.00840199 0.363992 -0.082408 0.0778935 0.358327 0.0821929 0.0760216 0.374193 -0.0775 0.0778936 0.35391 0.0852277 0.070906 0.354022 0.0829642 0.0695921 0.353993 0.093901 -0.0050338 0.353993 0.0509103 -0.0486928 0.353993 0.0509103 -0.0530049 0.353993 0.0406573 -0.0617361 0.353993 -0.0509103 -0.0486928 0.353993 -0.0773617 -0.0128812 0.353993 0.0945014 -0.0102904 0.353993 0.0905128 -0.00807796 0.353993 0.0929912 0.000470543 0.353993 0.0128383 -0.0724766 0.353985 -0.0938588 -0.00502632 0.353993 -0.0945014 -0.0102904 0.353993 -0.0495228 -0.00703286 0.353993 0.0673 -0.0486928 0.363864 -0.0494974 -0.045284 0.353993 -0.0494967 -0.0453546 0.369934 -0.0830969 0.069978 0.353993 0.0494993 -0.0453547 0.353993 0.0495009 -0.0100343 0.375226 0.0825004 -0.00609774 0.353993 0.0623808 -0.00610637 0.415522 -0.0324369 0.0548584 0.412095 -0.0325663 0.0475678 0.426947 0.0321244 0.0269695 0.427897 -0.0293524 0.00909373 0.433226 0.0245737 0.073699 0.44059 -0.00981794 0.0670037 0.440562 0.00950266 0.0673011 0.441633 0.0262505 0.0422605 0.440885 0.0316194 0.0134568 0.433536 0.0317629 0.0700836 0.44308 -0.0212847 0.0585873 0.43598 -0.0314282 0.0707171 0.446574 -0.0199536 0.0245336 0.441112 -0.027962 0.0112747 0.440761 0.0288738 0.0106705 0.438644 -0.0234125 0.069575 0.424451 -0.0321244 0.0554893 0.440989 -0.0314328 0.0137256 0.435021 -0.0318202 0.0345257 0.443523 0.000661593 0.015922 0.446675 0.0191801 0.0237716 0.43465 -0.0274158 0.0737675 0.419957 -0.0314425 0.0730033 0.443055 0.0211261 0.0590268 0.413962 0.027954 0.0726894 0.43628 0.030558 0.0728458 0.376265 0.0824126 0.0738622 0.374529 0.0822155 0.0751831 0.374496 0.0864421 0.00857577 0.37449 0.0904992 0.0161811 0.363993 0.0905 0.010422 0.374422 0.090497 0.063215 0.374755 0.0831183 0.0697822 0.376493 0.0825 0.0718936 0.374492 -0.0904984 0.014403 0.374492 -0.0904963 0.0632783 0.353993 -0.0905 0.0156294 0.374501 -0.0837864 0.0689465 0.408381 0.0321244 -0.021166 0.375999 -0.0271463 -0.0539864 0.428262 0.00218104 -0.0244653 0.409797 0.0267058 -0.0416105 0.397682 0.018532 -0.0583419 0.386459 0.0316526 -0.0599975 0.40787 -0.0263762 -0.0437395 0.397958 -0.0190122 -0.057966 0.427687 -0.0314953 -0.020325 0.384132 -0.0285921 -0.0617734 0.429366 -0.0281575 -0.018033 0.389966 0.000308015 -0.0606117 0.386642 -0.0315095 -0.0599166 0.384087 0.0267616 -0.0617821 0.376793 0.0318816 -0.0517578 0.42748 -0.0129752 -0.0273573 0.426057 0.0186082 -0.0309445 0.429633 0.0275655 -0.0188778 0.427627 0.03166 -0.020213 0.379047 0.0325846 -0.0314235 0.399518 0.0326153 -0.0116526 0.412699 -0.0350009 0.00106454 0.43694 -0.0317383 0.0721422 0.408846 0.0360324 0.0738197 0.436067 0.0438353 0.0113 0.426417 0.0341192 0.0088898 0.435995 0.0390207 0.00525004 0.41575 -0.0390236 0.00399517 0.415875 0.0380699 0.00435924 0.415582 -0.0345517 0.00770956 0.37732 0.0391733 -0.0616422 0.388607 0.0489664 -0.0533658 0.365634 0.0420038 -0.0450436 0.364034 0.0488812 -0.0453298 0.416987 0.0404243 0.00513996 0.364903 -0.0414259 -0.0452792 0.412441 0.0967542 0.0397758 0.41689 -0.0880439 0.0462427 0.42412 -0.0399964 0.059307 0.436837 0.0318708 0.0722016 0.424103 0.039887 0.0594648 0.414013 -0.0325245 0.0256456 0.385449 0.0400902 -0.0433203 0.373444 0.0488157 -0.0368307 0.385462 -0.0401246 -0.0432999 0.389074 -0.0486881 -0.0533321 0.373366 -0.0488515 -0.0369 0.399344 0.0772387 0.0808399 0.390223 0.0803101 0.0808947 0.399417 0.0587898 0.0808895 0.399516 -0.0759212 0.0807158 0.396898 -0.0569923 0.0808953 0.363993 0.0623808 -0.00610637 0.363993 0.0864999 -0.00610635 0.363993 0.093286 -0.00142093 0.353993 0.0905073 0.0102131 0.363994 -0.090502 0.0118856 0.388234 0.0321243 -0.0406217 0.388234 -0.0321244 -0.0406217 0.37703 -0.0319968 -0.0514481 0.379063 -0.032534 -0.0314058 0.42839 -0.0319408 0.0107845 0.426947 -0.0321244 0.0269695 0.427283 0.0399507 0.0231353 0.428257 0.0321155 0.0119883 0.415582 0.0345534 0.00770781 0.414583 -0.0460957 0.0191666 0.41483 0.0464104 0.0188653 0.410903 0.0465019 0.0612147 0.423139 -0.0320875 0.0705313 0.420681 0.0336359 0.0726981 0.423141 0.0321235 0.0704564 0.424451 0.0321244 0.0554893 0.408627 -0.03887 0.0764925 0.411482 0.0325989 0.0545824 0.416484 -0.0419942 0.0739216 0.416976 -0.0477181 0.0647359 0.416793 0.0469904 0.0339802 0.420877 0.0341583 -0.008235 0.429455 0.0318745 -0.0206184 0.429737 0.0395672 -0.0105811 0.407242 0.0475708 -0.00419628 0.421111 0.0484836 -0.0225473 0.404353 0.0467128 -0.00698542 0.422223 0.0402036 -0.0296203 0.411208 -0.0401671 -0.0184384 0.40422 -0.0463456 -0.00711237 0.424266 -0.0456754 -0.0176037 0.421154 -0.0474796 -0.0236475 0.407018 -0.0478535 -0.00439473 0.429764 -0.0391716 -0.0109932 0.429454 -0.0318969 -0.0205968 0.408381 -0.0321244 -0.0211659 0.419479 -0.0320885 -0.0104587 0.420871 -0.033984 -0.00844556 0.411249 0.0403526 -0.0183939 0.398493 0.0574725 0.0738936 0.398493 -0.0574725 0.0778936 0.413403 -0.0325597 0.032625 0.41209 -0.0465106 0.0476153 0.434021 -0.0318095 0.0494753 0.363993 -0.0624917 -0.00615721 0.383882 -0.0325618 -0.0267525 0.364621 -0.0495169 -0.00681821 0.383847 -0.0494909 -0.0267165 0.384771 -0.0674224 -0.00610644 0.394666 -0.0493366 -0.0163263 0.38482 -0.0511591 -0.0061276 0.399159 -0.0318113 -0.04256 0.409926 -0.0318118 -0.0321416 0.409934 -0.0673995 -0.0321525 0.365847 -0.0674338 -0.00610633 0.399148 -0.0674143 -0.0425419 0.363959 -0.0660505 -0.00611866 0.416993 -0.0669232 0.0479941 0.433978 -0.0674035 0.0494615 0.416992 -0.0474547 0.0329337 0.435285 -0.0673625 0.0345537 0.363572 -0.0376239 -0.0453521 0.36684 -0.0353627 -0.0456347 0.37033 0.0348132 -0.0485034 0.362268 0.0387949 -0.0453432 0.438333 0.0635019 0.0535618 0.439008 0.0638839 0.0574509 0.438324 0.0773646 0.0442951 0.439034 0.0750096 0.0535576 0.439227 0.0676723 0.0198161 0.439153 0.0821966 0.0427905 0.439132 0.0546048 0.0258246 0.438965 0.0507702 0.0526503 0.44353 0.0450432 0.0333385 0.43924 0.0457706 0.0434166 0.433241 0.0509103 0.0209374 0.407998 -0.0411278 0.0738941 0.429294 0.0391933 0.0786533 0.405105 0.0403704 0.0738946 0.389132 -0.0270655 0.134234 0.393532 -0.0308475 0.13484 0.394684 -0.0345134 0.0906855 0.385045 -0.0345274 0.095401 0.39114 -0.036693 0.0976304 0.386094 -0.0358216 0.13538 0.391448 -0.0359479 0.133962 0.384551 -0.0306077 0.135438 0.385753 -0.0281566 0.0952825 0.384342 -0.0357482 0.0925645 0.386192 -0.0320757 0.085479 0.389121 -0.0260709 0.0763452 0.383049 -0.02903 0.0781556 0.395006 -0.0318889 0.076319 0.38368 -0.0350199 0.0755471 0.390655 -0.0388246 0.0753902 0.389549 -0.0258855 0.0919293 0.39359 -0.0295196 0.0944417 0.399742 -0.061139 0.0886606 0.399556 -0.0645049 0.0781182 0.39797 -0.0669113 0.0900551 0.270128 -0.0632081 0.0920809 0.281816 -0.0663403 0.0970663 0.282849 -0.0630454 0.0895123 0.304652 -0.0597041 0.12998 0.313162 -0.0552702 0.130234 0.308172 -0.0657754 0.131922 0.422073 -0.0368989 0.120371 0.421957 -0.0369933 0.122271 0.429478 -0.031061 0.119295 0.441228 -0.0329966 0.122783 0.426995 -0.0417419 0.126645 0.429546 -0.0435369 0.126168 0.392541 0.0583267 0.0880913 0.407626 -0.0515705 0.121562 0.390093 -0.0687986 0.0785857 0.311198 -0.0679177 0.123902 0.2846 -0.0718661 0.0989136 0.282597 0.0752342 0.0897619 0.291687 0.0707058 0.0901833 0.311578 0.0576146 0.122114 0.318677 0.0561726 0.124222 0.314334 0.0659403 0.12531 0.313958 0.067197 0.129 0.429569 0.0303453 0.119886 0.425956 0.0413097 0.114339 0.431483 0.0456591 0.116692 0.438853 0.034343 0.114795 0.434947 0.0308705 0.113981 0.433044 -0.0307674 0.114469 0.31924 -0.0554732 0.132277 0.426277 -0.0386776 0.125354 0.320014 -0.0595981 0.134504 0.320452 -0.0615335 0.134389 0.317463 -0.0643947 0.13347 0.428952 -0.0473253 0.123138 0.316803 0.062018 0.134697 0.427071 0.0415078 0.126584 0.426557 0.0386979 0.125384 0.411902 0.0499853 0.118412 0.392785 0.0650466 0.0944804 0.262795 0.0658087 0.0911668 0.250344 0.0636484 0.0880979 0.259424 -0.068761 0.0916714 0.267002 -0.0723658 0.0846397 0.260447 -0.0689405 0.0828955 0.250493 -0.0650578 0.0828938 0.276979 0.0730674 0.0858082 0.403129 0.0444444 0.116468 0.390117 0.0612067 0.0921575 0.411054 0.0442156 0.115512 0.319326 0.0583447 0.122814 0.406907 0.0413187 0.117673 0.401422 0.047665 0.116593 0.314693 0.0631373 0.123087 0.402144 0.0504965 0.118 0.425503 0.0360966 0.121347 0.31848 0.0659322 0.131275 0.428612 0.0476069 0.122825 0.407345 0.0514711 0.121001 0.412216 -0.0497388 0.117792 0.314751 -0.0629 0.123054 0.317268 -0.0662576 0.126305 0.402058 -0.0503291 0.117864 0.407221 -0.0416956 0.117267 0.410545 -0.043541 0.115826 0.423864 -0.0371155 0.118229 0.320656 -0.066102 0.129055 0.430407 0.0303928 0.123244 0.432925 0.0314576 0.125431 0.434383 -0.0310114 0.125954 0.441404 0.0279928 0.118993 0.429538 0.0432812 0.126293 0.440729 0.0329249 0.123286 0.436513 0.0325377 0.126008 0.438045 0.0398634 0.122098 0.308878 0.0559447 0.128738 0.307059 0.0681001 0.127107 0.320014 0.0595981 0.134504 0.31963 0.0575941 0.133987 0.305166 0.0632448 0.13088 0.318841 0.0545015 0.130245 0.319302 0.0554607 0.13227 0.319446 0.0640334 0.133349 0.30687 0.0578696 0.130362 0.290282 0.0646327 0.0905538 0.282923 0.0658953 0.0988054 0.275596 0.0652216 0.095174 0.283763 0.0721302 0.097536 0.283183 0.0629233 0.0895834 0.440853 -0.0324311 0.116656 0.436465 -0.0335638 0.114137 0.431511 0.0307093 0.115538 0.428008 -0.0442285 0.114208 0.43699 -0.0422398 0.12104 0.31759 -0.0562744 0.124289 0.310859 -0.0580959 0.121032 0.318644 -0.0543079 0.128013 0.318939 -0.0584558 0.122826 0.292661 -0.0688615 0.0914692 0.291216 -0.0729065 0.0933533 0.287415 -0.0647382 0.0872162 0.282902 -0.0704912 0.0848323 0.282653 -0.0753995 0.0895458 0.276595 0.0687531 0.0837932 0.399365 -0.0732177 0.0785069 0.390458 -0.0584134 0.0778529 0.389288 -0.0627888 0.0903286 0.393243 -0.0653465 0.0947487 0.393611 -0.05783 0.0876399 0.401636 -0.0463388 0.11632 0.399465 0.0618147 0.0778998 0.391391 0.0580535 0.0778421 0.396677 0.0681471 0.0819616 0.398621 0.0592629 0.0883651 0.396771 0.0671736 0.0918942 0.270012 0.0744226 0.092324 0.269751 -0.074985 0.09203 0.250497 0.0727327 0.0837127 0.250447 -0.0749921 0.0889491 0.250443 0.0750293 0.0890803 0.256739 0.0695635 0.0915769 0.390302 -0.0770941 0.079755 0.389783 0.0685575 0.0784825 0.398021 0.0773262 0.0790428 0.260093 0.0700342 0.0828801 0.267979 0.0730552 0.0828936 0.263048 0.0657615 0.0839784 0.250487 0.0650589 0.0828937 0.267976 -0.0650576 0.0828936 0.250486 -0.0727295 0.0833395 0.250238 -0.0640697 0.0875387 -0.220749 0.0678477 0.0779 -0.181311 -0.0671596 0.0829 -0.359 -0.032 0.0766 -0.360432 -0.0355074 0.0808995 -0.329011 0.015236 0.0809001 -0.28689 -0.0165761 0.0745339 -0.200024 -0.0156227 0.0809 -0.168009 -0.0220835 0.0729 -0.168004 -0.0221287 0.0779 -0.206223 0.0220157 0.0779 -0.260813 0.0695047 0.0779 -0.21815 0.0697231 0.0779 -0.206214 0.118754 0.0779 -0.283977 0.0798119 0.0779 -0.283969 -0.0220078 0.0779 -0.261042 -0.0836341 0.0779 -0.206214 -0.118754 0.0779 -0.219696 -0.0692595 0.0779 -0.260531 -0.0695203 0.0779 -0.221446 -0.0674001 0.0779 -0.289041 0.0806019 0.0729001 -0.349964 0.0806059 0.0779 -0.349978 0.0220187 0.0779 -0.289022 0.0806223 0.0779 -0.164504 -0.13045 0.0809002 -0.359752 -0.0274434 0.0808596 -0.3635 -0.0773069 0.0809 -0.357907 0.0356966 0.0808999 -0.1965 0.021 0.0809 -0.27 0.0620801 0.0809 -0.239715 0.019905 0.0809001 -0.28468 0.0201096 0.0809 -0.1645 -0.0620801 0.0809 -0.240134 -0.013634 0.0809 -0.288366 -0.0195 0.0809 -0.28224 -0.0175797 0.080815 -0.330238 -0.0209094 0.0809 -0.349985 0.0806269 0.0728998 -0.354 0.0849935 0.072901 -0.354 -0.0825585 0.0729 -0.201214 0.027 0.0729 -0.164 0.129 0.0729 -0.168005 0.0221499 0.0729 -0.206214 0.118754 0.0729 -0.173 -0.012 0.0729 -0.164 -0.130995 0.0729 -0.206214 -0.118754 0.0729 -0.283979 -0.0798271 0.0729 -0.260202 -0.0842454 0.0729 -0.289022 -0.0806375 0.0728997 -0.289017 -0.0243688 0.07291 -0.201214 -0.121912 0.0729 -0.206224 -0.0220101 0.0729 -0.2865 -0.0149 0.0729 -0.349589 -0.0119969 0.0729 -0.330221 -0.0173356 0.0728999 -0.2865 0.0149 0.0729 -0.240701 -0.0166793 0.0729001 -0.206216 0.0220171 0.0729 -0.196166 0.0173244 0.0729 -0.195653 -0.0172787 0.0729 -0.164 -0.0731 0.0829 -0.164 0.0731 0.0829 -0.164 0.0649 0.0829 -0.164 -0.129 0.0804 -0.164 -0.0618982 0.0804 -0.203714 0.131 0.073259 -0.269374 -0.0804935 0.0808986 -0.256057 -0.0929688 0.0733096 -0.278739 0.0795476 0.0806868 -0.260518 0.083716 0.0809 -0.252737 0.0890117 0.0806868 -0.256224 0.093194 0.0729051 -0.207136 0.127275 0.0806868 -0.212876 0.129092 0.0728999 -0.194655 -0.0154272 0.0767052 -0.197246 -0.0204785 0.0809 -0.191987 -0.0162901 0.0809002 -0.24066 -0.0172176 0.0771952 -0.24307 -0.0194175 0.0809 -0.332082 -0.0174597 0.0770071 -0.330813 -0.0155325 0.0809 -0.330228 0.016542 0.0729001 -0.287214 0.0169581 0.0754195 -0.2875 0.0132679 0.0809 -0.241789 0.0177383 0.0728993 -0.241466 0.0169242 0.0768281 -0.243627 0.0151722 0.0808997 -0.197241 0.0172283 0.0771832 -0.195488 0.0148783 0.0809 -0.164 0.0731 0.0859 -0.181359 0.0708316 0.0829 -0.221967 0.0702228 0.0828998 -0.268 0.0649 0.0829 -0.268 0.0731 0.0829 -0.265 0.0649 0.0859 -0.1645 0.0620801 0.0809 -0.164 0.0618982 0.0804 -0.164 -0.0649 0.0859 -0.164 -0.0649 0.0829 -0.179051 -0.0701715 0.0829 -0.268 -0.0731 0.0829 -0.260364 -0.0689938 0.0829005 -0.265 -0.0731 0.0859 -0.363999 -0.0815671 0.0779001 -0.354 0.0814979 0.0779 -0.27 -0.0759199 0.0809 -0.268 -0.0649 0.0829 -0.265 -0.0649 0.0859 -0.164 0.0638282 0.0857026 -0.265 0.0731 0.0859 -0.35855 -0.0324253 0.0779 -0.359049 0.0316821 0.0779 -0.357931 0.0293408 0.0808936 -0.278739 0.0847132 0.0733096 -0.267482 0.0866536 0.072894 -0.201846 0.130003 0.0808999 -0.278752 -0.0849952 0.0729022 -0.265927 -0.0872192 0.0728943 -0.27 -0.0620801 0.0809 -0.164 -0.0638282 0.0857026 -0.164 -0.0741718 0.0857026 -0.164 -0.0731 0.0859 -0.265197 -0.0741718 0.0857026 -0.164 0.0649 0.0859 -0.265197 0.0638282 0.0857026 -0.269998 0.0759219 0.0809021 -0.164 0.0741718 0.0857026 -0.168006 -0.126713 0.0729038 -0.349978 -0.0220187 0.0729 -0.34998 -0.0806114 0.0779 -0.289041 -0.0806019 0.0779 -0.345 0.012 0.0729 -0.173 0.012 0.0729 -0.168 0 0.0779 -0.345 0.012 0.0779 -0.345 -0.012 0.0779 -0.212464 0.124226 0.0729002 -0.260205 0.0842445 0.0779 -0.261165 0.0835421 0.0728986 -0.168005 0.126762 0.0779 -0.168008 0.0220655 0.0779 -0.289012 -0.0220076 0.0779 -0.201209 0.126762 0.0729 -0.201209 -0.0221499 0.0729 -0.201206 -0.0220655 0.0779 -0.214428 -0.122584 0.0779 -0.211632 -0.124899 0.072901 -0.168004 -0.126871 0.0779 -0.198876 -0.126883 0.0729014 -0.20121 -0.126779 0.0779 -0.168008 0.126846 0.0728999 -0.201206 0.126846 0.0779 -0.211272 0.125177 0.0778993 -0.283985 0.022008 0.0779 -0.28397 0.0220136 0.0729001 -0.283995 0.0778622 0.0729001 -0.201209 0.0220573 0.0778997 -0.28399 -0.0796474 0.0779 -0.206218 -0.022016 0.0779 -0.283989 -0.0220257 0.0729001 -0.34997 -0.0803027 0.0728996 -0.349959 -0.0220391 0.0779 -0.168112 0.00934869 0.0728999 -0.173 0.012 0.0779 -0.168085 -0.00966741 0.0729001 -0.170399 -0.0119988 0.0778999 -0.349915 -0.0096674 0.077898 -0.349915 0.00966741 0.0729001 -0.349888 0.00934862 0.0779039 -0.349959 0.0220391 0.0729 -0.289012 0.0244232 0.0729118 -0.289017 0.0220217 0.0779 -0.220116 -0.0692725 0.0828999 -0.180046 -0.0690915 0.0779 -0.218088 0.0675955 0.0828999 -0.260788 0.0701256 0.0829011 -0.258912 0.0671267 0.0829001 -0.179622 0.0695348 0.0779 -0.178902 0.0677286 0.0828992 -0.363999 0.0797321 0.0804241 -0.363999 0.0813311 0.0779001 -0.352 -0.0847132 0.0733096 -0.353466 -0.0845143 0.0728993 -0.354 -0.0808909 0.0779 -0.164864 0.130501 0.0729 -0.164006 0.0759199 0.0808999 -0.164016 0.131021 0.0808987 -0.269377 0.0804938 0.0808974 -0.362 0.0791381 0.0809 -0.364 -0.0773069 0.0804 -0.363514 0.0326242 0.0808999 -0.362 -0.0795476 0.0806868 -0.362 -0.0791381 0.0809 -0.278739 -0.0795476 0.0806868 -0.252737 -0.0890117 0.0806868 -0.260516 -0.0837171 0.0809 -0.207136 -0.127275 0.0806868 -0.213216 -0.129267 0.0729085 -0.192482 -0.131013 0.080126 -0.164006 -0.0759199 0.0808999 -0.0204991 0.130375 0.0523572 0.151579 0.153171 0.0572472 0.162322 0.13692 0.055291 0.156 0.149999 0.0524917 0.153243 0.1545 0.0541434 -0.158 0.149999 0.0524917 -0.151788 0.136873 0.0607085 -0.155965 0.150003 0.052274 0.159196 0.137308 0.0102993 0.155461 0.152999 0.0115388 0.156731 0.139849 0.0177816 -0.159693 0.137227 0.0102952 -0.155775 0.152999 0.0114624 -0.155152 0.155825 0.0171082 0.151898 0.136915 0.0112516 0.158 0.149999 0.0198083 -0.158 0.149998 0.019722 -0.156 0.149999 0.0198081 -0.153733 0.153291 0.0187828 -0.151695 0.150605 0.0158515 0.000758205 0.136167 0.0583156 -0.00935224 0.154536 0.0444594 -0.0128491 0.130254 0.0449939 -0.0186003 0.154491 0.0489528 -0.00346471 0.131102 0.0473914 -0.00275075 0.128053 0.0529875 -0.00225449 0.1575 0.0564686 -0.0052252 0.130744 0.0642811 -0.00625 0.1255 0.0492718 0.015 0.152999 0.0069 0.174769 0.149837 0.00689398 0.187215 0.144153 0.0743128 -0.187215 0.144153 0.0743128 -0.159148 0.152087 0.0637053 -0.00225451 0.139426 0.0784452 0.198886 0.134036 0.0805563 -0.198886 0.134036 0.0805563 -0.0182455 0.139426 0.0784452 0.000615426 0.130644 0.0538683 -0.177992 0.131 0.0237811 -0.195275 0.131 0.0740291 -0.202465 0.131 0.0809 0.202465 0.131 0.0809 0.18 0.131 0.0779 -0.191289 0.131 0.0779 -0.160013 0.151907 0.0200026 -0.186163 0.134578 0.0689689 -0.166441 0.1545 0.0554709 -0.157993 0.154498 0.0209764 -0.00045876 0.1545 0.0511226 0.156 0.1545 0.0201028 -0.00292419 0.1545 0.0206561 -0.156 0.1545 0.0201028 0.0755452 0.1545 0.0230112 0.152066 0.1545 0.0554709 -0.151672 0.154479 0.0555085 -0.0623478 0.1545 0.0546485 -0.000976452 0.1545 0.0220067 0.154094 0.153553 0.0190697 0.15801 0.1545 0.0518762 0.163254 0.15199 0.0588349 0.18112 0.141751 0.0725159 0.166441 0.1545 0.0554709 0.153367 0.149132 0.0626476 0.000743369 0.154496 0.055476 0.00075 0.139882 0.0744729 0.000755435 0.137366 0.077807 0.19135 0.131003 0.0781591 0.177992 0.131 0.0237811 0.185448 0.135211 0.0681684 0.17593 0.134909 0.0283257 0.157989 0.15449 0.0208585 -0.135 0.149999 0.015801 0.151339 0.150607 0.0158543 -0.151559 0.145399 0.0154115 -0.135 0.149999 0.0069 -0.005 0.152999 0.0069 -0.199225 0.131 0.0264712 -0.199076 0.129706 0.0260617 0.194958 0.129706 0.0727391 -0.174529 0.151598 0.0127516 -0.179861 0.139776 0.00839605 0.166824 0.140851 0.00687519 -0.167359 0.140767 0.00699188 0.179263 0.13914 0.00946795 0.187417 0.137838 0.0117942 -0.21079 0.130971 0.0735535 -0.186577 0.140045 0.0140928 -0.19206 0.134414 0.066617 -0.207275 0.132715 0.0674724 -0.19731 0.132703 0.0268836 -0.178245 0.150054 0.0148348 -0.18235 0.154742 0.0474274 -0.180442 0.15742 0.0484068 -0.175382 0.154939 0.0195222 -0.20397 0.137263 0.0709625 0.160437 0.153576 0.015144 0.154826 0.155482 0.0167337 -0.154024 0.152999 0.0140233 0.159954 0.151851 0.0196061 0.175424 0.154937 0.0196878 0.178088 0.150255 0.0148934 0.186264 0.140238 0.0140446 0.197322 0.132707 0.0269248 0.192798 0.134351 0.0662975 0.201289 0.138387 0.0693069 0.199221 0.13099 0.0264639 0.207436 0.132721 0.0681742 -0.190553 0.141247 0.0772234 -0.197651 0.142503 0.0684979 -0.194023 0.138263 0.0791251 0.198595 0.141688 0.0695608 0.190968 0.1409 0.0775345 0.194588 0.13774 0.0793192 0.210806 0.131003 0.0736993 0.181709 0.156337 0.049977 0.172891 0.156557 0.0577295 0.178941 0.1575 0.0425895 -0.17321 0.15629 0.0580875 -0.0430913 0.1545 0.0547197 -0.0209798 0.1545 0.0230112 -0.0222292 0.1545 0.0206561 -0.0314823 0.1545 0.021124 -0.0575692 0.1575 0.0537622 -0.0534967 0.1545 0.0526905 -0.038719 0.154499 0.0207365 -0.0515575 0.1545 0.0222265 -0.0121704 0.1545 0.0211144 -0.0355227 0.1545 0.0546284 -0.0237867 0.1545 0.0547197 -0.00208021 0.1575 0.0206571 0.0070985 0.1545 0.0211701 -0.0124784 0.157495 0.0445077 0.0183301 0.1545 0.0220004 0.0163808 0.1545 0.0206561 0.0650493 0.1545 0.0211144 0.0424509 0.1545 0.0535235 0.0541634 0.1545 0.0536738 0.0513437 0.154499 0.0547969 0.0457386 0.1545 0.0211226 0.0340769 0.154499 0.0547875 0.0232641 0.1545 0.0533516 0.0345691 0.1575 0.0547398 0.0568835 0.1545 0.0220854 0.0356857 0.1545 0.0206561 0.0264242 0.1545 0.0211366 0.0369352 0.1545 0.0230112 -0.02125 0.141751 0.0725159 -0.153827 0.149681 0.0619137 -0.0212437 0.15449 0.055484 -0.181255 0.141632 0.0726728 -0.02125 0.139882 0.0744729 -0.02125 0.140944 0.073473 -0.184539 0.138524 0.0761563 0.166634 0.151631 0.0463738 0.167516 0.142163 0.0165499 -0.175929 0.134923 0.0278898 -0.16683 0.142538 0.0166267 -0.162999 0.146452 0.0160553 -0.166801 0.151492 0.0466167 -0.160191 0.153427 0.0147602 0.1655 0.152999 0.0069 0.174416 0.15158 0.0127175 0.154024 0.152999 0.0140233 0.005 0.152999 0.0104 -0.170239 0.152992 0.00690084 0.15156 0.145397 0.0154113 0.155273 0.144383 0.00707107 0.135 0.149999 0.0069 0.135 0.149999 0.015801 -0.002 0.149999 0.0104 -0.154494 0.144608 0.00704763 -0.182929 0.131 0.0237811 -0.187429 0.137852 0.0117922 -0.183487 0.129706 0.0260532 -0.194958 0.129706 0.0727391 -0.210593 0.129706 0.0727391 0.210593 0.129706 0.0727391 0.183487 0.129706 0.0260532 0.199098 0.129706 0.026057 0.182929 0.131 0.0237811 0.152204 0.136902 0.0544127 0.157077 0.136907 0.0644124 -0.161513 0.136909 0.0620672 -0.160628 0.137269 0.0544042 -0.153023 0.136866 0.0539733 0.163159 0.146715 0.0158698 0.154319 0.136875 0.0195167 -0.151877 0.136896 0.0115672 -0.15428 0.136892 0.0195152 -0.160661 0.136887 0.018621 0.160351 0.139951 0.0586595 -0.154442 0.140028 0.0557031 -0.156637 0.14009 0.0166722 -0.0212574 0.137355 0.0778248 -0.18 0.136801 0.0779 -0.18 0.139882 0.0744729 0.18 0.136801 0.0779 0.180005 0.136831 0.0764555 0.18 0.1376 0.0775018 0.183153 0.139857 0.0745125 -0.18 0.131 0.0779 -0.0150074 0.1311 0.0779 -0.18 0.1376 0.0775018 0.00298587 0.157293 0.044675 0.0148504 0.1545 0.0546788 -0.0728017 0.1545 0.0526905 0.0749031 0.1545 0.0206575 -0.158 0.1545 0.0524917 -0.163509 0.152329 0.0583983 0.182219 0.154875 0.0472024 -0.000679027 0.1575 0.0223001 0.0760452 0.1575 0.0230112 0.0619557 0.157499 0.0207847 0.0555479 0.15613 0.0205896 0.0368852 0.1575 0.0206591 0.0426441 0.1575 0.0207934 0.0233921 0.1575 0.0207134 0.0567402 0.1575 0.0230112 0.0470402 0.157495 0.0548325 -0.0210243 0.1575 0.0206591 -0.0410342 0.1575 0.0206561 -0.054885 0.1575 0.0222261 -0.0345503 0.1575 0.0207573 -0.0397848 0.1575 0.0230112 -0.0615784 0.1575 0.0542639 -0.0204798 0.1575 0.0230112 -0.0382642 0.1575 0.0537621 -0.0427592 0.157424 0.0548981 -0.0234085 0.157496 0.0548571 -0.0139384 0.157519 0.04866 -0.0157818 0.157498 0.021523 0.00408895 0.157499 0.0207376 0.0172204 0.1575 0.020657 0.0186283 0.1575 0.0222964 0.00109247 0.1575 0.0526907 0.0152636 0.1575 0.0547421 0.0374352 0.1575 0.0230112 0.019107 0.157499 0.05456 0.00327539 0.154499 0.054336 -0.156069 0.141666 0.0611612 -0.160699 0.157885 0.0587925 -0.170385 0.1575 0.050607 -0.17313 0.1575 0.0189363 0.156071 0.153834 0.0545653 0.15933 0.157511 0.0608242 0.154293 0.157524 0.0614435 0.0397025 0.1575 0.0526907 -0.0042003 0.157443 0.0501192 -0.0761275 0.1575 0.0526907 0.17313 0.1575 0.0189363 0.139871 0.1575 0.0564686 0.0546634 0.1575 0.0536738 -0.139871 0.1575 0.0564686 0.159133 0.152094 0.0636967 0.143645 0.153302 0.0620805 -0.147 0.152069 0.0637301 -0.151868 0.157549 0.0617806 0.156 0.149999 0.0197389 0.156 0.1545 0.0524917 0.157999 0.149998 0.0525614 -0.156 0.1545 0.0524917 0.00075 0.141751 0.0725159 0.00075 0.140944 0.073473 -0.0165747 0.131082 0.0628088 -0.0177544 0.125393 0.053228 -0.0125993 0.128124 0.0481749 -0.0212581 0.136171 0.0585281 -0.00197852 0.13338 0.0779 -0.0185181 0.133373 0.0778998 -0.00549264 0.1311 0.0779 -0.00225451 0.144153 0.0743128 -0.0182455 0.144153 0.0743128 -0.0130693 0.133561 0.0640874 -0.0139718 0.1336 0.0806445 -0.00243091 0.136608 0.0581214 -0.0182853 0.157541 0.0564128 -0.0180254 0.136243 0.0588395 -0.0182474 0.137395 0.0794626 -0.0156153 0.134097 0.0805588 -0.00551787 0.133628 0.0627897 -0.00503129 0.133968 0.0805901 -0.00225393 0.137248 0.0795082 0.015 0.149999 0.0069 -0.005 0.149999 0.0069 0.195275 0.131 0.0740291 0.219696 0.0692595 0.0779 0.221446 0.0674001 0.0779 0.359 0.032 0.0766 0.200024 0.0156227 0.0809 0.168009 0.0220835 0.0729 0.20121 0.126779 0.0779 0.168004 0.126871 0.0779 0.206223 -0.0220157 0.0779 0.220749 -0.0678477 0.0779 0.21815 -0.0697231 0.0779 0.206214 -0.118754 0.0779 0.283977 -0.0798119 0.0779 0.283975 0.0220058 0.0779 0.261042 0.0836341 0.0779 0.206214 0.118754 0.0779 0.206218 0.022016 0.0779 0.349964 -0.0806059 0.0779 0.349978 -0.0220187 0.0779 0.289017 -0.0220217 0.0779 0.289022 -0.0806223 0.0779 0.364 0.0773069 0.0804 0.360432 0.0355074 0.0808995 0.359752 0.0274434 0.0808596 0.363514 -0.0326242 0.0808999 0.362 -0.0791381 0.0809 0.357931 -0.0293408 0.0808936 0.357907 -0.0356966 0.0808999 0.1965 -0.021 0.0809 0.239715 -0.019905 0.0809001 0.287302 -0.0165523 0.0776882 0.284693 -0.0201364 0.0809 0.329011 -0.015236 0.0809001 0.1645 0.0620801 0.0809 0.240134 0.013634 0.0809 0.288366 0.0195 0.0809 0.28224 0.0175797 0.080815 0.332082 0.0174597 0.0770071 0.289041 -0.0806019 0.0729001 0.354 -0.0849935 0.072901 0.349959 -0.0220391 0.0729 0.168005 -0.0221499 0.0729 0.168085 0.00966741 0.0729001 0.173 0.012 0.0729 0.283978 0.0220227 0.0729001 0.211632 0.124899 0.072901 0.195653 0.0172787 0.0729 0.201209 0.0221499 0.0729 0.201214 0.121912 0.0729 0.164 0.130995 0.0729 0.28397 -0.0220136 0.0729001 0.349589 0.0119969 0.0729 0.2865 0.0149 0.0729 0.286425 -0.0169327 0.0729003 0.206224 0.0220101 0.0729 0.241423 0.017331 0.0729003 0.201209 -0.126762 0.0729 0.201214 -0.027 0.0729 0.196166 -0.0173244 0.0729 0.206216 -0.0220171 0.0729 0.164 0.0638282 0.0857026 0.164 -0.0618982 0.0804 0.164 -0.0731 0.0829 0.164 -0.129 0.0729 0.164 0.0649 0.0829 0.203714 -0.131 0.073259 0.260516 0.0837171 0.0809 0.278739 -0.0795476 0.0806868 0.207136 -0.127275 0.0806868 0.212876 -0.129092 0.0728999 0.197246 0.0204785 0.0809 0.194655 0.0154272 0.0767052 0.191987 0.0162901 0.0809002 0.240609 0.0171114 0.0771222 0.24307 0.0194175 0.0809 0.286874 0.0165628 0.0742296 0.330221 0.0173356 0.0728999 0.330238 0.0209094 0.0809 0.330813 0.0155325 0.0809 0.330795 -0.0169573 0.0729006 0.2875 -0.0132679 0.0809 0.241789 -0.0177383 0.0728993 0.241466 -0.0169242 0.0768281 0.243627 -0.0151722 0.0808997 0.197241 -0.0172283 0.0771832 0.195488 -0.0148783 0.0809 0.164006 -0.0759199 0.0808999 0.268 -0.0731 0.0829 0.181359 -0.0708316 0.0829 0.221967 -0.0702228 0.0828998 0.178902 -0.0677286 0.0828992 0.218088 -0.0675955 0.0828999 0.268 -0.0649 0.0829 0.164 -0.0649 0.0829 0.27 -0.0620801 0.0809 0.164 0.0649 0.0859 0.268 0.0649 0.0829 0.181311 0.0671596 0.0829 0.164 0.0731 0.0829 0.179051 0.0701715 0.0829 0.268 0.0731 0.0829 0.265 0.0731 0.0859 0.27 0.0759199 0.0809 0.363999 0.0815671 0.0779001 0.35855 0.0324253 0.0779 0.354 -0.0814979 0.0779 0.27 0.0620801 0.0809 0.265 0.0649 0.0859 0.265 -0.0649 0.0859 0.269998 -0.0759219 0.0809021 0.265 -0.0731 0.0859 0.359049 -0.0316821 0.0779 0.278739 -0.0847132 0.0733096 0.267482 -0.0866536 0.072894 0.201846 -0.130003 0.0808999 0.256224 -0.093194 0.0729051 0.265927 0.0872192 0.0728943 0.256057 0.0929688 0.0733096 0.164 0.0741718 0.0857026 0.265197 0.0741718 0.0857026 0.164 0.0731 0.0859 0.164 -0.0638282 0.0857026 0.164 -0.0649 0.0859 0.265197 -0.0638282 0.0857026 0.164 -0.0731 0.0859 0.164 -0.0741718 0.0857026 0.168006 0.126713 0.0729038 0.168004 0.0221287 0.0779 0.289058 0.0220609 0.0729005 0.349978 0.0220187 0.0729 0.260202 0.0842454 0.0729 0.289041 0.0806019 0.0779 0.349959 0.0220391 0.0779 0.34998 0.0806114 0.0779 0.345 -0.012 0.0729 0.173 -0.012 0.0729 0.168 0 0.0779 0.345 -0.012 0.0779 0.345 0.012 0.0779 0.168008 -0.0220655 0.0779 0.201206 -0.126846 0.0779 0.261165 -0.0835421 0.0728986 0.260205 -0.0842445 0.0779 0.168005 -0.126762 0.0779 0.179622 -0.0695348 0.0779 0.289012 -0.0244232 0.0729118 0.289012 0.0220076 0.0779 0.206214 -0.118754 0.0729 0.206214 0.118754 0.0729 0.214428 0.122584 0.0779 0.198876 0.126883 0.0729014 0.168008 -0.126846 0.0728999 0.211272 -0.125177 0.0778993 0.212464 -0.124226 0.0729002 0.283985 -0.022008 0.0779 0.283995 -0.0778622 0.0729001 0.201209 -0.0220573 0.0778997 0.201206 0.0220655 0.0779 0.283979 0.0798271 0.0729 0.28399 0.0796474 0.0779 0.34997 0.0803027 0.0728996 0.289022 0.0806375 0.0728997 0.168112 -0.00934869 0.0728999 0.173 -0.012 0.0779 0.170399 0.0119988 0.0778999 0.349915 0.0096674 0.077898 0.349888 -0.00934862 0.0779039 0.349915 -0.00966741 0.0729001 0.349985 -0.0806269 0.0728998 0.260531 0.0695203 0.0779 0.260364 0.0689938 0.0829005 0.220116 0.0692725 0.0828999 0.180046 0.0690915 0.0779 0.260788 -0.0701256 0.0829011 0.260813 -0.0695047 0.0779 0.258912 -0.0671267 0.0829001 0.363999 -0.0813311 0.0779001 0.353466 0.0845143 0.0728993 0.354 0.0825585 0.0729 0.352 0.0847132 0.0733096 0.354 0.0808909 0.0779 0.164 0.129 0.0804 0.164864 -0.130501 0.0729 0.164016 -0.131021 0.0808987 0.252737 -0.0890117 0.0806868 0.269377 -0.0804938 0.0808974 0.260518 -0.083716 0.0809 0.363999 -0.0797321 0.0804241 0.3635 0.0773069 0.0809 0.362 0.0791381 0.0809 0.362 0.0795476 0.0806868 0.252737 0.0890117 0.0806868 0.269374 0.0804935 0.0808986 0.278747 0.0826269 0.0762951 0.164504 0.13045 0.0809002 0.213216 0.129267 0.0729085 0.207136 0.127275 0.0806868 0.192482 0.131013 0.080126 0.164006 0.0759199 0.0808999 0.1645 -0.0620801 0.0809 0.164 0.0618982 0.0804 -0.45994 0.00468165 0.0616493 -0.453109 -0.0208515 0.0516147 -0.451189 -0.0255339 0.0296679 -0.451961 0.0266232 0.038482 -0.455693 0.00681164 0.0105197 -0.458298 0.0250423 0.0418269 -0.457128 -0.0248545 0.0286252 -0.459498 -0.0153795 0.0560863 -0.45857 -0.0240979 0.0448217 -0.457253 -0.0179144 0.0207937 -0.455433 -0.0103747 0.0120538 -0.454121 0.0225283 0.0218117 -0.459926 0.0172624 0.0514279 -0.461027 -0.00990511 0.0560016 -0.45656 0.0137013 0.0171287 -0.457544 -0.00616652 0.0133549 -0.471968 0.00924719 0.0509725 -0.464098 0.0086756 0.0156472 -0.47974 0.00187861 0.0440155 -0.460474 0.00145905 0.0584478 -0.476179 0.0122296 0.028763 -0.46968 0.0176838 0.0266899 -0.458213 0.022108 0.0289826 -0.469154 0.0191138 0.0410036 -0.459394 -0.0226608 0.0387922 -0.460491 -0.0190233 0.0486356 -0.474571 -0.00997852 0.0476938 -0.45801 -5.20945e-06 0.0131103 -0.476797 0.000319931 0.0211902 -0.474777 -0.0154999 0.0352693 -0.469798 -0.0165771 0.0241484 -0.469122 -0.00030966 0.0552368 -0.47891 -0.00796812 0.0325976 -0.454422 0.0138986 0.0577292 -0.449799 -0.0127485 0.0138661 -0.454031 -0.00155695 0.0623937 -0.449576 0.00451841 0.0104584 -0.382847 -0.0448984 0.0997569 -0.386234 -0.0463173 0.0849337 -0.381055 -0.0346638 0.0998285 -0.393127 -0.0430525 0.0799161 -0.389464 -0.0290662 0.101216 -0.393336 -0.030216 0.0851888 -0.397376 -0.0389368 0.0836482 -0.380465 -0.0372475 0.0851011 -0.386438 -0.0430103 0.0787063 -0.395687 -0.0448206 0.100695 -0.384487 -0.0345725 0.0784796 -0.390982 -0.0327405 0.0789087 -0.397186 -0.0344372 0.0997051 -0.385298 -0.0298488 0.0865647 -0.484685 0.00734716 0.0441454 -0.484292 0.010611 0.0389624 -0.457615 0.0329354 0.0651295 -0.478707 0.02273 0.0493741 -0.449459 0.0356596 0.0100143 -0.452149 -0.0388934 0.0712973 -0.49075 -0.00958643 0.0213099 -0.492356 -0.0109825 0.0378689 -0.421785 -0.0466003 0.0627784 -0.419108 0.0407184 0.0189693 -0.416355 -0.033226 0.00937107 -0.416359 0.0332164 0.00936877 -0.421532 -0.0332171 0.068504 -0.49144 0.0109887 0.0272747 -0.492724 0.00328129 0.0313705 -0.492925 -0.0033882 0.033548 -0.450476 -0.034 0.00927897 -0.45402 -0.035655 0.0621447 -0.485201 -0.00158116 0.0363327 -0.483295 -0.0113149 0.0269536 -0.484649 0.00157066 0.0299941 -0.482847 0.00821407 0.0236083 -0.42512 -0.03605 0.0648361 -0.422409 0.0475239 0.0615041 -0.418695 -0.047564 0.0160686 -0.417659 0.0458632 0.0143721 -0.422098 0.0406077 0.0607654 -0.425384 -0.0424347 0.0692447 -0.474804 -0.0237279 0.0561326 -0.492772 0.00743546 0.0421349 -0.468712 0.0326418 0.00441964 -0.482879 0.0258151 0.0159611 -0.454153 -0.0397884 0.00687427 -0.459223 -0.0398722 0.0643656 -0.454276 0.0390005 0.0641803 -0.454362 0.0392893 0.00727322 -0.458325 0.04 0.0645698 -0.458942 0.0342159 0.0605537 -0.459035 -0.0350121 0.0610764 -0.455921 -0.0339406 0.062449 -0.450476 0.034 0.00927766 -0.455148 0.034 0.0626725 -0.454688 0.035 0.0115193 -0.422267 -0.0404785 0.0586217 -0.418397 -0.0404226 0.0172112 -0.483054 0.0115569 0.0270242 -0.459238 0.0389964 0.0635225 -0.44934 0.0397269 0.00735281 -0.422041 -0.0399814 0.0728185 -0.416177 -0.0389897 0.00394169 -0.421528 0.0332198 0.068478 -0.425246 0.036322 0.0650731 -0.454071 0.0355903 0.0620358 -0.420628 0.0359271 0.0123702 -0.454407 -0.0397733 0.0648712 -0.420637 -0.0359262 0.0123737 -0.449429 -0.0398734 0.00717567 -0.449523 -0.0355603 0.010051 -0.453585 0.034 0.0103951 -0.471242 0.0277664 0.0146662 -0.474698 -0.0207313 0.0143972 -0.452276 -0.0328464 0.00652938 -0.482712 -0.00853176 0.0232681 -0.447271 0.0330366 0.006787 -0.472259 0.0239861 0.0119556 -0.484159 -0.0118658 0.0390682 -0.479188 -0.0222529 0.0489108 -0.471919 -0.0259884 0.0159999 -0.454589 -0.0340947 0.0107564 -0.456357 -0.0328541 0.0651763 -0.484665 -0.00813075 0.0426163 -0.478916 0.0195567 0.0523626 -0.48803 -0.0193142 0.0522069 -0.473129 -0.0331533 0.0647342 -0.492918 -0.00734458 0.0439448 -0.487367 0.0214172 0.0540104 -0.472259 0.0331548 0.0648093 -0.45551 0.038765 0.0708659 -0.422326 0.0390018 0.0738748 -0.425572 0.0425086 0.0693408 -0.452753 0.0424302 0.0668765 -0.467308 0.0386003 0.062483 -0.48474 0.0279182 0.0522433 -0.492355 0.0111418 0.0379519 -0.466956 0.0368616 0.00835174 -0.45396 0.0408386 0.00581516 -0.444217 0.0422391 0.00544131 -0.420267 0.0420734 0.00818333 -0.416648 0.0391462 0.00394366 -0.445855 0.0389224 0.00134218 -0.486255 0.0175183 0.0151859 -0.490985 0.00747085 0.0229608 -0.490582 0.000115097 0.0201884 -0.476343 -0.0275053 0.00796326 -0.452196 -0.038483 0.00110153 -0.420601 -0.0425365 0.00772009 -0.491365 -0.0109664 0.0272815 -0.463901 -0.0387493 0.00698144 -0.484132 -0.0243818 0.0170322 -0.484498 -0.0280012 0.0523468 -0.457056 -0.0419158 0.0665335 -0.424491 0.0355794 -0.0298004 -0.393277 0.0302733 -0.0690163 -0.382278 0.0338996 -0.0612532 -0.427772 0.00981128 -0.0661245 -0.4058 -0.0270336 -0.0813925 -0.39355 -0.0301694 -0.0692132 -0.372426 -0.0389033 -0.061956 -0.360837 0.0440981 -0.0328514 -0.356681 0.0390722 -0.0381603 -0.359854 0.0332159 -0.0336368 -0.409041 0.033223 -0.000462314 -0.372559 0.038858 -0.0620417 -0.426783 -0.00334102 -0.0778937 -0.36986 -0.0400851 -0.0308639 -0.41253 -0.00903435 -0.0767252 -0.381248 -0.034 -0.0602177 -0.376128 -0.0331563 -0.0576794 -0.410475 0.000249916 -0.0778741 -0.412236 -0.0424641 -0.00313283 -0.403484 -0.0404673 -0.00613478 -0.365484 -0.0456745 -0.0318463 -0.3668 0.0452932 -0.032942 -0.42503 0.0033671 -0.0790918 -0.418863 0.00157296 -0.0736544 -0.424038 -0.00148765 -0.0702832 -0.402252 0.0403756 -0.00543874 -0.429181 0.0328878 -0.0307567 -0.408731 0.036322 -0.00549684 -0.396409 0.0242824 -0.0748484 -0.376865 0.0331077 -0.0587148 -0.407182 0.0255531 -0.0813564 -0.424604 -0.0356646 -0.0297184 -0.378925 -0.0398736 -0.0606767 -0.429382 -0.0398775 -0.0324079 -0.426128 -0.0338943 -0.0316495 -0.381198 0.03564 -0.0590007 -0.426834 0.0398695 -0.0283599 -0.381274 -0.0355724 -0.0589516 -0.425683 0.034 -0.0302455 -0.429562 0.0397543 -0.0324105 -0.368634 0.040577 -0.0289109 -0.405162 0.0460235 -0.00664835 -0.404428 -0.0475988 -0.00581025 -0.421124 0.0108409 -0.0807091 -0.42601 -0.0116685 -0.067263 -0.42679 -0.0349976 -0.0343234 -0.426963 -0.0397936 -0.0283299 -0.381802 -0.0397513 -0.0646263 -0.381688 0.0398763 -0.0645758 -0.37912 0.0397809 -0.0605952 -0.384614 0.0349976 -0.0627717 -0.413538 -0.039104 0.00215275 -0.364867 0.0359277 -0.0350763 -0.40851 -0.0359274 -0.00563973 -0.364876 -0.0359269 -0.035078 -0.406231 0.0208918 -0.0745798 -0.426228 0.0341744 -0.034181 -0.430173 0.022761 -0.0568835 -0.359847 -0.0332265 -0.0336411 -0.392095 -0.0269099 -0.0722715 -0.413275 0.0105365 -0.0758315 -0.430436 -0.0272126 -0.0508313 -0.404636 -0.0221459 -0.074059 -0.416222 -0.0106371 -0.0744562 -0.384766 -0.0340454 -0.0620953 -0.40906 -0.0332347 -0.000459347 -0.429669 -0.0313213 -0.03376 -0.432921 -0.0240224 -0.0491467 -0.429452 -0.00879757 -0.0653823 -0.43263 0.0195291 -0.0552318 -0.431124 -0.0388725 -0.0235569 -0.434287 -0.00884385 -0.0718008 -0.439496 -0.0312631 -0.0469304 -0.434176 0.00843508 -0.071971 -0.434948 0.0379861 -0.0304348 -0.439411 0.0258117 -0.0547265 -0.413704 0.0389721 0.00231359 -0.412568 0.0426283 -0.00342758 -0.435273 0.0246034 -0.0632346 -0.434525 0.0369618 -0.0441388 -0.42998 0.0115694 -0.0744772 -0.391607 0.0364861 -0.0740716 -0.376491 0.0424064 -0.0603343 -0.361178 0.0424755 -0.0376035 -0.387411 0.033435 -0.0761613 -0.415355 0.0105309 -0.0844335 -0.414958 0.000477452 -0.0847541 -0.417236 -0.00755805 -0.0829916 -0.405336 -0.0205181 -0.0841855 -0.35559 -0.0388993 -0.036873 -0.361233 -0.0423193 -0.0375312 -0.376149 -0.0421758 -0.0603792 -0.420953 -0.0110089 -0.0806939 -0.385865 -0.0342872 -0.0749249 -0.429737 -0.0108953 -0.0749103 -0.435028 -0.0239623 -0.0635401 -0.433424 -0.038805 -0.0399388 -0.426182 -0.0422628 -0.0233007 -0.410667 -0.024336 -0.0390862 -0.421808 -0.0127071 -0.0315591 -0.383671 -0.0118545 -0.0572864 -0.38426 0.0142046 -0.0569755 -0.38546 0.0073764 -0.0634525 -0.410414 0.0230115 -0.0466274 -0.386487 -0.0104814 -0.0623251 -0.401702 0.0260563 -0.0451327 -0.420497 0.0157601 -0.0324614 -0.425734 0.0102197 -0.0358399 -0.416124 -0.0231993 -0.0426289 -0.42705 -0.00686814 -0.0352751 -0.419234 0.0180084 -0.0421051 -0.396797 0.0233728 -0.055869 -0.425605 0.00163773 -0.0367906 -0.387109 -0.000547917 -0.0627005 -0.400531 -0.0238224 -0.0531728 -0.428906 0.00205627 -0.0476925 -0.402859 0.00470471 -0.0718319 -0.412673 0.0141594 -0.0666015 -0.425603 0.0112895 -0.0525592 -0.39528 0.0149266 -0.0631777 -0.413447 0.0201326 -0.0588494 -0.396783 0.0190665 -0.0562967 -0.411882 -0.0187351 -0.0615788 -0.421914 -0.0173359 -0.0509287 -0.421288 -0.0153127 -0.0399014 -0.42494 -0.00879673 -0.0595328 -0.396139 -0.000495818 -0.0697992 -0.394534 -0.0178209 -0.0595948 -0.405197 -0.0101616 -0.0698519 -0.429051 -0.000417226 -0.0491414 -0.425894 0.00147312 -0.0618736 -0.411467 -0.000427331 -0.0720354 -0.394086 -0.0232985 -0.0502675 -0.380606 0.0362751 0.0855995 -0.397567 0.0359246 0.0998803 -0.391406 0.046296 0.0857659 -0.39601 0.0326932 0.0853546 -0.379483 0.0375041 0.0996277 -0.384434 0.0445419 0.0844287 -0.396786 0.0404502 0.0848402 -0.391333 0.0435756 0.078577 -0.383909 0.035943 0.0773757 -0.393068 0.0339231 0.0782671 -0.387971 0.0470199 0.101086 -0.38476 0.0305155 0.0855675 -0.388775 0.0289242 0.101084 -0.417004 -0.0763518 0.0551518 -0.416999 -0.0688598 0.0430578 -0.404501 -0.0267466 -0.0465263 -0.424312 0.0111176 -0.0331759 -0.413586 0.0238587 -0.0404241 -0.391076 0.02327 -0.0494757 -0.395569 0.0251725 -0.0525957 -0.389196 -0.0185438 -0.0568751 -0.405444 -0.0254698 -0.0380503 -0.419846 -0.0186124 -0.0361986 -0.457062 0.000312585 0.0627411 -0.455668 0.0251423 0.0467325 -0.44773 0.0126157 0.0133251 -0.448917 -0.0158381 0.0153474 -0.448062 -0.0241097 0.0247515 -0.456337 -0.0188724 0.0544788 -0.449894 0.000649601 0.0634577 -0.434691 0.031964 0.0687418 -0.399665 -0.0757864 0.0811977 -0.395882 -0.0782802 0.0812077 -0.398555 0.0588966 0.078209 -0.392889 0.0576929 0.0812082 -0.416674 -0.00790312 0.0842079 -0.411906 0.0138878 0.0842079 -0.381844 0.00579034 0.0742076 -0.38866 -0.0151899 0.0742084 -0.392048 0.0317148 0.0842079 -0.395285 0.0349515 0.0742079 -0.455785 -0.0298191 0.0482641 -0.390673 0.0485 -0.0125425 -0.378231 0.0494918 -0.0209213 -0.38613 0.0518537 -0.00580692 -0.368263 0.0495318 -0.00614158 -0.354031 0.0495482 -0.00630284 -0.396755 0.0326875 -0.00844108 -0.380115 0.0321244 -0.0353448 -0.390536 0.0318096 -0.0391442 -0.372671 0.0325659 -0.024685 -0.373279 0.0299607 -0.0554568 -0.378943 -0.0482855 -0.0481509 -0.417086 -0.0467035 0.0180836 -0.417001 -0.0712176 0.0654058 -0.416993 -0.0548277 0.0660062 -0.416996 -0.0530584 0.0471381 -0.428561 -0.0672608 0.00543917 -0.422188 -0.0904478 0.0255144 -0.419215 -0.0681069 0.0069755 -0.429841 -0.0509125 0.00754265 -0.422494 -0.00295172 -0.025885 -0.403365 0.0259594 -0.0391054 -0.390476 -0.0229752 -0.0501254 -0.382818 0.0132295 -0.0553722 -0.45035 0.0239501 0.0481115 -0.435123 0.0393487 0.000821035 -0.417007 0.0478706 0.0174572 -0.445652 0.0398403 0.0185349 -0.430309 -0.0401469 0.0200503 -0.440227 -0.0471261 0.0157619 -0.435109 -0.0394153 0.000836563 -0.393545 -0.057548 0.081208 -0.418941 0.0808951 0.0812092 -0.364 -0.0809243 0.0812079 -0.364 0.0809243 0.0812079 -0.398994 0.0610349 0.0812079 -0.389411 0.07586 0.0812056 -0.3985 -0.0181019 0.0782058 -0.401004 -0.0180016 0.0782077 -0.398499 -0.0181862 0.0742079 -0.398496 0.018062 0.078206 -0.401005 0.0178666 0.078208 -0.374313 -0.0357997 0.0758522 -0.421619 0.0464904 0.0742036 -0.364955 -0.047919 -0.0298885 -0.36712 -0.04661 -0.0284292 -0.402568 -0.0470817 -0.00451954 -0.40704 -0.0464898 -0.00150298 -0.41599 -0.0399053 -0.0301642 -0.407052 -0.0400923 -0.0171743 -0.407062 0.0401182 -0.0171663 -0.403413 0.0491304 -0.00394957 -0.415016 0.0390346 0.00387073 -0.425029 0.0326204 0.00631855 -0.416108 0.0337614 0.00686494 -0.416914 0.0700458 0.0741985 -0.417002 0.0465 0.0447132 -0.417002 0.0667296 0.0297245 -0.41653 -0.0446478 0.00983543 -0.415185 -0.0396578 0.00397901 -0.414639 -0.0383051 0.00361682 -0.424021 -0.032933 0.00637967 -0.415831 -0.0367342 0.00492217 -0.421819 0.0339863 0.0715577 -0.44435 -0.0466801 0.0584872 -0.422094 -0.0390576 0.075829 -0.448088 -0.0319201 0.0668333 -0.422142 0.039138 0.0759573 -0.448884 0.0397911 0.0551519 -0.447966 0.0320649 0.0669748 -0.379047 0.0483987 -0.0480857 -0.359212 0.0438497 -0.0339796 -0.374992 0.0320441 -0.0558045 -0.354031 -0.0673 -0.0406695 -0.354032 -0.0795783 -0.013012 -0.354031 0.0509103 -0.0406695 -0.354031 -0.0509103 -0.0406695 -0.354106 -0.090388 -0.00686306 -0.354031 -0.0937938 -0.00378131 -0.354031 -0.0633086 -0.0057921 -0.354031 0.0633086 -0.0057921 -0.354031 0.0390975 -0.035786 -0.354032 -0.039589 -0.0367674 -0.364002 -0.0785 0.0782079 -0.363999 0.082598 0.0782079 -0.378125 -0.0341101 0.0782079 -0.353962 0.0934772 -0.00328102 -0.354031 0.0891882 -0.00902386 -0.354031 0.0775631 -0.0121765 -0.364002 0.0815517 -0.00578712 -0.376502 0.0825 0.0712079 -0.416996 0.0824949 0.0182933 -0.398502 0.0825 0.0652079 -0.363985 0.0904852 0.012871 -0.354034 0.0905026 0.00883416 -0.400663 -0.052586 -0.00579825 -0.376502 -0.0825 0.00313683 -0.400823 -0.0824943 -0.00576513 -0.364002 -0.0824377 -0.00578879 -0.354031 -0.0925254 0.000431474 -0.354032 -0.0905018 0.00886396 -0.416795 -0.0824935 0.0179679 -0.398502 -0.0825 -0.0037921 -0.364003 -0.0825745 0.00518677 -0.363996 0.0633199 -0.00579207 -0.363974 -0.0805735 -0.0132605 -0.364002 -0.0928484 -9.80202e-05 -0.363992 -0.0633139 -0.00579209 -0.363989 -0.0904864 0.0126562 -0.364 0.0930092 -0.00166274 -0.363991 0.0825016 -0.01235 -0.363999 0.0766089 -0.0118556 -0.375111 0.0830634 0.00567607 -0.375889 0.0825882 0.00365064 -0.406115 -0.0673145 -0.0316379 -0.396526 -0.0672577 -0.0386634 -0.387737 -0.0672999 -0.0406678 -0.444315 0.0673481 0.0449223 -0.354031 0.0673 -0.0406695 -0.401825 0.0672406 -0.0359185 -0.388732 0.0673007 -0.0406639 -0.442389 0.0673023 0.0282908 -0.408422 0.0673 -0.0278642 -0.408422 0.0509103 -0.0278642 -0.444764 0.0509202 0.0437513 -0.430576 0.0673429 0.0806048 -0.431275 0.0509112 0.0788156 -0.382394 0.00053679 -0.0614642 -0.380207 -0.0132562 -0.0630694 -0.41323 0.0301971 -0.0406733 -0.394295 0.0297525 -0.0534405 -0.396731 -0.0303042 -0.0517864 -0.426071 -0.00410981 -0.0319982 -0.452377 0.00256815 0.00921569 -0.454695 -0.0266905 0.0357236 -0.453128 -0.0184948 0.0177102 -0.453721 0.0236855 0.0244595 -0.455792 0.0298502 0.0482841 -0.393669 -0.0509141 -0.0442354 -0.453644 0.0299331 0.0238362 -0.452084 0.00825074 0.00586039 -0.429719 0.00834695 -0.0295384 -0.452325 0.0150396 0.00850208 -0.427277 0.0154526 -0.0311979 -0.429711 -0.00912446 -0.0295437 -0.452077 -0.0123127 0.00610207 -0.426543 -0.0164098 -0.0316789 -0.453319 -0.0265381 0.0200005 -0.446755 -0.0509298 0.0343192 -0.454043 -0.0303386 0.0282417 -0.354031 0.00872746 -0.0675251 -0.379366 0.00915597 -0.0635077 -0.382641 0.0165225 -0.0612938 -0.354031 -0.0126903 -0.0674439 -0.457361 0.0125567 0.0660746 -0.457346 -0.0126954 0.0660182 -0.450387 -0.0127094 0.0842079 -0.429085 -0.0625519 0.0693664 -0.427696 -0.0693361 0.0672792 -0.424732 -0.0509644 0.0605621 -0.425333 -0.0549583 0.0450975 -0.428174 -0.066328 0.0410926 -0.425578 -0.0774345 0.0551024 -0.43241 -0.0509104 0.0775681 -0.432689 -0.050939 0.0677031 -0.390391 -0.0995394 0.00189087 -0.404048 -0.0979156 0.0251158 -0.354026 -0.085227 0.0712208 -0.40556 -0.0955836 0.0584788 -0.398815 -0.0951911 0.0640767 -0.354031 -0.0943815 -0.00892682 -0.403234 -0.0852275 0.0712167 -0.391846 -0.093789 -0.00372328 -0.392412 -0.094382 -0.00892429 -0.400587 -0.0939918 -0.0054825 -0.411713 -0.0859563 0.0648442 -0.408628 -0.0911722 0.0191719 -0.417251 0.0891791 0.0366293 -0.354031 0.0943815 -0.00892682 -0.392381 0.0943821 -0.00892458 -0.354031 0.0847026 0.075812 -0.418385 0.0847354 0.0755216 -0.400496 0.094007 -0.00564013 -0.387758 0.0937762 -0.00362005 -0.409833 0.0858054 0.0661666 -0.42859 0.0887327 0.0405538 -0.425954 0.0898307 0.0309155 -0.37553 0.0508458 0.0842074 -0.394621 0.0427701 0.0842079 -0.432437 0.0509103 0.0842079 -0.389 -0.0315 0.0842079 -0.394968 0.0177124 0.0842081 -0.390544 -0.016179 0.0842086 -0.385722 0.0126544 0.0842094 -0.39377 -0.0436208 0.0842079 -0.432437 -0.0509103 0.0842079 -0.381278 0.00343487 0.0842081 -0.384048 0.0335236 0.0842079 -0.370002 0 0.0842079 -0.383217 0.0419189 0.0842079 -0.381302 -0.0373323 0.0842079 -0.381964 -0.00684191 0.0842079 -0.401173 -0.0181663 0.0842075 -0.393952 -0.0335236 0.0842079 -0.386819 0.0994295 0.00183888 -0.404968 0.0852285 0.0712148 -0.399741 0.0950779 0.0640706 -0.354031 0.085227 0.0712208 -0.411028 0.0969971 0.0366242 -0.403797 0.0952948 0.0609679 -0.359516 0.0950761 0.0640755 -0.360437 -0.09955 0.00170364 -0.354637 -0.0959976 -0.0016813 -0.367007 -0.0438807 0.0812088 -0.375407 -0.0508731 0.0842062 -0.37838 -0.0509103 0.0812079 -0.36701 0.0439969 0.0812076 -0.37838 0.0509103 0.0812079 -0.425958 0.0509102 0.0812047 -0.401772 0.0509126 -0.0355954 -0.445194 0.0509089 0.0270837 -0.389582 0.0509112 -0.0406353 -0.441984 0.0509119 0.0276211 -0.41508 -0.080918 0.0812073 -0.414401 -0.0847029 0.0758062 -0.422419 -0.0858057 0.0661869 -0.421588 -0.0762057 0.0812 -0.426786 -0.0725924 0.0776848 -0.389582 -0.050914 -0.0406353 -0.408422 -0.0509103 -0.0278642 -0.408327 -0.0509118 -0.0335362 -0.401719 -0.0509023 -0.0355882 -0.42832 -0.0509105 0.0812017 -0.445622 -0.0398373 0.0184451 -0.426738 -0.0389258 -0.0132903 -0.44024 -0.050902 0.0189012 -0.421212 -0.044632 -0.0176995 -0.41595 -0.0482456 -0.0234099 -0.41469 -0.0300073 -0.0396805 -0.424662 -0.0319772 -0.0223875 -0.442848 -0.0319157 0.00726668 -0.448693 -0.0400709 0.0553053 -0.442232 -0.0473312 0.063179 -0.441989 -0.0389111 0.0741041 -0.446233 -0.0509107 0.0481146 -0.439293 0.0482581 0.0151443 -0.442786 0.0319087 0.00716487 -0.415895 0.0400643 -0.030447 -0.407566 0.0509158 -0.0344374 -0.417365 0.0480964 -0.0211918 -0.426752 0.0389426 -0.0132715 -0.438799 0.018263 -0.0105982 -0.424693 0.0319172 -0.02237 -0.365344 -0.0395863 -0.0540222 -0.354031 -0.0509106 -0.0508307 -0.375058 -0.0320124 -0.0558078 -0.385554 -0.0399456 -0.0507266 -0.354031 0.0161806 -0.065969 -0.365386 0.0395649 -0.0540256 -0.354031 0.0509106 -0.0508332 -0.393154 0.0509104 -0.0444062 -0.385448 0.0402515 -0.0506327 -0.450247 0.0130059 0.0842079 -0.441654 0.0394198 0.0743505 -0.447323 0.0509222 0.0441821 -0.355333 0.0923566 0.0660487 -0.355525 0.0973672 -0.000300838 -0.360136 0.099439 0.00169802 -0.360008 -0.0951874 0.0640847 -0.356361 -0.0978658 9.90022e-05 -0.355315 -0.0924673 0.066034 -0.3985 0.0185502 0.0742076 -0.400996 -0.0794824 0.0742081 -0.401002 -0.0765 0.0782079 -0.410999 0.0139045 0.0742078 -0.417079 0.0028533 0.074208 -0.412936 -0.0127653 0.0742077 -0.401004 0.0181519 0.0742079 -0.400969 0.0766663 0.0782889 -0.416893 -0.0465117 0.0729093 -0.374499 -0.0255293 0.0782035 -0.374202 -0.0785 0.0782079 -0.375864 0.0806493 0.0742134 -0.421435 -0.0464765 0.0741969 -0.417004 0.0416136 0.00521154 -0.400887 0.0824946 -0.00572223 -0.400659 0.0520486 -0.0058048 -0.354033 -0.0494986 -0.0368094 -0.394935 -0.0495012 -0.0096672 -0.364006 0.0828983 0.00557135 -0.364304 0.0822208 0.0764831 -0.416951 0.0463874 0.0728521 -0.376502 -0.0825 0.0712079 -0.374505 -0.0837735 0.0699172 -0.37453 -0.083532 0.0062043 -0.374605 -0.0904974 0.0631482 -0.374414 0.0809671 0.0782057 -0.375545 0.0826247 0.0717225 -0.374538 0.090498 0.0132646 -0.374503 0.0838472 0.00651877 -0.374507 0.0838868 0.0698237 -0.374564 -0.0258031 0.0752857 -0.401002 -0.0865 -0.000719742 -0.398502 -0.0865 0.0622079 -0.401002 -0.0865 0.0622079 -0.401002 -0.0825 0.0652079 -0.398502 0.0865 -0.000719742 -0.398502 0.0825 -0.0037921 -0.401002 0.0864989 0.0640714 -0.398502 0.0865 0.0622079 -0.398519 -0.0864985 -0.00269382 -0.401 0.0864977 -0.00182132 -0.416995 0.082485 0.0653776 -0.401012 0.0799445 0.0742098 -0.416632 -0.0703299 0.0742009 -0.416826 -0.0824697 0.0654674 -0.406306 -0.0824815 0.0729217 -0.388499 -0.0798015 0.0742387 -0.388502 0.079902 0.0742454 -0.401003 0.0824999 0.0721968 -0.398502 -0.0825 0.0652079 -0.404585 0.0822219 -0.00270852 -0.416765 0.0749085 0.00531007 -0.416661 -0.0743495 0.0049891 -0.416196 -0.0775981 0.00785762 -0.382647 0.0359495 0.0742079 -0.382539 -0.0335209 0.0742902 -0.376147 -0.0807364 0.0742034 -0.388814 -0.0587876 0.0742079 -0.398392 0.0563549 0.0741968 -0.388332 0.0456978 0.0742079 -0.393952 -0.0424764 0.0742079 -0.385952 -0.0442852 0.0742079 -0.398501 -0.0584838 0.0742079 -0.387599 0.0314731 0.0742079 -0.387333 0.0141645 0.0742094 -0.39377 -0.0323792 0.0742079 -0.376502 -0.0247129 0.0742079 -0.381233 -0.00472904 0.0742072 -0.374502 0.0904981 0.0631543 -0.354202 0.0904957 0.0631151 -0.354044 0.0827023 0.0710544 -0.354054 -0.0827205 0.0710453 -0.354035 0.0494967 -0.0367668 -0.354031 -0.0524425 -0.00584806 -0.354032 -0.0495021 -0.00971815 -0.354275 -0.0904974 0.0630983 -0.354031 -0.0846126 0.0759949 -0.354031 0.0825 0.0789576 -0.417686 -0.0325448 0.0248591 -0.440971 0.0318235 0.044704 -0.430653 0.0321244 0.0239268 -0.433148 0.0321243 0.0524465 -0.441391 0.0267347 0.00547756 -0.447825 0.030323 0.0651159 -0.442053 0.0314703 0.00813264 -0.445631 0.0316863 0.0652331 -0.447661 -0.0306751 0.0676597 -0.440997 -0.0316891 0.00809577 -0.449751 -0.0245768 0.0457719 -0.430653 -0.0321244 0.0239268 -0.445388 -0.0317318 0.0649615 -0.441426 -0.0268402 0.00551259 -0.445492 -0.00350553 0.0106466 -0.448763 0.0220345 0.0193698 -0.428118 -0.0340605 0.0709411 -0.446258 0.0289097 0.0686878 -0.452754 -0.0177538 0.055998 -0.452478 0.0158763 0.0573918 -0.416118 -0.0325453 0.00694922 -0.417682 0.0326297 0.0248186 -0.37268 -0.0325448 -0.0246801 -0.418722 -0.0262566 -0.0101349 -0.417711 0.0196037 -0.0331387 -0.421439 0.0316853 -0.0211218 -0.373918 0.0314281 -0.0549711 -0.3975 -0.0317637 -0.0360763 -0.380115 -0.0321244 -0.0353448 -0.367067 -0.0320479 -0.0442144 -0.372477 -0.0292462 -0.0555001 -0.358807 -0.0349223 -0.0368254 -0.380279 -0.00916321 -0.0553952 -0.366573 0.0338451 -0.0474997 -0.417541 -0.0197831 -0.0329981 -0.375111 -0.0310178 -0.054509 -0.424653 -0.0287034 -0.0209847 -0.423415 -0.0308724 -0.0220166 -0.42454 0.0303875 -0.0214985 -0.423667 0.0291793 -0.0180516 -0.411347 -0.0341747 0.00140204 -0.374504 -0.0904961 0.0132626 -0.399117 0.0774147 0.0812089 -0.388645 0.062603 0.0742415 -0.388648 -0.0650361 0.081205 -0.398555 -0.058831 0.0782088 -0.421237 -0.0458462 0.0671135 -0.42079 -0.0463649 0.0603805 -0.417003 -0.0472596 0.0627297 -0.41701 0.0477366 0.0639532 -0.420794 0.0464403 0.0604162 -0.430314 0.0401306 0.0200728 -0.429328 0.0319313 0.00851117 -0.429325 -0.0319748 0.00860437 -0.374432 -0.0823997 0.0758931 -0.363999 -0.0824999 0.0789577 -0.425807 0.0279393 0.0712067 -0.443251 0.0480913 0.0596091 -0.420221 0.0326684 0.0538391 -0.433478 0.0399637 0.0562168 -0.421767 -0.0335529 0.0715202 -0.420215 -0.0325246 0.0537706 -0.433148 -0.0321244 0.0524466 -0.433493 -0.0401223 0.0563309 -0.43497 -0.0319209 0.068413 -0.415811 0.0366728 0.00495125 -0.43417 -0.0509313 0.0411016 -0.425517 -0.0776497 0.0160889 -0.421002 -0.0493509 0.00781936 -0.421002 -0.0493505 0.0401068 -0.416966 -0.0493853 0.00749809 -0.421748 -0.0774455 0.00749833 -0.417002 -0.0493511 0.0409546 -0.417002 -0.0776442 0.0409542 -0.425578 -0.0776246 0.0408943 -0.421004 -0.0509108 0.00854453 -0.421018 -0.0509118 0.0409428 -0.429638 -0.0594261 0.00721252 -0.416904 -0.0596541 0.00547023 -0.366441 0.0481906 -0.0288868 -0.376926 0.0401948 -0.037548 -0.3673 0.0320269 -0.0439948 -0.376847 -0.0402476 -0.0375427 -0.364764 -0.0349104 -0.0455832 -0.411459 0.0343001 0.00146263 -0.403799 0.0321244 -0.0193699 -0.417368 0.0319294 -0.0103112 -0.39669 -0.0325245 -0.00848454 -0.403799 -0.0321244 -0.0193699 -0.417424 -0.0319872 -0.0103048 -0.356211 -0.036621 -0.0357876 -0.358203 0.0351224 -0.0362183 -0.440984 0.0667199 0.0447038 -0.419421 0.0464033 0.0447132 -0.419423 0.0326864 0.0447131 -0.41758 0.033024 0.0297102 -0.390674 0.0326617 -0.0125436 -0.378238 0.0326229 -0.0209313 -0.402949 0.0318071 -0.0307603 -0.402956 0.0667276 -0.0307719 -0.386099 0.0667529 -0.0057921 -0.368045 0.0667318 -0.00579205 -0.390528 0.0667412 -0.0391277 -0.417002 0.0667467 0.0447013 -0.440965 0.066741 0.0297231 -0.440985 0.0317805 0.0297211 0.153563 0.124753 -0.0338676 0.075325 0.128 -0.0842613 0.0935831 0.131991 -0.0343834 0.0988191 0.139413 -0.0250758 -0.153372 0.125173 -0.0251087 -0.15312 0.142612 -0.0247737 -0.154846 0.125016 -0.0329357 0.149272 0.125171 -0.0234867 0.147256 0.125307 -0.0346714 0.057682 0.15212 -0.0239594 -0.039702 0.122946 -0.0604724 0.0545909 0.149132 -0.0236 0.0564751 0.125 -0.023618 0.165537 0.138935 -0.0741377 -0.00765121 0.140635 -0.0708461 0.0782791 0.141852 -0.0684893 -0.077524 0.134929 -0.0818961 -0.00812888 0.154428 -0.0441083 0.0746062 0.133682 -0.0841804 0.0352549 0.139911 -0.0722498 -0.0795 0.130434 -0.0905999 0.013 0.138 0.00574206 -0.156093 0.137515 -0.0312199 -0.144538 0.138169 -0.0306 -0.0879397 0.137582 -0.0306714 -0.0932098 0.1318 -0.0357936 -0.0976745 0.135452 -0.0370719 -0.0292656 0.152521 -0.0122795 -0.0981669 0.145156 -0.021566 -0.0877283 0.139609 -0.028559 0.102151 0.151782 -0.0338908 0.148839 0.15174 -0.0351229 0.0975038 0.151672 -0.0371118 0.0982236 0.131985 -0.0369428 0.0907205 0.15174 -0.0351676 0.0912234 0.132015 -0.0356039 0.101291 0.15212 -0.0240105 0.0869972 0.150497 -0.0286544 0.103433 0.151963 -0.0286 0.143923 0.151963 -0.028598 0.16887 0.153035 0.00274206 0.148589 0.152115 -0.0241516 -0.163275 0.152521 -0.0122769 -0.0546408 0.121006 -0.0474608 0.0744924 0.125003 -0.0236453 0.0340136 0.125001 -0.068528 -0.0490173 0.129 -0.0276052 -0.0350176 0.138945 -0.0355884 -0.0560179 0.141899 -0.0304996 -0.0530073 0.144047 -0.0276755 -0.0490167 0.144145 -0.027614 -0.0460182 0.138982 -0.0355882 -0.039058 0.138891 -0.0355356 -0.0558179 0.144041 -0.0277999 -0.0532292 0.139035 -0.0356133 -0.0278533 0.140183 -0.0290463 -0.0596266 0.132 -0.0286001 -0.061794 0.137513 -0.030844 0.160246 0.125 -0.0830999 -0.163335 0.125 -0.0830999 -0.149245 0.13248 -0.0800999 -0.167552 0.155609 -0.00976466 -0.0550269 0.1232 -0.0661171 -0.0685499 0.132955 -0.0736613 -0.0613994 0.123186 -0.0605868 -0.0696492 0.133498 -0.0650255 -0.0490992 0.126193 -0.0600168 -0.0346466 0.126207 -0.0543439 -0.0336631 0.122582 -0.0503817 -0.0185541 0.136205 -0.0697703 -0.0306865 0.126199 -0.064922 -0.0282304 0.126198 -0.0588285 -0.0538916 0.125973 -0.0461442 -0.0585929 0.126196 -0.0649341 -0.0572998 0.137957 -0.0419229 -0.0471377 0.121647 -0.0396124 -0.0744905 0.130943 -0.0833848 -0.013 0.138 0.00274206 -0.16887 0.153035 0.00274206 -0.167337 0.152794 -0.00430643 -0.181242 0.138 0.00274206 -0.17304 0.137709 -0.0302617 -0.164158 0.135119 -0.0392371 -0.150984 0.132786 -0.0763609 0.160983 0.128 -0.0801 -0.00887375 0.136522 -0.0788109 -0.0205374 0.152412 -0.0154807 -0.00695716 0.151438 -0.0433782 0.0289946 0.151453 -0.0433431 0.0793573 0.135539 -0.0741761 0.160983 0.13248 -0.0800999 0.0404965 0.135494 -0.0742645 0.032407 0.138777 -0.067906 -0.00655734 0.137225 -0.0709111 0.159482 0.151558 -0.0404181 0.159091 0.150751 -0.0447089 0.179739 0.137884 -0.0037654 0.181242 0.138 0.00274206 0.163554 0.137884 -0.0696355 0.175502 0.133762 -0.0210069 0.171648 0.125 -0.0366922 0.180613 0.138393 0.01177 0.163335 0.125 -0.0830999 0.174614 0.125001 -0.0371948 0.179187 0.134602 -0.0185828 0.0734539 0.139891 -0.0722871 -0.15376 0.130433 -0.0905953 0.161493 0.130434 -0.0905999 0.161493 0.128 -0.0905999 0.0795 0.130434 -0.0905999 -0.159387 0.128 -0.0905999 -0.0705 0.130434 -0.0905999 0.0705 0.130434 -0.0905999 -0.0741349 0.128 -0.088353 -0.149093 0.135514 -0.0807625 -0.0662262 0.13584 -0.0755854 -0.0686662 0.136328 -0.0678171 -0.0228368 0.135839 -0.0755904 -0.0120843 0.135516 -0.0807587 -0.0531198 0.138101 -0.0396253 -0.157833 0.136171 -0.0703194 -0.0306641 0.137807 -0.0413691 -0.0250629 0.138502 -0.0326239 -0.0184609 0.132944 -0.0730861 -0.0137792 0.13256 -0.0799455 -0.00794837 0.133726 -0.0776873 -0.0590179 0.13512 -0.0392371 -0.154655 0.132674 -0.0778285 -0.0637833 0.132766 -0.0766696 -0.0255648 0.132766 -0.076672 -0.0308934 0.123198 -0.0660648 -0.0560176 0.139259 -0.0349845 -0.165424 0.138114 -0.0394253 -0.0349244 0.138065 -0.0396273 -0.0489758 0.134004 -0.0363093 -0.170114 0.128206 -0.0429371 -0.159785 0.125145 -0.0860938 -0.178544 0.137639 -0.00939414 -0.170078 0.152999 0.00574206 0.179454 0.138 0.00574206 -0.1792 0.138 0.00574206 0.177066 0.146221 0.00574206 -0.130281 0.153263 0.010953 -0.171648 0.125 -0.0366922 -0.174238 0.131889 -0.0261533 -0.186923 0.138589 0.0117535 -0.165732 0.138805 -0.0360976 -0.162702 0.127165 -0.0845383 0.0312978 0.15442 -0.0439723 0.0312118 0.155402 -0.0158157 0.0818479 0.155402 -0.0158276 0.0809645 0.152343 -0.0175156 0.0814316 0.153548 -0.0458336 0.176167 0.152024 0.0129593 0.160562 0.153277 -0.0463589 0.186712 0.138878 0.0118545 0.160802 0.154531 -0.0411786 0.13004 0.152999 0.010953 0.133619 0.152999 0.0140236 0.140056 0.155944 0.0172376 0.127466 0.156157 0.00626796 0.139871 0.156512 0.016633 0.130281 0.153263 0.010953 -0.159038 0.155486 -0.0133696 -0.153753 0.142997 -0.0291018 -0.147783 0.140922 -0.0318267 -0.148322 0.144511 -0.0272075 -0.0350168 0.144145 -0.0276142 -0.0405179 0.144199 -0.0276008 -0.0460189 0.144079 -0.0276492 -0.0261862 0.140754 -0.0347703 -0.173627 0.156544 0.0177595 0.173639 0.156552 0.0178341 -0.023988 0.155435 -0.0148608 -0.0290734 0.155486 -0.0133696 -0.127466 0.156157 0.00626796 0.0817005 0.154543 -0.0406114 0.153337 0.154928 -0.0296768 -0.174738 0.125 -0.0366922 -0.178722 0.134516 -0.0204662 -0.177684 0.138935 -0.0247006 -0.174947 0.136428 -0.0358291 -0.172338 0.129262 -0.0464573 -0.13004 0.152999 0.010953 -0.17994 0.14133 0.0119109 -0.133619 0.152999 0.0140236 0.170078 0.152999 0.00574206 -0.141301 0.156549 0.0178316 -0.175572 0.152963 0.0138012 -0.158798 0.128 -0.0801 -0.0320121 0.142162 -0.0302173 -0.0460208 0.129 -0.0276018 -0.0420173 0.129 -0.0276052 -0.0390208 0.129 -0.0276018 -0.0420172 0.134747 -0.0368181 -0.0460179 0.129 -0.0370999 -0.0337263 0.128891 -0.0365399 -0.0390263 0.128999 -0.0368283 -0.0316463 0.128997 -0.0257751 -0.035017 0.129 -0.0246641 -0.0560173 0.129 -0.0276052 -0.0530208 0.129 -0.0276018 -0.0264452 0.12885 -0.0308355 -0.0584089 0.129002 -0.0246029 -0.0538297 0.129011 -0.0363851 -0.0299217 0.135344 -0.0373376 -0.0290311 0.123219 -0.0389161 -0.0606521 0.129171 -0.03266 -0.0579644 0.142749 -0.0246015 -0.0594027 0.139577 -0.0285999 -0.0306988 0.142755 -0.0245995 0.0835556 0.149899 -0.0463687 0.0839911 0.151306 -0.0425195 0.0867207 0.1502 -0.0304447 0.0289623 0.149468 -0.0139288 0.0833284 0.152463 -0.0139861 0.0357602 0.152466 -0.0139001 0.0287847 0.152213 -0.021284 0.0290026 0.14827 -0.0425703 0.0808606 0.151429 -0.0433181 0.0320985 0.151446 -0.0433116 0.0319439 0.152346 -0.0174522 0.0404279 0.139668 -0.0661269 0.07645 0.128002 -0.0660587 0.0361573 0.136921 -0.071505 0.076475 0.151936 -0.0291652 0.0764595 0.128 -0.0261116 0.0738542 0.152037 -0.026101 0.0365094 0.128 -0.0261235 0.0365149 0.128002 -0.0660779 0.0719533 0.127998 -0.0306804 0.071958 0.125 -0.0615215 0.0719084 0.125001 -0.0306314 0.0410354 0.128 -0.0306382 0.0410347 0.127999 -0.0615379 0.0410076 0.125 -0.030679 0.0719348 0.128 -0.0615638 0.0410704 0.125 -0.0615733 0.0339821 0.148185 -0.0431337 0.0789096 0.125001 -0.0684616 0.0339907 0.125 -0.0283443 0.0384882 0.125 -0.0236282 0.0338563 0.133505 -0.0716688 0.0746179 0.135045 -0.0685958 0.0367209 0.135064 -0.0685603 0.0363001 0.132137 -0.0742276 0.0795133 0.132276 -0.0739926 0.0789821 0.147234 -0.0449922 0.0789764 0.137422 -0.0639917 0.0839571 0.148033 -0.0434275 0.0588888 0.149133 -0.0235923 0.0742575 0.149132 -0.0236117 0.0829109 0.14944 -0.0145638 0.0340338 0.149008 -0.0278221 0.0387416 0.149131 -0.0236432 -0.0590127 0.123251 -0.0381609 -0.0286811 0.122611 -0.0538069 -0.0528475 0.123199 -0.0371934 -0.0408523 0.122698 -0.0379111 -0.0590177 0.123201 -0.0524178 -0.0520639 0.122772 -0.0578259 0.0555177 0.149361 -0.0167975 0.153502 0.15208 -0.0251694 0.153587 0.151784 -0.0339019 -0.144592 0.132 -0.0306 -0.144558 0.139577 -0.0286 -0.146743 0.14243 -0.0250026 -0.147192 0.136132 -0.0346259 0.152201 0.128009 -0.0322105 0.147691 0.154319 -0.0321579 0.149447 0.15502 -0.0270417 0.149903 0.128227 -0.0260644 -0.147159 0.125261 -0.0250122 -0.152139 0.127918 -0.030201 -0.164495 0.136574 -0.0333619 0.173541 0.138 -0.0286 0.155753 0.136901 -0.0285825 0.161972 0.152031 -0.0286366 0.17305 0.138 -0.0306 0.160934 0.152412 -0.0305899 0.155408 0.138 -0.0306 0.0927768 0.152079 -0.0251845 0.0915368 0.15183 -0.0326338 0.0923735 0.132015 -0.022628 0.0908895 0.152132 -0.0237414 0.096 0.152185 -0.0221 0.103433 0.132 -0.0286 0.144603 0.132 -0.0306 0.10079 0.132039 -0.0235921 0.103433 0.132 -0.0306 0.0789822 0.131999 -0.0305993 0.101076 0.13208 -0.0328881 0.100439 0.151802 -0.0332636 -0.088567 0.132 -0.0306 -0.102771 0.131998 -0.028589 -0.103433 0.132 -0.0306 -0.0942627 0.131951 -0.02207 -0.0902981 0.131997 -0.0285921 -0.100985 0.135706 -0.033655 -0.0930062 0.141928 -0.0253099 0.143951 0.151894 -0.0306017 0.103433 0.151894 -0.0306 0.144592 0.132 -0.0286 0.088567 0.132 -0.0306 0.0789821 0.148893 -0.0306 0.0793337 0.148966 -0.028313 0.0789964 0.125049 -0.0285433 0.0900453 0.132024 -0.0283794 -0.0623131 0.132 -0.0306 -0.144592 0.132 -0.0286 -0.103433 0.139577 -0.0286 -0.103702 0.138068 -0.0306029 -0.013 0.138 0.00574206 0 0.146 0.00574206 -0.007 0.146 0.00274206 0.013 0.138 0.00274206 -0.135002 0.135069 -0.0559765 -0.150999 0.133814 -0.0759346 -0.135001 0.133814 -0.075934 -0.150999 0.134071 -0.0559134 -0.151 0.135069 -0.0559771 -0.135 0.133443 -0.0658928 -0.175833 0.148321 0.00574258 0.170139 0.152996 0.014014 0.0741198 0.128 -0.0879791 -0.0751625 0.128 -0.0854306 -0.147119 0.125189 -0.0347781 0.0540315 0.152331 -0.0173311 0.0764846 0.151448 -0.0431768 0.0768871 0.136926 -0.0714915 0.0764799 0.140334 -0.0642159 0.0366572 0.152018 -0.0261107 0.0364811 0.151449 -0.0433479 0.0364825 0.140679 -0.0630571 0.153712 -0.139946 0.0584818 0.156595 -0.156335 0.0176696 -0.161688 -0.154502 0.0547184 0.151504 -0.152573 0.0580464 -0.00471329 -0.125525 0.0490654 -0.00945413 -0.1545 0.0449 0.0125798 -0.133481 0.0651953 -0.194958 -0.131 0.0727391 0.194958 -0.131 0.0727391 0.00779895 -0.130987 0.0651533 -0.0161931 -0.131 0.0779 0.0162244 -0.131 0.0779 -0.0155402 -0.133777 0.0625208 -0.016239 -0.157622 0.0503088 -0.0190225 -0.128569 0.0588855 -0.016856 -0.12533 0.0515665 0.00882626 -0.138513 0.0481854 0.0170869 -0.157512 0.0516219 0.0235767 -0.157495 0.0205483 0.034614 -0.1575 0.0547399 -0.0538054 -0.1575 0.0207192 -0.0233014 -0.1575 0.0547399 -0.139871 -0.1575 0.0564686 -0.06191 -0.1575 0.0547364 0.0068761 -0.157479 0.0445221 0.01195 -0.157491 0.0482467 -0.157769 -0.157496 0.0544263 0.154494 -0.1575 0.0569284 0.01825 -0.1575 0.0564686 -0.0761048 -0.1575 0.0526582 -0.0525903 -0.1575 0.0189363 0.191289 -0.131 0.0779 -0.0203713 -0.135121 0.0779 -0.158 -0.1545 0.0211167 -0.151695 -0.150605 0.0158515 0.17593 -0.134898 0.0282792 0.158 -0.1545 0.0211167 0.177992 -0.131 0.0237811 0.166441 -0.1545 0.0554709 0.0211849 -0.1545 0.0547055 0.0642725 -0.1545 0.0222265 0.0426503 -0.154499 0.0547297 0.0683379 -0.1545 0.0206563 0.046034 -0.1545 0.0207021 -0.0157102 -0.1545 0.0463484 -0.0197763 -0.1545 0.0504 0.0103739 -0.154501 0.0206577 0.00679554 -0.1545 0.0216006 -0.0515575 -0.1545 0.0222265 -0.156 -0.1545 0.0201028 -0.0243188 -0.154499 0.0547381 -0.0548301 -0.1545 0.0546269 -0.0430943 -0.1545 0.0547242 0.153111 -0.1545 0.0540109 -0.0182562 -0.137952 0.0791743 -0.0180718 -0.136365 0.0798894 -0.0139718 -0.1335 0.080663 0.0143459 -0.133501 0.0806673 0.202465 -0.131 0.0809 0.190358 -0.141417 0.0770914 0.198413 -0.134441 0.0804634 -0.01825 -0.144153 0.0743128 -0.159419 -0.153843 0.0614184 0.139871 -0.1575 0.0564686 0.01825 -0.144153 0.0743128 0.187215 -0.144153 0.0743128 -0.154814 -0.157658 0.0614154 -0.16411 -0.1575 0.0564669 0.00344446 -0.157497 0.044155 0.00236665 -0.1545 0.0449 -0.0123081 -0.157487 0.0443574 0.0185686 -0.154482 0.0480663 0.0102333 -0.154501 0.0448957 0.15786 -0.139956 0.0547103 0.159988 -0.157495 0.0567187 0.158048 -0.157127 0.0614514 0.162635 -0.136889 0.0557026 -0.173001 -0.156467 0.0578496 0.159161 -0.152088 0.0637037 0.145572 -0.157501 0.0617176 -0.16028 -0.139837 0.0151416 -0.153527 -0.139825 0.0144092 0.156083 -0.140089 0.0111696 -0.154015 -0.152999 0.0140232 0.1655 -0.152999 0.0069 0.15625 -0.152999 0.011601 -0.155397 -0.152999 0.0119722 0.158229 -0.139822 0.0169703 -0.135 -0.149999 0.015801 -0.135 -0.149999 0.0069 -0.154307 -0.139714 0.0596305 -0.158954 -0.13977 0.055424 -0.155533 -0.136904 0.0518673 -0.147 -0.152069 0.0637301 -0.153349 -0.136891 0.0189576 -0.18 -0.136801 0.0779 -0.18 -0.1376 0.0775018 -0.179273 -0.139054 0.00962231 -0.174558 -0.150257 0.00690207 -0.174646 -0.151549 0.0126939 -0.183487 -0.129706 0.0260532 -0.19911 -0.129706 0.0260572 -0.167039 -0.142407 0.0164915 -0.185742 -0.134953 0.0684251 -0.200814 -0.138723 0.0688351 0.175946 -0.149958 0.0124651 -0.17313 -0.1575 0.0189362 -0.160541 -0.152907 0.0137561 -0.155688 -0.156148 0.0174611 0.15376 -0.152998 0.0140229 0.173062 -0.156415 0.0579191 0.164234 -0.15759 0.0563444 0.207205 -0.13292 0.0683834 0.186463 -0.140134 0.0141082 0.194958 -0.129706 0.0727391 0.160292 -0.145434 0.00764913 0.17469 -0.149912 0.0069005 -0.1655 -0.152999 0.0069 0.135 -0.149999 0.0069 0.1609 -0.153691 0.0144673 -0.194958 -0.129706 0.0727391 0.183487 -0.129706 0.0260532 0.210593 -0.129706 0.0727391 0.194516 -0.137802 0.0793247 0.199777 -0.14064 0.0709174 -0.1876 -0.143813 0.0747622 -0.190423 -0.14136 0.0771356 -0.19491 -0.137461 0.0794458 -0.19986 -0.140567 0.0710305 -0.198438 -0.13442 0.0804686 -0.202465 -0.131 0.0809 -0.210593 -0.129706 0.0727391 0.18 -0.1376 0.0775018 0.18 -0.136801 0.0779 0.02125 -0.139882 0.0744731 0.0554908 -0.1575 0.0206561 0.0427553 -0.1575 0.0206937 0.0189968 -0.157499 0.0547149 0.0231993 -0.1545 0.0534526 0.0338501 -0.154497 0.0547469 0.0567402 -0.1575 0.0230112 0.0576495 -0.1545 0.0209815 0.0619094 -0.157502 0.0208559 0.0537397 -0.1575 0.0549682 0.0389947 -0.1575 0.053706 0.0541634 -0.1545 0.0536738 0.0760452 -0.1575 0.0230112 0.0755452 -0.1545 0.0230112 -0.00163118 -0.154499 0.0206625 -0.0120134 -0.1545 0.0208906 -0.0152405 -0.1575 0.0207533 -0.035516 -0.1545 0.0546272 -0.038819 -0.1575 0.0545757 -0.0016748 -0.1545 0.0230112 0.000284541 -0.157497 0.0208758 -0.0383197 -0.157428 0.0208483 -0.0624349 -0.1545 0.0547712 -0.0728017 -0.1545 0.0526905 -0.0402848 -0.1545 0.0230112 -0.0580615 -0.157498 0.0544889 -0.042606 -0.1575 0.0547399 -0.0191464 -0.157503 0.0210802 -0.0209798 -0.1545 0.0230112 -0.0281726 -0.1545 0.0206564 -0.0316755 -0.1545 0.0213998 -0.0345938 -0.1575 0.0208214 -0.156 -0.1545 0.0524917 -0.152098 -0.136889 0.0622738 -0.163304 -0.136864 0.0581416 0.162524 -0.154421 0.0557756 0.152661 -0.136905 0.0538061 0.158 -0.149999 0.0524917 0.155863 -0.136952 0.064072 0.0212499 -0.1545 0.0554709 0.0222864 -0.157352 0.0446966 0.038155 -0.1575 0.0219767 0.0384697 -0.1545 0.0207958 0.0265562 -0.1545 0.0209457 0.0176302 -0.1545 0.0230112 0.0153925 -0.157485 0.0203496 0.00345632 -0.1575 0.0216169 -0.021249 -0.154499 0.0554723 -0.0154951 -0.129512 0.0462125 -0.153019 -0.152865 0.0183182 -0.155374 -0.143981 0.00704065 -0.150543 -0.145673 0.0151552 0.135 -0.149999 0.015801 0.151371 -0.145322 0.0161683 0.151695 -0.150605 0.0158515 0.155051 -0.144459 0.00707674 0.160569 -0.151946 0.0182052 0.177875 -0.150481 0.0148706 0.175576 -0.154718 0.01959 -0.175358 -0.154936 0.0194154 -0.182216 -0.155907 0.0505845 -0.178941 -0.1575 0.0425895 -0.178245 -0.150059 0.0148426 -0.197703 -0.132644 0.0263641 -0.210698 -0.131004 0.0731403 -0.207244 -0.132712 0.06733 -0.185999 -0.140423 0.014055 -0.182242 -0.154864 0.04723 -0.160496 -0.151914 0.0180889 -0.161188 -0.136906 0.0182383 -0.158 -0.149999 0.0198083 -0.152378 -0.149597 0.0620255 -0.18112 -0.141751 0.0725159 -0.162105 -0.150428 0.0609148 -0.152066 -0.1545 0.0554709 -0.18 -0.139882 0.074473 -0.187409 -0.137835 0.0117988 -0.182929 -0.131 0.0237811 -0.167454 -0.140778 0.0069191 -0.161859 -0.140473 0.0103174 0.17313 -0.1575 0.0189363 0.182168 -0.154935 0.0471212 0.18037 -0.157474 0.0483176 0.210723 -0.131006 0.0732161 0.199674 -0.129713 0.0260945 0.197314 -0.132701 0.0268643 0.201351 -0.138304 0.0694112 0.167166 -0.142203 0.0166095 0.182929 -0.131 0.0237811 0.187459 -0.137849 0.0117985 0.167094 -0.140561 0.00700935 0.179289 -0.138762 0.0101338 0.18367 -0.139291 0.0752252 0.02125 -0.141751 0.0725159 0.1603 -0.149201 0.0625559 0.153864 -0.149511 0.0621408 0.18112 -0.141751 0.0725159 0.158001 -0.1545 0.0521831 -0.191289 -0.131 0.0779001 -0.175949 -0.134892 0.02798 -0.177992 -0.131 0.0237811 -0.184267 -0.138754 0.0758928 -0.166441 -0.1545 0.0554709 -0.16646 -0.151801 0.0461231 0.156325 -0.136944 0.00814561 0.160583 -0.13689 0.0190726 0.185764 -0.134951 0.0685349 0.166476 -0.151836 0.0460968 0.156 -0.1545 0.0201028 0.155873 -0.150023 0.0201384 0.158 -0.149999 0.019801 0.156 -0.150409 0.0525082 -0.158002 -0.1545 0.0522277 -0.156 -0.149999 0.0524917 -0.158 -0.149999 0.0525077 -0.156 -0.149999 0.0198008 -0.02125 -0.139882 0.0744731 -0.02125 -0.141751 0.0725159 -0.0212598 -0.137356 0.0778199 0.0212478 -0.137396 0.0777703 0.0212487 -0.135889 0.0563372 0.020996 -0.135813 0.0779007 0.0183615 -0.137252 0.0796192 0.01825 -0.142647 0.076018 -0.0182504 -0.157501 0.0564677 -0.01825 -0.142647 0.076018 -0.01025 -0.1575 0.0482 0.017028 -0.131043 0.0624286 -0.0169869 -0.131271 0.0637461 0.0161975 -0.125802 0.0504744 0.0108149 -0.127873 0.0457803 -0.00228272 -0.130639 0.0608941 0.0023582 -0.125504 0.0590552 0.0051284 -0.125422 0.0495506 -0.00751241 -0.13347 0.0643866 -0.0119577 -0.125371 0.0482159 -0.01025 -0.1385 0.0482 0.00154591 -0.136832 0.0554838 -0.00289224 -0.137125 0.0524539 0.00938493 -0.135953 0.044869 7.80458e-06 -0.132404 0.0535195 -0.0110981 -0.136002 0.0448955 0.0182552 -0.136689 0.0580421 -0.0182492 -0.137089 0.0567103 -0.0212472 -0.131734 0.0558918 -0.0197851 -0.129749 0.0506569 0.0160492 -0.131097 0.0465005 0.0199303 -0.129445 0.0510792 0.0592053 0.152364 -0.0177811 0.057277 0.142319 -0.0179938 0.0561361 0.134151 -0.0203464 0.0558201 0.143734 -0.0231806 0.058187 0.151472 -0.0417462 0.0579836 0.151912 -0.0301018 0.0724821 0.149891 -0.0466589 0.0404822 0.151511 -0.0417456 0.0404821 0.152048 -0.0260987 0.036538 0.151981 -0.0280312 0.0724821 0.152048 -0.0260987 0.0764061 0.151988 -0.0278286 0.0805897 0.154421 -0.0444118 0.037949 0.139061 -0.0717015 0.0364817 0.151438 -0.0430867 0.0764823 0.151326 -0.0434489 0.0543839 0.152296 -0.0192347 0.0808456 0.152497 -0.023202 0.0746422 0.139873 -0.0660541 0.03327 0.152555 -0.0480385 0.0322373 0.154321 -0.0431091 0.0629962 0.141505 -0.0674487 0.0322686 0.155334 -0.0171332 0.0697104 0.140129 -0.0720673 0.0807635 0.155103 -0.0172002 0.0765053 0.138227 -0.0699875 0.0549829 0.151513 -0.0417432 0.0406738 0.150785 -0.0447483 0.0724477 0.141924 -0.0620848 0.0724741 0.12819 -0.0301055 0.0724793 0.128189 -0.0620947 0.0375355 0.128181 -0.0271294 0.0754455 0.128181 -0.0271989 0.0374967 0.128189 -0.0650545 0.075437 0.128189 -0.0650835 0.0364643 0.131729 -0.0287898 0.039762 0.131193 -0.0260992 0.0764821 0.13119 -0.0300987 0.0365186 0.13147 -0.0660908 0.036466 0.139784 -0.0660937 0.0729205 0.131194 -0.0260982 0.076401 0.131144 -0.0660587 0.0724162 0.151915 -0.030134 0.0404895 0.12819 -0.0301052 0.0405659 0.152108 -0.0301147 0.0404856 0.12819 -0.0620907 0.0405099 0.141922 -0.062094 0.0336567 0.152634 -0.0170869 0.0798048 0.152454 -0.0171239 0.0808427 0.152599 -0.0258231 0.0806234 0.151366 -0.044398 0.064003 0.136991 -0.071651 0.0490269 0.139049 -0.0676808 0.0482396 0.140071 -0.0721827 0.0322793 0.151457 -0.0426981 0.0323149 0.152057 -0.0258489 0.0571254 0.148186 -0.0429686 0.0404819 0.148191 -0.0430233 0.0565207 0.150828 -0.0448153 0.0565429 0.147682 -0.0301 0.072248 0.151476 -0.0417454 0.0724815 0.148015 -0.0427608 0.0321079 0.153051 -0.0245641 -0.0249196 -0.15545 -0.014396 -0.0290734 -0.155486 -0.0133696 0.149 -0.138 -0.0241917 0.144604 -0.151892 -0.0306631 0.145183 -0.124995 -0.0325619 -0.153913 -0.136569 -0.033564 -0.151261 -0.130434 -0.0905999 -0.149093 -0.135514 -0.0807625 -0.0720243 -0.134429 -0.0828631 -0.00825715 -0.13667 -0.0785247 0.149 -0.13248 -0.0800999 0.074 -0.138 -0.069411 -0.000999996 -0.144205 -0.0573961 0.074 -0.144205 -0.0573961 -0.149 -0.133852 -0.0593961 -0.0137792 -0.13256 -0.0799455 -0.000999997 -0.138 -0.0593961 3.43425e-09 -0.138 -0.069411 -0.0224803 -0.133852 -0.0593961 -0.00716669 -0.133736 -0.0776676 -0.151 -0.133852 -0.0593961 0.179739 -0.137884 -0.0037654 0.161361 -0.144205 -0.0573961 0.173034 -0.138 -0.0306631 0.164752 -0.142226 -0.059466 0.161215 -0.132782 -0.0796214 0.166562 -0.128 -0.0573961 0.16607 -0.128 -0.0593961 0.166562 -0.137884 -0.0573961 0.175521 -0.134593 -0.0209312 0.151 -0.13248 -0.0800999 0.151 -0.143172 -0.0593961 0.151 -0.128 -0.0800999 0.076 -0.143169 -0.0593982 0.074 -0.143172 -0.0593961 0.001 -0.143167 -0.0593982 -0.00445354 -0.143969 -0.0593712 -0.000999996 -0.153035 0.00274206 -0.074 -0.153035 0.00274206 -0.074 -0.138 0.00274206 -0.000999989 -0.151115 -0.0439941 -0.00699799 -0.151447 -0.0432832 -0.000999996 -0.151892 -0.0306631 -0.0130803 -0.151892 -0.0306631 -0.000999997 -0.138 -0.0286631 -0.0313017 -0.139556 -0.0286646 -0.074 -0.139527 -0.0286631 -0.0227286 -0.143174 -0.0286633 -0.076 -0.153035 0.00274206 -0.149 -0.153035 0.00274206 -0.076 -0.152521 -0.0122795 -0.076 -0.139527 -0.0286631 0.074 -0.151961 -0.0286631 0.001 -0.153035 0.00274206 0.001 -0.151961 -0.0286631 0.074 -0.153035 0.00274206 0.000999915 -0.151384 -0.0434478 0.0739999 -0.150985 -0.0442552 -0.14458 -0.138 -0.0286631 -0.145335 -0.141367 -0.0263435 0.151 -0.138 -0.0242335 0.154074 -0.124963 -0.0255351 0.151544 -0.151726 -0.0354485 -0.0277227 -0.13578 -0.0358755 0.14458 -0.151961 -0.0286631 0.076 -0.151961 -0.0286631 0.146346 -0.152063 -0.0256795 0.149 -0.152114 -0.0241917 -0.147666 -0.135891 -0.0352744 -0.0337352 -0.138143 -0.0306631 0.149 -0.138 0.00274206 0.149 -0.153035 0.00274206 0.076 -0.153035 0.00274206 0.151 -0.152114 -0.0241917 0.153876 -0.152064 -0.0256352 0.16887 -0.153035 0.00274206 0.158911 -0.151299 -0.0436027 -0.149 -0.13255 -0.0800999 -0.0309634 -0.1351 -0.0394772 0.160246 -0.125 -0.0830999 0.163335 -0.125 -0.0830999 -0.162844 -0.124998 -0.0829422 -0.177684 -0.138935 -0.0247006 -0.0705 -0.130434 -0.0905999 0.0795 -0.130434 -0.0905999 0.18667 -0.138936 0.011871 0.176167 -0.152024 0.0129593 0.174257 -0.125069 -0.0386486 0.165537 -0.138935 -0.0741377 0.151044 -0.126057 -0.0356624 -0.151 -0.128 -0.0350026 -0.149 -0.128 -0.0573961 0.149 -0.128 -0.0593961 -0.149 -0.128 -0.0593961 -0.151 -0.128 -0.0800999 -0.149 -0.128 -0.0800999 0.163302 -0.128 -0.0830999 0.151 -0.128 -0.0573961 0.149 -0.128 -0.0350057 0.149 -0.128 -0.0800999 -0.159387 -0.128 -0.0905999 0.161493 -0.128 -0.0905999 0.161493 -0.130434 -0.0905999 -0.0795 -0.130434 -0.0905999 -0.156895 -0.13047 -0.0882263 -0.0135136 -0.135514 -0.0807624 -0.0345742 -0.138531 -0.0371149 -0.0301115 -0.138499 -0.0357872 -0.0333248 -0.141899 -0.0304995 -0.0342325 -0.139389 -0.0347436 -0.165563 -0.139391 -0.034744 -0.0347119 -0.138114 -0.0394253 -0.174125 -0.13767 -0.0268215 0.076 -0.151589 -0.0395389 -0.156745 -0.140014 -0.0283737 -0.163706 -0.152529 -0.0120192 -0.168895 -0.153081 0.00273678 -0.171648 -0.125 -0.0366922 0.182878 -0.137897 -0.003561 0.171648 -0.125 -0.0366922 0.151 -0.153035 0.00274206 0.149 -0.151383 -0.0421594 0.149 -0.149899 -0.0463687 -0.0140463 -0.151961 -0.0286631 -0.0234454 -0.15252 -0.0123071 -0.159203 -0.133875 -0.0595758 -0.158568 -0.127994 -0.0808593 -0.150998 -0.133912 -0.0572764 -0.170065 -0.128306 -0.0430742 -0.151034 -0.132626 -0.0803669 -0.015079 -0.136088 -0.0574002 -0.0237962 -0.140782 -0.0306621 -0.170078 -0.152999 0.00574206 -0.179289 -0.138002 0.0118302 -0.13004 -0.152999 0.010953 -0.130281 -0.153263 0.010953 0.130281 -0.153263 0.010953 0.134439 -0.153341 0.0144584 0.160807 -0.152565 -0.0477452 0.173624 -0.156549 0.0177653 0.160799 -0.154526 -0.0412072 -0.00819613 -0.153501 -0.0457395 -0.00806289 -0.152565 -0.0477452 0.160531 -0.153828 -0.0446374 -0.00765945 -0.141249 -0.0696576 -0.0245868 -0.141799 -0.0361688 -0.14753 -0.141005 -0.0317955 -0.148122 -0.144227 -0.027566 -0.159038 -0.155486 -0.0133696 -0.157833 -0.136171 -0.0703194 -0.163341 -0.126966 -0.0830604 -0.165424 -0.138114 -0.0394253 -0.177455 -0.137481 -0.0141919 -0.1792 -0.138 0.00574206 0.181331 -0.137973 0.00274352 -0.151 -0.138 -0.0241917 0.151 -0.138 0.00274206 0.1792 -0.138 0.00574206 0.076 -0.138 0.00274206 0.001 -0.138 0.00274206 -0.148995 -0.138479 -0.0248775 -0.151 -0.138 0.00274206 -0.181241 -0.138001 0.00274205 0.076 -0.138 -0.0573961 0.074 -0.138 -0.0573961 -0.144606 -0.138003 -0.0308478 0.074 -0.138 -0.0306631 0.144657 -0.138 -0.0286631 0.076 -0.138 -0.0306631 0.144604 -0.138 -0.0306631 0.074 -0.138 -0.0286631 0.001 -0.138 -0.0286631 0.139871 -0.156512 0.016633 -0.165237 -0.155549 -0.0114963 0.152445 -0.154855 -0.0318506 -0.127466 -0.156157 0.00626796 0.127466 -0.156157 0.00626796 0.147922 -0.155009 -0.0273085 -0.0204022 -0.155293 -0.019013 -0.00916942 -0.154505 -0.041978 0.14872 -0.154838 -0.0323131 0.151935 -0.155021 -0.0269513 -0.133619 -0.152999 0.0140236 -0.141176 -0.156527 0.0177413 -0.17364 -0.156549 0.0178318 -0.176395 -0.151611 0.0125977 -0.172344 -0.129264 -0.0464337 -0.187068 -0.13842 0.0118007 -0.179423 -0.135628 -0.0176233 -0.175175 -0.136714 -0.0349248 -0.174609 -0.125001 -0.037215 0.13004 -0.152999 0.010953 -0.169018 -0.155827 -0.00340319 -0.170021 -0.152993 0.0139885 -0.166043 -0.127229 -0.0593976 0.145957 -0.124994 -0.0258015 -0.154119 -0.125006 -0.0253682 -0.14539 -0.125011 -0.0261256 -0.154098 -0.12506 -0.0331915 0.1529 -0.127994 -0.031016 0.151338 -0.127669 -0.0267292 0.146748 -0.12798 -0.0287783 0.147497 -0.15421 -0.0319875 -0.146628 -0.128115 -0.0301653 -0.152858 -0.12802 -0.0288288 -0.153511 -0.143357 -0.0286899 -0.151 -0.128 -0.0583322 -0.149 -0.135119 -0.0392371 -0.148722 -0.126708 -0.0358674 0.149 -0.128 -0.0573961 0.149 -0.144205 -0.0573961 0.148457 -0.151728 -0.0354657 0.151 -0.144205 -0.0573961 0.151 -0.151129 -0.0438968 -0.149 -0.152521 -0.0122795 -0.149 -0.138 0.00274206 -0.150999 -0.152432 -0.0124715 -0.151 -0.153035 0.00274206 0.076 -0.138 -0.0286631 0.076 -0.151892 -0.0306631 0.161975 -0.152016 -0.0286897 0.15542 -0.138 -0.0286631 0.15535 -0.138 -0.0306631 0.173526 -0.138 -0.0286631 0.160775 -0.152641 -0.0306547 -0.165197 -0.135558 -0.0344326 0.074 -0.138 0.00274206 0.076 -0.150921 -0.0443146 0.0739999 -0.151907 -0.0306632 -0.075 -0.138 -0.0309016 -0.0740218 -0.138 -0.0286631 -0.074 -0.152521 -0.0122795 -0.076 -0.138 0.00274206 -0.000999997 -0.138 0.00274206 -0.000999996 -0.151961 -0.0286631 0.001 -0.144205 -0.0573961 0.00100003 -0.151892 -0.0306631 0.001 -0.138 -0.0306631 -0.000999997 -0.138 -0.0306631 -0.0754999 -0.130594 -0.083062 -0.0769219 -0.128 -0.0867699 -0.0733394 -0.128 -0.0874202 0.075769 -0.128 -0.0849431 0.0740672 -0.128 -0.0875804 0.179821 -0.139201 0.0118394 0.175846 -0.148279 0.00574206 -0.177621 -0.146468 0.00574445 0.170078 -0.152999 0.00574206 0.171065 -0.152992 0.0140007 -0.159808 -0.133854 -0.0574429 0.151 -0.128 -0.0593961 0.076 -0.144205 -0.0573961 0.001 -0.138 -0.0573961 -0.0233271 -0.133978 -0.0573961 -0.000999997 -0.138 -0.0573961 -0.00668603 -0.144166 -0.057421 -0.149 -0.133978 -0.0573961 0.149 -0.143172 -0.0593961 0.074 -0.138 -0.0593961 -0.0152349 -0.135088 -0.0593959 0.0755912 -0.130552 -0.0832656 0.0705 -0.130434 -0.0905999 0.0742227 -0.134603 -0.0825266 -0.0778763 -0.134468 -0.0827877 -0.448846 -0.0402557 0.125592 -0.448003 -0.0442379 0.123653 -0.453658 -0.0430089 0.120016 -0.44193 -0.0391594 0.123031 -0.445808 -0.0362594 0.122909 -0.456192 -0.0342995 0.123266 -0.454 -0.0351516 0.125231 -0.441935 -0.0363577 0.120211 -0.399745 0.0618939 0.0878693 -0.394152 0.0681494 0.0913444 -0.400139 -0.0636857 0.0901517 -0.394275 -0.067239 0.0928076 -0.349877 0.0677737 0.084417 -0.349379 0.0708539 0.0846277 -0.346418 0.0731606 0.0859717 -0.449876 0.0430222 0.11385 -0.44532 -7.35391e-05 0.118528 -0.454529 0.0353583 0.114951 -0.451519 -0.0314805 0.126043 -0.454159 0.0348698 0.125222 -0.354139 0.070476 0.0852877 -0.4442 0.0370839 0.113694 -0.442059 0.0361343 0.120029 -0.349283 0.063586 0.092674 -0.350008 0.0634601 0.0883473 -0.443284 0.0358784 0.115599 -0.451117 -0.0409221 0.113803 -0.351318 -0.070651 0.0845644 -0.394458 0.0615985 0.0996321 -0.405265 0.0579949 0.101901 -0.350063 0.0731778 0.0948126 -0.274277 0.0705892 0.0963366 -0.272489 0.0643145 0.0938466 -0.349243 0.0648955 0.0947049 -0.274087 -0.0674672 0.0963296 -0.348125 -0.0678896 0.0964655 -0.35059 -0.0746414 0.0924885 -0.273766 -0.072309 0.0955469 -0.346223 -0.0750001 0.0904004 -0.250297 -0.0729223 0.0859717 -0.346276 -0.0731765 0.0860556 -0.250215 -0.074747 0.0887797 -0.349664 -0.0674187 0.0845086 -0.346236 -0.0649521 0.0859717 -0.250274 -0.0630039 0.0887762 -0.346335 -0.0633632 0.0882785 -0.346404 0.0631126 0.0904004 -0.250478 0.0651903 0.0859717 -0.250483 0.0652395 0.0829009 -0.268115 0.0683622 0.084199 -0.348887 0.0650552 0.0859767 -0.260774 0.0731452 0.0857706 -0.25045 0.0751067 0.0887564 -0.255917 -0.0721729 0.0828945 -0.253986 -0.0648406 0.0859523 -0.258337 0.0722803 0.0828977 -0.403832 0.0528013 0.0997538 -0.398856 0.0519929 0.0991347 -0.390297 0.0588528 0.0848315 -0.392225 0.0585332 0.0964734 -0.391882 -0.0609467 0.097232 -0.400364 -0.0606474 0.104559 -0.40525 -0.057866 0.101907 -0.447402 -0.0461197 0.121319 -0.351647 -0.073047 0.0948492 -0.352999 -0.0702596 0.0969328 -0.351741 -0.0656131 0.096576 -0.351506 0.0747008 0.0882889 -0.447508 0.0432313 0.124368 -0.350368 0.0710711 0.0961408 -0.450434 0.0370893 0.125693 -0.445234 0.0317019 0.120772 -0.446055 -0.0315621 0.116644 -0.451384 0.0363794 0.11377 -0.456401 0.0363863 0.117021 -0.456224 -0.0353373 0.116873 -0.457246 -0.0355803 0.120156 -0.447789 0.0334083 0.115069 -0.447194 0.0467014 0.118749 -0.447486 0.0459374 0.121406 -0.446011 0.0361714 0.123055 -0.457368 0.0381782 0.120364 -0.400687 0.0605475 0.104549 -0.350855 0.0746825 0.0926725 -0.34642 0.0751126 0.0904004 -0.349689 0.0668595 0.0960835 -0.445554 -0.046388 0.114434 -0.443829 -0.035273 0.117938 -0.448796 -0.0364 0.114374 -0.447029 -0.0468701 0.118707 -0.351746 -0.0628113 0.0937566 -0.353913 -0.0636815 0.087239 -0.443376 -0.0362236 0.115165 -0.347853 -0.0629796 0.091596 -0.351631 -0.0744097 0.0878381 -0.26261 0.0660603 0.0829101 -0.392946 -0.0578457 0.0869323 -0.395563 -0.0533811 0.0978785 -0.403898 -0.0532012 0.0998778 -0.389804 -0.0589935 0.0778585 -0.39541 -0.0688414 0.0812239 -0.399194 0.0601429 0.077875 -0.39023 0.0689937 0.0786415 -0.394061 0.0773704 0.0795628 -0.398887 0.0697872 0.0781569 -0.390127 0.0591527 0.0778746 -0.399612 -0.0607593 0.077921 -0.398455 -0.0753582 0.0781305 -0.389318 -0.0650382 0.0815979 -0.266709 0.0633073 0.0914342 -0.274174 0.0668755 0.0960011 -0.270122 0.0750606 0.0920921 -0.269007 -0.0748048 0.0919091 -0.269708 -0.0630479 0.0919621 -0.349066 -0.064843 0.0947358 -0.259757 0.0691775 0.0916353 -0.250259 0.0633664 0.0887996 -0.259599 -0.0684801 0.0916324 -0.250493 0.0732358 0.0829001 -0.267053 0.0652166 0.0859282 -0.266872 -0.072896 0.0859282 -0.267891 -0.0705779 0.084514 -0.267819 -0.0674312 0.0845823 -0.250309 -0.0648768 0.0829001 -0.389448 -0.0749579 0.0789272 -0.262984 -0.0663448 0.0829095 -0.198114 -0.0294958 0.015857 -0.201024 -0.0332734 -0.0239721 -0.211868 -0.1241 -0.0149067 -0.205289 -0.0465906 0.0279553 -0.222489 -0.120015 -0.00803651 -0.217956 -0.0616948 -0.0296011 -0.217359 -0.11649 0.0098939 -0.222498 -0.0519112 -0.0193976 -0.207647 -0.0318056 -0.000330432 -0.222446 -0.113516 0.00236893 -0.209014 -0.0686401 -0.0366962 -0.217 -0.10386 -0.0300993 -0.209013 -0.0930606 -0.0365207 -0.222494 -0.110892 -0.0268565 -0.212 -0.0973875 -0.0370605 -0.222494 -0.0659491 -0.0381474 -0.212 -0.05212 -0.0295903 -0.209004 -0.0959775 -0.0397083 -0.198002 -0.0468491 -0.027141 -0.208999 -0.0619984 -0.0387412 -0.208999 -0.118741 -0.0180015 -0.199563 -0.0962117 0.0501307 -0.197933 -0.079143 0.0527387 -0.197775 -0.0458464 0.0399479 -0.197949 -0.0332948 0.0248262 -0.216499 -0.0445333 0.0387494 -0.211996 -0.0292642 0.0157895 -0.198232 -0.0293027 -0.0154523 -0.197906 -0.0367452 -0.0298292 -0.208975 -0.0641356 -0.0503242 -0.196915 -0.113738 -0.0402611 -0.212 -0.119012 -0.0353368 -0.212 -0.0805809 -0.0527054 -0.219569 -0.120539 0.0232384 -0.211949 -0.130388 0.0155956 -0.211995 -0.0799757 0.0525709 -0.206449 -0.063993 0.0503603 -0.211998 -0.121801 0.0326654 -0.208984 -0.0800139 0.0437041 -0.197943 -0.0965874 0.0397436 -0.19807 -0.0649222 0.0449951 -0.197639 -0.122343 0.0310046 -0.1976 -0.102261 -0.0472914 -0.197069 -0.121385 -0.0322932 -0.19806 -0.126774 -0.0239973 -0.197079 -0.0535288 -0.0456224 -0.205605 -0.0452037 -0.0352815 -0.205517 -0.0793173 0.0494147 -0.208282 -0.107673 -0.0332397 -0.205706 -0.0798188 -0.0491597 -0.198416 -0.0530783 -0.0332631 -0.208767 -0.0530366 0.0331983 -0.198415 -0.0755343 0.0426701 -0.208753 -0.123327 -0.00170013 -0.198003 -0.122714 0.00426941 -0.212 -0.0275221 -0.00347578 -0.212001 -0.0427741 0.0168978 -0.211999 -0.0958016 -0.0503378 -0.212 -0.0490734 0.0264023 -0.212 -0.064692 -0.0376635 -0.212 -0.0588872 -0.0425266 -0.212 -0.0793315 -0.0406501 -0.212 -0.0395067 0.00361937 -0.212 -0.0417682 -0.0362209 -0.212 -0.104824 -0.0467092 -0.212 -0.112036 -0.0250308 -0.212 -0.121097 -0.0201466 -0.212 -0.120588 -0.00673258 -0.212 -0.13256 -0.0020261 -0.212 -0.119036 0.011369 -0.222512 -0.119247 0.0113287 -0.219453 -0.0459372 0.00613354 -0.21995 -0.102632 -0.027565 -0.219058 -0.0882343 -0.0331468 -0.220423 -0.11547 -0.00252456 -0.220513 -0.11154 0.0148573 -0.217783 -0.10884 0.0169503 -0.218381 -0.110301 -0.0161957 -0.219327 -0.0978776 0.0299753 -0.2188 -0.0681722 0.0332613 -0.217646 -0.0515936 0.0199474 -0.217302 -0.0882389 -0.0372337 -0.2172 -0.0478484 -0.0209738 -0.217123 -0.0418316 -0.00259807 -0.209744 -0.043374 0.0107426 -0.217001 -0.0470149 0.0191948 -0.217001 -0.0565683 0.030125 -0.217009 -0.118118 -0.0022001 -0.217212 -0.1144 -0.0164054 -0.21727 -0.0669751 -0.0365079 -0.216958 -0.105911 0.0283321 -0.217001 -0.0904951 0.0366949 -0.209007 -0.0928349 0.0360087 -0.209007 -0.0763566 0.0382853 -0.217221 -0.0728694 0.0377208 -0.209014 -0.0421334 -0.00625114 -0.208999 -0.0980019 0.038741 -0.209005 -0.120479 0.0134131 -0.20901 -0.117861 0.00749824 -0.209014 -0.114256 -0.0181895 -0.209014 -0.0510235 -0.0252195 -0.209005 -0.0395213 -0.0134131 -0.208999 -0.0412252 0.0179077 -0.209 -0.0623325 0.0388636 -0.211999 -0.0642647 0.0378548 -0.212 -0.0821896 0.040601 -0.212001 -0.0949745 0.0433087 -0.212 -0.100977 0.0352136 -0.222403 -0.0994889 0.0276405 -0.222476 -0.0394834 0.00548108 -0.222262 -0.0732745 -0.0336498 -0.222494 -0.0886748 -0.040409 -0.222472 -0.101943 -0.0268898 -0.222494 -0.0410891 -0.0117734 -0.222494 -0.0504077 -0.0282821 -0.220016 -0.0577256 -0.0271469 -0.220626 -0.0471917 -0.0128056 -0.221099 -0.0543721 0.0243836 -0.222428 -0.0473258 0.00766267 -0.221178 -0.0824631 0.0342231 -0.212 -0.055248 0.0322688 -0.212 -0.112265 0.024768 -0.208893 -0.0373383 0.00438778 -0.208825 -0.0464017 -0.0267254 -0.198196 -0.0497223 0.0348545 -0.205622 -0.115323 0.0353667 -0.208857 -0.113627 0.026677 -0.205515 -0.127949 0.000497507 -0.198216 -0.116171 -0.0328696 -0.198328 -0.0844647 -0.0426711 -0.208758 -0.0754956 -0.0426191 -0.209004 -0.107858 0.0265617 -0.209007 -0.054176 0.0291002 -0.222369 -0.0662633 0.0318891 -0.217517 -0.0863724 0.0341382 -0.217531 -0.0462699 -0.00396506 -0.222505 -0.11261 0.0252041 -0.222494 -0.0918815 0.0391844 -0.222494 -0.0732357 0.0400905 -0.222557 -0.0551213 0.0326415 -0.222525 -0.0486679 0.026629 -0.21749 -0.115174 0.0149481 -0.21668 -0.123529 0.0292415 -0.211998 -0.048036 0.0416535 -0.212597 -0.0398739 0.0341769 -0.198097 -0.0399313 0.0158203 -0.197975 -0.0433654 -0.0373291 -0.197716 -0.131457 0.0112587 -0.197993 -0.0784173 0.0496756 -0.197879 -0.113204 0.0407355 -0.197914 -0.0802805 -0.0526295 -0.198799 -0.0370441 -0.00361847 -0.198182 -0.0952786 -0.0434756 -0.197998 -0.046331 0.0270497 -0.196922 -0.0991989 0.0487788 -0.19804 -0.120391 0.0149086 -0.197996 -0.113887 0.0276487 -0.198321 -0.107329 0.0336487 -0.198 -0.130027 -0.000899661 -0.198006 -0.121585 -0.0108136 -0.198587 -0.0847988 0.0427049 -0.198944 -0.113261 -0.0269192 -0.198138 -0.114525 -0.0371573 -0.198 -0.107007 -0.0332581 -0.198148 -0.0981736 -0.0390974 -0.198003 -0.0751379 -0.0425823 -0.198111 -0.0620762 -0.0392035 -0.198003 -0.037411 0.00484043 -0.198001 -0.0299244 -0.000824687 -0.19812 -0.040597 -0.0172174 -0.212003 -0.100805 0.0419362 -0.198037 -0.0567697 0.0469867 -0.198032 -0.0618774 0.0390322 -0.212001 -0.0648615 0.045349 -0.200986 -0.129812 0.0166617 -0.212339 -0.12112 0.0179819 -0.212 -0.0300753 -0.0160811 -0.212 -0.0418338 -0.0154545 -0.212 -0.033663 -0.0245472 -0.198036 -0.0353054 -0.0157678 -0.212 -0.0650998 -0.0437368 -0.19824 -0.0644851 -0.0455415 -0.20656 -0.0556315 -0.046868 -0.211999 -0.0950216 -0.0431143 -0.198089 -0.122697 -0.020156 -0.212 -0.0372969 0.0151887 -0.211904 -0.0561025 0.0468897 -0.211997 -0.0962329 0.0503716 -0.206333 -0.104144 0.0468102 -0.203468 -0.130044 -0.0159926 -0.212 -0.12666 -0.0241589 -0.198033 -0.0961678 -0.0502661 -0.198167 -0.125811 0.0224252 -0.191003 -0.0332233 0.024509 -0.169495 -0.0282167 0.0079859 -0.1695 -0.0547325 0.0460589 -0.164006 -0.123193 0.0117679 -0.164066 -0.0604392 0.0406343 -0.177425 -0.0807832 -0.0088635 -0.196993 -0.0321403 -0.0198388 -0.196996 -0.0989426 -0.0380456 -0.196959 -0.121776 -0.00781091 -0.162492 -0.1027 -0.0358213 -0.191022 -0.0878894 0.0522271 -0.193431 -0.0709432 0.0518322 -0.193603 -0.0367104 0.0304713 -0.193666 -0.0496617 0.0433449 -0.191012 -0.0601386 0.048138 -0.191004 -0.0998736 0.0484095 -0.193855 -0.110486 0.0433058 -0.180125 -0.0849763 0.0213949 -0.170425 -0.0986183 0.0119494 -0.169938 -0.0585839 0.00599556 -0.1692 -0.0870527 0.0212036 -0.162533 -0.0824968 0.0295056 -0.162512 -0.10548 0.0142258 -0.169169 -0.0674873 0.0188834 -0.162534 -0.0568934 -0.0357955 -0.163025 -0.115853 -0.0226956 -0.162516 -0.122147 -0.0047746 -0.196997 -0.0463813 -0.0262672 -0.170696 -0.119543 -0.0154546 -0.160083 -0.0914416 -0.0248112 -0.160916 -0.103142 -0.0134008 -0.168155 -0.0599481 -0.00220316 -0.160055 -0.106584 -0.00543981 -0.167412 -0.0709505 -0.0187397 -0.168124 -0.0921453 -0.0165056 -0.177602 -0.0888149 0.00281524 -0.180414 -0.0847351 -0.0105661 -0.164018 -0.0421563 0.0245008 -0.16404 -0.113838 0.0297864 -0.164012 -0.124141 -0.00913087 -0.191 -0.0769522 0.0444946 -0.191002 -0.10998 0.0332722 -0.1815 -0.0787977 0.0453986 -0.177501 -0.108744 0.0358556 -0.171501 -0.108744 0.0358555 -0.1755 -0.124395 -0.00722923 -0.183 -0.0835354 0.053282 -0.1815 -0.0974735 0.0515857 -0.18301 -0.0496138 -0.0426833 -0.1815 -0.121452 0.0332807 -0.183 -0.0548178 0.0464747 -0.183 -0.132846 0.00275803 -0.182994 -0.103436 -0.0380712 -0.177497 -0.132999 0.00264182 -0.1715 -0.105298 0.0466156 -0.1695 -0.0320579 -0.0232227 -0.171229 -0.121639 0.0328181 -0.1755 -0.11394 -0.0295173 -0.1715 -0.115504 -0.0283182 -0.1715 -0.0350658 0.00971233 -0.1815 -0.11394 -0.0295173 -0.1815 -0.0608975 -0.0407218 -0.1815 -0.0398967 -0.0213122 -0.191 -0.104139 -0.0375872 -0.160006 -0.110905 -0.0460744 -0.159999 -0.132443 0.00891458 -0.16 -0.136473 -0.00559456 -0.16 -0.133098 -0.00113098 -0.16 -0.122319 0.0534889 -0.16 -0.0415 0.0535 -0.16 -0.0799782 0.0592905 -0.16 -0.0399482 0.0592951 -0.159999 -0.0275438 0.0451672 -0.169476 -0.113116 -0.0305593 -0.164019 -0.0584207 -0.0406859 -0.1695 -0.0359915 -0.00929621 -0.180475 -0.0807723 0.0121052 -0.182552 -0.0910812 0.00263792 -0.182364 -0.0734025 -0.0080189 -0.1774 -0.066918 -0.0150594 -0.177603 -0.0742778 0.0074794 -0.177401 -0.0825214 0.0198542 -0.177399 -0.0972693 -0.0101217 -0.177401 -0.0833536 -0.019751 -0.177398 -0.098239 0.0088893 -0.177399 -0.0686752 0.0160831 -0.177402 -0.0597281 0.00229915 -0.168167 -0.100037 0.00221998 -0.167896 -0.0885525 0.0184038 -0.167814 -0.0679549 0.0167507 -0.160143 -0.0535115 0.00899183 -0.16 -0.0483893 0.051 -0.160005 -0.108192 0.0324973 -0.160002 -0.0651099 0.020765 -0.16 -0.0360507 -0.00907125 -0.16 -0.0493754 -0.00650312 -0.159991 -0.0787873 -0.0279448 -0.160552 -0.0670229 -0.0352587 -0.159974 -0.120357 -0.0185453 -0.160207 -0.0804904 0.0269089 -0.160587 -0.0565794 -0.0254046 -0.159988 -0.0527272 -0.0354253 -0.197006 -0.0327785 0.0248351 -0.1965 -0.0375 0 -0.196995 -0.0403689 -0.0153514 -0.196981 -0.0728503 -0.0420603 -0.196996 -0.0581401 -0.0366378 -0.196996 -0.109257 -0.0310518 -0.197 -0.127704 -0.0198858 -0.196994 -0.118498 -0.0183882 -0.197153 -0.132354 -0.00594968 -0.197 -0.0382215 -0.00780176 -0.197004 -0.035725 0.0160821 -0.197002 -0.0582394 0.0479727 -0.197 -0.0771459 0.052527 -0.197 -0.119921 0.034096 -0.196994 -0.128081 0.0198677 -0.196981 -0.0885294 -0.0418023 -0.197002 -0.0585793 -0.0482245 -0.196919 -0.0277016 0.00761878 -0.170733 -0.122361 -0.00466609 -0.197 -0.121779 0.00780173 -0.196995 -0.119631 0.0153514 -0.196959 -0.0382235 0.00781092 -0.162545 -0.0961164 0.0394443 -0.170743 -0.072857 0.0420156 -0.170579 -0.0487255 0.0287123 -0.170675 -0.0388286 -0.0110144 -0.162512 -0.0424092 -0.0198368 -0.170673 -0.0485476 -0.0285167 -0.162533 -0.0679588 -0.0406695 -0.162518 -0.0795631 -0.0426287 -0.170858 -0.10181 -0.0366157 -0.170698 -0.0914492 -0.0408822 -0.170827 -0.111319 -0.0286564 -0.170693 -0.109229 0.0310202 -0.163139 -0.121137 0.0111555 -0.162548 -0.115014 0.0242135 -0.162551 -0.0580319 0.0365203 -0.170618 -0.0421695 0.0196384 -0.163061 -0.0376392 0.0046112 -0.162498 -0.108538 -0.00583551 -0.162517 -0.051958 0.0102784 -0.162501 -0.0952225 -0.0246768 -0.162528 -0.0755315 -0.0289949 -0.162514 -0.0546947 -0.0145242 -0.169262 -0.101024 -0.00859508 -0.169175 -0.0881566 -0.0205304 -0.169161 -0.0729146 -0.0211923 -0.169556 -0.0605339 -0.0105085 -0.179508 -0.058895 -0.00614623 -0.177807 -0.069145 -0.0193493 -0.179315 -0.0831264 -0.0215031 -0.180401 -0.0976331 -0.00859807 -0.177787 -0.0956805 -0.0159058 -0.18041 -0.0703579 -0.0180404 -0.180406 -0.0693863 -0.0047256 -0.180136 -0.0688672 0.0187032 -0.180405 -0.0716499 0.00788551 -0.179655 -0.10192 0.000333716 -0.197 -0.082854 -0.052527 -0.196707 -0.0287505 -0.0092974 -0.193675 -0.131872 -0.00910922 -0.196922 -0.109921 -0.0438044 -0.196542 -0.12272 -0.031312 -0.191005 -0.0596873 -0.0482944 -0.197 -0.0369846 -0.0309326 -0.191043 -0.0276523 -0.00767119 -0.190997 -0.0392124 0.0203039 -0.191 -0.121175 -0.0191597 -0.191003 -0.064406 -0.0426991 -0.191 -0.0423215 -0.0245662 -0.191 -0.0355937 -0.00485429 -0.191001 -0.0607532 0.0404731 -0.191 -0.0958524 0.0419336 -0.191 -0.119607 0.0206817 -0.191375 -0.123554 0.0298983 -0.191 -0.124406 0.00485427 -0.191 -0.0889309 -0.043769 -0.190986 -0.12767 0.0195676 -0.161862 -0.081541 0.0425428 -0.16 -0.0693421 0.0379277 -0.16103 -0.0802787 0.0317709 -0.160067 -0.0930218 0.0369242 -0.160628 -0.117347 0.0150023 -0.160492 -0.103837 0.0131029 -0.161002 -0.039668 0.012819 -0.16087 -0.0564081 0.016973 -0.160944 -0.0399925 -0.0113262 -0.160756 -0.0907491 -0.0331177 -0.161043 -0.113726 -0.0227556 -0.160327 -0.0561194 -0.0127341 -0.162514 -0.043131 0.0206291 -0.184079 -0.0695528 0.00392393 -0.196997 -0.113619 0.0262672 -0.196996 -0.10186 0.0366378 -0.196981 -0.0871497 0.0420603 -0.196981 -0.0714705 0.0418023 -0.196996 -0.0610574 0.0380456 -0.196996 -0.050743 0.0310518 -0.196993 -0.0415024 0.0183881 -0.196998 -0.100028 -0.0479946 -0.190988 -0.0323525 -0.0195457 -0.197002 -0.101357 0.0482795 -0.160124 -0.0930315 0.0234034 -0.162507 -0.0709744 0.0276149 -0.16 -0.0300151 0.0634959 -0.164 -0.0335 0.0635 -0.16 -0.1265 0.0635 -0.16 -0.0235024 0.0557731 -0.160001 -0.0235049 -0.00329814 -0.16 -0.0295176 -0.0268668 -0.16 -0.0976113 -0.0538685 -0.160004 -0.0801198 -0.0561903 -0.16 -0.0608111 -0.0533268 -0.16 -0.127584 -0.0322512 -0.164 -0.134251 -0.0174378 -0.163999 -0.126589 0.044052 -0.163013 -0.0457362 0.0358865 -0.164 -0.0480893 0.0486067 -0.16402 -0.0345856 -0.00365125 -0.163998 -0.0739988 -0.0571005 -0.164001 -0.0804406 -0.0519826 -0.163992 -0.109053 -0.0493176 -0.164 -0.1365 0 -0.164 -0.122211 -0.0378266 -0.164 -0.0326962 -0.0325578 -0.164 -0.0235135 -0.00551592 -0.164 -0.040009 0.0593235 -0.163969 -0.0379619 0.0480785 -0.164003 -0.0927379 0.0433073 -0.163999 -0.131097 0.0634881 -0.164 -0.110136 0.0445366 -0.164 -0.136515 0.0450842 -0.160007 -0.134335 0.0601017 -0.164 -0.0235299 0.0586291 -0.157 -0.036 0.045 -0.159944 -0.0428564 -0.0289012 -0.16 -0.0335 0 -0.159968 -0.125311 -0.0142329 -0.160001 -0.0798288 -0.0479881 -0.157 -0.0388769 0.0509925 -0.16 -0.111611 0.051 -0.161087 -0.122785 0.048602 -0.15697 -0.123746 0.0509514 -0.160005 -0.101238 -0.039324 -0.159128 -0.11293 -0.0318111 -0.160009 -0.124014 0.0345498 -0.158485 -0.0573457 -0.0402345 -0.159998 -0.0756215 -0.0441805 -0.16 -0.033551 0.0489861 -0.157019 -0.126467 0.0492777 -0.16 -0.1265 0.0455 -0.158497 -0.035549 -0.0109078 -0.158565 -0.126622 0.00808937 -0.158874 -0.124011 -0.00275107 -0.157258 -0.0339787 0.0120742 -0.157224 -0.093209 -0.0439085 -0.156895 -0.0682691 -0.0439055 -0.157015 -0.118468 0.0534948 -0.157008 -0.0336125 0.0534309 -0.160004 -0.0475746 -0.0457009 -0.164015 -0.048467 -0.0457653 -0.16 -0.0273786 0.00886163 -0.164 -0.0274306 0.00900883 -0.164 -0.132536 0.00887563 -0.163999 -0.0276647 0.0452808 -0.159997 -0.136458 0.0454992 -0.164 -0.0801516 0.0587439 -0.16 -0.119926 0.059323 -0.164 -0.119854 0.0596382 -0.164008 -0.0927324 -0.0439276 -0.164005 -0.107328 -0.0385309 -0.160039 -0.027722 -0.000212424 -0.1815 -0.0748001 -0.0522308 -0.181498 -0.0281507 0.00850888 -0.1815 -0.0356051 0.00722924 -0.181508 -0.0512196 -0.0441684 -0.1815 -0.0320579 -0.0232227 -0.181505 -0.0489208 0.0331007 -0.1815 -0.054995 0.0467772 -0.181498 -0.0878431 -0.0448358 -0.182539 -0.0946513 -0.0512611 -0.181503 -0.112831 -0.0419363 -0.1815 -0.121551 0.0172244 -0.1815 -0.124395 -0.00722923 -0.181519 -0.133407 0.0020037 -0.175495 -0.0282167 0.0079859 -0.175498 -0.0775278 -0.0457656 -0.1755 -0.0356051 0.00722924 -0.175496 -0.13347 -0.00309953 -0.1755 -0.057113 -0.0383624 -0.17551 -0.0512159 -0.0441992 -0.1755 -0.0320579 -0.0232227 -0.1755 -0.0398967 -0.0213122 -0.1755 -0.105323 0.0463979 -0.1755 -0.0766518 0.0532715 -0.1755 -0.0787977 0.0453986 -0.175502 -0.0490065 0.0331504 -0.1755 -0.0547325 0.0460589 -0.175496 -0.104093 -0.0395173 -0.1755 -0.121551 0.0172244 -0.177499 -0.0958761 -0.0510186 -0.177501 -0.0731287 -0.0450887 -0.1775 -0.115504 -0.0283182 -0.177499 -0.12075 -0.0359185 -0.176019 -0.0384163 0.0329343 -0.177501 -0.101858 0.0498831 -0.177499 -0.052725 0.0357734 -0.1775 -0.0430466 -0.0263993 -0.177499 -0.0564981 0.0479155 -0.177504 -0.0284269 0.0111314 -0.177505 -0.125638 0.00606594 -0.1775 -0.0350658 0.00971233 -0.1775 -0.0296526 -0.0173882 -0.1775 -0.0768978 0.0448725 -0.1695 -0.0368388 0.0115149 -0.169496 -0.13347 -0.00309953 -0.16951 -0.0512159 -0.0441992 -0.169496 -0.107207 0.0358091 -0.169424 -0.0960942 -0.0415444 -0.169485 -0.078901 0.0451631 -0.1695 -0.0766518 0.0532715 -0.169477 -0.0489394 -0.0333957 -0.1695 -0.121551 0.0172245 -0.1695 -0.124395 -0.00722925 -0.1715 -0.0430466 -0.0263993 -0.171501 -0.0731288 -0.0450887 -0.171497 -0.132999 0.00264182 -0.170019 -0.0384163 0.0329343 -0.171514 -0.049534 -0.0426699 -0.171504 -0.0284269 0.0111314 -0.171501 -0.0726811 -0.0524512 -0.171505 -0.125638 0.00606596 -0.1715 -0.0768978 0.0448725 -0.171498 -0.0639828 0.0518434 -0.1715 -0.0296526 -0.0173882 -0.171499 -0.052725 0.0357734 -0.169502 -0.0489312 0.0330894 -0.1695 -0.130721 0.015266 -0.171499 -0.12075 -0.0359185 -0.1715 -0.100515 -0.0402145 -0.171499 -0.0958761 -0.0510186 -0.169498 -0.0774549 -0.0456012 -0.1755 -0.130721 0.0152659 -0.175501 -0.117418 -0.0379683 -0.1775 -0.100515 -0.0402145 -0.175499 -0.0872594 -0.052449 -0.177501 -0.0726811 -0.0524512 -0.175496 -0.107327 0.0357135 -0.177514 -0.049534 -0.0426699 -0.177229 -0.121639 0.0328181 -0.1695 -0.105323 0.0463979 -0.169499 -0.0872594 -0.052449 -0.169499 -0.113134 -0.041781 -0.191019 -0.124545 -0.0293354 -0.191003 -0.0997172 -0.0479912 -0.193431 -0.0890568 -0.0518322 -0.191029 -0.0719819 -0.0521986 -0.191395 -0.0364463 -0.0299026 -0.194123 -0.0890585 0.0517476 -0.191167 -0.132164 0.00893512 -0.194123 -0.0709415 -0.0517476 -0.193843 -0.0495119 -0.0433081 -0.160027 -0.0359975 0.0423229 -0.16002 -0.0516236 0.0383587 -0.160897 -0.108716 0.0447017 -0.163979 -0.115804 0.0356559 -0.191366 -0.0347148 0.0187962 -0.183 -0.124542 0.00338801 -0.18299 -0.118797 0.0227396 -0.183 -0.120103 -0.0213122 -0.182999 -0.122 -0.0335233 -0.181969 -0.038375 0.0325035 -0.182998 -0.0284285 0.0109455 -0.182995 -0.039435 0.0200436 -0.183 -0.0460604 -0.0295173 -0.182998 -0.0829369 -0.0448959 -0.183001 -0.0727406 -0.052449 -0.183 -0.0631786 -0.0413827 -0.183002 -0.105318 0.045373 -0.181688 -0.105832 0.0365732 -0.182994 -0.126196 0.0278076 -0.182993 -0.0554857 0.0374497 -0.183003 -0.0811663 0.0454584 -0.183 -0.0297503 -0.0175979 -0.183 -0.0356051 -0.00722924 0.193431 -0.0890568 0.0518322 0.175495 -0.131783 0.00798592 0.177504 -0.131573 0.0111314 0.169495 -0.131783 0.00798592 0.16 -0.0269016 -0.00113098 0.164006 -0.0368066 0.011768 0.164003 -0.0672621 0.0433074 0.16404 -0.105055 0.0383198 0.180674 -0.0915058 0.00256121 0.163138 -0.0582564 -0.0366401 0.160944 -0.120007 -0.0113262 0.160008 -0.103254 -0.0125906 0.193603 -0.12329 0.0304713 0.191012 -0.0998614 0.048138 0.191004 -0.0601264 0.0484095 0.193855 -0.0495143 0.0433058 0.169938 -0.101416 0.00599552 0.178104 -0.0909829 0.0191915 0.177905 -0.0747696 0.0216408 0.18021 -0.0634853 0.0140943 0.162509 -0.105746 0.0137462 0.169556 -0.0605339 0.0105085 0.1692 -0.0729473 0.0212036 0.169169 -0.0925127 0.0188834 0.163058 -0.0405018 -0.0155243 0.162503 -0.0377134 0.00078023 0.196997 -0.113619 -0.0262672 0.169858 -0.096008 -0.0395059 0.196996 -0.10186 -0.0366378 0.170681 -0.0439591 -0.022441 0.177665 -0.037477 -0.00360403 0.196959 -0.0382235 -0.00781092 0.162803 -0.101299 -0.0142924 0.16004 -0.0834624 -0.0271083 0.160044 -0.0533048 -0.00431557 0.167921 -0.0886222 -0.018346 0.1774 -0.093082 -0.0150594 0.168124 -0.0678546 -0.0165056 0.177401 -0.0766464 -0.019751 0.1695 -0.038449 0.0172245 0.1695 -0.0356051 -0.00722924 0.190997 -0.120788 0.0203039 0.181688 -0.0541678 0.0365732 0.18299 -0.0412026 0.0227396 0.1815 -0.118785 0.0227784 0.1815 -0.0725166 0.0440396 0.1815 -0.0356051 -0.00722924 0.1775 -0.0350658 -0.00971233 0.1715 -0.0412145 0.0227784 0.1755 -0.0356051 -0.00722924 0.169496 -0.0265304 -0.00309948 0.163973 -0.0412323 0.0364178 0.181501 -0.124569 0.00410677 0.181495 -0.126191 0.0275371 0.182999 -0.0379996 -0.0335234 0.1815 -0.0877735 0.0523927 0.183 -0.0764645 0.053282 0.181501 -0.133263 0.00190955 0.1815 -0.0385481 0.0332807 0.183 -0.105182 0.0464747 0.183001 -0.120841 0.0326407 0.181503 -0.0471691 -0.0419363 0.163621 -0.0385962 0.0491609 0.1755 -0.0833481 0.0532715 0.1775 -0.0720594 0.0523847 0.17551 -0.108784 -0.0441992 0.1775 -0.130347 -0.0173882 0.177229 -0.0383613 0.0328181 0.1715 -0.0720594 0.0523847 0.1715 -0.130347 -0.0173882 0.1755 -0.0460604 -0.0295173 0.171501 -0.0845977 -0.0458233 0.1715 -0.11975 -0.0230944 0.1775 -0.0933172 -0.042963 0.1775 -0.11975 -0.0230944 0.1815 -0.120103 -0.0213122 0.191 -0.117679 -0.0245662 0.191 -0.124406 -0.00485427 0.16 -0.0623887 -0.0538684 0.160004 -0.0798802 -0.0561903 0.160008 -0.13299 0.0454836 0.159999 -0.0400161 0.0594967 0.16 -0.1185 0.0535 0.16 -0.0800218 0.0592905 0.160003 -0.13192 0.00892533 0.182111 -0.0689722 0.00164506 0.180651 -0.0835126 0.0107632 0.18063 -0.0865006 -0.0091547 0.177403 -0.0751308 0.0190773 0.177478 -0.0754326 -0.00835224 0.177401 -0.0611139 -0.0078996 0.1774 -0.0631815 0.0107326 0.167896 -0.0714475 0.0184038 0.177398 -0.0883308 0.0184308 0.177402 -0.100272 0.00229913 0.168167 -0.059963 0.00222 0.168164 -0.0920658 0.0165086 0.160158 -0.10298 0.0142228 0.160409 -0.0849408 0.0271981 0.167861 -0.100408 -0.0015368 0.160133 -0.0755932 -0.044854 0.160552 -0.0929771 -0.0352587 0.160083 -0.0685584 -0.0248112 0.160004 -0.104832 -0.029197 0.197 -0.0400787 0.034096 0.197006 -0.127222 0.0248351 0.1965 -0.1225 0 0.196995 -0.119631 -0.0153514 0.196996 -0.0610574 -0.0380456 0.196542 -0.0372801 -0.031312 0.196996 -0.050743 -0.0310518 0.196994 -0.0415024 -0.0183881 0.197004 -0.0321237 -0.0195467 0.197132 -0.0276014 0.000291713 0.196877 -0.132073 0.00888273 0.197002 -0.101761 0.0479727 0.197 -0.082854 0.052527 0.196994 -0.0319187 0.0198677 0.196981 -0.0714705 -0.0418023 0.196981 -0.0871497 -0.0420603 0.196993 -0.12786 -0.0198388 0.197 -0.123015 -0.0309326 0.197 -0.121779 -0.00780173 0.196996 -0.0989426 0.0380456 0.170623 -0.0609794 0.0379532 0.170808 -0.11948 0.015585 0.16253 -0.122379 0.00451686 0.170872 -0.121168 -0.0110142 0.163111 -0.11765 -0.0197392 0.170642 -0.111509 -0.0284476 0.16255 -0.104592 -0.0346962 0.170721 -0.0807013 -0.0426191 0.170683 -0.0685709 -0.0408868 0.162543 -0.0477337 -0.0276732 0.170673 -0.0485476 0.0285167 0.170819 -0.0382305 0.00753303 0.170827 -0.0403275 0.0150898 0.16254 -0.0429131 0.020664 0.170635 -0.0758801 0.0422534 0.170677 -0.0871281 0.0420196 0.170822 -0.101823 0.0366068 0.170704 -0.113577 0.0262535 0.1625 -0.0622065 0.0225174 0.162523 -0.117907 0.0192732 0.16251 -0.0519636 0.00859662 0.162539 -0.0833122 0.0298627 0.162481 -0.0774254 -0.0422728 0.162513 -0.107694 -0.00977808 0.162499 -0.053583 -0.0117515 0.162502 -0.0943881 -0.025296 0.169154 -0.058047 -0.00261738 0.177828 -0.0642198 -0.0157585 0.169466 -0.0663467 -0.0180251 0.169207 -0.0882795 -0.0205702 0.17791 -0.0958605 -0.0156672 0.169556 -0.0994661 -0.0105085 0.180092 -0.0581737 -6.138e-05 0.180414 -0.0909342 0.0171872 0.193431 -0.0709432 -0.0518322 0.197 -0.0771459 -0.052527 0.196707 -0.131249 -0.0092974 0.196922 -0.050079 -0.0438044 0.191005 -0.100313 -0.0482944 0.191043 -0.132348 -0.00767118 0.191 -0.0388249 -0.0191597 0.191 -0.0710691 -0.043769 0.191003 -0.095594 -0.0426991 0.191022 -0.0721106 0.0522271 0.191003 -0.126777 0.024509 0.191001 -0.0992468 0.040473 0.191 -0.0830478 0.0444946 0.191 -0.0641476 0.0419336 0.191002 -0.0500202 0.0332722 0.191 -0.0403931 0.0206817 0.191375 -0.0364459 0.0298983 0.191 -0.0355937 0.00485429 0.191 -0.055861 -0.0375872 0.191029 -0.0880181 -0.0521986 0.190986 -0.0323301 0.0195676 0.180326 -0.0776449 -0.0217911 0.180246 -0.101098 -0.00424441 0.16 -0.0906579 0.0379277 0.160064 -0.0669375 0.0368249 0.160018 -0.0547891 0.0111383 0.161006 -0.0440431 0.00638664 0.160197 -0.0534227 0.0299322 0.161002 -0.117205 0.00597652 0.160497 -0.105771 0.029866 0.160001 -0.120618 0.010112 0.161003 -0.104555 -0.0285584 0.161 -0.110954 -0.00688538 0.160993 -0.0699556 -0.0325041 0.160957 -0.0400313 -0.0138521 0.160885 -0.057121 -0.0148254 0.162508 -0.0709808 -0.0280808 0.163361 -0.0542338 0.0336866 0.162511 -0.0795247 0.0421602 0.162817 -0.0982565 0.0387501 0.16251 -0.0679214 0.040682 0.180652 -0.0725955 -0.00907659 0.197 -0.0382215 0.00780176 0.196995 -0.0403689 0.0153514 0.196997 -0.0463813 0.0262672 0.196996 -0.0581401 0.0366378 0.196981 -0.0728503 0.0420603 0.196981 -0.0885294 0.0418023 0.196996 -0.109257 0.0310518 0.196993 -0.118498 0.0183882 0.196959 -0.121776 0.00781091 0.196998 -0.0599716 -0.0479946 0.197002 -0.101421 -0.0482245 0.190988 -0.127648 -0.0195457 0.197002 -0.0586432 0.0482795 0.160124 -0.0669685 0.0234034 0.161064 -0.0817861 0.0365276 0.180561 -0.0723778 0.00775192 0.177562 -0.0844987 0.00815994 0.164 -0.0235 0 0.16 -0.131612 0.06349 0.16 -0.0335 0.0635 0.16 -0.1365 0.0535 0.164 -0.127304 -0.0325578 0.16 -0.136476 -0.00508414 0.16 -0.0991889 -0.0533269 0.16 -0.130482 -0.0268668 0.16 -0.0324162 -0.0322512 0.16 -0.0235267 -0.00559457 0.164 -0.0257493 -0.0174378 0.16404 -0.0461622 0.0297864 0.164 -0.1265 0.0635 0.164 -0.133229 0.00840901 0.163998 -0.0860012 -0.0571005 0.164015 -0.111533 -0.0457653 0.164001 -0.0795594 -0.0519826 0.163992 -0.0509474 -0.0493176 0.164001 -0.111211 0.0480045 0.164 -0.0377895 -0.0378266 0.164008 -0.120296 -0.0195041 0.164 -0.136486 -0.00551593 0.164 -0.12461 0.0413178 0.164007 -0.120134 0.0592747 0.163999 -0.0289028 0.0634881 0.164 -0.0401185 0.0594108 0.164 -0.0498638 0.0445366 0.164 -0.0235697 0.0454209 0.160007 -0.0256652 0.0601017 0.164 -0.13647 0.0586291 0.157258 -0.126021 0.0120742 0.157 -0.118 0.051 0.15697 -0.036254 0.0509514 0.157019 -0.126495 0.0476032 0.157008 -0.121381 0.0534838 0.16 -0.1265 0 0.159968 -0.0346895 -0.0142329 0.160001 -0.0801712 -0.0479881 0.16 -0.111611 0.051 0.160014 -0.0360253 0.0347408 0.159591 -0.0470702 -0.0309292 0.159988 -0.107273 -0.0354253 0.156998 -0.0730844 -0.0449328 0.16 -0.123949 -0.00907126 0.16 -0.126449 0.0489861 0.16 -0.0376812 0.0534889 0.16 -0.0335 0.0455 0.158485 -0.102654 -0.0402344 0.159944 -0.117144 -0.0289012 0.158497 -0.124451 -0.0109078 0.157907 -0.0596815 -0.0404493 0.157 -0.124 0.045 0.158565 -0.033378 0.00808941 0.159859 -0.0361353 -0.00971515 0.156895 -0.0917309 -0.0439055 0.157019 -0.0335327 0.0492777 0.157015 -0.0415325 0.0534948 0.160004 -0.112425 -0.0457009 0.160006 -0.0490946 -0.0460744 0.164 -0.0500193 -0.0429377 0.164 -0.0274641 0.00887563 0.159999 -0.0275574 0.00891458 0.159997 -0.0235417 0.0454992 0.164 -0.0798484 0.0587439 0.160001 -0.120251 0.0595783 0.164024 -0.125068 0.00949089 0.164024 -0.107435 -0.0358233 0.164025 -0.0799357 -0.0456092 0.164014 -0.0374653 -0.0176954 0.160034 -0.132852 8.42993e-05 0.1815 -0.125658 -0.0267381 0.1815 -0.0460604 -0.0295173 0.1815 -0.0557944 0.0476532 0.182295 -0.104754 0.0372906 0.181499 -0.10294 0.0410917 0.181508 -0.0982262 -0.0419399 0.1815 -0.0666828 -0.042963 0.181497 -0.0783075 -0.0527014 0.1815 -0.038449 0.0172245 0.181519 -0.0265934 0.00200376 0.1755 -0.12031 0.0192497 0.1755 -0.124542 0.003388 0.175496 -0.0265304 -0.00309949 0.1755 -0.102887 -0.0383624 0.1755 -0.127942 -0.0232227 0.1755 -0.120103 -0.0213122 0.1755 -0.0812023 0.0453986 0.1755 -0.105267 0.0460589 0.1755 -0.0666828 -0.042963 0.1755 -0.038449 0.0172245 0.1755 -0.0292789 0.015266 0.1775 -0.0412145 0.0227784 0.1775 -0.0831022 0.0448725 0.177501 -0.0563561 0.0390739 0.177514 -0.110466 -0.0426699 0.177499 -0.103502 0.0479155 0.1775 -0.119654 0.0205679 0.177504 -0.0273116 0.00655612 0.1775 -0.124406 0.00485426 0.176019 -0.121584 0.0329343 0.1695 -0.125954 -0.00129032 0.1695 -0.0292789 0.015266 0.169476 -0.0468842 -0.0305593 0.1695 -0.127942 -0.0232226 0.169424 -0.0639058 -0.0415444 0.1695 -0.0833481 0.0532715 0.169485 -0.0810989 0.0451631 0.1695 -0.105267 0.0460589 0.169498 -0.0825451 -0.0456012 0.16951 -0.108784 -0.0441992 0.1695 -0.109696 -0.03436 0.171504 -0.131573 0.0111314 0.171499 -0.0392497 -0.0359185 0.1715 -0.0350658 -0.00971233 0.171501 -0.056356 0.0390739 0.1715 -0.0831022 0.0448725 0.1715 -0.119654 0.0205679 0.170019 -0.121584 0.0329343 0.171499 -0.103502 0.0479155 0.171501 -0.0873189 -0.0524512 0.1715 -0.124406 0.00485426 0.171514 -0.110466 -0.0426699 0.171499 -0.107275 0.0357734 0.169502 -0.111069 0.0330894 0.171504 -0.0273116 0.00655612 0.171498 -0.0544809 -0.0371488 0.171499 -0.0641239 -0.0510186 0.169499 -0.0727406 -0.052449 0.1695 -0.0546772 0.0463979 0.169496 -0.0527926 0.0358091 0.177499 -0.107275 0.0357734 0.175502 -0.10872 0.0345706 0.177499 -0.0392497 -0.0359185 0.177498 -0.0544809 -0.0371488 0.177499 -0.0641239 -0.0510186 0.1765 -0.08 -0.045336 0.1755 -0.0851999 -0.0522308 0.1755 -0.0546772 0.0463979 0.175496 -0.0526731 0.0357135 0.177501 -0.087319 -0.0524512 0.175499 -0.0727406 -0.0524491 0.175499 -0.0468659 -0.041781 0.169499 -0.0468659 -0.041781 0.171229 -0.0383613 0.0328181 0.191019 -0.0354551 -0.0293354 0.191003 -0.0602828 -0.0479912 0.191395 -0.123554 -0.0299026 0.194123 -0.0709415 0.0517476 0.193675 -0.0281278 -0.00910922 0.191167 -0.0278363 0.00893512 0.194123 -0.0890585 -0.0517476 0.193843 -0.110488 -0.0433081 0.193666 -0.110338 0.0433449 0.160605 -0.122075 0.0495487 0.160076 -0.108063 0.0404151 0.160046 -0.123913 0.0393225 0.160042 -0.0524802 0.0407207 0.16 -0.0483893 0.051 0.191366 -0.125285 0.0187962 0.197004 -0.124275 0.0160821 0.183 -0.0354578 0.00338802 0.183 -0.027154 0.002758 0.182994 -0.0565639 -0.0380712 0.183 -0.0398967 -0.0213122 0.183 -0.11394 -0.0295173 0.183 -0.0551376 -0.0468555 0.182998 -0.131572 0.0109454 0.182995 -0.120565 0.0200436 0.183 -0.0968214 -0.0413827 0.183001 -0.0770574 -0.045018 0.182225 -0.0996779 -0.0494213 0.183002 -0.0546817 0.045373 0.182994 -0.0338044 0.0278076 0.183 -0.13025 -0.0175979 0.183 -0.124395 -0.00722924 0.18301 -0.110386 -0.0426833 0.183003 -0.0788337 0.0454584 0.211931 -0.100295 0.0415026 0.217241 -0.115845 0.0145344 0.222495 -0.109592 -0.0282821 0.222494 -0.0425249 -0.0174289 0.222347 -0.110819 0.0127907 0.22225 -0.0713073 0.0336151 0.222333 -0.0532913 0.0214386 0.20901 -0.0939186 0.0362378 0.209015 -0.117538 0.00768351 0.207647 -0.0318056 0.000330432 0.221539 -0.0466658 0.0106457 0.21995 -0.102632 0.027565 0.209007 -0.109726 0.0239952 0.217324 -0.0629004 0.0340919 0.209012 -0.0656006 0.0359909 0.217215 -0.0767211 0.0379949 0.216995 -0.108479 0.0253722 0.218343 -0.0871936 0.0334413 0.212 -0.10788 -0.0295903 0.212 -0.12075 -0.00140935 0.198328 -0.0844647 0.0426711 0.208999 -0.0619984 0.0387412 0.209004 -0.0959775 0.0397083 0.211996 -0.0292258 -0.0157044 0.212 -0.0409875 -0.0353368 0.197089 -0.11765 -0.0370425 0.212 -0.118146 -0.0362986 0.197686 -0.0412194 0.0357077 0.219416 -0.121325 0.0216761 0.212 -0.0480331 0.0416563 0.198463 -0.0755371 -0.0426712 0.208999 -0.0980019 -0.038741 0.208999 -0.0412252 -0.0179078 0.197861 -0.0410057 -0.0354589 0.197028 -0.0751629 -0.0522834 0.198083 -0.122015 -0.0173547 0.197982 -0.130648 0.0152149 0.205701 -0.0454645 0.0350089 0.205706 -0.0798188 0.0491597 0.205517 -0.0793173 -0.0494146 0.197998 -0.046331 -0.0270498 0.208889 -0.0373382 -0.00438772 0.212 -0.0275394 0.00361685 0.212 -0.0794191 -0.0527054 0.212 -0.0439096 -0.0187179 0.212001 -0.0397292 0.033896 0.212 -0.0531084 -0.0304913 0.212 -0.0644079 -0.0502879 0.212 -0.0659391 -0.0381466 0.212 -0.0806685 -0.0406501 0.212032 -0.0486887 0.0265542 0.212 -0.0300967 0.0160805 0.212001 -0.100806 -0.0422198 0.211999 -0.0949488 -0.0436144 0.212 -0.0953081 -0.0376635 0.211994 -0.0555859 -0.0470626 0.212 -0.116687 -0.0175207 0.212064 -0.121374 0.0137018 0.212 -0.132546 0.00233701 0.212026 -0.0388267 0.00175934 0.2183 -0.112878 0.0123887 0.219999 -0.0462744 -0.00646762 0.217807 -0.0772743 -0.0340461 0.217784 -0.0496038 -0.0170627 0.217977 -0.0611861 0.029474 0.21729 -0.048967 0.0225551 0.217009 -0.107776 -0.026523 0.217204 -0.0940298 0.0357879 0.216987 -0.0421405 0.00490326 0.216981 -0.0431288 -0.00977328 0.217234 -0.089819 -0.0371206 0.217199 -0.118092 -0.00612952 0.217 -0.0723712 -0.0373751 0.217203 -0.0531486 -0.027943 0.209007 -0.0498722 0.0235411 0.209005 -0.0395213 0.0134132 0.20888 -0.0540071 -0.0346782 0.209013 -0.0773373 -0.0383219 0.209005 -0.120479 -0.0134131 0.208999 -0.118741 0.0180015 0.211993 -0.0800287 0.0525708 0.212 -0.055247 0.0322797 0.212 -0.0994352 0.0361043 0.212 -0.121077 0.0332276 0.212 -0.112257 0.0247687 0.212 -0.0808336 0.0406514 0.222488 -0.0395799 0.00740268 0.222587 -0.0551436 0.0323509 0.222503 -0.0487814 -0.0142145 0.222494 -0.0608959 -0.0362024 0.222493 -0.11891 -0.0117752 0.222494 -0.086509 -0.040814 0.219472 -0.0575174 -0.0271471 0.222262 -0.0937699 -0.0325947 0.222368 -0.0941818 0.0310182 0.220318 -0.112183 -0.0144394 0.2189 -0.0977385 -0.0310493 0.222586 -0.04897 0.0265108 0.198196 -0.0497224 -0.0348545 0.208822 -0.0464017 0.0267254 0.208719 -0.0754953 0.0426194 0.198941 -0.11326 0.0269195 0.198219 -0.116171 0.0328695 0.208758 -0.106977 0.0331836 0.208763 -0.123327 0.00170016 0.205622 -0.115323 -0.0353667 0.208858 -0.113627 -0.0266771 0.208626 -0.0828619 -0.0437181 0.205515 -0.127949 -0.000497508 0.20901 -0.0421194 0.00687005 0.209014 -0.0457439 -0.0181895 0.209014 -0.0604404 -0.0327551 0.209014 -0.0943518 -0.0353483 0.209014 -0.108976 -0.0252196 0.209013 -0.116897 -0.00973937 0.222349 -0.067525 -0.0316378 0.222433 -0.113816 -0.00438505 0.217832 -0.105102 -0.0237915 0.222494 -0.0708274 0.0399317 0.222494 -0.0937403 0.0385718 0.222524 -0.11252 0.0250691 0.21647 -0.0480172 0.0416726 0.215703 -0.126941 0.0240942 0.216492 -0.121672 0.0319689 0.222495 -0.120227 0.0106035 0.216479 -0.0398973 0.0342866 0.198022 -0.11512 0.0390087 0.197442 -0.103766 0.0471684 0.19779 -0.0659133 0.0511192 0.198134 -0.118807 0.0188613 0.198001 -0.122699 0.00434296 0.197933 -0.10164 -0.0476764 0.197847 -0.0842575 -0.0523217 0.197937 -0.0610048 -0.0461328 0.197947 -0.0813849 0.0523976 0.198098 -0.0650173 0.0450433 0.201513 -0.11167 0.0354368 0.197303 -0.132576 -9.12304e-05 0.198 -0.107007 0.0332581 0.198003 -0.122714 -0.00426941 0.198098 -0.0956709 0.040222 0.197999 -0.115365 -0.0261246 0.198004 -0.112605 -0.0360555 0.198003 -0.0751379 0.0425823 0.198542 -0.106895 -0.0332746 0.198085 -0.0618414 0.0391343 0.198049 -0.0950213 -0.0403802 0.198241 -0.052378 0.0335721 0.197991 -0.0458837 0.0287474 0.197993 -0.0784173 -0.0496756 0.198003 -0.0848621 -0.0425823 0.198786 -0.0370451 0.00362006 0.198034 -0.040803 0.0180328 0.197996 -0.0631941 -0.0394091 0.198003 -0.037411 -0.00484043 0.205289 -0.0465906 -0.0279553 0.212 -0.0948842 0.0439468 0.198187 -0.0561894 0.047175 0.212 -0.0658374 0.0383991 0.212 -0.06512 0.044701 0.198151 -0.123657 0.0148639 0.212 -0.0336445 -0.0242339 0.212 -0.0372969 -0.0151887 0.198132 -0.0294675 -0.0157754 0.201031 -0.0331875 -0.0239722 0.200938 -0.0649407 -0.0436505 0.212 -0.0605443 -0.0409357 0.201179 -0.0566278 -0.045553 0.197984 -0.0620116 -0.050993 0.208025 -0.105488 -0.0461634 0.198006 -0.0967259 -0.0500008 0.201209 -0.100567 -0.0417589 0.212003 -0.130413 -0.0146272 0.212 -0.121557 -0.0205677 0.198401 -0.129817 -0.0167176 0.19811 -0.0293735 0.0148456 0.197978 -0.0333199 0.0240779 0.21199 -0.0557665 0.0470493 0.211981 -0.0638847 0.050393 0.211999 -0.0958442 0.0504712 0.197994 -0.09618 0.050159 0.21189 -0.104284 0.0470853 0.211987 -0.12999 0.0162183 0.212 -0.126729 -0.0241678 0.197959 -0.126768 -0.0239732 0.211999 -0.095832 -0.0503556 0.211999 -0.0382389 0.019321 0.198101 -0.0399656 -0.0159173 0.197887 -0.125593 0.0264569 -0.212 0.0589352 -0.0419949 -0.222407 0.0408447 0.0151172 -0.209014 0.108976 -0.0252196 -0.212042 0.11094 0.0263849 -0.2189 0.0977385 -0.0310493 -0.217009 0.118188 -0.00253918 -0.21697 0.110352 -0.0241276 -0.20901 0.0423383 -0.00768714 -0.222488 0.0399848 -0.00803653 -0.212 0.0479635 -0.0250308 -0.222494 0.0513522 -0.0297901 -0.222494 0.118911 -0.0117734 -0.198371 0.113521 0.02703 -0.197979 0.119523 -0.01654 -0.209004 0.0640225 -0.0397083 -0.198006 0.0631927 -0.0394089 -0.197941 0.0539877 0.0459121 -0.197775 0.114154 0.0399479 -0.216499 0.115467 0.0387494 -0.21177 0.120105 0.0340537 -0.211996 0.130736 0.0157895 -0.197026 0.0378076 -0.0313486 -0.19804 0.0434782 -0.0378656 -0.197028 0.0751629 -0.0522834 -0.19792 0.10635 -0.0456997 -0.211995 0.0848544 0.0525429 -0.208685 0.0803311 0.0437805 -0.209005 0.0395213 0.0134131 -0.197015 0.07416 0.0521928 -0.198078 0.0619393 0.0391398 -0.207656 0.0379563 0.0211476 -0.197719 0.0414554 0.035861 -0.19796 0.0287456 -0.0121824 -0.197022 0.0635996 -0.0497784 -0.20021 0.0566657 -0.0458489 -0.197848 0.0624854 -0.0455727 -0.198755 0.123692 -0.0157061 -0.19791 0.123344 -0.0297145 -0.197075 0.115585 -0.0385886 -0.200001 0.126185 -0.0235235 -0.198509 0.126861 0.0238446 -0.198032 0.123116 0.0217844 -0.205499 0.0451829 0.0351619 -0.198292 0.107045 -0.0335771 -0.208782 0.123356 0.00160503 -0.197997 0.108413 0.0342734 -0.198005 0.0843226 0.0426998 -0.208891 0.0373616 -0.00449922 -0.198 0.0529926 -0.033258 -0.198704 0.0370446 0.0036187 -0.208806 0.0464167 0.0267419 -0.212 0.132478 -0.00347579 -0.212001 0.117226 0.0168978 -0.211999 0.0641985 -0.0503378 -0.212 0.0794191 -0.0527054 -0.212 0.120493 0.00361938 -0.212 0.0806685 -0.0406501 -0.212 0.0953081 -0.0376635 -0.211967 0.0960668 -0.0503031 -0.212 0.10788 -0.0295903 -0.212 0.129925 -0.0160811 -0.212 0.118232 -0.0362209 -0.212 0.0409875 -0.0353368 -0.212 0.0650674 -0.0433279 -0.212 0.0626125 -0.0370605 -0.212 0.0274838 0.000196123 -0.2119 0.0293249 -0.0150061 -0.212232 0.0391598 0.0138731 -0.212 0.0293471 0.0155918 -0.212 0.0394123 -0.00673259 -0.21786 0.105745 -0.0212486 -0.220661 0.112819 -0.0127703 -0.217807 0.0913019 -0.0315403 -0.21995 0.057368 -0.027565 -0.219988 0.0878626 0.0335981 -0.218811 0.0982731 0.0293946 -0.217869 0.0480072 -0.0133263 -0.217166 0.0447993 0.0145744 -0.217677 0.0527957 0.0206782 -0.218059 0.114627 0.00224526 -0.217278 0.0561606 -0.0300824 -0.217709 0.0685383 -0.0318347 -0.217 0.0723722 -0.0373754 -0.217291 0.0896404 -0.0371583 -0.216991 0.0416865 -0.00754412 -0.20962 0.0520367 0.0262942 -0.216995 0.0596999 0.0320969 -0.217269 0.0875002 0.0376507 -0.209007 0.0836434 0.0382853 -0.217245 0.114968 0.0159962 -0.208999 0.0619981 0.038741 -0.209014 0.0499287 -0.0234774 -0.208999 0.0412587 -0.0180015 -0.209013 0.0669394 -0.0365207 -0.209014 0.0913599 -0.0366962 -0.208514 0.0848297 -0.0426044 -0.208999 0.0980016 -0.0387412 -0.209005 0.120479 -0.0134131 -0.208999 0.118775 0.0179078 -0.209 0.0976676 0.0388636 -0.211999 0.0962714 0.0377912 -0.212004 0.0598606 0.0412917 -0.222561 0.104878 0.032641 -0.212 0.0778104 0.040601 -0.212 0.0590232 0.0352136 -0.222349 0.0675249 -0.0316378 -0.222494 0.0752634 -0.0406589 -0.2225 0.113904 -0.000934258 -0.222495 0.109592 -0.0282821 -0.222495 0.0940509 -0.0381474 -0.22118 0.0742002 0.0342546 -0.222415 0.0691507 0.0316383 -0.222424 0.0477149 -0.0122064 -0.220052 0.0803092 -0.0339824 -0.22237 0.0987488 -0.0292435 -0.222402 0.103414 0.0261476 -0.220523 0.04511 -0.000918777 -0.219644 0.0619105 0.0306842 -0.21668 0.036471 0.0292415 -0.212 0.0477352 0.024768 -0.212 0.104752 0.0322688 -0.205439 0.128036 -0.000406253 -0.205635 0.114958 -0.0352739 -0.208856 0.113588 -0.0267422 -0.208659 0.106966 0.0331985 -0.205538 0.114807 0.0347604 -0.205706 0.0798188 0.0491597 -0.208724 0.0530332 -0.0331906 -0.205656 0.0446425 -0.0352681 -0.19851 0.0755328 -0.0426691 -0.205517 0.0793173 -0.0494147 -0.207708 0.0318805 0.000410693 -0.20901 0.0432591 0.0110499 -0.210271 0.0683213 0.0364419 -0.21083 0.101592 0.0316287 -0.209014 0.117867 -0.00625119 -0.208995 0.114867 0.0173514 -0.222263 0.0492575 0.0159031 -0.218126 0.0628972 0.0285851 -0.217521 0.080908 0.0337078 -0.217998 0.108006 0.0198982 -0.222506 0.0473899 0.0252041 -0.222494 0.0681185 0.0391844 -0.222494 0.0867643 0.0400905 -0.222476 0.120517 0.00548109 -0.211998 0.0381991 0.0326654 -0.211998 0.111964 0.0416535 -0.222482 0.111734 0.0273066 -0.197848 0.0842575 -0.0523216 -0.198093 0.0964857 -0.0500835 -0.198112 0.0650438 0.0441542 -0.197946 0.0813848 0.0523975 -0.197981 0.0344157 -0.0192002 -0.198042 0.0395545 0.0151565 -0.198002 0.0463209 0.0275926 -0.197101 0.0274353 -6.52659e-06 -0.198334 0.0520473 0.0335022 -0.198005 0.0384152 -0.0108136 -0.198003 0.0751379 0.0425823 -0.198945 0.0467367 -0.0269154 -0.198 0.0968432 0.0395735 -0.197993 0.0784173 -0.0496756 -0.198003 0.0848621 -0.0425823 -0.198003 0.122589 0.00484044 -0.197998 0.115932 -0.0331222 -0.198001 0.130076 -0.000824673 -0.198 0.122714 -0.00426934 -0.198004 0.113151 -0.027141 -0.212 0.0648525 0.0503736 -0.197979 0.0960079 0.0499818 -0.198076 0.0305813 0.0193961 -0.212 0.118166 -0.0154545 -0.212 0.126321 -0.0245787 -0.197996 0.130737 -0.0153196 -0.212 0.101113 -0.0425266 -0.212 0.0949002 -0.0437368 -0.198109 0.0960757 -0.0400866 -0.201049 0.064342 -0.0424062 -0.212 0.0389028 -0.0201466 -0.200899 0.0382327 -0.016523 -0.212 0.122703 0.0151887 -0.198111 0.130463 0.0160501 -0.198163 0.12051 0.0145919 -0.207296 0.103944 0.0466316 -0.212 0.0954121 0.0469838 -0.201033 0.063186 0.049563 -0.207774 0.0557809 0.0468695 -0.211872 0.0332402 -0.0240537 -0.211997 0.0556424 -0.0471028 -0.207073 0.104369 -0.0468688 -0.169495 0.131783 0.00798592 -0.1695 0.105267 0.0460589 -0.164006 0.0368066 0.011768 -0.16404 0.105055 0.0383198 -0.196959 0.0382235 -0.00781092 -0.162503 0.0377134 0.00078023 -0.160197 0.0534227 0.0299322 -0.191022 0.0721106 0.0522271 -0.193431 0.0890568 0.0518322 -0.193603 0.12329 0.0304713 -0.191004 0.0601264 0.0484095 -0.178104 0.0909829 0.0191915 -0.169938 0.101416 0.00599552 -0.177905 0.0747696 0.0216408 -0.18021 0.0634853 0.0140943 -0.169169 0.0925127 0.0188834 -0.1692 0.0729473 0.0212036 -0.169556 0.0605339 0.0105085 -0.162539 0.0833122 0.0298627 -0.162481 0.0774254 -0.0422728 -0.163138 0.0582564 -0.0366401 -0.163058 0.0405018 -0.0155243 -0.196995 0.119631 -0.0153514 -0.196997 0.113619 -0.0262672 -0.169858 0.096008 -0.0395059 -0.196996 0.0610574 -0.0380456 -0.177665 0.037477 -0.00360403 -0.16004 0.0834624 -0.0271083 -0.162803 0.101299 -0.0142924 -0.160044 0.0533048 -0.00431557 -0.167921 0.0886222 -0.018346 -0.168124 0.0678546 -0.0165056 -0.18063 0.0865006 -0.0091547 -0.180674 0.0915058 0.00256121 -0.164003 0.0672621 0.0433074 -0.18299 0.0412026 0.0227396 -0.1815 0.118785 0.0227784 -0.182295 0.104754 0.0372906 -0.1775 0.0412145 0.0227784 -0.1755 0.0812023 0.0453986 -0.1755 0.0356051 -0.00722924 -0.175496 0.0265304 -0.00309949 -0.181501 0.124569 0.00410677 -0.1815 0.0877735 0.0523927 -0.183 0.0764645 0.053282 -0.1815 0.125658 -0.0267381 -0.181501 0.133263 0.00190955 -0.183 0.027154 0.002758 -0.1815 0.0557944 0.0476532 -0.1755 0.0833481 0.0532715 -0.17551 0.108784 -0.0441992 -0.1755 0.127942 -0.0232227 -0.1715 0.0720594 0.0523847 -0.16951 0.108784 -0.0441992 -0.171229 0.0383613 0.0328181 -0.1755 0.0460604 -0.0295173 -0.1755 0.0666828 -0.042963 -0.1815 0.0356051 -0.00722924 -0.1815 0.0460604 -0.0295173 -0.1815 0.0666828 -0.042963 -0.1775 0.0933172 -0.042963 -0.191 0.0710691 -0.043769 -0.191003 0.095594 -0.0426991 -0.183 0.11394 -0.0295173 -0.191 0.117679 -0.0245662 -0.183 0.124395 -0.00722924 -0.160006 0.0490946 -0.0460744 -0.16 0.0623887 -0.0538684 -0.160004 0.0798802 -0.0561903 -0.160008 0.13299 0.0454836 -0.160034 0.132852 8.42993e-05 -0.16 0.130482 -0.0268668 -0.16 0.0235267 -0.00559457 -0.16 0.0269016 -0.00113098 -0.159999 0.0400161 0.0594967 -0.16 0.0376812 0.0534889 -0.16 0.0800218 0.0592905 -0.16 0.1185 0.0535 -0.16 0.136476 -0.00508414 -0.160003 0.13192 0.00892533 -0.1695 0.0356051 -0.00722924 -0.164025 0.0799357 -0.0456092 -0.164024 0.125068 0.00949089 -0.180651 0.0835126 0.0107632 -0.177403 0.0751308 0.0190773 -0.177478 0.0754326 -0.00835224 -0.177401 0.0766464 -0.019751 -0.1774 0.093082 -0.0150594 -0.177401 0.0611139 -0.0078996 -0.167896 0.0714475 0.0184038 -0.177398 0.0883308 0.0184308 -0.177402 0.100272 0.00229913 -0.168167 0.059963 0.00222 -0.168164 0.0920658 0.0165086 -0.160409 0.0849408 0.0271981 -0.160158 0.10298 0.0142228 -0.167861 0.100408 -0.0015368 -0.16 0.111611 0.051 -0.160497 0.105771 0.029866 -0.160004 0.104832 -0.029197 -0.160008 0.103254 -0.0125906 -0.160552 0.0929771 -0.0352587 -0.159591 0.0470702 -0.0309292 -0.160018 0.0547891 0.0111383 -0.159988 0.107273 -0.0354253 -0.197 0.0400787 0.034096 -0.197006 0.127222 0.0248351 -0.197004 0.124275 0.0160821 -0.196981 0.0871497 -0.0420603 -0.196996 0.10186 -0.0366378 -0.196981 0.0714705 -0.0418023 -0.196996 0.050743 -0.0310518 -0.196994 0.0415024 -0.0183881 -0.196877 0.132073 0.00888273 -0.197002 0.101761 0.0479727 -0.197 0.082854 0.052527 -0.196994 0.0319187 0.0198677 -0.197002 0.101421 -0.0482245 -0.1965 0.1225 0 -0.196993 0.12786 -0.0198388 -0.197 0.121779 -0.00780173 -0.196995 0.0403689 0.0153514 -0.196996 0.0581401 0.0366378 -0.170635 0.0758801 0.0422534 -0.170677 0.0871281 0.0420196 -0.170822 0.101823 0.0366068 -0.170808 0.11948 0.015585 -0.170872 0.121168 -0.0110142 -0.163111 0.11765 -0.0197392 -0.170642 0.111509 -0.0284476 -0.16255 0.104592 -0.0346962 -0.170721 0.0807013 -0.0426191 -0.170683 0.0685709 -0.0408868 -0.162543 0.0477337 -0.0276732 -0.170681 0.0439591 -0.022441 -0.170827 0.0403275 0.0150898 -0.16254 0.0429131 0.020664 -0.170673 0.0485476 0.0285167 -0.170819 0.0382305 0.00753303 -0.170623 0.0609794 0.0379532 -0.170704 0.113577 0.0262535 -0.16253 0.122379 0.00451686 -0.1625 0.0622065 0.0225174 -0.16251 0.0519636 0.00859662 -0.162509 0.105746 0.0137462 -0.162523 0.117907 0.0192732 -0.162499 0.053583 -0.0117515 -0.162502 0.0943881 -0.025296 -0.162513 0.107694 -0.00977808 -0.162508 0.0709808 -0.0280808 -0.169154 0.058047 -0.00261738 -0.169466 0.0663467 -0.0180251 -0.169207 0.0882795 -0.0205702 -0.17791 0.0958605 -0.0156672 -0.169556 0.0994661 -0.0105085 -0.177828 0.0642198 -0.0157585 -0.180414 0.0909342 0.0171872 -0.180092 0.0581737 -6.138e-05 -0.182111 0.0689722 0.00164506 -0.197 0.0771459 -0.052527 -0.193431 0.0709432 -0.0518322 -0.196998 0.132511 0.00017315 -0.196707 0.131249 -0.0092974 -0.196922 0.050079 -0.0438044 -0.196542 0.0372801 -0.031312 -0.191003 0.0602828 -0.0479912 -0.193843 0.110488 -0.0433081 -0.197 0.123015 -0.0309326 -0.191375 0.0364459 0.0298983 -0.191 0.124406 -0.00485427 -0.190997 0.120788 0.0203039 -0.191003 0.126777 0.024509 -0.191012 0.0998614 0.048138 -0.191001 0.0992468 0.040473 -0.191 0.0830478 0.0444946 -0.191 0.0641476 0.0419336 -0.191002 0.0500202 0.0332722 -0.191 0.0388249 -0.0191597 -0.191 0.0403931 0.0206817 -0.191 0.0355937 0.00485429 -0.191 0.055861 -0.0375872 -0.191029 0.0880181 -0.0521986 -0.190986 0.0323301 0.0195676 -0.180326 0.0776449 -0.0217911 -0.1774 0.0631815 0.0107326 -0.180246 0.101098 -0.00424441 -0.160064 0.0669375 0.0368249 -0.16 0.0906579 0.0379277 -0.161006 0.0440431 0.00638664 -0.160001 0.120618 0.010112 -0.161002 0.117205 0.00597652 -0.160944 0.120007 -0.0113262 -0.161003 0.104555 -0.0285584 -0.161 0.110954 -0.00688538 -0.160993 0.0699556 -0.0325041 -0.160083 0.0685584 -0.0248112 -0.160957 0.0400313 -0.0138521 -0.160885 0.057121 -0.0148254 -0.163361 0.0542338 0.0336866 -0.162511 0.0795247 0.0421602 -0.162817 0.0982565 0.0387501 -0.16251 0.0679214 0.040682 -0.180652 0.0725955 -0.00907659 -0.197 0.0382215 0.00780176 -0.196997 0.0463813 0.0262672 -0.196981 0.0728503 0.0420603 -0.196981 0.0885294 0.0418023 -0.196996 0.0989426 0.0380456 -0.196996 0.109257 0.0310518 -0.196993 0.118498 0.0183882 -0.196959 0.121776 0.00781091 -0.196998 0.0599716 -0.0479946 -0.190988 0.127648 -0.0195457 -0.197002 0.0586432 0.0482795 -0.160124 0.0669685 0.0234034 -0.161064 0.0817861 0.0365276 -0.180561 0.0723778 0.00775192 -0.177562 0.0844987 0.00815994 -0.16 0.131612 0.06349 -0.16 0.0335 0.0635 -0.16 0.1365 0.0535 -0.16 0.0991889 -0.0533269 -0.16 0.0324162 -0.0322512 -0.164 0.0257493 -0.0174378 -0.16404 0.0461622 0.0297864 -0.163621 0.0385962 0.0491609 -0.164 0.0500193 -0.0429377 -0.164007 0.120134 0.0592747 -0.164001 0.0795594 -0.0519826 -0.164015 0.111533 -0.0457653 -0.163998 0.0860012 -0.0571005 -0.163992 0.0509474 -0.0493176 -0.164 0.0377895 -0.0378266 -0.164 0.0235 0 -0.164001 0.111211 0.0480045 -0.164 0.133229 0.00840901 -0.164 0.127304 -0.0325578 -0.164 0.136486 -0.00551593 -0.164 0.13647 0.0586291 -0.164 0.12461 0.0413178 -0.164 0.1265 0.0635 -0.163999 0.0289028 0.0634881 -0.164 0.0498638 0.0445366 -0.164 0.0235697 0.0454209 -0.160007 0.0256652 0.0601017 -0.157 0.118 0.051 -0.15697 0.036254 0.0509514 -0.157008 0.121381 0.0534838 -0.16 0.1265 0 -0.159968 0.0346895 -0.0142329 -0.160001 0.0801712 -0.0479881 -0.160014 0.0360253 0.0347408 -0.160133 0.0755932 -0.044854 -0.156998 0.0730844 -0.0449328 -0.157 0.124 0.045 -0.16 0.123949 -0.00907126 -0.16 0.126449 0.0489861 -0.157015 0.0415325 0.0534948 -0.16 0.0335 0.0455 -0.158485 0.102654 -0.0402344 -0.159944 0.117144 -0.0289012 -0.158497 0.124451 -0.0109078 -0.157258 0.126021 0.0120742 -0.158565 0.033378 0.00808941 -0.159859 0.0361353 -0.00971515 -0.157907 0.0596815 -0.0404493 -0.156895 0.0917309 -0.0439055 -0.157019 0.0335327 0.0492777 -0.157019 0.126495 0.0476032 -0.160004 0.112425 -0.0457009 -0.159999 0.0275574 0.00891458 -0.164 0.0274641 0.00887563 -0.159997 0.0235417 0.0454992 -0.164 0.0798484 0.0587439 -0.160001 0.120251 0.0595783 -0.164 0.0401185 0.0594108 -0.164008 0.120296 -0.0195041 -0.164024 0.107435 -0.0358233 -0.164014 0.0374653 -0.0176954 -0.181495 0.126191 0.0275371 -0.1815 0.120103 -0.0213122 -0.1815 0.0725166 0.0440396 -0.181499 0.10294 0.0410917 -0.181508 0.0982262 -0.0419399 -0.181497 0.0783075 -0.0527014 -0.1815 0.0385481 0.0332807 -0.1815 0.038449 0.0172245 -0.181503 0.0471691 -0.0419363 -0.181519 0.0265934 0.00200376 -0.1755 0.102887 -0.0383624 -0.1755 0.12031 0.0192497 -0.1755 0.124542 0.003388 -0.1755 0.120103 -0.0213122 -0.175496 0.0526731 0.0357135 -0.1755 0.0546772 0.0463979 -0.175495 0.131783 0.00798592 -0.177229 0.0383613 0.0328181 -0.1755 0.038449 0.0172245 -0.1755 0.0292789 0.015266 -0.1775 0.0350658 -0.00971233 -0.177499 0.107275 0.0357734 -0.177499 0.0641239 -0.0510186 -0.177499 0.103502 0.0479155 -0.176019 0.121584 0.0329343 -0.1775 0.11975 -0.0230944 -0.1775 0.119654 0.0205679 -0.177501 0.087319 -0.0524512 -0.177504 0.0273116 0.00655612 -0.1775 0.0720594 0.0523847 -0.177504 0.131573 0.0111314 -0.1775 0.124406 0.00485426 -0.1775 0.130347 -0.0173882 -0.1775 0.0831022 0.0448725 -0.177514 0.110466 -0.0426699 -0.1695 0.125954 -0.00129032 -0.169496 0.0265304 -0.00309948 -0.1695 0.109696 -0.03436 -0.1695 0.127942 -0.0232226 -0.1695 0.038449 0.0172245 -0.169476 0.0468842 -0.0305593 -0.169424 0.0639058 -0.0415444 -0.1695 0.0833481 0.0532715 -0.169485 0.0810989 0.0451631 -0.169499 0.0468659 -0.041781 -0.1715 0.0412145 0.0227784 -0.171514 0.110466 -0.0426699 -0.171499 0.0568836 -0.0391503 -0.171499 0.0392497 -0.0359185 -0.1715 0.0350658 -0.00971233 -0.1715 0.0831022 0.0448725 -0.170019 0.121584 0.0329343 -0.1715 0.104921 -0.0379658 -0.171499 0.103502 0.0479155 -0.1715 0.119654 0.0205679 -0.17029 0.0813875 -0.0449789 -0.171501 0.0873189 -0.0524512 -0.171504 0.131573 0.0111314 -0.1715 0.124406 0.00485426 -0.1715 0.130347 -0.0173882 -0.1715 0.122311 -0.0152637 -0.171499 0.107275 0.0357734 -0.169502 0.111069 0.0330894 -0.171504 0.0273116 0.00655612 -0.1695 0.0292789 0.015266 -0.170614 0.0657857 -0.0512737 -0.1695 0.0851999 -0.0522308 -0.171501 0.056356 0.0390739 -0.169496 0.0527926 0.0358091 -0.175502 0.10872 0.0345706 -0.1755 0.105267 0.0460589 -0.177499 0.0392497 -0.0359185 -0.175499 0.0468659 -0.041781 -0.177498 0.0544809 -0.0371488 -0.175499 0.0727406 -0.0524491 -0.1765 0.08 -0.045336 -0.1755 0.0851999 -0.0522308 -0.177501 0.0563561 0.0390739 -0.1695 0.0546772 0.0463979 -0.191019 0.0354551 -0.0293354 -0.191005 0.100313 -0.0482944 -0.191395 0.123554 -0.0299026 -0.194123 0.0709415 0.0517476 -0.193855 0.0495143 0.0433058 -0.193675 0.0281278 -0.00910922 -0.191167 0.0278363 0.00893512 -0.194123 0.0890585 -0.0517476 -0.191043 0.132348 -0.00767118 -0.193666 0.110338 0.0433449 -0.160076 0.108063 0.0404151 -0.160046 0.123913 0.0393225 -0.160605 0.122075 0.0495487 -0.160042 0.0524802 0.0407207 -0.16 0.0483893 0.051 -0.163973 0.0412323 0.0364178 -0.191366 0.125285 0.0187962 -0.197004 0.0321237 -0.0195467 -0.183 0.0354578 0.00338802 -0.182994 0.0565639 -0.0380712 -0.182999 0.0379996 -0.0335234 -0.183 0.0398967 -0.0213122 -0.183001 0.0770574 -0.045018 -0.183001 0.120841 0.0326407 -0.183 0.0551376 -0.0468555 -0.182994 0.0338044 0.0278076 -0.183 0.0968214 -0.0413827 -0.182225 0.0996779 -0.0494213 -0.181688 0.0541678 0.0365732 -0.183003 0.0788337 0.0454584 -0.182998 0.131572 0.0109454 -0.182995 0.120565 0.0200436 -0.183 0.13025 -0.0175979 -0.18301 0.110386 -0.0426833 -0.183002 0.0546817 0.045373 -0.183 0.105182 0.0464747 + + + + + + + + + + -0.0162262 0.947616 0.319 -0.398334 -0.903881 0.15598 -0.566155 -0.579731 0.585987 -0.779875 -0.4128 0.470522 -0.652526 -0.110249 0.749703 -0.68027 0.457984 0.572262 -0.556792 -0.110177 0.823313 0.612341 0.491638 -0.619137 -0.612341 -0.491638 0.619137 0.104016 -0.102888 0.98924 0.506195 0.851698 0.135566 -0.506195 -0.851698 -0.135566 0.865974 -0.0828216 0.493184 -0.823292 -0.130832 0.552335 -0.21628 0.82949 -0.514946 0.21628 -0.82949 0.514946 -0.147149 -0.756149 0.637641 0.992303 -0.105291 0.0651777 -0.494909 -0.655181 0.570792 -0.99869 0.0400939 0.0317965 -0.952787 0.0574371 -0.298156 -0.99584 -0.0704541 -0.0577791 0.997341 0.0686513 0.0244738 -0.999502 0.0140252 -0.0282572 0.355485 0.921781 0.154757 -0.122598 -0.0405355 0.991628 0.212751 -0.22881 0.949939 0.0328669 0.303403 0.952295 0.409184 0.157634 0.898733 0.117758 0.0931306 0.988666 -0.0912851 -0.841741 0.532108 -0.0861374 -0.955482 0.282196 0.336814 -0.664605 0.666976 0.57483 -0.550261 0.605627 -0.113967 -0.437036 0.892195 -0.0715907 -0.308309 0.948588 -0.0488811 0.281673 0.958265 -0.0924407 0.451615 0.887411 0.45108 0.541865 0.709161 -0.0670135 0.708271 0.702752 0.185747 0.852406 0.488775 -0.0818835 0.924804 0.371528 -0.082214 0.918494 0.386794 0.446951 0.701849 0.554655 0.439473 -0.837416 0.324958 0.111836 -0.814466 0.569332 0.036917 -0.164668 0.985658 -0.0397226 -0.117605 0.992266 0.103151 0.614752 0.781946 -0.191208 0.973582 0.124812 0.727239 -0.543687 0.41896 0.796659 -0.0724176 0.600075 0.749104 0.661523 0.0350622 0.669155 0.734708 0.111517 0.549658 0.462854 0.695444 0.592096 0.464326 0.658653 0.769972 -0.10496 0.629386 0.52461 -0.573419 0.629266 0.223534 0.957588 0.181816 0.156111 0.731303 0.663947 0.200809 -0.276307 0.939857 0.0471815 -0.38096 0.923387 0.00457529 -0.64185 0.766816 0.125835 -0.703301 0.699667 0.135974 -0.933531 0.331708 0.0218792 -0.967333 0.252563 0.0156595 0.996387 0.0834763 0.0116373 0.995615 0.0928137 -0.0112038 0.961783 0.273582 0.00673329 0.92873 0.370697 -0.0109273 0.875871 0.482421 0.016371 0.809034 0.587534 -0.0112912 0.650966 0.759023 -0.00559648 0.661438 0.749979 0.00778614 0.403093 0.915126 -0.0112286 0.34584 0.938227 0.0161669 0.166472 0.985914 -0.0196907 -0.0164524 0.999671 0.0171392 -0.156889 0.987467 -0.00991264 -0.380614 0.924681 0.0142234 -0.339338 0.940557 -0.0162911 -0.561138 0.827562 0.0196186 -0.641705 0.7667 -0.00834333 -0.801118 0.598448 -0.0118546 -0.807749 0.589407 0.0137048 -0.896688 0.442452 -0.0102761 -0.967487 0.252713 0.01423 -0.955048 0.29611 -0.410567 0.503876 0.759963 -0.538521 0.837134 0.0959231 -0.765331 0.519495 0.379991 -0.715466 -0.04943 0.696896 -0.576803 -0.54892 0.604967 -0.804082 -0.572428 0.160557 -0.74346 -0.615671 0.261185 -0.162166 0.911649 0.377622 0.133485 0.827863 0.544816 -0.236585 0.266708 0.934288 0.234002 -0.109682 0.966029 -0.244024 -0.551851 0.797442 -0.22539 -0.973004 0.0496207 0.235416 -0.895804 0.376981 0.800303 0.560034 0.214189 0.816967 -0.48087 0.318323 0.209865 0.248638 0.945588 0.401135 -0.849278 0.343244 0.591754 -0.342133 0.729912 -0.64491 -0.271507 -0.714405 0.0814066 -0.995856 0.040543 -0.150009 -0.983133 0.10463 0.253017 -0.843946 0.473009 -0.265296 -0.759709 0.593684 0.426949 -0.337708 0.838849 0.425431 0.283808 0.859338 -0.263449 0.520801 0.81201 0.27631 0.760795 0.587234 -0.189213 0.871321 0.452767 0.179273 0.977213 0.113647 -0.0618139 0.997064 0.045184 -0.0436399 -0.988871 0.142232 -0.0320583 -0.989775 0.138987 -0.0424666 -0.734488 0.677291 0.171436 -0.673382 0.719143 -0.162455 -0.293706 0.94199 -0.0100056 -0.240935 0.97049 0.186831 0.131907 0.973496 -0.186483 0.324139 0.927447 0.069232 0.52142 0.850487 -0.0855597 0.730968 0.677027 0.0755485 0.792122 0.605669 -0.0221513 0.956735 0.290117 -0.0358528 0.958038 0.28439 0.374525 -0.824458 0.424264 -0.380837 -0.76547 0.51867 0.24757 -0.368751 0.895953 0.0441867 -0.351945 0.934977 -0.247959 0.263932 0.932124 0.0525125 0.309575 0.949424 0.397704 0.714016 0.576205 -0.438418 0.781822 0.443333 0.569977 0.81616 0.0949164 0.375258 -0.823397 0.425675 -0.372553 -0.768259 0.52056 0.245121 -0.368641 0.896671 0.0441868 -0.351945 0.934977 -0.247959 0.263932 0.932124 0.146055 0.318033 0.936762 0.289681 0.758577 0.583649 -0.438416 0.781823 0.443334 0.569977 0.81616 0.0949164 0.737671 0.64349 -0.204357 -0.894929 0.394928 -0.20769 0.737676 0.643485 -0.204355 -0.735494 0.61541 -0.283406 -0.777234 0.224934 0.587632 -0.57152 0.363931 0.735472 0.784146 -0.519995 -0.338703 -0.336288 0.793482 0.507244 0.897524 -0.271933 0.347135 0.453209 0.854057 -0.255319 -0.953792 0.272243 -0.127141 0.166684 -0.227425 0.959424 -0.908098 -0.047104 0.4161 0.903334 0.146303 0.403216 -0.12045 -0.732436 -0.670096 0.746077 -0.522165 -0.413175 -0.730074 -0.678242 -0.083551 0.251799 -0.966744 -0.0447529 -0.50281 -0.279795 -0.817861 0.443734 -0.348471 -0.825632 -0.856936 0.48162 0.183582 -0.432763 -0.82626 0.360569 -0.91117 -0.0631572 0.407162 0.943265 -0.303326 0.135072 -0.131489 -0.988621 -0.0730669 0.22882 0.940861 0.249845 0.970303 0.0573243 -0.235002 0.98774 0.112058 -0.108688 -0.87041 -0.26093 -0.417495 0.844879 0.263931 -0.465317 0.573499 0.487747 -0.658181 -0.939103 0.305094 0.158123 0.94181 0.0801143 0.32646 -0.835929 -0.0162132 -0.548598 -0.17192 0.265312 -0.948711 0.963381 0.023029 -0.267145 -0.51828 -0.26731 0.812361 0.913047 -0.0177052 0.407471 -0.790357 0.14283 0.595764 -0.104491 -0.734321 -0.670711 0.650667 -0.597077 -0.469182 -0.64178 -0.761134 -0.0937787 0.169353 -0.984646 -0.0423407 -0.407123 -0.294592 -0.864561 0.352275 -0.364133 -0.862154 -0.899296 0.266349 -0.34688 0.957619 0.283258 0.0522589 -0.793236 -0.190326 0.578405 0.832798 0.0694522 0.549203 -0.102434 0.23191 0.967329 -0.104489 -0.734322 -0.670711 0.650665 -0.597079 -0.469183 -0.641776 -0.761137 -0.0937789 0.169351 -0.984646 -0.0423408 -0.962424 -0.0149296 -0.27114 0.35227 -0.364134 -0.862155 -0.70026 0.272122 -0.659989 0.957618 0.283261 0.0522591 -0.540251 0.807199 -0.237821 0.221231 0.882905 -0.414169 0.0682548 0.71088 -0.699994 -0.387167 0.57318 -0.722196 -0.0120317 0.204168 -0.978862 -0.180719 0.172332 -0.968319 0.346302 -0.288445 -0.892678 -0.564969 -0.435412 -0.700875 0.329953 -0.664264 -0.670735 -0.443237 -0.875284 -0.193439 0.0409837 -0.988053 -0.148567 -0.540251 0.807199 -0.237821 0.221231 0.882905 -0.414169 -0.0603776 0.505304 -0.860827 0.72897 0.425552 -0.536197 -0.503441 0.151375 -0.850666 0.525726 -0.128357 -0.840914 -0.565958 -0.435055 -0.700299 0.37099 -0.630301 -0.681973 -0.443237 -0.875284 -0.193439 0.0409837 -0.988053 -0.148567 0.0412384 0.990225 -0.133241 -0.083976 0.980756 -0.176253 0.0839755 0.731691 -0.676444 -0.0196116 0.708915 -0.705022 0.0229417 0.376462 -0.926148 -0.102444 0.314197 -0.943814 0.170768 -0.0429217 -0.984376 -0.13388 -0.173499 -0.975692 -0.0477672 -0.569024 -0.820932 0.178797 -0.624364 -0.760396 -0.158265 -0.893928 -0.41934 0.0941179 -0.942194 -0.321578 -0.999999 0.00119566 0.000822882 -0.999998 0.000944944 -0.00161335 -0.97786 0.19022 -0.0872152 -0.998067 0.00397254 -0.0620239 -1 0.000117381 0.000585564 -1 -0.000178071 -0.000307896 -1 0.000155201 -0.000296072 -1 -4.6688e-05 0.000423096 -0.999993 -0.000337325 -0.00367548 -1 0.000373958 -4.43383e-05 -0.999991 -0.00410586 0.000619695 -0.999975 -0.00495882 -0.00497335 -1 5.49111e-07 -2.93825e-05 -1 -0.000259831 -0.000169749 -0.999999 0.00118454 0.000231505 -1 -0.00026817 0.00013832 -0.999999 -0.00127725 -5.66646e-06 -1 -0.000291793 -5.66643e-05 -1 -0.000148709 -0.000434667 -0.999999 0.00108064 -0.00052876 -1 0.000314686 0.000505674 -0.999983 0.00576627 -0.00100505 -1 -1.06591e-05 1.86478e-05 -1 -2.72514e-05 0.000146346 -1 -0.000331742 -0.00021781 -1 -0.0002918 -0.000147124 -0.999998 -0.00197529 -0.000281746 -0.999995 0.00329486 0.000463996 1 -1.38727e-05 0.000117918 -1 -7.0186e-06 -8.46125e-05 -1 -7.18056e-06 0.000114757 -1 2.53146e-09 -2.48584e-05 -1 -2.0529e-06 1.74496e-05 -1 2.85529e-05 2.56453e-05 -0.999997 -0.00195217 0.00125478 -0.999996 0.00275694 0.000205203 -0.999999 0.0013449 6.81898e-05 0.10854 0.894943 -0.432776 -0.191446 0.852048 -0.4872 0.28487 0.204936 -0.936403 -0.492463 -0.0820156 -0.866461 0.477614 -0.346004 -0.807568 -0.0444098 -0.880058 -0.472786 -0.970811 0.23581 0.043809 -0.348102 -0.922715 0.165595 0.736452 -0.605798 -0.301077 0.286525 -0.678718 -0.6762 -0.0179878 0.585316 -0.810606 0.635787 0.756639 0.152554 0.912077 -0.12518 -0.390443 -0.999999 0.00145637 0.00067792 -0.999999 -0.00157134 2.99882e-05 -0.999901 -0.00439767 -0.0133935 -0.999999 -0.000752309 -0.00077534 0.999673 -0.0254623 0.00236171 -0.999997 -0.0014338 0.00183218 -0.999997 0.000713985 0.00233923 -0.999858 0.00872614 0.0143906 -0.999108 0.0257548 -0.033467 -1 0.000289495 -0.00040304 0.24875 -0.791857 -0.55775 -0.231459 -0.556647 -0.797854 -0.0866239 0.261813 -0.961223 0.198346 0.0776281 -0.977053 -0.100444 0.834538 -0.541718 0.205393 0.902857 -0.377706 -0.560306 -0.821159 -0.108424 -0.778148 -0.505985 -0.37211 -0.653602 -0.510411 -0.558824 -0.613323 -0.216391 -0.759611 -0.765833 0.0544791 -0.640728 -0.793661 0.555163 -0.248789 -0.522886 0.322195 -0.789165 -0.527349 0.602107 -0.599474 -0.975781 -0.161554 0.147484 -1 -6.94796e-05 -0.000111365 -0.999883 0.0148193 -0.0037828 -1 0 0 -0.999964 0.00250697 -0.0081062 -0.999601 0.008363 -0.0269882 -0.999977 -0.00532936 -0.00416632 -0.999992 -0.00397948 0.000459817 0.885049 0.457794 -0.0843379 -0.998955 -0.0423002 0.0172907 0.999205 -0.0152283 0.0368356 -1 0.000687074 0.000307026 -0.993637 -0.0566396 -0.0973545 -0.999921 0.0120343 -0.00373727 -0.999951 -0.00190602 0.00973851 -0.99895 0.0457096 -0.00298088 -0.999339 -0.0292637 -0.0215544 -0.991078 -0.112861 -0.0708999 -0.99616 0.0277551 -0.0830337 -0.995655 -0.0170721 0.0915453 -0.994402 0.0381403 0.098541 -0.999987 -0.00490872 0.000992196 -0.999988 -0.00427979 0.00244488 -0.999997 -0.00232468 0.000515425 -0.99824 0.038919 0.0447448 -0.999438 0.00456368 -0.0332056 -0.999961 -0.0077937 -0.00416801 -0.999147 -0.0300335 -0.0283294 -0.998443 0.02203 0.0512496 -0.913752 0.343112 0.217559 0.999997 -0.00050921 -0.0023517 0.999998 5.73535e-05 -0.00181019 0.999999 -0.00126264 -0.000630556 1 -0.000659866 -0.000604509 1 -8.87614e-05 -0.000286376 1 -8.7724e-05 -0.000287211 0.999999 0.00146357 -0.000189467 1 0.000358508 -0.000503156 0.999999 0.000818663 -0.000707018 0.999999 0.000848526 -0.000793313 0.999999 0.0017056 0.000366465 0.999984 0.0036162 -0.00442036 0.999634 0.0269426 0.0026278 -0.833384 0.55269 -0.00226652 0.999998 0.00203191 -9.70559e-05 0.999999 0.00123279 0.000549579 1 0.000592553 0.000525311 1 0.00015238 0.00028078 1 0.000135457 0.000314867 0.999957 0.0018989 -0.00913078 0.999977 0.00376429 -0.00557498 0.999426 0.0336337 -0.00401669 0.999157 0.0332368 -0.024081 -0.0222504 -0.999752 0.000190334 0.99992 -0.0123692 -0.00263429 0.999994 -0.00016968 0.00335479 0.999287 -0.00675829 -0.0371523 0.99979 -0.020026 -0.00427298 0.999955 -0.0094106 -0.00117204 0.999967 -0.0076954 -0.0027982 0.999998 0.000578994 -0.00208624 1 0.000847215 5.0207e-05 0.999995 -0.00323905 -0.000238416 0.999955 -0.00823707 0.00479541 0.998823 -0.012246 0.0469315 0.999996 0.00278239 0.000307432 0.999998 -5.92714e-05 0.00181121 0.999997 0.000469535 0.00231663 0.999999 -0.00134109 8.33075e-05 0.999306 -0.0334716 0.0163161 0.999488 -0.0286432 -0.0142949 0.0118061 -0.997374 -0.0714486 -0.00888851 -0.961806 -0.273587 0.0122673 -0.905539 -0.424085 -0.00671803 -0.875903 -0.48244 0.00828382 -0.757036 -0.65332 -0.0251279 -0.661239 -0.749755 0.0238651 -0.55081 -0.834289 -0.0187737 -0.345794 -0.938123 0.0199124 -0.208789 -0.977758 -0.0201242 0.0400693 -0.998994 -0.00725933 0.0164553 -0.999838 0.0104578 0.342461 -0.939474 0.0118444 0.339347 -0.940587 -0.012643 0.561168 -0.827606 0.0174243 0.65142 -0.758517 -0.0100349 0.810505 -0.585647 -0.00751234 0.807783 -0.589432 0.0102699 0.955949 -0.293353 0.011488 0.955084 -0.296111 -0.00850468 0.995747 -0.0917354 0.0268513 -0.997573 -0.0642434 0.200776 -0.614761 -0.76273 0.187005 0.248925 -0.950298 0.17706 0.717738 -0.673425 0.0245934 0.810369 -0.585403 0.0727681 0.944198 -0.321239 0.998151 -0.0364269 0.0486488 0.999996 -0.000932478 -0.00278154 0.999996 -0.00213247 -0.00163605 0.999999 -0.00129001 -0.000897069 0.999376 0.0222603 0.0274286 0.999994 0.00107747 -0.00336018 1 -0.000561486 -0.000501975 0.999999 0.00112562 -4.97142e-05 1 0.000709429 -0.000328949 0.999999 -0.0013658 7.50916e-05 1 0.000135075 0.000395916 1 -0.000560989 0.000848496 0.999999 0.0014662 -0.000346805 0.999999 0.00130482 -0.000394529 1 -3.05846e-05 0.000903322 1 0.000175744 0.00033784 1 -0.000145057 -0.000113334 1 -0.00037616 -4.00567e-05 0.557629 0.677938 -0.479009 0.766111 0.027201 -0.642132 0.627669 -0.771276 -0.105664 0.663531 -0.743629 -0.082115 0.595241 -0.45862 -0.659815 0.695279 -0.456738 -0.554958 0.640795 0.165298 -0.749706 0.761109 0.438311 -0.478118 0.242444 0.895956 -0.372135 -0.197472 0.667391 -0.718049 0.120119 0.416426 -0.901199 -0.0740786 0.0433338 -0.99631 0.136201 -0.165165 -0.976816 -0.123911 -0.650543 -0.749293 0.14379 -0.772636 -0.618351 -0.112565 -0.987081 -0.114021 0.563794 -0.61563 -0.550578 0.508838 -0.184411 -0.840878 0.877706 0.28017 -0.388765 0.403903 0.837425 -0.368215 -1 0.000800311 -0.000216909 0.996774 -0.0801496 0.00417066 0.997262 -0.0738223 0.00443098 0.994603 0.0166807 -0.102406 1 -0.000429472 0.000243969 0.992586 0.0558252 -0.107961 0.999996 0.00142962 -0.00241861 0.999645 -0.0170761 0.0204663 0.999169 -0.00606305 0.0403133 0.996445 0.0670399 0.0510273 0.998737 0.0476307 0.0159984 0.155612 0.936514 -0.314207 0.0371061 -0.302518 -0.952421 0.414691 -0.158785 -0.896001 -0.125369 0.0389084 -0.991347 0.113238 -0.0920801 -0.989292 0.247391 0.247271 -0.936832 0.172486 -0.982988 -0.0631117 0.097072 -0.948257 -0.302301 -0.10938 0.993509 -0.0312508 0.0521781 0.936711 -0.346194 0.155211 0.903186 -0.400205 -0.0255719 0.697868 -0.71577 -0.0207548 0.389801 -0.920665 -0.0179382 0.335304 -0.941939 -0.0410615 -0.282675 -0.958336 -0.0737981 -0.455361 -0.887243 0.501368 -0.540838 -0.67537 -0.0609506 -0.709208 -0.702359 0.0144791 -0.916345 -0.400128 -0.0508036 -0.928101 -0.368847 -0.0507519 -0.928693 -0.367361 -0.998751 -0.040224 -0.0296393 -0.999209 0.0329889 0.0222027 -0.999998 0.00145546 -0.00134556 -0.999996 -0.000254138 -0.00290072 -1 -5.84001e-05 -0.000243699 -0.999999 0.00146928 0.000501476 -0.999998 -0.00168348 -0.000962502 -0.999983 -0.00570667 0.000700012 -1 -0.000494324 0.000731115 -0.999999 -0.000887014 0.00140831 -0.999999 -0.000425056 0.00144535 -0.999996 -9.87333e-05 0.00295128 -1 8.91171e-05 0.000582051 -0.999994 -0.000384592 0.00335561 -1 0.000356365 0.000416099 -0.999084 0.0339467 0.0260701 -0.999998 -0.0017826 -0.000529252 -0.99994 0.0107826 0.00174333 -0.999725 0.0232274 -0.00312539 -0.999231 0.00368572 0.0390361 -0.999667 0.0249835 -0.00646599 -0.999997 -0.00058419 -0.0022371 -0.999999 0.00124803 -0.000832625 -1 0.000148495 -0.000365317 -0.999998 0.00146577 -0.00152908 -0.999978 -0.00623947 0.00220214 -0.998559 -0.0231638 -0.0484076 -0.967012 0.18792 0.171969 -0.977448 -0.138371 0.159528 0.941915 -0.0169009 -0.335427 -0.989885 0.127867 0.0614676 -0.989791 -0.110964 0.0894479 -0.998247 0.00670519 -0.0588024 -0.994163 -0.033318 0.102618 -0.999345 0.0305752 -0.0193822 -0.994282 0.0180244 -0.105258 -0.997906 0.00272564 0.0646275 -0.994851 -0.0601458 -0.0815681 -0.990449 -0.0980421 -0.0969483 0.933452 -0.0726185 0.351274 0.494909 0.655181 -0.570792 0.977745 -0.203465 -0.0511489 0.994509 0.104633 -0.00191288 0.147149 0.756149 -0.637641 0.975061 0.19883 -0.0986068 0.828723 -0.559657 0.00157869 -0.00708116 0.999975 0.000292694 -0.0142153 0.999899 -0.000335023 -0.00236765 -0.000101835 0.999997 0.0028443 0.000122336 0.999996 0.00714578 -0.999974 0.000254976 -0.00481919 -0.999988 -0.000555994 0.282908 -0.908213 -0.308403 -0.247073 -0.943892 -0.219139 -0.163844 0.648953 -0.742978 -0.313317 0.605924 -0.731224 -0.422893 0.458459 -0.78165 0.441047 0.194599 -0.876133 -0.0242586 0.131541 -0.991014 -0.410444 -0.133687 -0.902033 0.428896 -0.366309 -0.825752 0.096678 -0.496847 -0.862436 0.129439 -0.636727 -0.760148 -0.380222 -0.667587 -0.640124 0.408759 0.785851 -0.464063 -0.378994 0.877873 -0.292751 0.169811 0.977379 -0.126075 0.999996 -0.00254129 0.000887347 0.999998 0.000342151 -0.00218776 0.99988 0.0144637 0.00563287 1 6.16473e-05 -5.94051e-05 1 -7.88072e-05 -5.94195e-05 0.999999 -0.00129392 -0.000975596 0.999999 0.000657658 -0.00105803 0.999999 0.000360705 -0.0011055 0.999999 -0.00138284 -0.000478986 1 -0.000338614 -0.000122658 0.999999 0.000395142 -0.00102727 0.999999 0.000179436 -0.00113785 0.999999 0.000352506 -0.0009736 0.999999 0.000196812 -0.00127708 0.999999 0.000455126 -0.00167127 1 5.07529e-05 -1.59466e-05 1 0.000316865 -0.000179078 1 0.000694702 -0.000661336 0.99995 0.00408949 0.00910931 1 0.000163227 0.000344492 0.999992 0.000412091 0.00407653 0.999999 0.00129143 6.49068e-05 1 0.000739368 0.00032229 0.999997 -0.00235938 -0.000363547 1 1.48616e-06 -3.35263e-06 0.999999 0.000467341 -0.000956592 1 0.000105939 0.000120252 0.999999 0.00138295 7.94512e-05 1 -1.58111e-05 4.03156e-09 0.999999 -0.00143408 0.000136539 0.999999 -0.000750379 -0.00115518 0.999998 -0.00195955 0.000928308 1 -0.000107144 -0.000152711 1 2.35064e-05 0.00023057 -1 0 0 1 1.39415e-05 0.000388921 1 -4.21248e-06 -1.70238e-05 1 -0.000119302 -0.000137597 -1 -0.000728346 -0.000286687 0.999996 0.00206458 0.00179763 0.999999 -0.00161938 -0.000340646 1 -0.000132963 -6.23529e-06 0.000884852 0.989591 0.143908 0.474054 0.844643 0.248697 -0.414233 0.362469 0.834882 -0.486515 -0.784765 0.383988 0.487761 -0.383204 0.784375 -0.99966 -0.0253267 -0.00626742 -0.999999 -0.00126382 0.000547044 -0.999997 -0.000348176 0.00252387 -0.999837 7.85904e-05 0.0180352 0.975536 0.10219 0.194643 -0.0190136 -0.999819 0.00104093 -0.214257 -0.976727 -0.00994216 -0.527049 -0.845453 -0.0861891 -0.0211092 -0.000751329 0.999777 0.00179552 0.000136853 0.999998 -0.00653692 0.999973 0.0035113 0.917511 -0.183569 -0.35281 0.689204 -0.688949 -0.224382 0.522218 0.852638 -0.0172553 0.669738 0.340254 -0.660059 -0.810026 0.0106434 -0.586298 -0.0390084 -0.323421 -0.945451 0.262881 0.939368 -0.220185 -0.356881 0.842126 -0.404302 -0.401307 0.127289 -0.907056 -0.51436 -0.131821 -0.847383 0.0141112 -0.000479573 -0.9999 0.00248571 0 -0.999997 -0.261313 -0.963121 -0.0641315 0.075691 -0.997129 -0.00224083 0.142387 -0.527508 0.837533 -0.97119 -0.176086 0.160571 0.915991 -0.372141 0.149905 -0.917366 -0.397064 0.0279415 -0.364123 0.930314 0.04393 -0.683181 0.616931 0.390716 0.487525 0.700853 0.520696 -0.967351 -0.057891 0.24674 -0.607172 0.284057 0.74206 -0.734622 -0.126174 0.666641 0.0908073 -0.00108383 0.995868 0.00173734 0.999998 0.00103346 -0.793595 0.606892 -0.0434674 0.788398 -0.30379 0.534921 -0.514667 0.4 0.758365 0.500336 0.767121 0.401485 -0.958231 -0.229734 -0.170343 -0.982304 0.171986 -0.0741602 -0.980086 0.184871 -0.0724906 -0.999283 -0.00512536 -0.0375228 -0.998982 0.0281281 -0.0352803 -0.104016 0.102888 -0.98924 -0.549726 -0.684554 -0.478736 0.0331787 0.541876 -0.839803 0.706841 0.245479 -0.663412 -1 0.000230996 7.63633e-05 -0.99999 0.00397313 -0.00186379 -0.999999 0.0015505 -0.000367596 -1 0.00022366 3.36304e-05 -1 -0.000565721 -0.000612099 -1 7.21647e-05 -0.000296093 -1 1.21118e-05 -4.96951e-05 -0.999928 -0.0120074 -6.0213e-05 -1 0.000210658 -0.000247982 -0.989639 0.0167274 -0.142604 -0.999938 0.00348843 -0.0105685 -1 1.83033e-06 -4.40602e-05 -0.998163 -0.0461538 0.0392523 -1 -1.7014e-05 -0.000369424 -1 -0.000547972 -0.000661936 -1 -7.72997e-05 -9.3376e-05 -0.999999 0.00159914 2.37939e-05 -0.999998 0.0018439 0.000214439 -1 0.000621501 -0.00025291 -1 -0.000505313 0.000136146 -1 -0.000563691 0.000264426 -1 -4.65347e-05 -0.000117894 -1 0.000657527 9.88683e-05 -0.999999 -0.000816414 -0.000824367 -0.997919 -0.0495763 0.0412178 -1 9.14814e-05 -0.00037535 -1 3.6267e-05 -0.000148804 -0.984068 0.14101 0.10829 -1 0.000340735 4.14943e-05 -1 -1.31307e-05 0.000333652 -1 0 0 -1 -5.56066e-07 -1.51563e-07 -1 -3.72355e-06 -0.000135718 -0.999999 -0.000721542 -0.000920219 -1 0.00020173 0.000257276 -1 -0.000270927 0.000169459 -0.993653 0.0234815 0.110014 -1 -1.49972e-05 -1.74412e-06 0.989739 -0.118267 0.0801865 0.999999 0.000641477 0.00110108 1 0.000527597 -9.81718e-06 1 3.16957e-05 -4.87044e-05 1 -8.71768e-05 -0.000130754 0.999999 0.00100368 -0.000257758 0.998002 0.0137588 0.0616644 1 -3.03162e-05 -3.93138e-05 0.999605 0.0243838 0.013989 1 -3.35294e-05 -4.8488e-05 1 7.20645e-05 -0.000120591 1 -3.13745e-05 -3.40418e-05 1 0.000555373 -0.000110933 1 0 0 0.999999 0.000777191 0.0011552 -0.454675 -0.821036 0.345209 -1 0.000676645 -0.000297757 -1 -0.000505313 0.000136146 -1 0.000564173 -2.29685e-05 -0.999998 -0.00115832 0.00157108 -0.999991 0.0036655 -0.00200444 -0.997912 -0.049694 0.0412658 -0.999987 -0.00359803 -0.0037443 -0.999999 -0.00114653 0.000323848 -1 0.000377937 -0.000106751 -0.984129 0.140576 0.1083 -0.999988 0.00439181 -0.00200326 -0.999937 0.0042759 -0.010336 -1 0.000530906 0.000442087 -0.999999 -0.000542497 0.00164866 -0.999998 0.000461503 0.00192716 -1 -0.000598704 0.000132229 -0.999995 -0.000625465 -0.00311794 -0.999986 -0.00299821 -0.0044429 -0.993653 0.0234817 0.110015 -1 -1.49972e-05 -1.74412e-06 0.989739 -0.118269 0.0801873 0.999999 0.000641476 0.00110108 1 0.000527596 -9.81993e-06 1 3.16957e-05 -4.87043e-05 1 -8.71768e-05 -0.000130754 0.999999 0.00100176 -0.000257535 0.998002 0.0137589 0.0616651 1 -1.41979e-05 1.76117e-05 0.999605 0.0243838 0.013989 1 -8.21775e-05 8.07512e-05 1 7.20646e-05 -0.000120592 1 -2.46181e-05 0.000187393 1 0.000555373 -0.000110933 1 0 0 0.999999 0.000777192 0.0011552 -0.454673 -0.821038 0.34521 -0.768293 -0.0472073 0.638355 0.764268 -0.58865 0.263411 0.905215 -0.348036 0.243838 0.954016 0.296485 0.0441675 -0.928768 0.155488 0.336471 0.900907 0.0901506 -0.424546 0.95034 -0.178269 -0.255098 -0.284863 -0.241833 -0.927561 0.908248 0.417663 -0.0253777 -0.00699238 0.984503 0.175228 -0.593261 0.766673 0.245468 -0.19166 0.221189 0.956212 -0.758995 -0.0503118 0.64915 0.759968 -0.594092 0.263635 0.493733 -0.830451 0.258031 0.954016 0.296483 0.0441673 -0.928771 0.155483 0.336467 0.637161 0.0887817 -0.7656 0.0304703 0.207577 -0.977744 0.954682 -0.182608 -0.235025 -0.522562 -0.215125 -0.825015 0.903979 0.396283 -0.160566 0.724178 0.688343 -0.0418383 0.810118 0.576267 0.107821 -0.554152 0.747237 0.366813 -0.222207 0.219097 0.950064 0.832627 0.508878 -0.218577 0.98684 0.148551 -0.0638742 -0.782531 0.611205 -0.118633 -0.425747 0.543728 -0.723256 -0.672765 0.110357 -0.731579 -0.666043 -0.469721 -0.579439 0.916098 -0.400834 0.00980438 -0.989184 0.100294 0.107036 -0.953802 -0.275024 -0.120928 -0.893267 0.447155 0.0461195 -0.984038 0.0597178 -0.167637 -0.901485 -0.431669 0.0314011 -0.476592 -0.112978 0.871835 0.0162262 -0.947616 -0.319 1 4.72829e-05 0.000552281 1 -0.000627409 7.79196e-05 1 -0.000219004 -0.00014141 1 0.000159534 -8.25999e-05 1 5.31108e-06 -9.54464e-07 0.993882 -0.0811473 0.0749204 0.999999 0.000639813 0.00092306 1 0.000664129 0.00066945 0.995072 -0.063009 0.0765614 0.998901 0.0149763 -0.0444131 1 0.000146618 0.00022229 0.989018 -0.000493579 -0.147793 0.9976 -0.039519 0.0568539 1 -0.000147517 -0.000730797 1 0.000143839 0.000163383 1 -0.00011108 6.27229e-05 1 0 0 1 -0.000103211 0.000417897 1 3.03316e-05 0.000377458 0.999999 0.000683114 0.000934747 0.099734 0.86442 -0.492779 0.0299233 0.833867 -0.551154 -0.330868 -0.324879 -0.885991 0.174171 -0.876472 -0.448844 0.00172038 0.984494 -0.175411 -0.993574 0.00290779 -0.113151 -0.869404 0.493754 0.0185648 -0.354324 0.329895 -0.874999 0.354324 -0.329895 0.874999 -0.664702 -0.166849 0.728239 -0.886608 0.456395 0.075031 -0.264085 0.404357 0.875645 0.545186 0.0887345 0.833605 -0.673187 -0.652787 0.347402 0.82778 0.317677 0.462451 -0.104057 0.945322 0.309094 0.129987 0.897802 0.420778 -0.155854 0.623078 0.766474 0.0905854 0.54361 0.834436 -0.0242562 -0.00718652 0.99968 0.105142 0.0337696 0.993884 -0.162855 -0.412489 0.896287 0.181694 -0.598357 0.780356 -0.108406 -0.786962 0.607404 0.101659 -0.896598 0.43102 -0.116568 -0.961229 0.249902 -0.994558 0.100167 0.028642 -0.975049 -0.22189 0.00660214 -0.923231 0.335809 0.186751 -0.0445777 -0.970068 0.238706 0.144152 -0.907776 0.393908 -0.0439784 -0.832739 0.551917 -0.00511482 0.89983 -0.43621 0.0251486 0.905668 -0.423242 -0.0650942 0.633288 -0.771174 0.157952 0.514224 -0.842986 -0.149373 0.1928 -0.969802 0.110356 -0.0984216 -0.989007 -0.0212279 -0.199847 -0.979597 0.025262 -0.53575 -0.843999 0.0167212 -0.54027 -0.841326 -0.0584892 -0.807198 -0.587376 0.109958 -0.865563 -0.48858 -0.0381188 -0.994971 -0.0926288 0.0193133 -0.992454 -0.121084 0.0168935 0.916871 -0.398825 -0.139866 0.937025 -0.320034 -0.076596 0.601657 -0.795073 -0.0271387 0.652169 -0.757588 -0.123908 0.985009 0.120014 -0.104678 0.607675 0.787257 -0.0315057 0.54994 0.83461 -0.123713 -0.138162 0.982653 -0.0832359 -0.804409 0.588217 0.0728657 -0.884262 0.461271 0.00740138 0.967587 0.252428 -0.072795 0.885603 0.458703 0.0145124 0.846072 0.532871 -0.0388172 0.275291 0.960577 -0.00501931 0.250398 0.96813 0.00343099 -0.252206 0.967667 -0.0491524 -0.485737 0.872722 0.0341457 -0.550723 0.833989 -0.072477 -0.960386 0.269084 0.0806991 0.975114 -0.206494 0.151684 0.986536 -0.061147 0.254369 0.948292 -0.189841 0.251671 0.887299 -0.386475 -0.0278206 0.998209 0.0529628 0.023316 0.993922 0.10759 -0.0418799 0.948475 0.314072 -0.30139 0.845948 0.439927 0.669385 0.67353 0.313497 -0.0231909 0.927367 0.373434 -0.0160558 0.901279 0.432941 -0.0517013 0.727309 0.68436 0.0823086 0.606873 0.790525 -0.0827776 0.500569 0.86173 -0.0179206 0.399048 0.916755 -0.0194043 0.152826 0.988063 0.00389127 0.134057 0.990966 0.0203331 -0.143894 0.989384 -0.171317 -0.246063 0.953993 -0.0201544 -0.541215 0.840643 0.599658 0.113844 0.792117 -0.0167331 -0.544529 0.838575 -0.0615684 -0.768355 0.637056 -0.00324851 -0.699026 0.715089 0.00498235 -0.63446 0.77294 -0.0152469 -0.976521 0.214882 0.0543253 -0.994465 0.0899337 0.0458843 -0.979066 -0.198303 -0.129882 -0.881735 -0.453513 0.00370091 -0.859363 -0.511353 -0.0409198 -0.366199 -0.929637 -0.0578981 0.51896 -0.852836 -0.12943 0.945475 -0.298875 0.0394039 0.97892 -0.200409 0.035998 0.625021 -0.779778 -0.0264099 0.721487 -0.691924 0.0216418 0.83723 -0.546422 0.000174846 0.825322 -0.564662 -0.00228799 -0.142889 -0.989736 -0.008471 0.147195 -0.989071 -0.00104392 0.153701 -0.988117 0.034081 -0.820942 -0.569994 -0.0330377 -0.749153 -0.661573 -0.0108778 -0.632758 -0.774273 0.0286017 -0.601766 -0.79816 -0.0653874 -0.995202 -0.072785 0.766994 0.634333 -0.0966492 0.0179206 -0.399048 -0.916755 0.492053 -0.819917 0.29261 -0.83506 -0.543009 -0.088415 0.284419 -0.794563 -0.536447 -0.155499 -0.604578 -0.781221 -0.0158012 -0.493031 -0.869868 0.0965404 0.00193942 -0.995327 -0.468559 0.695681 -0.5445 0.0260196 0.88577 -0.463395 -0.00828971 0.868753 -0.495177 -0.0212655 -0.976781 -0.213184 -0.0554724 -0.886851 -0.458714 -0.0618708 -0.888858 -0.453987 -0.0533149 -0.26555 -0.962622 -0.019399 -0.244583 -0.969434 -0.0147406 0.257762 -0.966096 -0.0257687 0.263933 -0.964197 -0.0347158 0.520738 -0.85301 -0.241896 0.312465 -0.918614 -0.0611388 0.959401 -0.27534 -0.00279501 0.974653 -0.223703 -0.99985 -0.000204459 -0.0172947 -0.288297 0.171471 0.942063 -0.669385 -0.67353 -0.313497 -0.999344 -0.0191747 0.0307093 -0.998422 -0.0420814 -0.0371847 -0.996981 -0.0767349 0.0118685 -0.969093 -0.168314 0.180357 -0.994259 0.105173 0.0196897 -0.4051 0.0496513 -0.912923 -0.999458 -0.0323845 0.00586579 -0.999757 0.0190178 0.0111319 -0.999843 -0.00169244 -0.0176417 -0.120108 0.374283 0.919504 -0.154736 -0.375511 0.91381 0.0467709 0.986688 -0.155751 -0.122796 0.915134 -0.383992 0.0651158 -0.738782 -0.670791 -0.00655355 -0.981927 0.189148 0.665278 -0.485756 -0.566963 -0.00774422 -0.577195 -0.81657 -0.300176 -0.572922 0.762663 -0.392059 -0.700521 0.596288 -0.610375 -0.735734 0.293493 -0.0313812 0.460641 0.887031 -0.224637 -0.894988 0.385402 -0.0256412 0.828418 0.559524 -0.148956 0.879703 0.451591 0.892457 0.39664 0.214936 1 -0.000483486 0.000257197 0.898277 -0.220283 -0.380228 1 5.49652e-06 1.11328e-06 0.998758 0.0415899 -0.0274537 1 5.64678e-06 1.07858e-06 1 -0.000182295 -3.48198e-05 1 1.45821e-05 9.79134e-07 1 6.68327e-06 1.04074e-05 1 0 0 1 -6.22642e-07 6.58558e-06 1 -1.47071e-07 8.32613e-06 1 1.66989e-05 -4.21253e-06 1 -5.12207e-06 2.7309e-07 0.690887 -0.249891 -0.678402 1 3.65518e-05 7.97089e-05 1 2.71405e-05 3.59364e-05 1 4.94031e-05 -5.24634e-05 1 3.08472e-05 -0.000142225 1 2.97119e-05 -0.000149454 1 -0.000127975 -8.78275e-05 1 -5.43661e-06 6.62034e-06 1 1.06531e-05 -1.49411e-05 1 -4.72479e-05 2.05305e-05 1 -5.48192e-05 3.45763e-05 0.999148 0.0412513 0.00160351 0.999974 0.00263853 -0.00674037 0.99989 0.00541562 -0.0138047 0.551332 0.694712 -0.461962 0.999924 0.0122574 0.0013429 0.0736397 0.996926 0.0267517 0.0587442 0.997676 0.0345158 0.960789 0.266319 0.0771899 0.674196 0.608637 0.418355 0.960575 -0.150237 0.233932 0.901183 -0.432476 0.0288849 0.811682 -0.410725 -0.415305 0.826904 -0.157537 -0.539826 -0.96404 -0.265754 -0.00157485 0.90478 0.186426 -0.382909 0.802059 0.582144 -0.133454 -0.978834 -0.204609 0.00434426 -0.960312 -0.199891 -0.194535 -0.943687 -0.240841 -0.226828 -0.990377 -0.0174589 -0.137293 -0.955021 -0.0747578 -0.28696 -0.993551 0.0638817 -0.0936733 -0.996102 0.0869937 -0.0145889 -0.961679 -0.274178 0.000894776 -0.919625 -0.246591 0.305748 -0.872358 -0.31436 0.374392 -0.915001 0.0905158 0.393166 -0.99472 0.00497541 0.102507 -0.944122 0.209876 0.254136 -0.997168 0.0705924 0.0259481 -0.998222 -0.0444964 -0.0396601 -0.452682 0.822036 -0.345449 -0.758622 -0.000326771 0.651531 -0.976998 0.160564 -0.140333 -0.993439 0.0645152 -0.0944267 -0.998658 -0.0517906 -0.000710529 -0.998083 -0.0406234 0.0467011 0.0686478 -0.865751 -0.495744 0.0903075 -0.994713 -0.0488843 -0.0736734 -0.986387 -0.147013 -0.0151515 -0.843907 -0.536275 -0.0748253 -0.583037 -0.808993 0.052649 -0.531578 -0.845371 -0.1087 -0.0898719 -0.990004 -0.00792794 -0.136854 -0.990559 -0.0107209 0.423803 -0.905691 0.0995665 0.380697 -0.919324 -0.13957 0.745569 -0.65165 0.0711054 0.994595 -0.0756609 0.149926 0.854743 -0.496927 -0.999993 -0.000491981 -0.00379006 -0.999996 3.62867e-05 -0.00290994 -0.999999 -0.000912219 -0.00111628 -0.999472 -0.0250689 -0.0206651 -0.999573 -0.0251885 -0.0148015 -0.999951 0.00442602 -0.00890497 -0.999999 -0.0011579 -7.28112e-05 -0.998601 -0.0524358 0.00677342 -0.999122 -0.041772 -0.00334002 -0.999997 -0.00219992 0.000802707 -0.994383 -0.0577173 0.0887164 -0.9933 -0.0702935 0.0917253 -0.998487 -0.0419872 -0.0354954 -0.999871 0.0102753 0.0123335 -0.999083 -0.000320611 0.0428195 -0.999398 -0.00821361 0.0336972 -0.999996 0.0014733 0.00223942 -0.999128 0.031897 0.026932 -0.99924 0.035279 0.016566 -0.999885 -0.0138049 0.00633932 -0.999869 0.0156017 -0.00438591 -0.994043 0.103162 0.0351452 -0.981329 0.186764 -0.045961 -0.994083 0.0713507 -0.081898 -0.998054 0.0411027 -0.0468954 -0.997695 0.0517249 -0.0439212 -0.999999 0.000448245 -0.00108569 -0.999991 0.000314279 -0.00433423 0.661428 -0.323129 0.676831 1 -3.85826e-05 0.000941163 1 -0.000537427 -0.000459231 1 -3.11891e-05 -8.3871e-05 1 -1.84288e-05 -0.000264973 1 -3.9918e-06 -0.000212285 1 4.06352e-05 0.000446363 1 -1.57111e-06 0.000197269 0.999908 0.00305048 0.0132362 0.715493 0.282332 0.639029 1 9.67211e-05 9.4536e-05 1 3.073e-05 -0.000444751 -0.0363042 -0.5263 0.849523 0.126686 -0.376877 0.917559 -0.080865 -0.150934 0.985231 0.0896402 0.048349 0.9948 -0.12386 0.273527 0.953856 0.16842 0.551105 0.817262 -0.05272 0.678242 0.732945 0.999962 -0.00827645 -0.00290566 0.999781 0.0208642 -0.00174974 0.894009 0.396232 0.20916 0.999987 -0.000264499 -0.00511395 0.999816 0.0162287 -0.0102603 0.999495 0.0150251 -0.0280041 0.999893 -0.000698084 -0.0146432 0.999954 -0.00222417 -0.00928524 0.999837 -0.0104688 -0.0147175 0.999883 -0.0100431 0.0115073 0.999988 -0.00250287 0.00410745 0.999996 -0.00249317 0.0014881 0.999993 -0.00316735 0.00213437 0.999966 0.00451529 0.00693315 0.999954 0.00771277 -0.00567827 0.999981 0.00516649 0.00347566 0.999999 0.000373602 0.00108146 1 -0.000614032 -0.000320425 0.999951 0.00968735 -0.00206362 0.999547 0.0161351 0.0254215 0.999002 0.00443131 0.044456 -0.963874 -0.0328008 -0.26433 -0.677088 -0.222457 -0.701473 -0.358194 -0.680674 -0.639045 -0.201228 -0.935484 -0.290476 -0.872493 -0.454637 0.179055 -0.343769 -0.832976 0.43356 -0.326346 -0.324029 0.887977 -0.95309 0.223168 0.204488 -0.436391 0.89917 0.0325123 -0.158748 0.864768 -0.47642 -0.806106 0.465281 -0.36566 -0.382527 -0.884203 -0.268063 0.244279 -0.742217 -0.624053 0.338286 -0.178252 -0.924007 -0.0763305 0.136682 -0.98767 0.455453 0.303026 -0.837101 -0.685656 0.637793 -0.350852 -0.0084332 -0.645776 -0.763481 -0.0119928 0.792853 0.609295 0.586959 0.0138121 0.809498 -0.0110069 -0.637794 0.770129 -0.539035 -0.472968 0.696952 -0.649601 -0.680167 0.339693 -0.31896 0.695648 -0.643692 -0.691417 0.0101614 0.722385 -0.644815 0.668534 -0.370509 -0.625319 -0.72846 -0.279861 -0.639116 -0.744299 -0.193775 -0.943541 -0.288954 -0.161973 0.888206 -0.315572 0.333923 0.705141 -0.700214 0.1117 -0.999337 -0.0334439 -0.0143669 -0.938226 0.344765 -0.029478 -0.991036 0.0204238 0.132025 -0.386112 -0.384285 -0.838596 -0.855544 -0.381513 0.34999 -0.416357 -0.5682 0.709785 -0.993361 -0.0683535 -0.0925298 -0.997844 0.0566656 -0.0331124 -0.997199 0.0145921 0.0733639 -0.998999 -0.0443908 0.00553267 -0.99856 -0.0491368 -0.0215302 -0.99807 -0.000156751 -0.0621042 -0.999547 -0.0150187 -0.0260993 -0.949414 -0.313684 0.0147065 -0.999763 -0.0216529 -0.00223375 -0.990764 0.128297 0.0438952 -0.990465 -0.0819327 -0.110756 -0.999959 -0.00159928 0.00891537 -0.986164 -0.126484 0.107159 -0.997316 -0.0711265 -0.0173669 -0.999967 -0.00477113 0.00663652 -0.9978 0.0318631 0.0581379 -0.997996 -0.00802269 0.0627722 -0.999555 0.00294737 -0.0296929 -0.999915 -0.0112086 -0.00662403 -0.999869 0.00540778 0.0152904 -0.999929 -0.0111082 -0.0043025 -0.989784 -0.130621 0.0571421 -0.999851 0.0165474 0.0049603 -0.999182 -0.0356216 -0.0191695 -0.999989 0.00237313 0.00399153 -0.997729 0.0517179 -0.0431479 -0.999953 0.00963434 -0.000593111 -0.997593 -0.0152905 -0.0676423 -0.99991 0.00583492 -0.0120958 -0.99991 -0.0134127 0.000970183 -0.996841 -0.0773312 -0.0181012 -0.998423 -0.0439299 0.0349454 -0.999798 0.00128653 -0.0200319 -0.997579 0.0176777 -0.0672555 -0.999158 0.00142202 0.0410151 -0.99972 -0.0119639 0.0204107 -0.999494 0.0304404 -0.00928434 -0.995842 0.0900376 -0.0138317 -0.999833 0.00667674 -0.0170329 0.122125 -0.746861 0.65367 -0.215379 0.223837 0.950531 0.109231 0.993837 0.0189117 0.511408 -0.205875 -0.834312 4.48757e-05 -0.98532 -0.170715 -0.00635957 -0.996824 0.0793778 0.187204 -0.87534 0.445797 -0.0702514 0.740565 0.668303 0.0442191 0.84065 0.53977 0.0842909 0.807566 -0.583723 0.13512 -0.221932 0.965654 0.11234 -0.24674 0.962548 -0.0061036 0.978989 -0.20382 -0.0425439 -0.0538241 -0.997644 -0.00247374 0.0532194 -0.99858 0.144622 -0.263571 -0.953737 -0.0186115 -0.74368 0.668277 0.0626192 -0.663122 0.745888 0.942299 0.0482339 0.331279 0.942788 0.0739913 0.325078 0.0301513 0.781158 -0.623605 -0.268505 -0.184188 -0.945505 0.0878303 -0.931744 -0.352335 0.0268581 -0.990795 0.132681 0.72302 0.640732 0.258272 0.401209 0.244773 0.882676 0.015058 0.991465 0.129503 0.996981 0.0767349 -0.0118685 0.0781627 0.683979 0.725303 0.831462 -0.377891 -0.40727 0.316417 0.281669 -0.905838 0.206195 -0.789341 -0.578295 -0.0130772 -0.297847 0.954524 0.0593214 0.0744202 0.995461 0.00492073 0.00352296 0.999982 0.999843 0.00169244 0.0176417 0.0141626 0.584919 0.810968 0.026617 0.993869 0.107316 0.487992 -0.857905 -0.160818 -0.999843 -0.00169244 -0.0176417 0.999843 0.00169244 0.0176417 0.918319 -0.328277 0.221191 -0.122888 -0.453715 -0.882633 0.0941315 0.347463 -0.932957 -0.975389 0.107593 -0.192459 0.379601 0.151528 -0.912657 0.987924 0.0599405 -0.142872 -0.973457 0.14061 -0.180586 -0.365888 0.0949908 -0.925799 0.976442 0.108013 -0.186802 -0.557378 0.15094 0.816423 -0.305751 0.0687519 0.949626 0.30417 0.199885 0.931411 0.357342 -0.0916224 0.929469 -0.357342 0.0916224 -0.929469 0.649965 0.638811 -0.411663 -0.0335245 0.653423 0.75625 0.0325811 -0.931442 0.362429 0.0399093 0.902955 0.427878 0.0877394 -0.965571 0.244898 0.0155049 -0.575077 0.817952 -0.961172 -0.252591 0.111111 0.961172 0.252591 -0.111111 -0.363547 0.929403 0.0635897 0.772153 -0.605505 0.192726 0.639353 -0.674364 -0.369407 0.426072 -0.785135 0.449473 0.183084 -0.941825 -0.28186 0.164216 -0.868689 0.467347 0.187091 -0.660465 0.727174 0.620511 -0.754809 -0.21267 0.681798 -0.416964 0.601077 0.90455 -0.31464 -0.287735 0.701688 -0.581945 -0.411064 0.236198 -0.9645 -0.118115 -0.114543 -0.831225 -0.544009 0.62161 -0.781232 -0.0572564 -0.205397 -0.608527 -0.76649 0.384478 -0.761592 -0.521684 -0.706206 0.703189 -0.0824556 0.0782649 0.568726 -0.818795 -0.718606 0.690749 -0.0804426 -0.747939 0.597879 -0.28832 0.134649 0.976959 -0.165591 -0.167553 0.963985 0.206541 0.288001 -0.945839 -0.149812 -0.314879 0.800923 -0.509287 -0.0281763 0.78211 0.622503 -0.172463 -0.984265 -0.0384516 -0.879744 -0.131568 -0.456882 -0.764383 0.634015 0.117231 0.105994 -0.854623 -0.508315 -0.980482 0.173208 0.093022 -0.72412 0.500302 -0.474708 0.408519 -0.889424 -0.205029 0.425853 0.475994 0.769467 0.558961 -0.546575 0.623553 -0.330803 -0.674502 0.660013 -0.303113 -0.776212 0.552827 -0.363058 0.744804 0.559871 -0.321901 0.762093 0.561777 0.186027 0.282202 0.941146 0.250578 0.148757 0.956599 0.109698 0.136656 0.984526 -0.975736 -0.00217793 0.218938 -0.981135 -0.00443036 0.193272 -0.0563693 -0.998318 0.0135613 0.760641 -0.0394497 0.647973 0.975739 0.000424016 0.218939 -0.975739 0.000124916 0.218939 -0.967571 0.00308025 0.252581 -0.0176986 -0.999832 0.00485846 0.000103683 -0.996796 0.0799841 0.997226 -0.00403343 -0.0743286 0.975355 -0.0280558 0.218852 -0.975739 6.46632e-05 0.218939 -0.870857 -0.0455991 -0.489417 4.49019e-06 -0.910214 0.414139 0.113298 -0.993236 0.0254227 0.975738 0 0.218943 0.975739 3.22105e-07 0.218939 -0.975739 0 0.218939 -0.975739 0 0.218939 -0.14294 -0.989212 0.0320732 0.813846 -0.0263078 0.580485 0.975739 0.000269102 0.218939 -0.978555 -0.0402811 0.202007 0.982957 -0.00256843 0.183819 -0.963093 -0.00623978 -0.269095 -0.000111347 -0.994389 0.105783 0.0243145 -0.999674 0.00781213 0.973051 0.0011565 0.230585 -0.960334 -0.0214696 0.278024 0.982711 -0.00432501 0.185098 -0.864641 -0.000456839 0.50239 0.0446293 -0.998938 0.0114662 0.97174 -0.000241907 0.236054 -0.743185 0 0.669086 -0.434265 -0.773049 0.462395 -0.0112164 -0.557068 0.830391 0.493855 -0.869544 -0.000610666 -0.464914 -0.320945 0.825136 -0.30771 -0.540807 0.782842 -0.0123306 -0.999918 -0.00339168 0.418047 -0.238443 0.876574 0.118791 0.932578 0.340861 0.310141 0.186685 0.932181 -0.383862 0.636186 0.669266 -0.482037 0.20806 0.851088 0.234429 0.76054 -0.605494 0.316953 -0.236509 -0.918479 0.227444 0.828015 0.512505 -0.673501 0.472039 -0.568837 -0.342945 0.89472 -0.286119 0.959462 0.0253323 0.280697 -0.982761 0.00396586 0.184837 0.846459 0.0010183 0.532452 -0.049008 0.998704 0.0137185 -0.968512 -0.00117502 0.248962 0.975738 0.00086101 0.218938 0.972911 0 0.231181 0.143177 0.989112 0.0340411 -0.756721 0.0308678 0.653009 -0.975737 -0.0017699 0.218938 0.975739 -0.000124897 0.218939 0.961492 -0.00504374 0.274787 0.0228264 0.999714 0.00707955 -4.70362e-06 0.994896 0.100906 -0.98564 0.003857 -0.168814 -0.975116 0.0357185 0.218799 0.975736 0.00216697 0.218938 0.980383 0.00408774 0.19706 0.481123 0.871082 0.0986744 9.16478e-06 0.551305 0.834304 -0.549747 0.826203 0.123156 -0.97581 -0.000456121 0.218618 -0.975739 -0.000428065 0.218939 0.975739 -6.46632e-05 0.218939 0.897999 0.042571 -0.437934 -4.05748e-06 0.927336 0.374229 -0.0984688 0.994875 0.0229878 -0.974204 0 0.225671 -0.975739 -0.000472573 0.218938 0.980396 0.0301713 0.194713 -0.982957 0.00256843 0.183819 0.989995 0.00633488 -0.140963 -0.000330429 0.995991 0.0894562 -0.0201675 0.999772 0.00706039 -0.973133 -0.00112891 0.230241 0.704691 0.703592 -0.0914776 -0.704691 -0.703592 0.0914776 -0.218052 -0.975937 0 -0.243565 -0.967424 0.0690479 -0.708048 -0.698424 -0.10427 -0.773218 -0.604192 0.192579 -0.929784 -0.338414 -0.144834 -0.993244 0 0.116041 -0.980211 0.0313917 0.195449 -0.906117 0.377081 -0.191736 -0.732184 0.626426 0.26739 -0.551834 0.79969 -0.236593 -0.171491 0.972575 0.157128 -0.229918 0.97321 0 -0.218052 -0.975937 0 -0.244593 -0.966956 0.0718997 -0.708889 -0.699254 -0.09231 -0.770399 -0.606582 0.196329 -0.929785 -0.338414 -0.144834 -0.993245 0 0.11604 -0.980212 0.031392 0.195447 -0.929784 0.338414 -0.144834 -0.72795 0.669259 0.148936 -0.759922 0.649332 0.029773 -0.251306 0.964228 -0.0843204 -0.222316 0.974975 0 -0.0755597 -0.532272 0.843195 0.976801 0.0546344 0.207065 0.101733 0.653197 0.750323 -0.0207531 -0.523751 0.851619 0.450889 0.892343 0.0205933 -0.660742 0.491491 0.567324 -0.505097 0.683091 0.527507 0.0522737 -0.793008 0.606965 -0.686519 -0.628305 0.365956 -0.737755 -0.606961 0.295494 -0.50022 0.569649 0.652135 -0.561131 -0.722302 0.404241 0.662501 -0.675891 0.322899 0.596001 -0.357495 0.719013 0.962069 -0.197357 -0.188343 -0.968788 -0.180983 -0.169398 0.973404 -0.140492 -0.180961 0.344091 -0.101841 -0.933397 -0.976453 -0.108152 -0.186664 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -3.00811e-06 2.81643e-07 1 8.94065e-07 -4.7164e-07 1 0 0 1 -4.17625e-05 0 1 0 -1.39689e-05 1 0.000138106 1.2686e-05 1 0 0 1 0 0 1 0 0 1 0.589886 -0.796136 0.134915 -0.999972 0.00747888 -2.60591e-05 -0.36774 -0.845708 -0.386711 -0.999773 -0.0210117 0.00352862 -1 0.000110268 0 -0.999999 0.000572458 -0.00114492 -0.999981 0.00605438 -0.001145 -1 0 0 -1 0.000110268 0 -1 0.000110268 0 -1 9.96716e-06 7.20882e-05 -0.000577691 0.000168229 1 -0.0164909 0.261118 0.965166 -0.13116 0.374644 -0.917845 -0.0276453 -0.621762 -0.782718 0.000873005 0.0233318 -0.999727 0.616094 -0.411105 -0.671879 0.999814 0.0192558 0.00140673 0.999904 0.00592461 0.0125271 0.999724 0.023476 0 0.5988 0.792523 0.115527 1 0 0 0.999984 0.00570926 0 0.999984 0.00570926 0 0.999984 0.00570926 0 1 0 0 0.113216 0.976967 0.18088 0.998167 0.0398993 0.0455108 -0.996123 0.0395863 -0.0785635 -0.613249 -0.490138 0.619428 1 0.000134471 -0.000283842 0.128457 -0.369806 -0.920186 -0.000648842 -0.0285262 -0.999593 0.0291399 0.64756 -0.761457 -0.983521 0.079107 -0.162568 -0.999998 -1.24176e-06 0.00214549 -0.999996 -0.00298244 0 -0.999981 -0.00608252 -0.001037 -0.859122 -0.506654 0.072187 -1 0 0 -0.999871 -0.0160644 0 -0.999871 -0.0160644 0 -0.999871 -0.0160644 0 -1 0 0 0 -0.00251977 0.999997 2.8609e-06 -0.00247287 0.999997 0.997083 -0.0763261 8.936e-05 0.325788 0.865468 -0.380561 0.999961 -0.00880546 0 1 0 0 0.999961 -0.00880546 0 0.985913 0.164559 0.0299236 0.99998 -1.24174e-06 0.00633648 0.999961 -0.00880546 0 0.999961 -0.00880546 0 1 0 0 -0.998234 -0.0455393 0.0381522 -0.0205909 -0.706959 -0.706954 -0.999813 -0.0137199 -0.0136516 -0.614126 0.487934 0.620298 0.0205909 -0.706959 -0.706954 0.615205 0.485179 0.621389 0.998295 -0.0413094 -0.0412411 0 0 1 5.35313e-06 -0.000186459 1 0 0.000110563 1 0 0 1 0 0 1 0 -0.100871 0.9949 0.12175 0 0.992561 0 0 1 -1.33817e-05 0.000471651 1 0.00303754 0.00125819 0.999995 -2.69015e-05 -1.1143e-05 1 -6.31079e-06 -0.000756855 1 0 -0.000129816 1 0 0 1 0 0 1 0 0.000240681 1 -1.84647e-05 0.000650808 1 0 0 1 0.219954 -0.0911078 0.971247 0.25361 0.506286 0.824231 -0.16776 0.971383 -0.168143 -0.0115523 -0.180718 0.983467 -0.445109 0.0366933 -0.894724 1 -0.000270147 -0.000555331 0.999998 0 0.00187354 1 5.5544e-05 0 1 0 0 1 0 0 0.999201 0 0.0399656 0.970916 -0.236982 0.0340729 0.988699 -0.130558 0.0736815 0.979615 -0.182731 0.0834506 0.984974 -0.106335 0.136084 0.868182 -0.375037 0.324971 0.959145 -0.156512 0.235679 0.963088 -0.0308036 0.267419 0.979171 0.0646656 0.192464 0.975237 0.062309 0.212205 0.962454 0.146545 0.228486 0.999736 -0.0192867 -0.0125024 0.999997 -0.00251864 -0.000362127 0.999995 -0.00321009 -0.000156806 1 8.36608e-05 4.08665e-06 0.00499838 0.0525535 0.998606 6.70381e-05 0 1 -3.72656e-06 -5.74353e-05 1 1.09784e-05 -1 0 -2.97954e-06 -1 -0.000117373 0.000186972 -0.999999 -0.00167882 -0.0061024 -0.999184 0.0399208 0 -5.56828e-05 -1 -0.000256093 0.000164361 -1 0.0594447 -0.744226 -0.665277 -0.0168141 -0.997701 -0.0656559 0.0409538 -0.922082 0.384822 8.95254e-11 -1 -0.000130396 8.00929e-05 -1 -0.000898734 -0.0011711 -0.695089 0.718923 0.0170144 -0.994109 -0.107038 -0.47324 -0.63383 -0.611803 -0.00153943 -0.999935 0.0112688 0.013064 -0.996873 0.0779287 -0.0333533 -0.97466 0.221192 0.0153072 -0.995664 0.0917552 -0.000138724 -0.99975 0.022379 -0.0327717 -0.996858 -0.0721125 -0.00662448 -0.998304 0.0578347 0.187349 -0.976118 0.109975 0 0 1 -0.000225001 -0.000198448 1 -0.0226626 0.239354 0.970668 -0.025386 0.292874 -0.955814 -4.0895e-06 0 -1 2.807e-06 -5.72575e-06 -1 -0.0065921 -0.99782 -0.0656593 -0.0885517 -0.985868 0.142205 7.02139e-08 -0.999687 -0.0250184 -0.00253635 -0.999696 -0.0245357 -9.13499e-12 -1 -0.000186277 -0.000115134 -1 0.00089509 0.00234866 -0.999831 -0.0182593 0.0234676 -0.97155 -0.235669 1.82964e-08 -1 -0.000683195 0.00257912 -0.999862 0.0164001 -0.0044602 -0.999985 0.00315869 -0.0969077 -0.993559 0.0587315 0.401391 0.742262 -0.536593 -0.000110315 0.992218 0.124512 0.103366 0.257919 -0.960621 -0.156604 0.98718 0.0308262 -0.481814 0.823878 -0.298464 -0.00242518 0.999997 -0.000384331 -0.00867905 0.999962 0.00014627 0.00464296 0.999989 9.7867e-06 0 1 0 -0.731278 -0.679409 0.0603027 0.647523 0.761425 -0.0307397 -0.180449 0.0935679 -0.979124 0.00104105 0.999999 -0.000601052 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.766683 0.628323 -0.131939 0.60437 0.752084 -0.262881 -0.00553292 0.99647 0.083762 0.0344535 0.999208 0.0198917 0.528713 -0.654939 -0.539924 -0.466214 0.706816 0.532029 0.00849546 -0.999917 -0.00969475 -0.00310916 0.999993 0.00188989 0.0332005 0.569977 -0.82099 0.721326 -0.0882105 0.686956 0.00552691 0.999824 0.0179182 0.056386 0.993451 0.0993788 0.0066829 0.999914 0.0112672 0 5.68753e-05 -1 0.000150619 -7.09296e-05 -1 -0.0603156 0.749925 -0.658767 0.0205062 0.995736 -0.089946 -0.0444217 0.907668 0.417331 -1.47985e-11 1 -0.000301762 0.000429511 0.999993 0.00381761 0 0.798636 0.601814 0 0.798636 0.601814 0.0493301 0.956805 0.286516 0 0 1 0.000202254 0.000178385 1 0.0226741 -0.239685 0.970586 9.83831e-05 1 0.000291529 0.0398708 0.991805 -0.12138 0.000753795 0.00016549 -1 -0.000195263 -4.15259e-07 -1 -2.67777e-05 0.000210223 -1 0.000292056 0.000475638 -1 0.000172854 0.00711367 -0.999975 0.0179166 -0.00169238 -0.999838 -0.00968081 0.000651998 -0.999953 3.1394e-05 5.73951e-05 -1 0.000237099 -0.000170929 -1 -0.000458694 -2.11601e-05 -1 0.000177545 0 -1 0.00044018 -0.000308351 -1 -0.00016238 0.00118456 -0.999999 0 0 -1 0.00745822 -0.0012775 -0.999971 0.013409 0.00205641 -0.999908 -0.0164605 0.00204392 -0.999862 -0.00251277 0.00368119 -0.99999 0 0 -1 0 0 -1 -0.00497298 -0.0525972 0.998603 -4.69803e-05 0 1 3.72658e-06 4.11936e-05 1 -0.00102469 0.999963 0.00850476 2.98006e-06 1 -0.000130548 4.50799e-05 1 0.000215796 0.00585962 0.999234 0.0386891 -0.00275377 -0.000858085 -0.999996 -0.00234744 -0.00999891 -0.999947 0.0114017 0.00134353 -0.999934 -0.0100359 -0.000345217 -0.99995 -0.0030454 8.76401e-05 -0.999995 -0.0020062 0.00803369 -0.999966 -2.78016e-05 -1.08383e-05 -1 -0.00226789 -0.000202399 -0.999997 3.88741e-05 0.000338574 -1 -3.9036e-07 3.90361e-07 -1 0.00356823 0.000588833 -0.999994 -0.0105981 -0.00200089 -0.999942 0.0260049 -0.00199959 -0.99966 -0.00519384 0.0212032 -0.999762 0.00596851 0.00874383 -0.999944 -0.000203175 -0.000441032 -1 1.43617e-05 9.67358e-05 -1 0 -2.15876e-06 -1 0.00117509 0.0032573 -0.999994 -3.99941e-07 -5.85911e-07 -1 -6.67731e-06 0.798627 0.601826 0 0.798553 0.601924 0 0 1 -0.0115319 -0.447184 0.894368 0.106981 -0.00923245 0.994218 0 0 1 0 0 1 0 0 1 0.0115319 -0.447184 0.894368 0.854229 -0.047565 0.517716 0.486105 0.0419508 0.872893 0 0 1 0 0 1 0 0 1 0 0 1 -0.011715 -0.447183 -0.894366 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.011715 -0.447183 -0.894366 0 0 -1 0 0 -1 -1.16882e-05 -6.24457e-05 1 0 -3.95236e-05 1 -0.000338672 0.000642184 -1 0 -1.20042e-05 -1 8.78067e-05 0.000160496 1 0 1.91181e-05 1 6.24715e-05 -0.000111626 -1 4.60989e-07 -1.51918e-05 -1 0.0705321 -0.0777273 0.994477 0 0 1 0 0 1 0 0 1 -2.23699e-08 0.00811207 -0.999967 0 0 -1 0.000136153 -0.000710836 -1 0.0001565 -0.000354409 -1 0.0563301 -0.127441 -0.990245 -0.0470023 -0.106338 -0.993219 1.1074e-08 -1.47414e-07 -1 0 0 -1 0 0 -1 0 0 -1 0.0983713 -0.400044 -0.911201 -0.0799341 -0.0880884 0.9929 0 0 1 -1.17888e-07 -6.14227e-07 1 -1.53879e-07 -1.69576e-07 1 0 -5.317e-05 1 6.63751e-05 8.27945e-05 1 0 7.0472e-05 -1 4.23274e-05 -1.60492e-05 -1 0.854231 -0.047565 -0.517714 -0.171181 0.0126803 0.985158 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.106982 -0.00923253 -0.994218 -0.554775 0.0478771 -0.830622 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 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.0743265 -0.0501215 0.995974 9.78968e-05 0.000739232 1 0 0 1 0 0 1 -3.08363e-07 -4.81985e-06 1 4.90397e-08 -3.30696e-08 1 0.1003 -0.051551 -0.993621 0 0 -1 -9.01977e-08 3.30902e-07 -1 -1.13617e-07 5.83957e-08 -1 0 -1 0 0 -1 0 0.0892414 0.0458671 -0.994953 0 0 -1 0.0206203 -0.181334 -0.983205 0.0241895 -0.0722617 -0.997092 0 0 -1 0 0 -1 0.0524677 -0.397521 0.916092 -0.236723 -0.159632 0.958373 5.07267e-06 0 1 9.42048e-07 -1.47246e-05 1 0 0 1 -6.86565e-07 -2.95681e-05 1 1.51569e-05 -1 -8.75084e-06 -0.0566488 -0.0715128 0.99583 0 0 1 -1.12754e-05 -2.45593e-05 1 -1.27426e-05 -1.60861e-05 1 -3.4587e-07 0 -1 5.95745e-06 -1.31856e-05 -1 6.94906e-06 -7.22645e-06 -1 0 -0.798635 0.601816 -1.26507e-06 -0.798648 0.601799 0 -0.798651 0.601795 1.56326e-06 -0.798635 0.601816 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.118323 -0.902085 -0.415021 0.0636003 -0.949972 -0.305792 -0.0824539 -0.995108 -0.0544197 0.18819 -0.973143 -0.132579 -0.645376 -0.691881 -0.323713 0.118673 -0.905278 -0.407908 -0.163829 -0.835885 -0.523886 -0.0587225 -0.954197 -0.293359 0.0799663 -0.987699 -0.134371 0.00725112 0.999973 -0.000968719 0.216845 -0.889038 0.403225 8.59635e-05 1 0.000152886 1.37025e-06 1 -2.23132e-05 -8.55346e-07 1 -2.38749e-05 0 1 0 -7.81834e-07 1 -2.05272e-05 4.18922e-05 1 0.000518498 6.56261e-06 1 0.00011875 1.90482e-07 1 -1.11511e-05 -1.57311e-07 1 1.92698e-05 1.8095e-07 1 -2.21655e-05 0 1 8.98614e-05 -6.21301e-07 1 -1.63124e-05 0 1 0 0 1 0 -0.0773474 0.487616 0.869625 -2.63302e-06 1 7.0197e-05 -1.35824e-06 1 -4.15913e-06 6.14911e-05 -9.98525e-06 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.21644 0.200358 -0.955516 0 0 -1 -1.80798e-05 -4.08623e-06 -1 0 0 -1 0 0 -1 0.000264454 -5.05262e-05 -1 -5.66464e-06 3.43659e-06 -1 1.4514e-05 -1 -0.00023694 -3.02579e-05 -1 -0.000893397 2.87309e-05 1 -0.000253443 4.18197e-05 1 -0.000449747 -1.83658e-05 3.30452e-06 -1 -4.67913e-06 1.50584e-06 -1 2.71232e-05 -3.37515e-06 -1 7.44942e-06 -7.98187e-07 -1 -0.0436407 -0.994873 -0.0912361 0.261781 -0.813266 0.519682 -0.0245705 0.990551 -0.134925 0.00962843 0.997694 -0.0671939 -2.70858e-05 -0.000181424 -1 1.51041e-05 -4.42562e-06 -1 6.00445e-07 4.59989e-06 -1 -1.64452e-07 -6.58171e-06 -1 -2.40535e-06 4.599e-07 -1 -0.805114 0.153937 -0.572796 7.47635e-05 8.12006e-05 -1 2.79679e-06 3.83123e-06 -1 -4.29544e-07 -6.32144e-06 -1 -0.000353829 0.000338903 -1 -2.51424e-05 -0.000105647 -1 -3.20599e-05 4.02142e-06 -1 -7.44993e-06 7.98187e-07 -1 0 0 -1 0 0 -1 1.63359e-05 4.07058e-06 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 9.14155e-07 -1.78892e-07 -1 0.60637 0.498634 -0.619419 -1 -8.2377e-05 0.000520761 -0.999998 8.62396e-05 -0.00194824 1 -1.68476e-05 -0.000396345 1 1.08353e-05 2.78611e-05 -1 4.88068e-05 -0.000705994 -1 4.60556e-05 -0.000661731 1 9.18807e-05 0.000661706 0.999999 -3.04372e-05 -0.00121739 2.40534e-06 -2.5852e-06 -1 0.810354 -0.153416 -0.5655 -0.00192042 -0.00187218 -0.999996 -5.16145e-07 6.59076e-06 -1 -8.43519e-05 0.000684375 -1 0 0 -1 0 0 -1 -3.51568e-05 1 0.000594382 3.51569e-05 1 -0.000594385 -4.15255e-05 -1 -0.000702049 -3.51569e-05 -1 -0.000594379 6.95023e-06 5.22395e-05 -1 5.56904e-06 -5.04084e-05 -1 2.11084e-05 -0.000188993 -1 9.58136e-07 3.68367e-06 -1 -1.58854e-05 3.59106e-06 -1 0 0 -1 7.95195e-07 4.8523e-07 -1 -4.74504e-06 1.83433e-07 -1 -6.33994e-08 2.23811e-07 -1 -1.80652e-07 1.16049e-07 -1 -0.745056 0.592882 0.305586 -0.670561 0.708037 -0.22143 -0.439563 0.834168 0.333089 -0.281148 0.930768 -0.233722 -0.0512783 0.966085 0.25308 0.262373 0.94344 -0.202687 0.26456 0.939481 -0.217676 0.592828 0.699288 0.399439 0.731984 0.521706 -0.438204 0.658184 0.638951 -0.398165 0.64442 0.76263 -0.0558405 0.314781 0.946508 0.070966 0.36077 0.910364 -0.202688 0.0512783 0.966085 0.25308 -0.199441 0.940718 -0.274358 -0.267829 0.963058 -0.0280694 -0.62946 0.742498 0.229077 -0.699558 0.700876 -0.139251 -0.837057 0.333158 0.433983 9.7949e-05 7.89905e-06 -1 0.747211 0.0587221 -0.661988 3.54482e-08 -0.000295221 -1 -0.000130367 -0.000159643 -1 0.00261855 -0.000782131 -0.999996 0 0 -1 -8.57234e-08 1.69223e-06 -1 -0.000120592 8.48704e-05 -1 1.2727e-07 -6.61689e-07 -1 0 0 1 -0.000120694 -6.75158e-06 -1 6.94627e-06 -9.11698e-05 -1 0.393234 0.604092 -0.693138 0 0 -1 3.18595e-05 -1.41598e-06 -1 -0.00123043 -1.4357e-06 -0.999999 -3.0242e-05 -2.98787e-06 -1 6.71356e-07 3.80994e-05 -1 -2.4072e-07 9.89922e-06 -1 -3.02133e-05 7.02635e-07 -1 0.000110188 -8.3351e-06 -1 -1.9059e-05 0.00025015 -1 -1.61757e-05 0.000605439 1 0.521487 -0.498621 -0.692408 -0.000237264 1.01858e-05 -1 0.964267 0.249405 -0.0893699 8.61272e-05 -1.36311e-06 -1 -0.985869 -0.130316 -0.105265 -1.41836e-06 -3.36912e-05 -1 1.6479e-07 1.83622e-06 -1 -2.04637e-05 -1.99106e-06 -1 -0.959562 0.266479 -0.0907182 0.98871 -0.14982 0.0026932 -0.110412 -0.702225 -0.703341 -1.20525e-06 1.10957e-05 -1 0.00956781 0.00706685 -0.999929 0 0 -1 0 0 -1 -2.66869e-07 -5.17725e-06 -1 4.36131e-05 2.18646e-07 -1 5.23658e-07 -4.8993e-06 1 -3.90105e-07 4.01768e-06 -1 0 0 -1 0 0 -1 0 0 -1 0.00272294 0.0022679 -0.999994 0.00403735 -0.00109453 -0.999991 8.74922e-08 -5.58051e-06 -1 1.35093e-06 -3.27089e-05 -1 2.8245e-06 2.85285e-05 -1 0 0 -1 -0.0036308 -0.00286492 -0.999989 -8.23837e-06 -8.49583e-05 -1 3.37065e-05 -0.000104715 -1 0.000103542 -8.93674e-07 -1 0.502589 0.753674 0.423532 0 0 -1 0 0 1 0 0 -1 -1.09121e-05 -5.43268e-06 -1 0 -4.57713e-06 -1 0 -1.05816e-06 -1 0.952747 0.223094 -0.206159 -0.341711 0.161707 -0.925789 5.56399e-07 1.0907e-05 -1 -7.79891e-07 -3.84962e-07 1 0.326148 -0.167907 -0.930288 2.94662e-08 7.90598e-06 -1 -0.15307 -0.140678 0.978151 3.72479e-06 1.77334e-10 -1 -5.20952e-06 -3.59954e-05 -1 0.273506 -0.833166 0.480655 3.26873e-06 3.66074e-07 1 -2.77645e-05 -5.41091e-05 -1 -3.08603e-06 -2.27242e-05 -1 0.419928 -0.649546 -0.633838 0.653546 0.350859 -0.670654 8.53909e-07 -1.0715e-05 -1 -0.960276 0.263775 -0.0910676 -0.668162 0.668163 0.327289 0 0 1 0 0 -1 -6.61633e-06 6.8231e-05 -1 -9.7315e-05 -2.13504e-05 -1 4.77276e-05 4.41854e-05 -1 -3.27755e-06 -4.78269e-07 1 3.90747e-06 5.32928e-07 -1 -0.906772 -0.290049 0.306 0 0 1 8.5749e-08 -8.31766e-07 -1 6.16002e-07 2.13785e-05 -1 0.000108064 -0.000176548 -1 0.00012894 5.97405e-06 -1 0 0 -1 3.31563e-06 -1.78534e-06 -1 -4.36179e-05 -5.17558e-05 -1 0 0 -1 -3.11949e-06 2.77288e-07 -1 0 0 -1 0 -1.00705e-05 -1 -3.67448e-05 -5.83886e-06 -1 0.000416753 -0.000208377 -1 -1.0198e-06 -1.06877e-05 -1 -6.02083e-07 5.90794e-06 1 0 0 1 5.89554e-06 -1.54907e-06 -1 -0.62639 -0.630179 -0.458813 2.28195e-06 5.70285e-05 1 0 0 -1 0 -0.000581551 -1 1.02305e-05 1.02305e-05 -1 -4.36125e-05 -2.84755e-06 -1 -1.05361e-05 1.27693e-05 -1 -0.000112122 9.90632e-05 -1 0.000137017 -5.11534e-05 -1 -4.6946e-06 7.70596e-07 -1 8.19638e-05 -5.46587e-05 -1 7.65144e-06 1.11652e-06 -1 0.570153 -0.809051 -0.142699 -7.65144e-06 -1.11652e-06 1 -0.570153 0.80905 0.142699 0.000108797 3.39451e-05 -1 2.93272e-05 -2.93272e-05 -1 -0.647101 0.647102 0.403138 6.07261e-06 -5.96084e-07 -1 -2.64447e-06 -2.11736e-07 -1 0 0 1 0 0 -1 0 0 1 0 0 1 0.00757867 0.00396376 -0.999963 -1.81454e-07 -1.00191e-05 1 1.92559e-06 1.90043e-05 -1 3.19728e-07 2.43892e-05 -1 -0.170372 -0.134434 0.976166 0.190092 0.156043 -0.969286 -3.22272e-06 1.36411e-07 -1 1.99593e-05 3.27174e-05 -1 -7.68234e-06 1.81104e-05 -1 4.84777e-05 6.08775e-07 -1 -7.1597e-06 -3.19146e-05 -1 -7.32456e-05 -2.18185e-05 -1 0 0 1 0 0 -1 1.39673e-05 1.47388e-06 1 3.78569e-05 -1.20409e-05 -1 -1 -1.96697e-07 4.86316e-06 -1 7.84119e-06 -3.87159e-05 -0.999998 0.00039779 -0.00176519 -1 0 0 -0.306268 0 -0.951945 -1 1.32714e-08 -5.09816e-06 -1 0 0 0.308279 0.021359 0.951056 -0.331925 -0.0202597 -0.943088 -1 0 0 -1 -5.56272e-05 -3.77304e-05 -1 0 0 0.30556 0.0342341 0.951557 -0.127718 -0.0459201 -0.990747 -1 0 0 -1 0 0 0.298596 0.0445293 0.95334 -0.95299 0.0858585 0.290584 -0.330645 -0.0383511 -0.942976 -0.584122 0.693626 -0.421528 -1 8.19576e-07 1.33085e-05 0.276174 0.060485 0.959202 -0.35166 -0.0513534 -0.934718 -0.999999 0.000576782 0.000847956 -0.587726 -0.455035 -0.66897 -1 -1.26899e-06 5.70102e-05 -1 0 1.23684e-05 -1 -1.64928e-07 -1.49581e-05 -1 -3.12599e-06 -6.02859e-06 -1 1.12948e-05 2.17824e-05 -1 -6.37418e-05 5.92014e-05 -0.630032 0.237921 -0.739225 1 -7.84119e-06 -3.87159e-05 1 0 0 1 4.71115e-06 9.17476e-06 1 -0.000118349 -4.46825e-05 1 0 0 0.306265 0.000501017 -0.951946 -0.307257 -0.0229249 0.95135 0.33263 0.0217273 -0.942807 1 5.37392e-08 -2.33189e-06 1 7.36473e-05 -3.74506e-05 1 0 0 -0.303792 -0.0368568 0.952025 0.129408 0.0484881 -0.990405 1 0 0 1 0 0 -0.296198 -0.0480563 0.953917 0.958242 -0.0866212 0.272525 0.332446 0.0412771 -0.942218 0.642348 -0.520584 -0.562478 1 -1.47594e-05 2.36978e-05 -0.272487 -0.0655245 0.959926 0.354234 0.0554138 -0.933514 1 -0.000576771 0.000679495 0.609784 0.512892 -0.604239 1 9.39209e-05 -0.000547994 1 1.98025e-06 6.44838e-05 1 5.16341e-07 2.39726e-05 1 -1.33263e-06 -6.1871e-05 -1 1.69501e-05 -0.000105551 0.811598 0.500836 -0.300786 0.701258 0.661421 -0.266007 0.55409 0.442257 -0.705261 0.0945857 -0.941401 -0.323756 0.50022 -0.569649 -0.652135 -0.551447 0.241125 -0.798602 -0.248821 0.882898 -0.39822 0.794555 -0.573901 -0.198296 0.682789 -0.628052 -0.373296 0.5768 0.815251 -0.051651 -0.686033 0.33692 -0.644859 -0.263445 -0.202396 -0.943203 -0.416373 -0.153363 -0.896166 -0.184351 -0.864505 -0.467597 -0.681395 0.591772 -0.430705 0.915583 -0.343954 -0.208336 -0.769314 0.0614876 -0.635906 0.201431 -0.822561 -0.531807 -0.21855 0.759046 -0.613258 -0.627379 0.145415 -0.765016 0.883324 -0.236623 0.404657 0.115559 0.868943 -0.481232 0.241857 -0.201938 -0.949066 -0.417621 -0.625957 -0.658612 1 0.000903583 6.45377e-05 0.999995 -0.00326591 -0.000280014 0.999999 -0.00139218 0.000421935 0.799275 0.572845 -0.181679 0.774007 0.621985 -0.118522 -0.999992 0.0039315 0.000321802 1 -6.97517e-05 5.8005e-07 1 -0.000190196 1.11919e-05 -0.999303 0.0349786 0.0130598 1 -0.000227521 0.000150137 -0.613102 0.596812 -0.517611 0.99926 0.0382751 -0.00384805 0.999958 0.00567832 0.00720775 1 -0.000929985 -0.000141613 0.999994 0.00350342 -0.000121042 0.976702 -0.0192609 0.213733 0.563945 0.0404946 0.824819 0.861899 -0.282117 0.421355 0.95396 -0.0781826 -0.289567 0.95837 -0.180427 0.2213 0.994881 0.0393549 0.0930748 0.823925 -0.0653546 0.562917 0.979411 -0.0704764 0.189173 0.96804 -0.0716544 0.240342 0.885782 -0.46319 -0.0290737 0.896192 -0.436329 0.0803612 0.793252 0.026617 0.608312 0.983561 0.178862 0.0248031 0.97679 0.191869 -0.0952217 0.976899 -0.200517 -0.0738954 0.980532 -0.183464 0.0699848 1 -5.39097e-05 1.86575e-06 1 -5.17702e-06 -0.00051182 -1 -6.51341e-05 2.25954e-05 0.999996 0.000811781 -0.00280308 1 -0.000415355 0.000552566 0.995779 0.0755123 0.0521655 1 -2.52149e-06 0.000248597 0.999996 -7.50073e-05 0.00290164 -0.133745 -0.949243 -0.284693 0.776434 0.192136 0.600195 0.827891 0.468003 -0.309144 0.999993 -0.00376714 -0.000286979 0.95952 0.2624 -0.102314 0.999303 -0.0349786 -0.0130598 1 0.000181721 9.46626e-05 1 4.11805e-06 0.000323551 -0.000338726 -0.000282876 -1 -0.649557 0.362895 -0.668119 -0.999999 -0.00117583 1.62088e-06 -1 0.000705181 -0.000176629 -1 4.7598e-05 1.26474e-05 1 2.858e-06 4.87799e-07 -1 4.69369e-05 8.01111e-06 0.999999 0.0013917 0.000128767 0.857931 -0.475309 0.195028 -0.999945 -0.00623601 0.00847319 -0.998488 -0.0511871 0.0200375 -0.563483 -0.0400068 0.825158 -0.822313 0.525067 -0.21933 -0.878057 0.0670526 0.473835 -0.74728 0.350404 0.564614 -0.999968 -0.00402886 -0.00684854 -0.842817 0.384187 -0.376908 -0.920561 -0.204742 -0.332637 -0.925071 0.230886 0.301554 -0.993477 -0.111561 -0.0235958 0.999971 0.00741144 -0.00174595 0.649557 -0.362895 0.668119 -1 -6.69371e-05 8.86104e-05 -0.966651 0.254699 0.0267309 -0.561387 0.712296 -0.421282 -0.987193 -0.157911 -0.0226755 -1 2.55289e-06 -3.99288e-05 -1 0 0 -0.999999 6.65389e-05 0.00153436 -1 -2.21964e-06 1.05504e-05 -0.970754 0.00822176 0.239935 -0.989565 0.000515663 -0.144087 0.345344 -0.327524 -0.879469 -0.73146 -0.108513 0.673195 0.99585 0.0159387 0.0896017 -0.708112 0.703427 -0.0613745 -0.99595 0.0750946 -0.0494496 -0.971951 0.234991 0.00948642 -0.797617 -0.0967072 0.595361 -1 0.000915386 -8.31299e-05 -1 0.000105777 -0.000312415 0.312542 0.171548 -0.934285 -0.312542 -0.171548 0.934285 -0.405975 -0.0944405 0.908992 -1 -0.000349879 0.000937956 -0.713275 0.688768 -0.12976 -0.0451679 -0.00742124 0.998952 -0.999949 -0.00996272 0.00155254 -1 1.20096e-05 -1.60919e-05 -1 -0.000137399 -0.00018986 -1 2.14589e-05 -0.000134139 -1 -0.000711754 -0.000306849 -0.999991 0.00408577 0.00130954 -0.999991 -0.00419107 -0.000606633 -1 0.000533465 7.91258e-05 -1 -0.000523028 -1.54455e-05 -0.995839 0.0855241 -0.031481 -0.99426 0.0940822 0.0509426 -0.775894 0.603078 0.185162 -0.767196 0.620478 0.162534 -0.227255 0.656411 -0.719361 -0.991556 0.12906 0.012663 -1 -5.15326e-05 0.000861612 -0.88171 -0.442165 0.164553 -1 2.06038e-05 5.84906e-05 -1 -3.72977e-06 -0.00011376 -1 -6.51319e-06 -0.0001619 -1 3.78114e-09 7.2767e-06 1 1.56682e-05 1.09992e-06 -0.943449 -0.316155 0.0997446 -0.984563 -0.174062 -0.0183758 -0.838569 -0.290469 0.460901 -0.232219 0.531936 0.814321 -0.904975 -0.304316 0.297343 -0.990354 0.036089 0.133781 -0.997604 0.0147331 0.0675894 -0.997809 -0.016493 -0.0640771 -0.996888 0.069393 0.0374027 -0.999962 -0.00748197 0.00458286 -1 -0.00010158 5.86853e-05 -0.999999 -0.00169331 -0.00034012 -0.753846 0.650779 0.0905762 -0.545072 -0.491012 0.679561 0.302076 0.843618 0.443914 -0.999994 -0.00344156 -0.000415443 -0.302076 -0.843618 -0.443914 -0.9256 0.0293489 0.377364 -0.959094 0.279453 -0.0452114 0.67948 -0.287949 0.674828 -0.948846 0.29481 0.113038 -0.848076 -0.050265 0.527484 -0.340185 0.623477 0.703953 0.118464 0.0205833 0.992745 -0.534089 -0.183852 0.825195 -1 -2.60665e-06 -0.000331461 -0.370143 0.757656 -0.537542 -0.943789 0.307921 -0.120196 0.943789 -0.307921 0.120196 -0.995401 -0.00073668 0.0957887 -0.439491 -0.0240321 -0.897925 -1 -5.95679e-05 -8.21201e-06 -1 0.000416199 9.54833e-05 -1 -2.26764e-05 -0.000167577 -1 8.80407e-05 -2.30074e-05 -0.999992 0.00410714 1.41954e-06 -0.00403226 -0.999992 0.000640513 0.00381003 -0.999986 -0.0036374 0.995636 -0.0928501 -0.00932346 0.967658 0.248845 -0.0414018 0.983822 0.177267 -0.0259139 0.995227 -0.0944912 -0.0243863 1 0 0 0.999897 0.00221085 0.0141986 1 6.14497e-05 0.000204085 0.672342 0.471914 -0.57031 0.982065 0.0543592 0.180537 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.000562889 -0.000239685 0.911811 -0.107757 0.39622 0.941031 -0.317021 -0.118146 0.925303 0.305377 0.224855 0.940284 0.139315 -0.310577 1 0.000405575 -0.000776274 -1 -3.96265e-06 -3.52637e-07 0.63979 -0.0754072 0.764841 0.528425 -0.710661 0.464465 1 0 0 1 0 0 1 0 0 1 0 0 0.965472 -0.19355 0.174363 0.945233 -0.0694815 0.318915 1 0.000185542 -1.62602e-05 1 0 0 1 0 0 1 0 0 0.999959 -0.00887614 -0.00206554 0.488942 -0.703342 0.51599 0.309416 0.104172 0.945204 0.507843 0.688271 -0.518052 0.382048 -0.608833 -0.695242 0.999907 0.00247201 -0.0133808 0.999952 0.00146451 -0.00971369 1 2.20548e-06 1.96266e-07 1 0.000209675 -1.45603e-05 0.585427 0.699814 0.409311 0.999997 -0.00238897 -0.000859087 0.910058 -0.292648 -0.293515 0.854843 0.462429 -0.235378 0.88039 -0.304227 0.363811 1 0 0 1 -0.000523431 -0.000222885 -1 -0.000313309 4.58013e-05 -1 0 0 1 -0.000329407 -0.000228869 1 -3.84743e-05 -6.15686e-05 1 -0.000495279 -0.000176933 1 3.74852e-05 -0.000803221 -1 0 0 1 -1.06581e-06 9.84876e-06 1 -4.78669e-07 -1.15643e-05 1 0 0 1 1.86078e-06 -5.73107e-05 1 0 0 -1 5.77346e-07 1.23236e-05 -1 9.38602e-05 9.97736e-05 1 7.10774e-05 9.99395e-06 1 0 0 0.999997 0.00228591 -0.000146872 0.0281763 -0.78211 -0.622503 0.812104 0.565314 0.144597 0.69966 0.714219 0.0191705 1 1.28169e-05 0.000656075 1 0.000677539 0.000110019 0.999999 -0.00125242 2.67811e-07 0.504202 0.837248 0.211651 0.608392 0.642761 0.46553 0.999921 -0.000218924 -0.0125947 0.977179 -0.00147469 0.212411 0.918426 -0.14641 0.367501 1 0 0 1 0 0 0.999994 2.38645e-05 -0.0034374 0.999999 -0.000928981 0.000910036 0.994662 0.0821084 0.0624943 0.9607 0.14375 0.237469 0.934309 0.0746393 0.348562 0.99489 0.0358347 0.0943946 0.992076 0.0303382 0.121924 0.987822 0.0290524 0.15285 0.999994 -0.00339561 0.000347072 1 -0.000794761 8.12343e-05 0.842961 0.402122 -0.357372 0.949913 0.217953 0.223969 0.999788 0.0174344 -0.0109484 0.991672 0.0970123 0.0847068 0.992191 0.0576042 0.110627 0.999626 0.0162556 0.0220091 0.99916 0.00872277 0.0400369 1 0 0 0.993878 0.0615879 -0.091729 0.989847 -0.0468969 0.13418 0.968646 0.0536589 0.242582 1 0 0 0.999999 0.000986811 0.000637163 1 7.16273e-05 -0.000687269 1 -0.000249657 -0.000563082 0.999963 0.00857492 0.000205262 0.999645 -0.014325 -0.0224695 0.229432 -0.96964 -0.0846109 0.982628 -0.183667 -0.0266301 0.491285 -0.70437 -0.512349 0.380355 -0.0677681 -0.922355 -0.96998 -0.239621 -0.0414934 -0.983822 -0.177267 -0.0259139 -0.995181 0.0945125 -0.0261341 -0.995647 0.0928467 -0.00810149 -1 0 0 -0.999706 -0.0132522 0.0203213 -0.999742 -0.0137688 -0.018085 -1 0 0 -1 0.000523431 -0.000222885 -1 0 0 -1 0 0 -0.956288 0.254181 0.144586 -0.922124 0.229857 0.311212 -0.956183 0.157426 0.246843 -0.943745 0.070392 0.323095 -1 -0.000185542 -1.62602e-05 -1 0 0 -1 0 0 -1 0 0 -0.999959 0.00887614 -0.00206554 -0.488942 0.703342 0.51599 -1 9.16254e-05 0.00025747 -0.999936 -0.00307636 -0.0109057 -0.999996 0.00293758 -0.000483517 -0.586227 -0.700748 0.406558 -0.999999 0.00156164 -0.000640271 -0.649194 0.0747312 0.756943 -0.545798 0.694026 0.469503 -0.999999 0.0002058 0.00145358 -0.617063 0.278248 -0.736078 -0.999966 -0.000806419 0.00822686 -1 -6.74661e-06 -0.000559272 -0.558332 -0.609014 -0.563354 -0.992411 -0.107353 0.0599709 1 0 0 1 0.000313309 4.58013e-05 -0.999776 -0.0104871 0.0184109 1 -2.72976e-05 4.79601e-06 -1 -4.45873e-05 3.5311e-07 -0.999783 0.00563767 -0.020033 -1 -0.000221053 0.000746087 -0.999999 2.33449e-05 0.00114557 -1 -0.000733178 0.000113183 -1 0.000483256 -0.000179739 1 0 0 -1 0 0 -0.999999 0.00125238 2.70276e-07 -1 2.11802e-07 1.95721e-06 -1 -5.81315e-07 1.38719e-05 -1 -4.00482e-07 9.55667e-06 -1 0 -2.94973e-06 -1 0 0 1 7.94786e-07 -1.65786e-05 -1 0.000282311 0.000180139 -1 0.000793485 -1.97327e-07 -1 0.000489471 -1.63983e-05 -0.120882 0.236371 0.964114 -0.159625 0.372118 -0.914357 0.832625 0.315813 0.45497 -0.762653 -0.620515 -0.182541 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.998109 0.0565499 0.0240797 -0.878541 0.0682922 0.472761 -0.999248 -0.0055488 -0.0383827 -0.941105 0.316919 -0.11783 -0.942731 -0.29047 0.163969 -1 -0.000396744 -0.000788272 -0.940491 -0.139609 -0.309817 -1 -0.000219795 0.000261476 -0.999557 -0.0252049 -0.0158282 -0.98315 -0.137696 0.12023 -0.984433 -0.106353 0.139931 -0.982389 -0.111008 0.150298 -0.977308 -0.0450918 0.206968 -1 0 0 -0.995587 -0.0523123 -0.0779139 -0.994325 0.0361976 0.100037 -0.999951 -0.00181532 -0.00978128 -0.999877 -0.00557487 -0.0146852 -0.999958 -0.00610689 -0.00689268 -1 0.000501097 0.000830721 -0.974078 -0.0453763 0.221615 -0.986374 0.00473724 0.164451 -0.999753 -0.000639673 -0.0222059 -0.189929 0.978266 -0.0832069 -0.982628 0.183667 -0.0266301 -0.218489 -0.960349 0.173182 -0.987662 -0.151822 0.0383797 0.999993 -4.88961e-05 -0.00367472 -0.999887 -0.00817894 -0.0125776 -0.920811 0.144344 0.362315 -1 0 0 -1 0 0 -0.999985 -3.81742e-05 -0.00549759 -0.9779 0.00145173 0.209068 -0.988141 -0.0283276 0.150911 -0.994877 -0.0288258 0.0968925 -0.984466 -0.0237419 0.17396 -0.981161 -0.0429743 0.18835 -0.977094 0.0942035 -0.190821 -0.972302 -0.227555 0.0533545 -0.999975 0.0070987 -0.000115729 -0.999965 0.0083917 9.55273e-06 -0.999783 0.019611 0.00708611 -0.999862 0.0117541 -0.0117482 -1 -0.000920924 9.36763e-05 -1 0 0 -0.17058 0.106498 -0.979572 -0.00269172 -0.999996 0.000572764 0.00732001 -0.999961 -0.00500667 -0.322123 -0.0116182 -0.946627 -1 7.29155e-07 7.11613e-07 -1 -1.82957e-06 5.7421e-06 0 -0.798636 0.601814 0 -0.798636 0.601814 -0.984204 0.0548025 0.168342 -0.000133283 0.00505805 0.999987 0 0 1 0 0 1 0 0 1 0.0538656 0.92609 0.373439 0 0 -1 -0.00116481 0.0423216 -0.999103 0 0 -1 0 0 -1 0 0 -1 0.00130532 0.999402 0.0345585 0 0.999997 -0.00238156 -0.037745 0.988221 0.148308 0 1 0 0.736532 0.676403 0 0.00150306 0.0570406 0.998371 0.0311089 0.0725516 0.996879 1.37193e-06 5.20642e-05 1 2.76927e-06 6.45844e-06 1 0 0 -1 -0.00107744 -0.0391469 -0.999233 0 0 -1 0 0 -1 0 0 -1 -0.0133221 0.996776 -0.0791226 7.81255e-06 0 -1 -5.58061e-07 1.80081e-05 -1 0 0 -1 -2.91168e-07 3.90302e-05 -1 -9.42392e-07 1.80068e-05 -1 -7.81247e-06 3.22169e-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.00010613 -0.999999 0.00145196 -3.93912e-05 -1 0.000206896 0.00439091 -0.999094 -0.0423366 -0.483479 -0.596788 -0.640385 0.00044065 -0.999993 0.003774 0.0123183 -0.999905 0.00622455 0.0233366 -0.996971 -0.0741874 0.77698 -0.567952 0.271538 0.000430658 0.000469578 -1 6.83332e-10 -2.38005e-06 -1 0.0147227 -0.476802 -0.878888 -0.000392846 -1 -9.90387e-05 -0.00143098 -0.999951 0.00976999 0.389178 -0.911748 0.131359 -2.51784e-08 -5.36441e-08 -1 -5.84742e-06 -1.24583e-05 -1 -0.0205661 -0.992326 -0.121929 -0.607194 -0.280995 0.743208 0.252152 -0.876701 -0.409651 0.0136708 -0.989291 0.145318 -3.90078e-05 0.000115776 -1 0 7.17118e-05 -1 0 -1 -0.000253338 -0.050276 -0.89264 0.447959 -0.000344381 -0.999994 -0.00355764 0.014959 -0.999284 -0.0347504 0.0750419 -0.983431 -0.165024 0.00498744 0.999907 -0.0127102 0.729524 0.595845 0.335803 0.015282 0.99612 -0.0866679 2.52201e-05 0.000137457 -1 2.4527e-05 0.000134585 -1 0.0848862 0.108631 -0.990451 5.12876e-05 5.0469e-05 -1 0.000427958 1 -2.2374e-05 3.13494e-06 0.999992 -0.00406143 0.388537 0.921432 -0.00159918 -0.347611 0.937639 -2.66664e-06 0.135518 0.952629 0.272274 -0.15903 0.930569 -0.329774 0 -0.000193271 -1 -0.000147023 4.15789e-06 -1 -6.92042e-06 1 5.04621e-05 0 1 -1.11765e-05 -0.00280841 0.999632 -0.0269783 0.487758 0.626468 -0.607972 -0.000118231 1 0.000862113 0.0254117 -0.29317 -0.955723 4.0895e-06 0 -1 -2.807e-06 5.72575e-06 -1 0 0 -1 -0.011715 0.447183 -0.894366 0 0 -1 0 0 -1 0.011715 0.447183 -0.894366 0.854229 0.047565 0.517716 0 0 -1 0 0 -1 0 0 -1 -0.854229 0.047565 0.517716 0 0 1 0 0 1 -0.0115318 0.447203 0.894358 2.95423e-08 1.33794e-06 1 0 0 1 -0.486105 -0.0419508 0.872893 -0.106981 0.00923246 0.994218 0 0 1 0.0115319 0.447184 0.894368 0 0 1 0 0 1 0 0 1 0 0 -1 -0.0124391 0.447179 -0.894358 -0.854229 0.0475653 0.517716 0 0 -1 0 0 -1 0 0 -1 0.854229 0.0475653 0.517716 0.0124391 0.447179 -0.894358 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.0122329 0.44718 0.89436 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.0122329 0.44718 0.89436 0 0 1 0 0 1 0 0 1 0.000112678 -0.000119306 -1 0 4.19095e-06 -1 -0.0262585 0.591255 -0.806057 -0.0973338 0.923488 0.371074 0.118419 0.932423 0.341414 0.00125989 0.00967361 0.999952 0 -0.000712031 1 0 0.00129594 0.999999 0.000251572 0.00964972 0.999953 -0.00332404 0.0189952 0.999814 0.0184393 -6.83006e-06 0.99983 0 0.0120248 0.999928 0 0 1 9.16711e-06 1.12834e-05 1 -0.000257921 0.00362614 0.999993 -0.0106897 0.325323 0.945543 0.000305781 0.00460689 0.999989 -3.62586e-05 0 1 0 4.07176e-05 1 6.28084e-05 1 -1.40931e-05 -0.0892414 -0.0458671 -0.994953 0 0 -1 -0.0205426 0.18065 -0.983333 -0.0241895 0.0722617 -0.997092 0 0 -1 0 0 -1 4.90403e-08 3.307e-08 1 0.236723 0.159632 0.958373 -0.0525117 0.397825 0.915957 -3.08339e-07 4.81948e-06 1 -9.42048e-07 1.47246e-05 1 -5.07267e-06 0 1 -1.51569e-05 1 -8.75084e-06 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.000804868 -2.49381e-05 1 -5.59564e-06 0.854231 0.047565 -0.517714 0.106982 0.00923251 -0.994218 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 6.56166e-05 -0.000103436 -1 0 0.000453051 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.263582 0.22828 -0.937237 -0.000140091 -4.61977e-08 -1 -3.97528e-05 2.69069e-08 -1 -0.586782 -0.0434662 0.808578 0.171181 -0.0126803 0.985158 -0.854231 0.047565 -0.517714 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.0006846 0.00569925 0.999984 0 0.000122446 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 2.46197e-05 -2.38095e-05 1 0 0 1 0 1 0 0 1 0 -1.90153e-07 2.50184e-06 -1 0 0 -1 0 0 -1 0 0 1 -0.135149 0.474326 -0.869914 0 0 1 0 0 1 0 0 1 0 0 1 -0.0948998 0.104581 0.989978 0 0 1 0 0 1 0 0 1 -0.00953775 0.0216456 -0.99972 0.0235506 0.770336 -0.637204 -8.86541e-07 -1.88551e-05 -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.0171072 -0.0115361 0.999787 -4.90397e-08 3.30696e-08 1 -9.78968e-05 -0.000739232 1 3.08363e-07 4.81985e-06 1 9.42072e-07 1.4725e-05 1 5.07259e-06 0 1 4.7463e-08 6.67337e-07 -1 0.98421 0.0548029 -0.168305 0.0556778 0.489629 -0.870152 0 0 -1 0 0 -1 0 0 -1 2.49403e-05 1 0.00100922 0 1 0 -4.01957e-06 -0.000342433 -1 0.0121132 0.0619873 -0.998003 -0.234888 0.000257844 -0.972022 -0.000103674 -1.90981e-05 -1 -4.15702e-05 -6.87544e-05 -1 0.00490056 0.0282539 0.999589 5.13855e-07 -0.000260798 1 -6.19059e-05 7.99729e-06 1 1.49868e-06 0.798635 0.601816 0 0.798627 0.601826 0 0.798686 0.601748 -9.34687e-06 0.798637 0.601813 0.274846 0.961471 0.00580148 0.476815 0.621619 -0.62148 0 1 0 0 1 0 0.45894 -0.628241 0.628242 -0.291669 -0.870965 0.39541 0.539354 -0.770866 -0.338914 -0.799291 -0.421043 -0.428785 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 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.0122329 -0.44718 0.89436 0 0 1 0 0 1 0 0 1 0.0122329 -0.44718 0.89436 0 0 1 0 0 1 0 0 1 0 0 1 -0.0124391 -0.447179 -0.894358 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.0124391 -0.447179 -0.894358 0.854229 -0.0475653 0.517716 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.78985 -0.457583 -0.408357 0 0 1 0 0 1 -9.20913e-06 -1.13351e-05 1 -3.1724e-06 -9.30384e-05 1 0.122374 -0.970842 -0.20613 -1.4851e-05 0.000116577 1 -2.51786e-08 5.64611e-08 1 -1.78183e-05 3.99563e-05 1 0.0107284 -0.315183 0.94897 -1.1753e-05 -0.000573292 1 3.07228e-05 4.3113e-08 1 -2.7127e-08 -3.45617e-05 1 3.14509e-05 -2.57507e-05 1 0 0 1 0.984204 -0.0548025 0.168342 0 0 1 0 0 1 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.81239e-06 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 4.54418e-08 1.09595e-07 -1 -5.58013e-07 -1.80065e-05 -1 0 0 -1 0 0 -1 0 0 -1 8.97475e-05 7.98818e-05 -1 0 -6.02716e-07 -1 0 -1 0 0 -1 0 0 -1 -0.000804868 2.49381e-05 -1 -5.59564e-06 -0.0285903 -0.684774 -0.728195 -0.00660976 -0.811295 -0.584599 5.66918e-05 -1 8.53583e-05 0.000220455 -1 -2.45155e-06 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.0200639 -0.999795 0.00278609 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -7.81574e-06 -1 1.26801e-05 0 -1 0 0 -1 0 0 -1 0 -0.0183205 -0.999811 -0.00648916 0.0176922 -0.999844 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.0003553 -0.999983 -0.00578564 0 -1 0 1.92132e-06 -1 0 1.5497e-07 -1 -2.28266e-06 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.999944 -0.0105922 0 -0.999944 -0.0105922 0 -0.999944 -0.0105922 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.0480149 -0.810357 -0.583966 0 -0.701441 -0.712728 0.365867 0.639403 -0.676244 0 -1 0 0 -1 0 0 -0.999944 -0.0105922 0 -0.999944 -0.0105922 0 -0.999944 -0.0105922 0 -0.999944 -0.0105922 0 -0.999944 -0.0105922 -0.242844 -0.710604 -0.660354 0 -0.681401 -0.73191 0.047743 -0.70289 -0.709694 0 -1 0 0 -1 0 0.0342014 -0.997995 -0.0532517 -0.00729233 -0.996233 -0.0864139 0 -1 0 0 -1 0 -0.00214386 -0.998131 -0.0610759 4.06742e-05 -1 0 0 -1 -0.000666824 0.00419876 -0.997929 -0.0641952 0.00397009 -0.999957 0.00833613 -1.74359e-08 -0.997726 -0.0673971 -0.000362823 -0.999996 0.00278413 1.95437e-05 -0.144786 0.989463 -2.81888e-06 -0.177746 0.984076 3.41256e-05 -1 -0.000995615 -1.07849e-06 -1 3.1465e-05 0 -1 -1.86329e-05 -4.4084e-06 -1 -0.000139307 -0.0172922 -0.980498 -0.195768 -0.0442729 -0.982522 -0.180804 0 -1 0 0 -1 0 0.0831906 -0.985204 -0.149842 0 -1 0 -0.110607 -0.766859 0.632213 0.000244064 -0.999999 0.00141557 0.036626 -0.988474 0.146893 0.00948377 -0.978123 -0.207813 0 -1 0 -0.0592251 -0.99461 0.0851129 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.103236 -0.260318 -0.959988 0.593437 -0.561624 -0.576551 -0.45251 -0.323341 -0.831075 0.852579 -0.450173 0.265431 -0.318557 -0.418884 -0.850328 0.0172272 -0.510795 -0.85953 -0.39194 -0.605095 -0.692996 0.358666 -0.776688 -0.517798 0.99784 0.0543339 -0.0369308 -0.407671 -0.728145 0.551008 0.163274 -0.98611 -0.0304898 0.290303 -0.872307 -0.393453 -1 0 0 -1 0 0 0.998868 -0.0475653 0 0.998868 -0.0475653 0 0.999267 0.0373326 -0.00845954 1 -0.000366392 8.30242e-05 -1 -5.54586e-06 -2.0904e-07 -0.999823 0.0181724 -0.00485889 0 0 -1 -0.0130245 0.447177 -0.89435 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.0130244 0.447174 -0.894352 0 0 -1 0 0 -1 0 0 -1 0 0 1 -0.0130245 0.447177 0.894351 0 0 1 0 0 1 0 0 1 0 0 1 0.0130244 0.447174 0.894352 0 0 1 0 0 1 0 0 1 0.0967107 0.993585 0.0586121 0.0110129 0.743594 -0.668541 0 0.856252 -0.516558 -0.0292063 0.713391 -0.700158 -0.461854 0.627153 -0.627193 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 8.20523e-07 1 -7.04456e-05 0.000551859 0.999995 -0.00325729 0 0.999821 -0.0189227 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.999953 -0.00968305 0 0.999953 -0.00968305 0 0.999953 -0.00968305 -0.55497 0.754285 -0.350803 0.149566 0.776642 -0.611929 0 0.999953 -0.00968305 0 0.999953 -0.00968305 0 0.999953 -0.00968305 0 0.999953 -0.00968305 0 0.999953 -0.00968305 0 0.999953 -0.00968305 0 0.999953 -0.00968305 0 0.999953 -0.00968305 0 0.999953 -0.00968305 0 0.999821 -0.0189227 0 0.999821 -0.0189227 0 0.999821 -0.0189227 0 0.999821 -0.0189227 0 0.999821 -0.0189227 0 0.999821 -0.0189227 -0.000360077 0.99983 -0.0184428 0 0.999953 -0.00968305 0 0.999953 -0.00968305 0 0.999821 -0.0189227 0 0.999821 -0.0189227 0 0.999821 -0.0189227 0 0.999821 -0.0189227 0 0.999821 -0.0189227 0 0.999821 -0.0189227 0 0.999821 -0.0189227 0 0.999821 -0.0189227 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 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.25276e-06 1 -7.04803e-05 0 1 -0.000108041 6.65162e-05 1 0.00048492 0.000947681 0.999957 -0.00920091 -0.000434407 0.999995 -0.00316693 -0.31659 0.621508 -0.716588 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.00158174 0.999891 -0.0146516 -2.6126e-11 1 0.000532751 -0.000329205 0.999997 -0.00255936 -0.00242601 0.999819 -0.0188607 0.0487836 0.766553 0.640326 -0.0151226 0.994496 -0.103674 -0.655396 0.754121 -0.0419147 0.894689 0.12285 -0.429464 0.393052 0.723969 -0.566902 -4.88738e-09 0.999999 0.00174051 0.000205959 0.999992 -0.00405224 0 1 0 -5.95176e-05 1 -0.000705283 -0.00683849 0.999583 0.0280712 -1.87947e-05 0.998556 0.0537117 0.000115461 1 0.000357775 -0.00019145 0.592856 0.805309 -1.38546e-05 1 -0.000873364 -1.70828e-05 1 -0.000966123 0 1 -0.000168494 2.48527e-06 1 -0.000236802 0.0221093 0.967837 -0.250606 0.0439098 0.98281 -0.179321 0 1 0 0 1 0 -0.081309 0.984875 -0.153003 -1.19454e-07 1 -8.13291e-06 0.110621 0.76724 0.631749 0 1 -6.70576e-05 -0.0855302 0.86388 -0.496383 0.0552828 0.994787 0.0856878 -0.582387 0.812912 0 -2.53304e-06 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.0757649 -0.622461 0.778975 0 1 0 0 1 0 -0.0196616 0.980082 -0.197619 -2.04131e-08 1 -0.000762339 -0.00267253 0.999853 0.0169385 0.00346527 0.999994 -0.000665728 0.00534999 0.997974 -0.0633922 2.36336e-07 1 4.6499e-06 0 1 0 -0.0106764 0.998244 0.0582644 0.0503697 0.97194 0.229772 -0.0170164 0.995393 0.0943602 0.331049 0.607943 -0.721673 -0.464977 0.411565 0.783844 -0.0287315 -0.802663 0.595741 0.671033 0.719014 -0.180926 -0.997814 0.0475687 -0.0458695 -0.756971 0.629556 0.175083 0.106299 0.588861 -0.801213 -0.364214 0.898543 -0.244884 -0.123687 0.927763 -0.352075 0.131523 0.50644 -0.852186 0.0122717 0.750139 -0.661166 0.457305 -0.0147707 0.889187 -0.049969 0.209026 -0.976633 -8.76852e-05 0.000144197 -1 -4.60974e-07 8.57991e-06 -1 -0.000181894 -0.000162608 -1 0 6.02928e-07 -1 0 1 0 0 1 0 5.55049e-06 3.93305e-06 -1 6.16139e-06 0 -1 0 1.19003e-05 -1 2.43697e-05 8.67371e-05 1 0 3.89539e-05 1 -2.30923e-05 1.88975e-05 1 0 0 1 -0.000146734 -0.000234989 1 0 0 1 0.938964 0.342567 0.0315493 0.0238234 0.999716 0.000730635 -0.0238234 -0.999716 -0.000730635 -0.137361 -0.310738 -0.940518 -0.892105 0.451828 -0.000759398 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.000186173 5.6276e-06 -1 -4.86039e-05 1.46919e-06 -1 -0.00105675 -0.000758489 -0.999999 0.000848358 0.00328844 -0.999994 -0.191304 -0.902602 0.385633 -0.00649519 0.999979 -0.000660761 -0.000257712 1 0.000435485 1 0 0 1 0 0 1 0 0 1 0 0 0.974193 0 0.225715 0.965929 0.000129089 0.258808 0.771987 -0.000180011 0.635639 0.258815 0 0.965927 0.707107 0.000148132 0.707107 0.331896 -0.000344085 0.943316 -0.258815 0 0.965927 -0.258815 0 0.965927 -0.707107 0 0.707107 -0.763958 -0.000377775 0.645266 -0.965929 0.000258116 0.258808 -0.984242 0 0.176827 0.325113 0 -0.945675 0.258822 -0.000347958 -0.965925 0.707107 1.53596e-05 -0.707107 0.773642 -0.000346587 -0.633623 0.965929 0.000251022 -0.258808 0.984242 0 -0.176827 -0.984192 0 -0.177105 -0.98443 -4.02657e-06 -0.17578 -0.842216 4.77428e-06 -0.539141 -0.8415 0 -0.540258 -0.520525 0 -0.853847 -0.528444 4.38783e-05 -0.848968 -0.164259 -0.000304037 -0.986417 -0.295865 0.840701 -0.453526 -0.03176 0.847383 -0.530031 -0.0915644 0.987086 -0.131444 0.218456 0.972744 -0.0777561 0 -0.989821 0.142315 -0.0049091 -0.990608 0.136644 -0.00181877 -0.909631 0.415414 -0.00156564 -0.909507 0.415685 -0.000793031 -0.755749 0.654861 -0.00357211 -0.757849 0.65242 -0.000783894 -0.540641 0.841253 0 -0.53988 0.841742 0 -0.281733 0.959493 -0.00262528 -0.284668 0.958623 -0.000842595 0 1 -0.00341679 -0.00296961 0.99999 -0.00132238 0.281732 0.959492 -0.00156155 0.281468 0.959569 -0.00078848 0.540641 0.841253 0 0.541409 0.840759 0 0.755749 0.654861 -0.00358278 0.753002 0.658008 -0.000797266 0.909632 0.415415 -0.00259148 0.90877 0.417288 -0.000877257 0.989821 0.142315 0 0.989965 0.141313 0.000198216 -1 -8.44807e-05 0.893977 -0.447542 -0.0226347 0.85759 -0.514298 -0.00602696 0.664764 -0.747047 0.00321297 0.303158 -0.952935 -0.00326428 0.21801 -0.975947 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0.00715383 0.999972 -0.00217107 -2.06906e-05 1 -2.67351e-05 0 1 0 0 1 0 -0.888187 -0.457918 -0.0378726 -0.757906 -0.652363 -0.000892976 -0.2667 -0.96378 0 -0.236242 -0.971693 -0.00154538 -0.660988 -0.750386 0.00381761 0.0126375 0.989839 0.141627 0.00422077 0.897325 0.44135 0.00731558 0.898416 0.439084 0.00115216 0.723564 0.690257 0 0.722932 0.69092 0 0.48312 0.875554 0.0189627 0.496444 0.867862 0.0014894 0.198156 0.980169 0 0.196996 0.980404 0 -0.105067 0.994465 0 -0.105067 0.994465 0 -0.398608 0.917121 0.00992359 -0.391192 0.920255 -4.08764e-06 -1 -0.00100937 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 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 4.17215e-06 0.000762349 1 0.000342133 0.000393513 1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 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.55631e-06 8.92882e-05 1 0.000204535 0.000313554 1 7.53524e-07 7.204e-05 1 0 0 1 0 0 1 -0.474634 -0.87671 -0.0781118 0 0 1 1.36876e-07 -2.07044e-07 1 1.30403e-05 1.29009e-06 1 -7.89421e-06 -4.22904e-06 1 2.46029e-07 1.31801e-07 1 2.43336e-07 -1.94692e-07 1 -1.30403e-05 -1.29009e-06 -1 -6.0823e-07 5.06389e-06 1 5.58105e-07 -2.89808e-07 1 0 0 1 0 0 -1 6.90588e-07 -2.14666e-07 1 -1.49102e-05 -3.57799e-05 1 6.0823e-07 -5.06389e-06 -1 -6.25818e-07 6.00623e-07 -1 -2.3127e-07 -2.13121e-07 1 -0.82125 -0.570088 0.0234111 2.17198e-07 -2.52789e-05 1 -3.32001e-05 -0.00017867 1 0 3.50087e-06 1 3.08002e-07 -2.25904e-07 1 2.66876e-07 0 1 -0.000298923 0.192737 0.98125 0 0.192196 0.981357 0 0.36073 0.93267 0.0227282 0.389005 0.920955 -0.119702 0.984376 0.12913 0.036 -0.581573 0.812698 0.155179 -0.548813 0.821416 -0.0124716 -0.266893 0.963646 0.016727 -0.303665 0.952632 0.0529619 0.996165 0.0696397 -0.0111202 0.924355 0.381372 0 0.928316 0.371793 0 0.790263 0.612768 0.00681641 0.793738 0.608221 -0.025564 0.991181 0.130023 -0.0614156 0.991361 0.115892 0.197662 0.55754 0.806275 0.0209849 0.339106 0.940514 -0.00126191 0.365342 0.930873 -0.042464 0.188397 0.981175 -0.144386 -0.0745272 0.986711 -0.0287754 -0.129069 0.991218 0.0186218 -0.236953 0.971343 0.0749321 -0.61463 0.785249 -0.0504388 -0.387085 0.920664 0.524135 -0.11849 0.843352 0.493665 -0.480491 0.724861 -0.00226954 0.793004 0.609212 0 0.7944 0.607395 0 0.924412 0.381395 0.0150641 0.930767 0.365301 -0.000630907 -0.00209875 -0.999998 0.00207361 0.00936392 -0.999954 -0.00365171 -0.000604094 -0.999993 -0.000169875 3.2416e-05 -1 -0.00040634 3.2416e-05 -1 1.79833e-05 -3.9874e-05 -1 0.000464851 6.97867e-05 -1 -0.00010832 8.64134e-06 -1 0.00369989 -0.000107011 -0.999993 -0.00571229 -0.000605145 -0.999983 -0.237956 -0.139473 0.96121 -3.88741e-05 -0.000338574 -1 3.9036e-07 -3.90361e-07 -1 -0.00524723 -0.00768715 -0.999957 -1.42582e-05 -9.60229e-05 -1 0 2.15876e-06 -1 0.000137819 0.000279922 -1 -7.51148e-06 -0.014471 -0.999895 3.99941e-07 5.85911e-07 -1 0.0076127 0.00130658 -0.99997 0.000221825 -1.22674e-05 -1 -0.122774 -0.989799 -0.0722732 0.00209037 0.000266337 -0.999998 -0.000406284 -0.000385734 -1 0.000223004 2.59503e-05 -1 -1.18008e-06 -1.22674e-05 -1 0.000662822 4.00219e-05 -1 0.948012 -0.0572559 -0.313041 -0.140255 0.304076 -0.942267 -2.29325e-05 -2.61541e-05 -1 -0.0022964 -8.62655e-05 -0.999997 -0.00384618 3.19666e-05 -0.999993 -0.000123666 -0.0612775 -0.998121 -4.13822e-05 -5.78707e-05 -1 -0.000239408 0.000166303 -1 -3.14903e-05 1.9959e-05 -1 1.2045e-05 -8.78678e-05 -1 0 0 -1 2.67777e-05 -0.000210223 -1 0.0254936 -0.0373479 -0.998977 0 0 -1 0 0 -1 -0.999999 0.00122905 5.2291e-07 -1 0.000666355 -0.000716899 -0.999994 0.00200421 -0.00271112 -1 -3.29753e-05 -0.000860339 1 -9.45292e-05 -0.000212973 -1 0.000116611 0.000592021 -0.999982 -0.000355388 -0.00600479 -1 3.57992e-05 6.73746e-05 1 0 0.000113312 -1 6.05555e-06 2.11148e-06 -0.999067 0.0407742 0.0142173 -1 0 0 -1 0 0 -0.999994 0.00237262 -0.00236161 -0.999997 0.00166453 -0.00206391 -0.999997 0.00251126 -0.000746313 -0.998526 0.0192068 -0.0507735 1 -1.50712e-05 -7.24236e-05 -1 0 5.65631e-05 -0.999994 -0.00146804 0.00313444 -0.99361 0.00457559 0.112776 -1 -4.43777e-05 1.88594e-08 -1 4.80254e-05 -0.000119329 -0.999524 -0.029117 0.0101526 -1 0 0 -1 0 0 -0.640092 -0.764841 0.0728045 -0.90152 0.430623 -0.0427252 -0.639532 0.768758 0.00319351 -0.311419 0.950266 -0.00358451 -0.21801 0.975947 0 -0.000402596 1 -0.000424974 -0.000549891 1 -0.000401606 0 1 0 0.0721711 0.993023 0.0932549 0 0 -1 0 0 -1 0.226756 0.555098 -0.80028 0 0.419427 -0.907789 0 -0.367116 -0.930175 0.0915037 -0.995646 -0.0177635 0.060449 -0.410955 -0.909649 0 0.989821 0.142315 0 0.989821 0.142315 0 0.909632 0.415415 0.00264131 0.910904 0.41261 0.000864812 0.755749 0.654861 0.00312941 0.757455 0.65288 0.000789268 0.540641 0.841253 0 0.539874 0.841746 0 0.281733 0.959493 0 0.281733 0.959493 0 0 1 0.00537332 0.00626581 0.999966 0.00245137 -0.281732 0.95949 0.00256197 -0.281606 0.959527 0.000879941 -0.54064 0.841253 0 -0.541495 0.840704 0 -0.755749 0.654861 0 -0.755749 0.654861 0 -0.909632 0.415415 0 -0.909632 0.415415 0 -0.989821 0.142315 0 -0.989821 0.142315 0 2.39097e-05 -1 -0.000297817 0 -1 -0.00275937 -0.999996 -0.000711535 -0.000582537 -1 -0.000425449 0 -1 0 0 -1 0 0 -1 0 0 -0.402983 -0.915207 0.0980173 -0.466961 -0.878829 0.216153 0.388922 -0.895554 -0.218532 0.802252 -0.55555 0.999999 -0.00102673 -0.000291621 0.985092 0.1718 -0.00884174 1 0.000749893 -0.000169362 1 0.00067617 -0.000113841 0.999999 0.00153346 -0.000179877 0.998139 -0.0585877 -0.0169279 0.342311 0.655703 -0.672961 -0.671397 0.524036 -0.524035 1 0.000551182 -2.31639e-05 1 -0.00101297 7.59653e-05 0.996816 0.0450906 0.0657639 0.987122 0.158379 -0.0224924 0.941114 0.321402 0.104908 0.233205 -0.535535 0.811676 0.910325 0.297162 0.288102 0.965345 0.0303126 0.259211 0.964364 0.0479797 0.260194 0.985607 0.0385618 0.164599 0.997081 0.0758349 0.00888226 0.999961 -0.00109892 0.00874216 0.999999 0.001323 9.00184e-05 1 0.00101385 -0.00018304 0.329469 -0.942889 0.0490919 0.303645 0.304613 0.90278 0.122723 0.923351 -0.363817 -0.122723 -0.923351 0.363817 0.999999 0.00135393 7.78291e-05 0.994848 -0.0787372 0.0638528 0.776244 0.0822402 0.625046 0.999053 -0.0429117 0.00714138 0.998767 -0.0485014 0.0105544 0.999963 0.00694108 -0.00505696 0.79316 -0.23108 0.56347 -1 3.11503e-05 -0.00069978 -1 -1.0776e-05 1.0776e-05 1 -3.07219e-05 0.000696783 0.852586 -0.278693 0.44207 1 -0.00025065 0.000945789 1 -1.4287e-06 0.000826499 0.999999 5.58666e-05 -0.00126707 0.87542 -0.407426 -0.260085 0.988861 -0.146066 0.0286063 1 -8.30785e-06 1.20839e-05 -0.999999 -0.00147309 0.000127114 1 4.58681e-05 2.83114e-05 1 0.000529524 0.000281778 1 0.000515914 -0.000125133 0 -0.398608 0.917121 0 -0.398608 0.917121 0 -0.105067 0.994465 0 -0.105067 0.994465 0 0.198156 0.98017 0 0.198156 0.98017 0 0.48312 0.875554 0 0.48312 0.875554 0 0.723564 0.690257 0 0.723564 0.690257 0 0.902327 0.431052 -0.0158626 0.89722 0.441298 0.03074 0.987947 0.151708 0 0 -1 0.0004057 -3.40705e-05 -1 0 0.997388 0.0722294 -0.0746774 0.995715 0.0545398 0.000582537 1 -0.000425449 0.00291246 0.999996 -0.000731655 0 0.381576 -0.924338 -0.125377 0.465518 -0.876113 -0.154489 -0.327185 -0.932246 0.163925 -0.771216 -0.615105 -0.240943 -0.969467 -0.0456024 -0.00551968 -0.999984 -0.00134302 0.000524907 -1 -0.00038336 0 -1 0 0 -1 0 0 -1 0 -0.00165905 0.000160028 -0.999999 0 2.5664e-05 -1 0.0001952 1 -5.21368e-05 0 1 0 0 -1 0 0 1 0 0.0248221 -0.435184 -0.899999 0 -0.418635 -0.908155 -0.321327 0.940177 -0.113211 0.161676 0.790849 -0.59027 0.999991 -0.000390396 -0.00432739 0.999999 -0.00130173 5.5382e-07 1 -0.000421667 -0.000831593 1 0 0 1 0 0 0.999999 -0.000394844 -0.00115487 0.99999 -0.00416619 -0.00166995 1 9.89165e-05 -0.00065872 1 0 3.63277e-05 0.999932 0.00553291 0.0102188 0.999981 0.00510973 0.00342341 1 0 0 1 -0.000934837 0.000325963 1 1.85918e-05 4.03316e-05 0.999999 0.00045959 -0.00114156 1 -1.89501e-05 -0.000103103 1 0 0 1 0 0 1 0 0 1 -0.000362595 0.000523393 1 0.000369663 4.96475e-07 1 0.000570262 0.000206387 0.999136 0.00179691 0.0415246 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 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.36246e-06 -4.36043e-06 -1 -4.39102e-06 0.00166234 -0.999999 -0.000762089 0.000857114 -0.999999 6.86857e-06 0.000319842 1 2.51694e-06 0.00025773 1 -1.97749e-06 -9.51643e-06 1 -2.32307e-05 0.00172155 0.999999 2.52519e-05 0.00048672 1 5.6388e-05 -0.00345571 0.999994 -0.000100033 -0.000397929 1 -1.7726e-06 0.0010691 0.999999 -9.71457e-06 0.000591904 1 0.496671 0.370696 0.784795 0.184984 -0.973938 -0.131244 0.203088 -0.932604 0.298336 7.8959e-05 0.00341561 0.999994 0.517056 -0.718113 0.465797 0.000405073 0.00101551 0.999999 -7.13621e-06 -1.5502e-05 1 -1.29968e-05 -2.82332e-05 1 6.42831e-06 -2.10848e-05 1 0.000620818 -0.0270376 0.999634 -0.0010446 0.00342628 0.999994 -6.42831e-06 2.10848e-05 1 -0.496671 -0.370696 0.784795 -0.184984 0.973938 -0.131244 0.000983215 0.0429666 0.999076 0.565744 0.552219 0.612363 0 0.0363464 0.999339 0 0 1 0 0 1 -0.0296621 0 0.99956 -0.12283 0.00131196 -0.992427 -0.0738481 -0.00246951 0.997266 -9.70236e-07 0.000945197 1 -3.75325e-05 -0.00126081 0.999999 -3.26415e-05 -0.00108102 0.999999 -0.00114909 -4.38956e-05 0.999999 0.000148192 0.00064738 1 -0.602714 -0.169165 0.77982 -6.51501e-06 -0.000350898 1 -2.22901e-05 -0.00120054 -0.999999 0.0449129 0.923545 0.380851 -0.855242 0.503893 0.121052 0.0257042 -0.0151567 0.999555 -1.38589e-06 6.64243e-07 1 0 0 1 5.16211e-06 8.00395e-07 1 0 0 1 0 -0.00542214 0.999985 0.00045974 -0.00184328 0.999998 0.00574791 0.0129841 0.999899 0.00492231 0.0132227 0.999901 -0.00064508 0.00243004 0.999997 -0.00404258 -0.256602 0.966509 0 -0.00542214 0.999985 0.000152938 0.000447554 1 -0.000255006 -0.00263168 -0.999997 0.180847 0.977679 -0.106945 0.0207873 0.00583442 0.999767 0 0 -1 5.09003e-06 -0.000208788 1 0.0109787 -0.252395 0.967562 -9.61694e-05 3.75732e-05 1 0.606471 -0.744871 -0.278136 0 0 1 0 0 1 1.31625e-05 0.000951266 1 -0.00038818 -0.0264424 0.99965 0.000166117 0.000133344 1 -0.00860221 -0.583677 0.81194 0.00860225 0.583677 -0.81194 -0.00495779 0.00914336 0.999946 -0.00720048 -0.0200551 0.999773 -0.000462753 -0.00333741 0.999994 0 0.00011882 1 5.52123e-05 0.00155143 -0.999999 -0.180847 -0.977679 -0.106945 -0.000107652 9.32479e-05 1 6.51501e-06 0.000350898 1 1.19216e-05 0.000642097 -1 -0.00454488 -0.0127929 0.999908 5.07851e-05 0.000354395 1 -0.000345451 0.000256802 1 0.0056389 -0.00620466 0.999965 -1.44636e-06 -3.5972e-05 1 -0.489091 0.327594 0.808376 -1.0088e-05 0.00011462 -1 -7.81704e-06 -0.000309039 -1 0 0.000246358 1 -0.450727 0.385348 0.805203 -2.24863e-06 -0.000222726 -1 0.0018635 -0.0130041 0.999914 0 0 1 0.000245829 2.54346e-05 1 0.00055349 0 1 -0.00036077 1.9456e-05 1 7.17642e-05 -0.000891437 1 4.85314e-05 1.85392e-06 1 -9.23293e-06 -1.0074e-06 1 0 0 1 -4.71053e-05 -7.34307e-07 1 -0.000452625 -2.15672e-05 1 0.000109333 3.06867e-05 -1 -2.1677e-07 -1.51269e-06 1 -1.4165e-05 0 1 -0.000602632 -2.12523e-05 1 -1.08807e-05 -1.18719e-06 1 1.62229e-05 -7.75501e-07 1 7.81704e-06 0.000309039 -1 0 -0.000246358 1 0.471443 -0.334275 0.816089 -2.02544e-06 0.000267644 -1 1.44636e-06 3.5972e-05 1 0.489091 -0.327594 0.808376 1.0088e-05 -0.00011462 -1 0.889422 0.457047 0.00610453 0.918243 0.395696 -0.0159779 0.269447 0.963015 0 0.246069 0.969252 -0.00119083 0.689052 0.724703 0.00354513 0.892779 0.434164 -0.1202 0.276044 0.513122 -0.812715 -0.993104 0.112404 -0.0333044 0.985476 0.166303 0.0343679 -0.789011 0.602762 0.118914 -0.148195 0.768755 -0.622136 -0.98545 -0.166457 0.0343637 0.790631 -0.598137 0.130901 0.176108 -0.76266 -0.622363 -0.418192 -0.88435 0.20746 -0.982082 -0.183927 0.0410635 0.0477138 -0.429601 -0.901758 0.979236 -0.201685 0.020491 0 0 -1 0 0 -1 -0.195376 -0.0437784 -0.979751 -0.000725614 0.00137551 -0.999999 0 0 -1 -0.410926 0.096692 -0.906527 0.000821503 0.00155728 -0.999998 0 0 -1 0 0 -1 0 0 -1 -1 0 0 -1 0 0 0 0 -1 0 0 -1 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 0 0 -1 0 0 -1 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 0 0 -1 0 0 -1 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 0 0 -1 0 0 -1 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 0 0 -1 0 0 -1 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 0 0 -1 0 0 -1 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 0 0 -1 0 0 -1 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 0 0 -1 0 0 -1 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 0 0 -1 0 0 -1 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 0 0 -1 0 0 -1 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 0 0 -1 0 0 -1 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 0 0 -1 0 0 -1 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 0 0 -1 0 0 -1 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 0 0 -1 0 0 -1 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 0 0 -1 0 0 -1 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 0 0 -1 0 0 -1 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 0 0 -1 0 0 -1 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 0 0 -1 0 0 -1 1 0 0 1 0 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 1 0 0 1 0 0 -0.351216 0.76182 0.544313 -0.328897 0.265778 -0.906195 -0.508927 0.28332 -0.812849 -0.090267 0.995663 -0.0225068 0.00160877 0.999999 -0.000248686 0.000294743 1 -0.000118613 -0.196548 0.979945 0.0328211 -0.156869 -0.982846 0.0969829 -3.72848e-06 1 -5.15343e-05 -0.183095 0.54626 0.817359 -0.0175395 0.549809 0.835106 0.141844 0.58744 0.79674 0.0867507 -0.987768 0.129575 0.0533103 -0.988262 0.143165 -0.0209849 -0.339106 0.940514 0.013214 -0.379245 0.925202 0.0423144 -0.188762 0.981111 0.25446 0.112889 0.960472 0.0365817 0.17541 0.983816 -0.017433 0.236931 0.97137 0.00274033 -0.792625 0.609704 0 -0.79432 0.607499 0 -0.924412 0.381395 -0.0146465 -0.930598 0.36575 -0.000440057 -1 0.00023233 -0.0404915 -0.998863 0.0251695 -0.00116408 -0.999999 0.000105238 0.0019894 -0.999998 -0.00021581 -0.111597 -0.993399 -0.0265614 -0.535298 -0.203587 -0.819762 0.405629 -0.665598 -0.626454 -1 5.58212e-05 0 -1 0 2.79301e-06 -0.999992 0 -0.0039959 -0.836582 0.410523 0.36277 -0.954464 0.164134 0.249114 -0.98245 -0.056815 0.177662 -0.980622 -0.105925 0.164802 -0.999711 0 0.0240532 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.999596 0.000880948 0.0284105 0.998177 0.0418658 -0.0434788 0.995894 0.0780399 -0.0458794 0 0.54017 -0.841556 -0.0930334 0.995663 0 0.838081 -0.524811 0.148977 -0.953042 -0.28516 0.101954 -0.917855 -0.298372 0.261755 -0.939559 -0.266216 0.215311 -0.958609 -0.175364 0.224312 -0.890521 -0.0390625 0.453263 -0.937246 -0.00103227 0.348667 -0.931268 0.128638 0.34087 -0.733473 0.19177 0.652106 -0.711504 0.539216 0.450565 -0.918287 0.359651 0.165528 -0.875588 0.460576 0.145651 0.612533 0.785019 0.0924571 -0.123595 -0.992333 0 0.105273 -0.994399 -0.00938913 -0.972165 -0.144589 -0.184364 -0.957851 -0.248041 -0.144904 0 -0.000519622 -1 0.0303125 0 -0.99954 -0.277992 -0.933572 0.226195 -0.962259 -0.0274818 0.270745 -0.762058 0.0880524 0.641494 0.235057 0.379627 0.89478 -0.819906 0.296458 0.489763 -0.513733 0.524997 0.678569 -0.645569 0.61967 0.446375 0.751295 0.658121 0.049319 -0.0691747 -0.997605 -0.000244174 -0.00326956 -0.999992 -0.00221553 0 -0.615475 -0.788156 -0.92709 0.209056 -0.311125 -0.927278 -0.205782 -0.312744 0.731177 -0.587739 -0.346328 0 0 -1 0 0 -1 0.984409 0.163591 -0.0646219 0 0.581198 -0.813762 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -6.45024e-05 3.85208e-06 -0.942634 -0.236116 0.235989 -0.904348 -0.275098 0.326305 -0.986105 -0.0662172 0.152353 -0.967827 -0.0264365 0.250224 -0.970994 -0.027079 0.237567 -0.999892 0.00290761 0.0143823 -0.999681 0.0121958 0.0221023 -0.999966 -0.00657728 -0.00491871 -0.999944 -0.00762718 -0.00727608 -0.999664 -0.0232758 -0.0114482 -0.986107 0.154089 0.0620445 -0.972991 0.228169 0.0350374 -0.99934 0 0.0363298 -0.999998 0 -0.00189705 -0.999231 -0.0392104 0 -0.999928 0.0120094 0 -1 2.22193e-06 0 -1 0 -7.44205e-05 -1 -4.47734e-05 -3.08789e-05 0.364847 0.79185 -0.489755 -0.0138709 0.88534 -0.464736 -0.0678739 0.986069 -0.151861 0.101592 0.988227 -0.1144 0.00334949 -0.999993 0.00193383 0.456752 -0.822765 0.338282 0 -1 0 0.0111972 0.999937 0.000701311 -0.00709543 -0.999975 -0.000178808 -0.467942 -0.273794 -0.840278 0.0103171 -0.999947 0.000634631 -0.0431954 -0.999067 0.000386062 0.438585 -0.845619 -0.304257 -7.54464e-05 -1 -5.62522e-06 0.850553 -0.520329 0.0762707 0.324401 -0.943382 -0.0692419 -0.861354 0.497034 -0.105009 -1.27148e-05 -1 0 -1.27148e-05 -1 0 -1.27148e-05 -1 0 -1.27148e-05 -1 0 -4.25762e-06 -1 -1.4287e-05 0.0552278 -0.233106 -0.970882 -1.27148e-05 -1 0 -1.27148e-05 -1 0 -0.0139773 -0.999848 -0.0104079 9.01239e-06 -1 3.5251e-06 1.0086e-05 -1 1.05856e-05 0 -1 0 0.133496 0.990292 -0.0387425 9.60693e-05 1 0.000167376 0.343301 -0.910019 0.232398 0.000829667 1 3.02847e-05 -0.00160822 0.999999 -0.000213834 0.0997375 0.994705 -0.0247829 0.58071 0.164403 -0.797338 -0.407759 0.664882 -0.625831 -0.28389 -0.657002 -0.698395 0.588322 -0.212807 -0.780122 0.0807662 -0.995871 -0.0414512 -0.000449928 -1 -0.000248687 0.14849 0.984643 0.0918054 -0.000243295 -1 -0.000204171 0.0267391 0.606104 0.794936 -0.246158 0.536489 0.807209 0.0124716 0.266893 0.963646 -0.0179027 0.305132 0.952142 0.000331248 -0.192796 0.981239 0.0378783 -0.260202 0.964811 -0.0186258 -0.366899 0.930074 0.209271 -0.607044 0.766618 -0.0555081 -0.465041 0.883547 0.0520402 -0.998475 -0.0184393 -0.0514198 -0.990194 0.129893 -0.0437673 -0.990036 0.133844 0.00666663 -0.924392 0.381387 0 -0.926774 0.37562 0 -0.794765 0.606917 0.00162356 -0.793631 0.608397 0 0.552937 -0.833223 -0.935813 0.20463 -0.28702 0.0172355 0.00033402 -0.999851 0 0 -1 0.828012 -0.560052 -0.0271775 0.94494 0.0205493 0.326597 0.207411 -0.665693 -0.716822 0.636523 -0.459444 -0.619475 -0.623898 0.767461 0.147496 0.898025 0.387905 0.20756 0.742458 0.505762 0.439273 0.885113 0.368988 0.283591 0.952049 0.171688 0.253231 0.50754 -0.224484 0.831871 0.124661 0.992195 0.00293392 0.206528 0.978425 0.00546029 0.992561 0.121488 -0.00792309 1 0 0 1 0 0 1 0 0 0.973219 -0.0241525 0.228606 0.983813 -0.0700435 0.164945 1 -3.00716e-05 -1.99604e-05 0.999101 -0.0423962 0 1 0 0 1 0 0 0.999996 0.0028234 0 0.999964 -0.00851269 -0.000447057 1 0 0 0.999788 0 0.0205694 0.988062 0.109237 0.108635 0.982927 0.072758 0.169 0.88528 0.108363 0.452257 0.980828 -0.0270308 0.192992 -0.800653 0.575592 0.166276 0.957348 0.26846 0.10684 0.941302 0.282527 0.184742 0.944005 -0.178197 0.277669 0.961691 -0.194549 0.193136 -0.840565 -0.484764 0.241774 0.785716 -0.601193 0.145663 0.639198 -0.767897 -0.0419604 0.116466 0.993195 0 0 0.999989 -0.00465496 1.50623e-06 0.606487 -0.795093 0 0.872092 -0.489342 0.0185175 0.000358865 -0.999829 0 0 -1 -0.963761 -0.259158 -0.0632664 0.53659 -0.49739 -0.68167 0 -1 0 0.0177423 0.99984 0.00248145 -0.690831 0.721851 0.0410341 0 -1 0 0 1 0 0 1 0 -0.00197012 0.999998 0.000602581 -0.0145251 0.99894 0.0436719 -0.856992 0.511261 0.0646283 0.467942 0.273794 -0.840278 0.690499 -0.721456 -0.0520726 -0.204139 0.975653 -0.0801731 0.777536 0.550959 0.303122 -0.335994 0.938727 -0.0768085 0.857113 -0.507334 -0.0892707 0 1 0 -0.0209747 -0.99973 0.0100049 0 1 0 0 1 0 0 1 0 2.76757e-05 1 0 -0.433063 0.66594 0.607438 0 1 0 0 1 0 0 1 0 0.00602454 0.999982 0 0.00487847 0.999967 -0.00652827 -0.0105332 0.999944 0.000696374 -0.0487732 -0.998101 -0.0376214 -0.0925438 -0.21824 0.971497 0.729361 0.682018 0.0536937 -0.597929 -0.801422 -0.0142597 0.0932124 -0.106358 -0.989949 -0.103366 -0.257919 -0.960621 0 -1 0 0 -1 0 0 -1 0 -0.625909 -0.763824 0.157514 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.763305 -0.631115 -0.138057 -0.00637365 -0.99998 3.01961e-06 -0.580139 0.592762 -0.558634 0.646844 -0.51833 0.559399 -0.0187358 0.999693 -0.016203 0 -1 0 0.00509551 -0.999984 0.00235121 0.00508203 -0.999984 0.00230074 0 -1 0 2.88233e-05 -0.999958 0.0091594 0.0141296 -0.9999 -0.000664933 0.00933094 -0.999956 -0.000910109 -0.779195 -0.583012 -0.230111 0.986244 -0.0597377 -0.154125 0.998949 -0.040994 -0.0204864 0.0755597 0.532272 -0.843195 0.218052 0.975937 0 0.232305 0.971894 0.0381713 0.74034 0.662738 -0.112587 0.78184 0.614424 0.105879 0.992696 0.0800099 -0.0902923 0.998975 0.0452705 1.34238e-06 0.939693 -0.34202 3.97093e-07 0.899518 -0.411983 0.145384 0.722502 -0.66425 -0.191737 0.528698 -0.826871 0.191737 0.249524 -0.957393 -0.145384 0.173648 -0.984808 0 0.173648 0.984808 0 0.232338 0.966209 0.111626 0.492757 0.85348 -0.169595 0.759821 0.637565 0.127211 0.768054 0.608542 0.199423 0.929784 0.338414 -0.144834 0.993245 0 0.116039 0.973035 0.120406 -0.196735 0.920315 -0.38299 0.0796136 0.938938 -0.317382 -0.132908 0.701698 -0.684517 0.197627 0.554174 -0.803082 -0.218976 0.172812 -0.980068 0.0979909 0.210957 -0.977495 0 0.998191 0.0475471 0.0368093 -0.998227 -0.0475489 0.0358162 0 -1 0 -0.00522711 -0.999985 -0.00189416 0 -1 0 -0.00598664 -0.999977 0.00331131 0.00635003 -0.999977 -0.00220479 -2.30252e-05 -1 0 -0.000183058 -0.999999 0.00104315 -0.20113 -0.953231 -0.225603 1.26011e-05 -1 0 -2.43898e-05 -1 -8.89235e-06 0 -1 0 0 -1 0 -0.000578335 -1 8.04507e-05 0.000246216 -1 -5.41483e-05 0.000405924 -1 0.000670867 1.95688e-05 -1 -5.24322e-06 1.47522e-05 -1 -1.47522e-05 8.00055e-06 -1 -2.9859e-05 2.85621e-06 -1 -4.23982e-05 8.74365e-08 -1 7.94878e-08 -1.95568e-07 1 -1.66233e-06 -1.81382e-06 1 -3.46434e-05 -4.29408e-08 -1 -3.19864e-06 0.00334086 -0.999993 0.00187656 6.45939e-06 -1 7.67631e-05 -5.54549e-06 1 -1.44242e-05 1.26564e-06 -1 -5.58206e-05 -5.70689e-08 -1 2.51699e-06 1.81382e-06 -1 3.46434e-05 0 -1 0 0 -1 0 0.00031927 -1 -7.58472e-05 0 -1 0 0 -1 0 0.000474566 1 -2.84286e-05 -0.000552477 1 -0.000152758 3.95831e-05 1 -0.000345577 -6.24477e-13 1 -1.49678e-07 -1.09705e-06 1 1.24331e-07 0 1 0 -0.999533 0.022232 0.020969 -1 -0.000243253 -6.16448e-05 -1 -0.000201455 -4.75552e-05 -0.999976 0.00370089 -0.00594743 -0.9995 0.0315769 -0.0013584 -1 6.50476e-06 9.77518e-08 -0.99872 -0.050525 0.00249515 -1 0.000182966 0.000186261 -0.998305 0.01069 -0.0572079 -0.999857 -0.00108687 -0.0168807 -0.999997 0.000357124 0.0025458 -1 0.000257887 0.000109928 -1.79234e-06 1 3.01876e-07 8.16543e-12 1 1.91797e-06 5.96033e-07 1 -1.00387e-07 7.35858e-07 1 -8.92301e-08 5.94602e-06 1 -8.14042e-07 4.42327e-06 1 -5.36366e-07 1 -0.000142296 0.000236732 0.995657 -0.0175186 -0.0914355 1 0.000277613 5.52462e-05 0.999999 0.00120738 0.000777299 0.998419 -0.000223645 -0.0562183 0.987903 -0.154586 -0.012294 0.999355 0.0358692 -0.00176247 0.991989 8.74819e-05 -0.126327 1 6.26236e-05 3.0878e-05 1 -2.78622e-05 8.51027e-06 0.999959 0.0048191 -0.00772215 1 -0.000171787 -5.79931e-05 -0.0348619 0.706677 -0.706677 -1 0 0 -0.997028 0.0151088 0.0755439 -0.996967 0.0157789 0.0762128 -0.0093506 0.999956 0.000564081 0.0381629 0.980053 0.195039 0.9699 0.149284 0.192376 0.997564 0.0220588 0.0661764 1 0 0 8.22925e-06 0.995872 0.0907735 -0.0178701 0.986748 0.161275 -0.000147867 0.999227 -0.0393033 0.00392412 0.997683 -0.0679257 0.00016071 0.998617 -0.0525812 -1 0 0 -1 0 0 0.0301304 0.985946 -0.164324 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 -0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447213 -0.894427 0 0.447214 0.894427 0 0.447214 0.894427 0 -9.97579e-05 1 6.91111e-05 2.71025e-05 1 1 0 0 1 0 0 1 0 0 1 0 0 -0.998868 0.0475653 0 0 1 0 0 1 0 1 0 0 1 0 0 -0.998868 0.0475653 0 -0.998868 0.0475653 0 0 1 0 0 1 0 0.994233 -0.107239 0 0.863603 -0.126993 0.487916 0 0 1 9.90541e-05 8.25997e-05 1 0 3.85731e-05 1 7.98666e-06 5.53236e-05 1 0 -4.52594e-05 -1 -2.94726e-05 1.6026e-05 -1 -0.834677 -0.127307 0.535824 -0.994217 -0.107386 0 0 -2.58303e-07 -1 -3.79626e-06 3.14605e-06 -1 0 1 0 0 1 0 -1 0 0 -1 0 0 0.998868 0.0475653 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0.998868 0.0475653 0 0 1 0 0 1 0 -1 0 0 -1 0 0 3.46002e-07 7.14265e-05 -1 3.41306e-05 1.2726e-05 -1 -8.61838e-05 0.0392151 -0.999231 0.00128115 0.88274 -0.46986 3.85069e-05 0.981762 -0.190116 0.00242652 0.255377 -0.966838 -0.115479 0.990841 -0.0699874 -0.492385 0.333721 0.803858 0.519645 0.30277 0.798936 0.089831 0.994468 -0.0544432 0.0930527 0.584278 -0.806202 -9.02418e-06 1 0.000857926 -3.32462e-05 1 0 0.0034197 0.508854 -0.860846 -0.000300768 0.999941 0.0108841 0 0.99998 -0.00634943 0.000175138 1 0 0.00135721 0.534962 -0.844875 1.43419e-05 1 8.69214e-06 -3.75678e-06 1 2.27686e-06 -0.00289912 0.0140627 0.999897 -2.15463e-05 1 0.000816881 0 1 -0.000549167 0 1 0 0 1 0 0.00170504 0.292183 -0.956361 -2.80802e-06 0.000238514 1 0.0216693 0.555346 0.831337 -0.0172827 0.791868 -0.610448 0.00014858 0.275715 -0.961239 -0.0100766 0.566612 -0.823923 0.0109567 0.440163 0.897851 -0.35467 0.934692 0.0236517 0.0130727 0.365637 -0.930666 -0.000556007 0.576413 0.817158 -0.00950711 0.754128 0.656659 0.0114666 -0.0100155 -0.999884 0.0012178 0.26169 -0.965151 0.00221631 0.569997 0.821643 -0.0075837 0.750429 0.660908 0.834788 0.127202 0.535677 0.994233 0.107246 0 0 0 1 -1.62996e-05 -1.35822e-05 1 0 2.58393e-07 -1 3.79426e-06 -3.14605e-06 -1 0 -1 0 0 -1 0 -0.994218 0.10738 0 -0.863159 0.127109 0.488672 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 4.54418e-08 1.09595e-07 -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 -1 0 0 -1 0 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0.998868 -0.0475653 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 -1 0 0 -1 0 -0.0897586 -0.994477 -0.0543993 0.079044 -0.679296 -0.729595 -0.621978 -0.547756 0.559559 0.60889 -0.755288 0.242472 0 -1 0 -0.0176477 -0.759773 -0.649949 0 -0.929555 -0.368685 0.0628939 -0.710671 -0.700707 -0.208734 -0.848854 -0.485673 -2.66346e-06 -1.08314e-05 -1 0 0 -1 -2.83787e-06 -6.36372e-06 -1 1.85132e-08 -0.000298449 1 -0.000133308 -7.25227e-06 1 0.000204652 0.011586 -0.999933 0.00127388 -0.905678 0.423964 0.0089185 -0.797908 0.602713 0.0180515 -0.462599 0.886384 -2.80809e-06 -0.00059124 1 0.00223327 -0.390378 -0.920652 -0.015854 -0.796372 -0.604599 0.00390869 -0.448478 0.893785 0.015422 -0.439511 -0.898105 0 -0.000219174 -1 -0.0114173 -0.74983 0.661533 -0.00353739 -0.42121 -0.906956 -0.000674266 -0.459351 0.888254 0.0325727 -0.971721 0.233875 -0.000648733 -0.990629 -0.136578 -2.5933e-07 -0.0750057 -0.997183 0.000198171 -0.984473 -0.175536 0.000192438 -0.873299 -0.487185 0.11291 -0.989721 -0.0877726 0.000385032 -0.979118 -0.203291 2.34013e-06 -0.798633 0.601818 0 -0.798607 0.601852 0 -0.798686 0.601748 9.34687e-06 -0.798637 0.601813 -1.49868e-06 -0.798635 0.601816 0 -0.798627 0.601826 0 0.798651 0.601795 -1.56326e-06 0.798635 0.601816 0 0.798635 0.601816 1.26507e-06 0.798648 0.601799 -0.832568 -0.0489746 0.551754 -1 -0.000342107 0 0.832567 -0.0489745 -0.551755 1 -0.000342107 0 4.54368e-05 -0.999999 0.00121164 -4.54367e-05 -0.999999 -0.00121164 -0.832566 -0.0489745 0.551757 -1 -0.000342107 0 0.832566 -0.0489745 -0.551757 1 -0.000342107 0 4.54368e-05 -0.999999 0.00121165 -4.54367e-05 -0.999999 -0.00121165 -0.832566 -0.0489745 0.551756 -1 -0.000341997 0 0.832566 -0.0489745 -0.551756 1 -0.000341997 0 4.50733e-05 -0.999999 0.00120195 -4.50733e-05 -0.999999 -0.00120195 -0.999992 0.000676852 -0.00383634 -1 0.000338074 0 0.252495 0.0853259 0.963829 1 0.0003298 0 -0.000448978 0.999989 0.00465731 0.0626865 0.724419 -0.686504 -0.832775 -0.0462745 0.551675 -1 -0.000375178 0.000245999 0.832735 -0.047312 -0.551647 0.568435 -0.0692728 -0.819807 -0.831869 -0.065873 0.551048 -0.849512 -0.0640137 0.523671 0.832732 -0.0473655 -0.551647 0.99989 -0.000375136 0.0148253 0.8552 0 0.518299 0.722764 -0.0195988 0.690817 -0.8552 0 0.518299 -0.8552 0 0.518299 -0.855197 0 -0.518303 -0.988626 -0.0413238 -0.144606 -0.996849 -0.0793178 0 -0.707837 -0.114409 0.697049 0.997381 -0.060447 0.0397174 -0.855195 -0.00259588 0.518301 -0.837835 0 0.545923 0.855197 -0.000197275 0.518302 0.854229 -0.047565 0.517716 -0.855197 0 0.518303 -0.855197 0 0.518303 0.854228 -0.0475649 0.517719 -0.855196 0 0.518306 -0.855196 0 0.518306 0.855196 -0.000158318 -0.518306 -0.855196 0 -0.518306 -0.855196 0 -0.518306 0.854231 -0.047565 -0.517714 -0.855199 0 -0.518301 -0.855199 0 -0.518301 0.846615 -0.127565 -0.516691 0.638886 -0.000277957 0.769301 -0.617789 0.00104723 0.786343 -0.994282 0.106033 0.0126684 0.224421 0.0812276 0.971101 0.999842 -0.0011414 -0.0177148 -0.99999 0.00191874 -0.0040751 -0.999895 0.000370368 0.0144588 0.58124 0.162975 0.797245 0.987162 0.113082 -0.112801 0.8552 0 0.518299 0.8552 0 0.518299 -0.777317 0 0.629109 -0.850928 0.0125057 0.525134 -0.854231 0.047565 -0.517714 -0.855196 0.000158318 -0.518306 -0.425841 0.105159 0.898666 -0.855197 0 -0.518303 -0.855197 0.000197275 0.518302 -0.723256 0 -0.69058 -0.996849 0.0793178 0 0.751138 0.0597669 -0.657435 1 0 0 0.855197 0.000158137 0.518303 0.854229 0.047565 0.517716 0.854228 0.0475649 0.517719 0.855195 0.000197174 -0.518306 0.854231 0.047565 -0.517714 0.944985 0 -0.327115 0.855051 0.0185011 -0.518214 -0.854228 0.0475649 0.517719 -0.854229 0.047565 0.517716 0.785009 0.0716144 -0.615331 -0.123335 0.164955 -0.978559 0.131392 0.131204 0.98261 -0.206835 0.233255 -0.950164 -0.228075 0.303915 -0.924996 -0.392274 0.80663 0.442118 0.928444 0.107054 0.355712 -0.444408 -0.846805 0.292272 -0.683506 -0.683508 -0.256198 -0.707106 -0.707108 -4.82339e-08 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.681092 -0.681094 -0.268745 -0.764679 -0.410662 0.496611 -0.622699 -0.759429 0.188452 -0.699772 -0.658479 -0.276994 -0.611423 -0.791304 -1.42243e-06 0.714461 -0.691321 -0.107798 0.536161 -0.822208 -0.191064 0.703161 -0.678196 0.213575 0.63763 -0.692065 0.338339 0.683165 -0.683167 -0.25801 0.707106 -0.707108 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.707106 -0.707108 2.06554e-11 0.468391 -0.800711 -0.37346 0.707106 -0.707108 -2.78777e-11 0.707106 -0.707108 0 0.622306 0.766327 -0.15962 0.624198 0.763476 -0.165777 0.570908 0.785207 0.239822 0.796014 0.36366 -0.483853 0.746493 0.471465 0.469541 0.681032 0.681033 -0.269053 0.707106 0.707108 0 0.707106 0.707108 0 0.707106 0.707108 0 0.707106 0.707108 0 0.707106 0.707108 0 0.707106 0.707108 0 0.707106 0.707108 -2.64092e-06 0.609563 0.718079 -0.335851 0.51267 0.855748 0.0697497 0.394346 0.841569 0.369124 0.684728 0.68473 -0.249585 -0.707106 0.707108 -5.95473e-08 -0.709329 0.697212 0.103673 -0.637821 0.692166 0.337773 -0.683247 0.683249 -0.257573 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.42184 0.800564 -0.425615 -0.593379 0.804923 0 -0.677471 0.677473 0.286467 -0.255829 -0.966049 0.0360544 -0.0273727 0.688214 0.724991 0.303117 0.926512 -0.222924 0.098991 0.988002 -0.118542 -0.0305731 0.655959 0.754177 -0.0764516 0.608321 -0.79 -0.000972335 0.999985 0.00535045 0.0472286 0.99577 -0.0788122 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.000542405 -0.999995 0.00323501 0.000287109 -1 -6.4422e-05 0 -1 0 0 -1 0 6.20313e-05 -0.999999 0.00148876 -6.20314e-05 -0.999999 -0.00148876 6.20314e-05 -0.999999 0.00148875 -6.20314e-05 -0.999999 -0.00148875 0.998363 -0.0571929 0 0.998868 -0.0475653 0 -0.998868 0.0475653 0 0.998868 0.0475653 0 0.998868 0.0475653 0 0.855664 0.436015 -0.278799 -0.67106 0.119262 -0.731748 -0.0912926 0.485963 -0.869198 -0.616777 0.782994 -0.0806675 -0.222263 0.944964 -0.240087 0.47446 0.0727304 0.877267 0.29556 0.714456 0.634189 -0.352244 -0.417516 0.837618 0.488942 -0.703342 -0.51599 -0.559534 -0.221647 -0.79862 -0.530104 0.518811 -0.67069 -0.42058 -0.690819 -0.588117 -0.488942 0.703342 -0.51599 0.387678 -0.00568057 -0.921777 0.866258 0.499597 0 0.784998 0.294561 0.544988 0.397005 0.694516 0.600029 1 0 0 1 0 0 -5.35926e-05 -1 0.000880741 -0.844871 -0.534971 0 -0.682357 -0.230726 0.693653 -1 0 0 -1 0 0 -0.954716 0.29752 0 -0.592775 0.390944 0.704117 -8.45098e-05 0.999997 0.00264337 -0.491529 -0.00589229 0.870841 -1 0 0 -0.782734 0.622357 0 -0.407028 -0.070615 0.910682 -0.167866 0.177484 0.969701 0.146862 0.98881 0.0262104 -0.000391234 0.999649 0.0264977 6.36168e-05 0.999991 -0.00430867 1.17868e-05 1 0 0.514022 0.0351224 0.857058 1 0 0 0.789929 -0.613199 0 0.666862 -0.198556 0.718241 0.230619 -0.280242 0.931815 -0.725124 -0.688376 0.0182469 0.000391234 -0.999649 0.0264977 0 -1 0 0.636444 -0.722997 0.268726 -0.602112 -0.756935 0.253987 -0.21059 0.977574 0 0.485496 0.854548 0.184505 -0.212881 -0.0881782 0.973091 0.0657055 -0.997839 0 -0.408519 0.889424 0.205029 0.982378 -0.100762 -0.157416 0.803651 0.398508 -0.441968 -0.450889 -0.892343 -0.0205933 0.764383 -0.634015 -0.117231 0.882732 -0.469441 -0.0202613 0.11508 0.927708 -0.355125 0.389026 -0.587664 0.709444 -0.389026 0.587664 -0.709444 0.0122512 0.00137018 0.999924 -0.112397 0.0975093 0.988867 -0.992487 -0.000888026 0.12235 0 0.0981311 0.995174 0.000632821 0.165297 0.986244 -0.00220306 -0.170102 -0.985424 -0.0132216 -0.672102 0.740341 -0.0618702 -0.000788209 -0.998084 -0.498466 -0.0132298 0.866808 -3.78235e-06 -0.970146 -0.242522 0.0140415 0.0831868 0.996435 1.12283e-05 0.192008 -0.981393 0.00491652 0.677523 0.735485 0.795612 0.600559 0.0795624 0 -0.0981311 0.995174 -0.000632821 -0.165297 0.986244 0.995037 0.000722215 0.0995052 0.164401 -0.000662908 0.986393 0.162918 -0.134031 0.977494 0.105426 -0.0975843 0.989628 0.0155616 -0.2916 -0.956414 0.966906 -0.255133 0 0.221422 -0.218167 0.950461 0.707107 0 0.707107 0.0668067 -0.000858541 -0.997766 0 -0.998762 0.0497385 0.682537 0.261317 0.682537 0.33466 0.937662 0.0937676 0 0.995037 0.0995052 -0.0141438 0.580164 -0.814377 0.693405 -0.713779 0.0985317 0.00154145 -0.994305 0.106565 -0.687384 -0.234534 0.687384 0.231015 -0.757728 0.610312 -0.707107 0 0.707107 -0.765478 9.8402e-05 0.643462 -0.0128029 0.58342 -0.81207 -0.741359 0.249048 0.623187 0.806056 -0.591839 0 0.171175 -0.955842 0.238882 -0.984524 0.0879248 0.151597 -0.431536 -0.701477 0.567192 -0.892806 -0.450441 -2.65203e-06 -0.185212 -0.96138 0.203579 -0.121724 -0.990176 0.0688048 -0.108979 0.916741 0.384331 -0.191706 0.979503 0.06182 -0.828607 0.549736 0.105834 -0.882732 0.469441 0.0202613 -0.858926 0.5121 -3.04688e-06 0.759156 0.617382 0.206207 0.709668 0.646733 0.279477 0.175863 0.957837 0.227201 0.14886 0.973382 0.174265 -0.00842453 0.999964 -0.000825745 0.786473 0.61762 -0.00239752 -0.994263 0.0336309 -0.101538 -0.887693 0.370352 0.273569 0.000842275 -0.999337 0.0363853 0.00494945 -0.999981 0.00378294 -0.823127 -0.525208 0.215912 0.872376 -0.415991 0.256734 -0.369614 -0.742081 0.559197 -0.751041 -0.327747 0.573166 0.991806 -0.119001 -0.0464725 0.943581 -0.287024 -0.165141 0.369628 0.742077 0.559194 0.752537 0.325081 0.572722 -0.909799 0.319918 -0.26442 -0.995678 -0.0688171 -0.0623663 -6.98785e-05 0.99998 0.00630122 0.375225 -0.904535 -0.202539 0.732796 -0.0960693 0.673633 0.050402 0.608627 -0.791854 -0.000140513 -0.999996 0.0027985 0 -1 0.000715211 -3.73713e-05 4.75449e-05 1 4.99444e-06 -0.000285839 1 -0.809964 0.389657 -0.438321 -0.979992 0.128509 0.151988 0.000140513 0.999996 0.0027985 0 1 0.000715211 0.982276 0.0679585 0.174685 6.99051e-05 -0.999999 0.00122581 -0.000564379 -0.99996 -0.00893075 3.73713e-05 -4.75449e-05 1 -4.99444e-06 0.000285839 1 -0.687536 0.614309 -0.387193 -0.741684 0.109298 0.661784 -0.027874 -0.999395 -0.0207806 0.000143749 0.999999 -0.00113827 0.000257354 1 0.000804984 0.982275 0.0679573 0.174693 3.16117e-05 -0.999999 0.00121907 0.000159546 -0.999995 0.0032748 3.41512e-05 -3.70254e-05 1 -6.70817e-06 0.00028572 1 -0.652432 -0.280235 0.704131 -0.947727 -0.0512486 0.31494 0.000277379 0.999982 0.00599922 -0.000264296 0.999998 -0.0021414 0.646422 -0.670686 -0.363756 0.82267 -0.121614 0.55536 0.369046 0.875676 -0.311444 2.30938e-05 -0.999999 0.00129826 -0.00056096 -0.999972 -0.00741666 -2.75672e-07 3.20928e-05 1 6.69272e-06 -2.30869e-05 1 -0.984559 -0.0413793 0.17009 -3.06902e-05 0.999999 0.00176481 0 0.999998 0.00222611 0.842737 0.100274 -0.528904 0.000391109 -0.999965 0.00829931 -0.000226443 -0.999998 -0.00196183 7.08788e-05 -0.000551803 1 -0.000107323 0.00083553 1 -0.982275 -0.0679573 0.174693 -0.000242184 0.999999 0.00125654 -0.000222997 1 0.000964699 0.47313 -0.772003 -0.424453 0.543293 0.246215 0.802627 0.463909 -0.0176062 0.885708 0.000100577 -0.999999 -0.00154187 -0.000257377 -0.999989 0.00470318 -3.11265e-05 -2.58411e-05 1 3.75165e-06 -0.000285925 1 -0.631767 0.688851 -0.355465 -0.82508 0.121971 0.551694 -0.410076 -0.843512 -0.346879 -2.30938e-05 0.999999 0.00129826 0.00056096 0.999972 -0.00741666 0.652432 0.280235 0.704131 0.947727 0.0512486 0.31494 -0.000277379 -0.999982 0.00599922 0.000264296 -0.999998 -0.0021414 2.75672e-07 -3.20928e-05 1 -6.69272e-06 2.30869e-05 1 -0.9597 0.12623 0.25108 -0.959671 -0.125679 -0.251469 -3.02894e-05 0.999999 -0.00110032 2.66228e-05 0.999998 -0.00199637 0.984559 0.0413793 0.17009 -0.000177555 -0.999991 0.00427237 -4.83241e-05 -0.999997 0.00226096 3.44286e-06 -4.31656e-05 1 0.000103932 -0.000835673 1 0.0138684 -0.00468912 -0.999893 -0.0142276 0.00108232 -0.999898 0.129368 -0.989461 0.0650427 -0.249724 0.968282 -0.00822633 -0.296205 0.621193 -0.725521 -0.55474 0.659643 0.507084 -0.0555545 0.998449 -0.00376622 0.0141985 0.999899 -0.000258428 -0.00266054 0.999994 0.00227507 -0.0121577 0.999916 0.00456062 -0.00250511 -0.000503322 0.999997 0.00152265 0.000382083 0.999999 -0.0177661 -0.999804 0.0087896 0.0106244 -0.999938 -0.003472 -0.0299433 -0.999532 0.00625669 0.0216283 -0.999765 -0.0015629 -0.763778 -0.103551 -0.637119 0.915028 -0.269235 -0.300392 -0.999577 -0.00466648 -0.0287116 -0.999934 -0.00942121 -0.0065116 -0.96014 0.254174 -0.116309 -0.999999 -0.00091525 -0.000715846 -0.939423 0.278245 0.200162 -0.828925 -0.259349 -0.495602 -0.772957 0.443225 -0.45397 -0.999992 6.45717e-07 -0.00404188 -0.999996 -0.00015512 -0.00285564 -1 1.03039e-09 -0.000906286 -0.969899 -0.220673 0.102956 -0.99972 0.00192451 -0.0235846 -0.999705 0.00194824 -0.024204 -0.99803 -7.1518e-08 0.0627336 -0.990004 0.0666696 0.124287 -0.546523 -0.461883 -0.698554 -1 -1.46184e-07 -0.000907422 -1 6.61824e-05 -0.000664126 -0.132704 -0.795017 0.591893 -0.0055923 -0.000487424 -0.999984 0.00776707 0.000820105 -0.99997 -0.235623 -0.255662 0.937614 -0.141908 0.83199 0.536334 -0.124967 0.838239 0.530791 0.323828 0.647872 -0.689491 -0.366331 0.863502 -0.34665 -0.308862 -0.114154 -0.944231 -0.539995 -0.0691264 -0.838825 0.139323 -0.814864 -0.562659 -0.24201 -0.874496 0.420343 -0.146135 -0.854342 0.498744 -0.374944 0.198009 0.905654 -0.0573154 0.807973 -0.586425 -0.321246 -0.64336 0.694902 0.121698 0.000159898 0.992567 -0.303526 0.695731 0.651022 -0.202168 0.772647 0.601784 -0.976341 -0.119326 -0.180333 -0.0367025 -0.833827 0.550804 -0.316127 0.27802 0.907066 -0.00242209 -0.000159764 0.999997 0.331756 0.935876 0.118631 -0.863745 0.151499 0.480617 -0.703981 0.219083 -0.675584 -0.505473 -0.595865 0.624053 -0.835207 -0.331261 -0.43897 -0.582433 0.777679 -0.236618 -0.531034 -0.663287 -0.527307 -0.806974 -0.27392 -0.523222 1 -3.28912e-06 7.13724e-06 1 3.64326e-07 2.88544e-09 0.0396712 -0.00269843 -0.999209 0.171583 -0.0296368 -0.984724 0.382993 -0.559635 -0.734932 0.470078 -0.667617 0.577333 0.0555534 -0.998448 -0.00382651 -0.0142115 -0.999899 -0.00024595 0.00257329 -0.999994 0.00227514 0.0119894 -0.999918 0.00453939 0.0012657 -0.000246868 0.999999 0.00226612 -0.000466908 0.999997 0.0228855 0.999707 0.00791761 -0.0127594 0.999906 -0.00494545 0.042988 0.999056 0.00622161 0.000747149 1 0.000577066 -0.119128 -0.992846 -0.00812582 -0.00776745 -0.000820151 -0.999969 0.00563593 0.0004917 -0.999984 0.976434 0.0470728 0.21062 0.967713 -0.204816 -0.146908 0.999679 -0.0233992 0.00975024 1 -5.79684e-10 4.34016e-06 0.99984 0.00380335 -0.0174979 0.952567 0.304327 -0.000892246 1 1.21251e-07 -0.000907822 0.999996 0.00015512 -0.00285563 0.99483 0.0137401 0.100623 0.973057 -0.215678 0.0815059 0.991314 -0.131513 -0.000408109 0.987544 -0.00479518 -0.157271 0.990314 -0.138798 0.00377242 0.115933 0.805601 0.581004 1 -0.000155236 -0.000337196 1 -1.44709e-07 -0.000905768 -0.910087 0.276311 -0.30886 0.949642 0.207329 0.234934 0.950332 0.0536699 -0.306576 0.564043 0.426669 -0.706972 0.843099 0.249726 -0.476257 -0.309617 0.461612 0.831295 -0.00538285 0.137652 -0.990466 0.139483 0.898041 -0.417214 0.392261 0.908158 0.146221 0.137577 0.123218 0.982797 0.319267 -0.66727 0.672918 0.118218 -0.878036 -0.463764 0.250492 -0.892688 -0.374649 0.208412 0.134336 -0.968772 0.0816857 0.838088 -0.539385 -0.355669 0.487689 0.797283 0.273988 0.789898 0.548628 -0.281046 -0.284954 0.916414 0.0248887 0.85513 0.517816 0.389533 -0.337565 0.856921 0.00182395 0.000159764 0.999998 -0.104255 -0.802062 0.588071 0.265723 -0.875285 -0.404064 0.107248 -0.84201 -0.528694 0.321521 0.270989 -0.907298 0.0135029 0.827685 0.561031 -0.201533 0.447745 -0.871154 0.872543 -0.155033 0.463286 0.703981 -0.219083 -0.675584 -0.131128 0.909652 -0.394131 0.77782 0.291871 -0.556603 0.741665 -0.48613 -0.462181 0.184455 -0.877128 0.443423 0.00271531 0.46262 -0.886553 0.0012754 0.45781 -0.889049 4.17029e-05 0.874695 -0.484674 -4.70372e-05 1 -4.19427e-06 -5.51698e-05 1 0 0.0113406 0.777046 0.629341 0.0683113 0.224585 0.972057 -0.0135742 -0.0368361 0.999229 3.03121e-05 -1 1.163e-05 -0.000196292 -1 -0.000101131 0.0101512 -0.8521 -0.523281 -0.00829907 -0.828084 -0.560543 0.011071 -0.0662786 -0.99774 -1 3.00933e-06 -5.07131e-08 -1 0 0 -1 0 0 -1 0.000379264 0.000750122 -1 2.84614e-05 -0.000158036 -1 -2.9508e-07 -3.56957e-07 -1 9.98516e-06 4.4005e-05 -1 -7.72623e-05 -8.04861e-05 0.00796261 0.827739 -0.561057 -0.0222437 0.863765 -0.503404 -6.20345e-05 1 4.28056e-05 0.000193442 1 -8.08744e-05 -0.00127602 0.818658 0.57428 0.00254439 -0.0421364 0.999109 0.0553513 -0.199807 0.978271 0.0162665 -0.624279 0.781032 -5.19824e-05 -1 2.49074e-05 -4.8503e-05 -1 2.6707e-05 0.0237985 -0.860624 -0.508684 0.0352919 -0.123009 -0.991778 -1 -2.56423e-06 -1.09764e-10 -1 -0.000169864 -0.000304163 -1 3.53219e-06 3.57788e-07 -1 3.6894e-06 3.73712e-07 -1 -1.10333e-07 5.87928e-07 -1 2.55442e-06 -1.36117e-05 -1 3.37563e-06 -1.20022e-05 0.0392936 -0.672042 0.73947 -0.0377543 0.75997 0.64886 -0.00170541 -0.799286 0.600948 -0.00466164 -0.80384 0.594827 -0.0193297 0.637023 0.770602 0.0333291 0.730021 0.682612 0.0310623 0.956814 -0.289035 0.00232726 0.870468 -0.49222 -0.00389484 -0.112935 -0.993595 0.0502821 -0.0785458 -0.995642 -0.0415523 -0.639486 -0.767679 -0.0363729 -0.619472 -0.784176 0.0143511 -0.956261 -0.292163 0.00141602 0.000911152 0.999999 -0.000534898 -0.000575251 1 0.00227735 -0.516512 -0.856277 0 -0.519846 -0.85426 0 -0.354913 -0.9349 0 -0.354913 -0.9349 0 -0.182476 -0.98321 -0.00294836 -0.186625 -0.982427 -0.000481917 1 -0.000278851 0.000577935 1 0.00044846 -0.00201228 0.999998 -2.90434e-05 -0.306249 0.0319844 -0.951414 0.00120984 -0.999999 -0.00098297 -0.00119741 -0.999993 -0.00358214 -1 2.47309e-07 4.06401e-07 -1 -1.37433e-07 4.67125e-07 -1 -0.000319985 0.00018688 -1 7.64123e-05 0.000201283 -1 0.000274977 0.000128308 -1 0 0 -1 0 0 -8.28814e-05 -0.000120071 1 -0.000490248 0 1 0.00214652 0.200591 -0.979673 0 0.197956 -0.980211 0 0.404355 -0.914602 0 0.404355 -0.914602 0 0.594107 -0.804386 0 0.594107 -0.804386 0 0.753265 -0.657717 -0.00121036 0.752243 -0.658884 -0.00129419 0.999993 -0.00349279 0.0011267 0.999999 -0.000890318 2.22021e-05 -1 -2.58457e-05 -0.280937 -0.284997 -0.916434 0.0858788 -0.791536 0.605058 -0.000411896 -1 0.000178732 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.000500316 6.45859e-05 1 -0.000751391 0.000134899 1 0.00290079 -0.752241 -0.658882 0 -0.754987 -0.65574 0 -0.594107 -0.804386 0 -0.594107 -0.804386 0 -0.404355 -0.914602 0 -0.404355 -0.914602 0 -0.19799 -0.980204 -0.002071 -0.200528 -0.979686 -0.000152085 1 -3.0012e-05 -0.000422847 1 9.34018e-05 0.0681843 0.873342 0.482312 -0.00089604 -0.999999 -0.000827327 -0.00117782 -0.999999 -0.00109211 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.00361911 -0.00227173 0.999991 -0.00280585 -0.00176152 0.999995 -0.183151 0.485286 -0.854958 -0.0566115 0.38261 -0.922174 0.00354588 0.188219 -0.982121 0.00305373 0.187657 -0.98223 -0.00136996 0.999998 -0.00133378 -0.00123251 0.999999 -0.00120419 -1 0 0 -1 0 0 -0.0136242 0.00551305 0.999892 -0.0080861 0 0.999967 -0.000596111 -0.999999 -0.0013327 -0.00158804 -0.999996 -0.00212914 0.00500488 -0.0133047 -0.999899 -0.00933927 0.00543285 -0.999942 -0.0034239 0.999992 -0.00205586 -0.000453089 1 0.00059887 -1 0 0 -1 0 0 -0.0136242 0.00551305 0.999892 -0.0080861 0 0.999967 -0.000418155 -1 0.000719159 -0.00344943 -0.999992 -0.00199762 -0.00964502 -0.00543284 -0.999939 -0.00451759 0.00106086 -0.999989 -0.00316768 0.999993 -0.00218768 -0.000493033 1 0.00010584 -1 0 0 -1 0 0 -0.39657 -0.432148 -0.809926 -2.3997e-05 -1 -4.90099e-05 -0.00143507 -0.999999 -0.000316333 -0.12251 0.111542 0.986179 0.109925 -0.641536 -0.759176 0.0470401 0.642746 -0.764634 -0.0440849 0.281973 -0.958409 0.0313925 -0.388792 0.920791 -0.0344241 -0.728133 0.684571 0.0276315 0.3971 0.917359 -0.0307145 0.684738 0.728142 0.0838973 -0.320055 0.943677 0.0100083 0.992933 0.118256 0.097534 -0.368298 0.924578 -0.0136155 -0.532103 -0.84657 0.00643037 -0.588299 -0.808618 0.0757633 0.339591 0.937517 0.0856087 0.683252 -0.725147 0.0779146 -0.323209 0.943115 0.075763 0.33959 0.937517 0.0430136 0.814131 -0.579086 0.0783387 -0.324794 0.942535 0.0795202 -0.768826 -0.634495 0.0607333 0.531104 -0.845127 -0.0570911 0.111282 -0.992148 -0.0237985 0.860624 -0.508684 -0.0323439 0.131694 -0.990763 -0.00796244 -0.827739 -0.561057 0.0204578 -0.861764 -0.506896 9.15077e-05 -1 4.28056e-05 -0.000193691 -1 -9.91445e-05 -0.0118059 -0.8186 0.574242 0.0103424 0.0421367 0.999058 -0.0521546 0.242188 0.968827 -0.0162665 0.624279 0.781032 5.19824e-05 1 2.49074e-05 4.8503e-05 1 2.6707e-05 1 2.56423e-06 -1.09778e-10 1 -3.53219e-06 3.57788e-07 1 -3.6894e-06 3.73712e-07 1 1.10333e-07 5.87928e-07 1 0.000181841 -0.000325939 1 -2.55442e-06 -1.36117e-05 1 -3.37563e-06 -1.20022e-05 -0.00333929 0.852139 -0.523305 0.00810871 0.83689 -0.547312 -0.0111266 0.0874043 -0.996111 0.000528734 -0.471251 -0.881999 0.0373564 -0.874085 -0.484334 0.000208312 -1 -6.14371e-05 4.86132e-05 -1 2.14488e-05 0.00414618 -0.612153 0.790729 -0.0410547 -0.174405 0.983818 -0.0085186 -0.0812752 0.996655 -3.03121e-05 1 1.163e-05 0.000196292 1 -0.000101131 1 -3.1721e-06 -3.49765e-07 1 -3.85161e-06 3.89504e-10 1 -2.00756e-07 8.84741e-07 1 5.49777e-06 6.06201e-07 1 -0.000121796 -0.00022821 1 -9.98516e-06 4.4005e-05 1 7.72623e-05 -8.04861e-05 -0.0381907 -0.697641 0.715429 0.00170541 0.799286 0.600948 0.0198368 0.826376 0.562769 0.00225251 -0.798414 0.602105 -0.0392936 0.672042 0.73947 0.0415523 0.639486 -0.767679 0.0363729 0.619472 -0.784176 -0.0143511 0.956261 -0.292163 -0.0502821 0.0785458 -0.995642 -0.00258003 0.112935 -0.993599 -0.00364098 -0.805624 -0.592416 -0.0684487 -0.743482 -0.665244 -0.0038065 0.000175034 0.999993 -4.15585e-05 -0.00204259 0.999998 -0.00305578 -0.186727 -0.982407 0 -0.182419 -0.983221 0 -0.354913 -0.9349 0 -0.354913 -0.9349 0 -0.517796 -0.855504 0.000985303 -0.516513 -0.856279 0.00136221 -0.999992 -0.00362967 -0.000486915 -0.999999 -0.00164432 0.50404 0.0992242 -0.857962 2.23868e-05 1 -1.02645e-06 4.14124e-05 1 -1.44562e-05 1 -1.67565e-06 1.994e-06 1 0.000206653 -2.64543e-05 1 3.33889e-05 0.000179963 1 6.28232e-05 0.000165487 1 0 0 1 -0.000347426 4.49087e-05 1 9.82867e-05 0.00016294 0.000500316 -6.45859e-05 1 0.000751391 -0.000134899 1 -0.00290079 0.752241 -0.658882 0 0.754987 -0.65574 0 0.594107 -0.804386 0 0.594107 -0.804386 0 0.404355 -0.914602 0 0.404355 -0.914602 0 0.19799 -0.980204 0.002071 0.200528 -0.979686 0.000152085 -1 -3.0012e-05 0.000422847 -1 9.34018e-05 -0.0681843 -0.873342 0.482312 0.00089604 0.999999 -0.000827327 0.00117782 0.999999 -0.00109211 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 8.28814e-05 0.000120071 1 0.000490248 0 1 -0.0147012 -0.215955 -0.976293 0 -0.197956 -0.980211 0 -0.404355 -0.914602 0 -0.404355 -0.914602 0 -0.594107 -0.804386 0 -0.594107 -0.804386 0 -0.753265 -0.657717 0.00121036 -0.752243 -0.658884 0.00597722 -0.999976 -0.00349273 -0.000914176 -0.999991 0.00402832 -2.22021e-05 1 -2.58457e-05 0.280937 0.284997 -0.916434 -0.0858788 0.791536 0.605058 0.000411896 1 0.000178732 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.00691441 -0.00234846 0.999973 -0.119387 0.420629 -0.899343 0.280149 0.532562 -0.798683 0.271983 0.407082 -0.871958 0.043367 0.284928 -0.957567 -0.00912989 0.172949 -0.984889 0.0120451 0.188992 -0.981905 0.306248 -0.0319866 -0.951414 0.000752414 0.999999 0.0012241 0.003099 0.999994 -0.00123061 1 0 0 1 0 0 0.0080861 0 0.999967 0.0136242 -0.00551305 0.999892 0.00158775 -0.999996 -0.00218769 0.0006153 -0.999999 -0.00140375 0.000418155 1 0.000719159 0.00344943 0.999992 -0.00199762 0.00964502 0.00543284 -0.999939 -0.00500519 -0.0131199 -0.999901 1 0 0 1 0 0 0.0080861 0 0.999967 0.0136242 -0.00551305 0.999892 0.0034239 -0.999992 -0.00205586 0.000453089 -1 0.00059887 0.000586553 0.999999 -0.00121724 0.00172343 0.999996 -0.00212914 -0.00368669 0.011583 -0.999926 0.00933927 -0.00543285 -0.999942 1 0 0 1 0 0 0.41179 -0.355939 -0.83889 0.001168 -0.999996 -0.00269702 -0.0150321 -0.999887 -3.838e-05 0.149958 0.188091 0.970636 -0.0150161 0.911218 0.41165 0.0107167 0.643311 -0.76553 -0.00488267 0.688913 -0.724828 0.009144 -0.877456 0.479569 0.0720379 -0.683835 0.726072 -0.0838973 0.320055 0.943677 0.0307145 -0.684738 0.728142 -0.0276315 -0.397101 0.917359 -0.086649 0.0564852 0.994636 0.0899038 0.535398 0.839801 -0.0607333 -0.531104 -0.845127 0.0570911 -0.111282 -0.992148 -0.0783387 0.324794 0.942535 -0.0795202 0.768826 -0.634495 -0.075763 -0.33959 0.937517 -0.0779146 0.323209 0.943115 -0.0757633 -0.339591 0.937517 -0.0856087 -0.683252 -0.725147 0.0136155 0.532103 -0.84657 -0.00643037 0.588299 -0.808618 -0.097534 0.368298 0.924578 0.00917345 -0.237029 -0.971459 -0.00645475 -0.250763 -0.968027 -1 0.000193556 0.000105774 -0.998037 0.0363424 0.0509999 -0.154725 -0.926535 0.34292 0.0276748 0.280676 -0.959404 -0.0131573 0.252517 -0.967503 -0.998564 0.0311028 -0.043626 -0.999999 0.000432831 -0.00163266 -0.011388 0.765905 -0.642853 0.0295938 0.784797 -0.619046 -0.0130205 0.959756 -0.280534 -0.00331223 0.96175 -0.273908 -0.311871 0.548912 0.77552 -0.999998 0.00154778 0.000879347 -0.999985 0.00505136 -0.00198451 -0.99999 0.00235241 -0.00372361 -1 -2.19042e-05 3.46719e-05 -0.00300932 -0.958708 -0.284376 0.0220611 -0.961914 -0.27246 -0.0757818 -0.833541 -0.547235 0.0163738 -0.775204 -0.631499 -1 0.000482573 0.000304 -0.999996 -0.00209541 -0.00188057 -0.999996 -0.00224009 -0.00174735 -1 0.00056709 -0.000732945 -0.13226 -0.471941 0.871653 0.0188893 -0.355551 -0.934466 0.0520661 -0.316675 -0.947104 -0.0279793 -0.220275 -0.975037 -0.999988 0.000345735 0.00489795 -0.999997 0.00175266 0.00187122 -0.999935 0.00778954 0.00827783 -0.0112375 0.25015 -0.968142 -0.014215 0.247559 -0.968768 -1 0.000251257 -0.000135047 -1 0.000241146 -0.000120455 -0.0762886 0.990669 -0.112936 0.0662644 0.113334 -0.991345 -0.27078 -0.671895 -0.689373 -0.260817 0.611383 -0.747118 0.18977 -0.55023 -0.813163 -0.096724 -0.992904 -0.0691817 0.108058 -0.95774 -0.266567 -0.120181 0.81848 0.561824 -0.0429464 -0.791071 -0.610215 0.178013 -0.240328 -0.954229 0.00336588 -0.040052 0.999192 -0.320704 0.469762 0.822479 -0.0799438 0.99388 -0.0762335 -0.0974316 -0.992106 -0.0789536 -0.0210069 -0.995547 0.0918975 -0.227721 0.851198 0.47287 0.100577 0.466705 0.878676 -0.213099 0.915718 0.340659 0.0238349 0.00510937 0.999703 -0.000707222 0.000725446 1 -0.999798 0.000646883 -0.0201131 -0.999985 -0.00382554 0.0038067 -0.00526698 -0.000593612 0.999986 -0.997195 0.0144674 -0.0734349 -0.999996 0.000518156 -0.00262009 0.000747193 0.999999 -0.000711874 0.0479478 0.998802 -0.00980666 -0.996904 -0.0786307 -9.57511e-05 -0.999844 0.00229004 0.0175314 -0.00723506 -0.999973 0.00144306 0.0408917 -0.999133 -0.00777364 -1 -0.000250274 5.27598e-06 -1 -2.82837e-05 5.3046e-05 0.0116367 0.000335931 0.999932 -0.999998 -0.000323724 0.00172483 -0.999998 0.000341295 -0.00174976 0.0337086 0.00549532 0.999417 0.00574507 0.000941342 0.999983 -0.19886 -0.957288 0.20989 -1 0.000910777 -0.000204851 -0.999989 1.81318e-06 0.00465772 -0.7205 -0.6896 -0.0730194 0.412779 -0.850456 -0.326095 0.0884972 -0.790732 0.605732 -0.564616 -0.075784 -0.821867 0.0232534 -0.595896 -0.802725 -0.129607 0.208697 0.969354 0.1003 -0.478611 0.872279 -0.565101 0.1725 0.806786 -0.079412 -0.000801865 -0.996842 -0.591247 0.464765 -0.659106 0.249479 -0.937567 0.242341 -0.571711 -0.786951 0.232068 -0.776839 -0.483392 -0.40355 0.0165919 -0.243916 -0.969654 0.012382 -0.247565 -0.968792 1 -0.000251257 -0.000135047 1 -0.000241146 -0.000120455 -0.037178 0.316871 -0.94774 0.0301783 0.270118 -0.962354 0.999999 -0.00113188 1.42749e-05 0.999988 -0.00079525 0.00493394 0.00512358 0.967305 -0.253563 -0.0401399 0.957088 -0.287005 0.0580135 0.862935 -0.501973 -0.0210799 0.765069 -0.643603 0.000878605 0.774831 -0.632167 0.999999 0.00124711 0.00059085 0.999992 0.00377836 -0.00157031 0.999993 0.00304089 -0.0023487 0.999999 -0.000776746 -0.000990381 0.271353 0.480345 0.834048 0.0142126 -0.761931 -0.647502 -0.0304303 -0.783653 -0.620453 -0.0146314 -0.960209 -0.2789 0.0248471 -0.952162 -0.304583 0.258752 -0.568747 0.780752 1 1.63387e-05 2.58624e-05 0.999996 -0.00157908 -0.00249951 0.999994 -0.00326516 -0.00127907 0.999999 -0.00174031 -4.19421e-05 -0.017676 -0.3234 -0.946097 -0.0459666 -0.280177 -0.958847 0.00532363 -0.229801 -0.973223 0.998564 -0.0311028 -0.043626 0.999999 -0.000432831 -0.00163266 0.0185437 0.26084 -0.965204 0.0060061 0.250764 -0.96803 1 -0.000193556 0.000105774 0.998037 -0.0363424 0.0509999 0.154725 0.926535 0.34292 -0.176669 0.596066 -0.783258 0.0953676 0.993035 -0.0691906 0.252881 -0.465539 -0.84813 -0.0354224 -0.196894 -0.979785 0.310202 0.657587 -0.686553 0.201662 -0.973917 -0.104009 -0.214829 -0.363544 -0.906468 -0.100577 -0.466705 0.878676 0.213099 -0.915718 0.340659 -0.0867634 -0.483852 -0.870839 0.1921 0.978319 -0.0773888 0.0210065 0.947728 0.318389 0.213442 -0.903771 0.371 0.027284 0.953535 0.300044 0.157991 -0.783616 0.60082 -0.00339248 0.351054 0.936349 0.261367 0.764069 -0.589819 -0.0473608 0.993853 0.100069 0.121708 -0.818374 0.56165 -0.0724455 0.980174 -0.18442 0.00172242 -0.000281515 0.999999 -0.00914103 0.00162516 0.999957 0.761922 0.600226 -0.243316 0.999983 -4.55215e-06 -0.00590794 0.999999 0.00137316 0.000384356 -0.0167286 -0.000434378 0.99986 -0.0135955 3.28907e-05 0.999908 0.992521 -0.0225037 -0.119979 1 2.67515e-05 -0.000342158 0.00245233 0.999996 0.0016941 -0.0145794 0.999893 -0.00158151 0.999883 0.00228773 -0.0151505 0.997796 -0.066359 -8.09736e-05 -0.00152718 -0.999978 -0.00650681 0.0164408 -0.999859 -0.00345113 0.999995 0.00159499 -0.00285344 0.999894 -0.0145513 0.000198343 0.460271 0.869177 0.180781 0.0372809 -0.00653535 0.999283 -0.000862919 0.000190937 1 0.999994 -0.00334533 -0.000644128 0.999809 -2.15227e-05 0.0195239 -0.0162292 -0.000453659 0.999868 1 1.96065e-05 -0.000131551 1 2.71655e-05 -9.22942e-05 -0.169436 0.78066 -0.601549 0.664537 0.729568 0.161619 -0.389223 -0.0568705 0.919386 0.267539 0.691396 0.671115 -0.0463099 -0.833365 0.55078 0.168699 0.107508 -0.979787 0.0883693 -0.139806 0.986228 0.580954 0.34149 0.738835 0.535427 -0.5435 0.646472 0.12908 -0.232667 0.963953 0.0966246 0.53019 -0.842355 -0.0131347 0.884846 -0.465699 0.678944 0.694034 0.239482 0.311094 -0.862106 -0.399993 -0.173279 0.37311 -0.911462 -0.0990773 0.678554 0.727838 -0.000718603 -0.00482026 0.999988 -0.00228152 -0.0125167 0.999919 -0.000269274 -0.00212627 0.999998 -0.673296 -0.65771 -0.337773 -0.358823 -0.751436 0.553706 -0.217552 -0.969218 -0.115269 -0.902626 -0.221996 0.368761 -0.560787 -0.626686 -0.541093 -0.469676 -0.821892 0.322333 -0.203895 -0.957035 -0.206181 -0.0657408 -0.973884 0.217321 -9.42779e-06 9.72634e-07 -1 -2.17728e-05 2.59652e-06 -1 0.000315224 -0.000149148 -1 0.000527343 -0.0026 -0.999996 -0.00116233 0.000225402 -0.999999 -0.00234494 -0.00172613 -0.999996 -0.00111741 -0.000896552 -0.999999 0.000916569 0.00412056 -0.999991 -0.00418041 0.00431825 -0.999982 4.21271e-05 0 -1 0.00201813 0.00247429 -0.999995 0.000108932 0 -1 -0.000321332 0.00245595 -0.999997 -0.000134736 0.000208937 -1 -5.99849e-05 0.000340192 -1 -9.60793e-05 4.54599e-05 -1 -0.00234747 0 -0.999997 0.00211122 -6.8634e-05 -0.999998 0.000476336 0.000660543 -1 0.000714796 -0.000847341 -0.999999 0.0523368 0.841139 0.53828 0.0841795 -0.478287 0.87416 8.28947e-05 0.000669055 -1 0.000428975 -0.000851915 -1 -0.517267 0.000205013 -0.855824 -0.223586 0.193132 -0.955358 -0.00121117 -5.44051e-05 -0.999999 -3.43837e-05 0.00016203 -1 1.51788e-05 -6.01275e-06 -1 -0.00105059 -0.000183805 -0.999999 -0.540585 0.102384 -0.835036 0.000683558 -0.000313521 -1 -0.00102078 0.000109856 -1 -0.000190727 -2.51849e-05 -1 -3.5438e-05 -0.00483516 -0.999988 0.00202909 -6.36213e-05 -0.999998 0.000481397 0.00194146 -0.999998 -0.00183827 0.00219189 -0.999996 3.88372e-05 0 -1 4.71091e-06 0 -1 0.000270807 -0.00185543 -0.999998 -0.00150612 -0.00158471 -0.999998 0.000691531 0.000748485 -1 0.000172853 -0.000370358 -1 0.00289844 -0.00346362 -0.99999 -2.45767e-05 -0.00534011 -0.999986 0.000442066 5.83733e-05 -1 0.000557474 0 -1 -1.11541e-05 0.000343131 -1 -0.000220857 0.000490751 -1 -0.000441556 0.000410375 -1 -0.0183786 -0.767834 0.640385 -0.194521 0.454144 0.869433 -0.00018647 -0.000406237 -1 -0.00089767 -0.000187508 -1 0.00126229 0.00026367 -0.999999 -0.000565587 -0.00117284 -0.999999 -0.00047803 -0.000384647 -1 -0.00372691 -0.00176783 -0.999992 0.00220481 0.000132191 -0.999998 0.0015349 -0.00176298 -0.999997 0.632368 4.65943e-05 -0.774668 0.0597622 0.532589 -0.844261 0.363547 -0.929403 -0.0635897 0.82125 0.570088 -0.0234111 0.474634 0.87671 0.0781118 -0.0155049 0.575077 -0.817952 0.19435 -0.666304 -0.719907 -0.0733238 0.987361 -0.140503 -0.132321 0.84705 -0.514779 -0.111982 0.136711 -0.984261 -0.152251 -0.984565 -0.0863202 -0.0149117 0.985665 -0.168054 -0.997066 -0.027417 0.0714615 -0.0037214 -0.998477 0.0550457 -0.000113224 -1 -0.000780144 0.00139508 0.999989 -0.0044668 -0.00139508 -0.999989 0.0044668 0.981263 -0.173547 -0.0836887 -0.986384 -0.108152 0.123893 2.04712e-05 -1 -0.000325389 7.17095e-05 -1 0.000453784 0.999166 -0.0408337 -0.000403773 0.956711 -0.159219 0.243627 -0.971282 -0.146158 0.187749 -0.991497 -0.102018 0.080787 -0.0054312 -0.999741 -0.0221008 0.00356227 -0.998603 0.052716 -2.88358e-06 -0.999999 -0.00118148 0.995634 0.020459 0.0910767 0.16978 0.983016 0.0696719 -0.0422125 0.97901 -0.199394 -0.0647478 -0.983843 -0.166915 0.274792 -0.809823 0.51834 1 5.84537e-05 0.000132153 1 -1.6266e-05 -0.00096493 0.99966 0.00661853 0.0252379 0.0038116 0.998451 0.0555159 -0.00488561 0.99986 -0.0160298 0.000108126 1 0.000325686 -0.992809 0.1169 -0.025782 0.998363 0.0506217 0.0266156 0.976833 0.123061 0.175081 4.20335e-06 1 -0.000627099 -4.21408e-05 1 0.000103582 -0.997781 0.0447893 -0.0492561 -0.949613 0.188957 0.250062 0.995311 0.096135 -0.0106899 0.987301 0.13838 0.0780268 -0.00362379 0.998603 0.0527098 0.00605197 0.999784 -0.0198785 1.56342e-06 1 -2.27407e-05 -1 1.68477e-05 -0.000353341 -1 -4.76091e-05 0.0006357 0.000567446 -0.996999 -0.0774179 -0.997113 -0.0105204 0.0752007 -1 -9.18803e-05 0.0006617 -1 -1.12401e-05 -0.000577124 0.999997 -3.57995e-05 -0.00230305 0.999999 6.64589e-05 -0.00145307 0.999992 -0.000113183 -0.00395382 1 0 0 1 0 0 1 2.7618e-05 -0.00096478 -1 -1.72411e-05 -0.00098791 -1 -2.41229e-05 -0.000842685 -1 0 0 -0.999999 -8.29074e-05 -0.00146502 -0.999991 0.000124111 -0.00433556 -1 0 0 0.999999 -6.2219e-05 -0.00113591 0.999999 0.000114687 0.00164893 -0.000120067 1 0 -0.00349855 0.998571 0.0533293 -2.85457e-05 -1 -0.000253372 -4.18197e-05 -1 -0.000452453 -1.48336e-05 1 0.000102904 -3.57358e-06 1 -8.21429e-05 -3.02063e-05 -1 -0.000974722 1.19339e-05 -1 -0.000276356 0.00336239 0.998697 0.0509206 0.000123812 1 0 0.353908 -0.567211 -0.743653 -0.00865004 -0.998876 -0.0465984 -0.000170992 0.999999 0.00173909 1.42715e-05 1 -0.000972976 1.53855e-05 -0.999999 -0.00122209 9.36767e-05 -1 3.86102e-05 0.000129798 -1 0 0.00344274 -0.998634 0.052143 0.0437698 0.998394 0.0359575 -0.0267133 0.994147 -0.104679 3.32895e-05 1 0.00012944 8.41243e-06 1 0.000550087 -3.45952e-05 -1 -0.000357694 -7.51026e-05 -1 -0.00102088 -0.999999 0.000123057 -0.00173399 -1 -3.97221e-05 8.10994e-06 -1 -2.53157e-05 0.000226256 -0.999999 -7.24833e-05 0.00102136 0.999999 0 -0.00106749 1 6.91073e-06 -0.000966218 0.999999 -3.87179e-05 -0.00136219 1 0.000100946 0.000687974 -0.999997 0.00012232 -0.00251379 -1 0 -0.000717974 0.999999 -7.71601e-05 -0.00108726 1 3.70601e-05 8.1113e-06 1 2.53157e-05 0.000187703 0.999999 8.93005e-05 0.00125833 -1 2.05704e-05 -0.000587152 -0.999999 6.19293e-05 -0.00121754 -0.493543 -0.853013 0.169657 -0.945109 -0.280013 -0.16841 0.171663 -0.689634 -0.703517 -0.964171 -0.109214 -0.241759 0.872796 0.487783 0.0172039 -0.803649 0.320434 0.501469 0.946353 0.0948247 -0.308909 -0.921007 0.109801 0.37375 -0.566398 0.7279 0.386464 0.550116 0.76103 0.343811 0.985136 0.170439 0.0213902 0.548581 0.0680524 -0.833323 -0.355684 -0.5836 -0.73 -0.936533 -0.0882691 0.339286 -0.922627 -0.382601 -0.0487314 -0.343702 -0.922777 0.174218 -0.575585 0.628412 -0.523259 0.881208 -0.414182 0.227873 0.996888 0.0787394 0.00386641 0.999161 0.0409393 0.000538597 0.444631 -0.751249 -0.487779 0.8836 0.465965 -0.04614 0.583667 0.583668 -0.564504 -0.823638 0.514221 -0.239159 0.210747 0.969574 -0.124543 -0.987892 0.155098 -0.00370238 0.412882 -0.860265 0.299118 -0.861852 0.410463 0.297878 -0.86882 -0.400917 0.290548 0.864841 -0.406649 0.294428 0.914735 0.383991 -0.125741 0.788949 0.614458 0 -0.767913 -0.640555 0 -0.694188 0.719794 0 -0.899191 -0.377106 0.221916 0.838288 -0.441632 0.319741 0.853276 0.42237 0.305817 0.838228 -0.441603 0.319939 -0.868084 -0.402029 0.291211 -0.838288 0.441632 0.319741 0.95993 -0.0559498 -0.274596 -0.373267 -0.248925 -0.893705 -0.676486 -0.658118 -0.330526 0.290431 0.484002 0.825465 0.647356 0.747284 0.149989 0.528031 0.729492 0.43477 0.707159 0.707055 -1.45126e-06 0.707139 0.707074 0 0.661422 0.740541 -0.11883 0.285855 0.476365 -0.831483 0.52532 0.734118 -0.430244 -0.181044 -0.00721473 -0.983449 -0.559798 0.713322 -0.421662 -0.262413 0.432475 -0.862615 -0.162456 0.176769 -0.970753 -0.707168 0.707045 -3.15459e-07 -0.707173 0.707041 0 -0.66143 0.740533 0.118831 -0.237654 0.396031 0.88695 -0.520051 0.732532 0.439253 -0.0366717 -0.00950039 -0.999282 -0.111776 0.0207088 -0.993518 -0.910317 -0.0577863 -0.409858 -0.988154 0.0951527 0.120402 -0.0192464 0.00301233 0.99981 -0.0929755 -0.0294485 0.995233 -0.94962 0.265908 -0.165878 -0.00944885 0.999925 0.00785061 0.000436977 0.999989 -0.0046556 0.0507456 0.0185795 0.998539 0.977785 0.111936 0.177221 0.905231 0.021038 0.424399 0.0823977 -0.0224232 -0.996347 0.0566074 -0.0101169 -0.998345 0.521862 0.725505 -0.448668 0.00240492 0.999687 0.0248864 -0.108569 -0.0289791 -0.993666 0.380742 -0.153959 -0.911774 0.707726 -0.503519 -0.495574 -0.83522 -0.35831 -0.41716 -0.228067 -0.696616 -0.680229 0.0176363 -0.301345 -0.953352 0.977183 -0.0319249 -0.209988 0.226889 0.110766 -0.967601 -0.226889 -0.110766 0.967601 0.567586 -0.0273141 -0.822861 -0.988614 0.0738876 -0.131085 0.910252 -0.00129123 -0.414053 0.560632 0.101637 -0.821804 -0.553824 -0.0929154 -0.827433 -0.973598 -0.0645002 0.218969 0.71161 -0.211524 0.669976 -0.0935058 -0.901795 -0.421926 -0.144702 -0.90426 -0.401716 -0.863501 -0.0762928 -0.498544 -0.877236 -0.157676 0.453427 0.861756 -0.0991657 -0.497537 0.966864 -0.0848107 -0.240791 0.866026 0 -0.499999 0.866026 0 -0.499999 -0.866026 0 -0.499999 -0.866026 0 -0.499999 -0.866027 0 0.499997 -0.456755 -0.060578 0.887527 0.609594 -0.118991 -0.783732 0.866027 0 0.499998 -0.866025 0 0.500001 -0.866025 0 0.500001 0.866025 0 0.500001 0.866025 0 0.500001 -0.936298 0.0166456 0.350813 -0.866025 0 0.500001 0.865922 0.0153944 0.499942 0.954973 0 0.296691 -0.866026 0 -0.499999 -0.866026 0 -0.499999 0.406324 -0.059404 -0.911796 0.866026 0 -0.499999 -0.0547562 0.285 0.956962 0.108134 0.515736 0.849896 -0.662307 0.0755743 0.745412 0.0040787 0.999392 -0.0346365 0.994656 0.102611 0.0114051 -0.997664 0.0623184 0.027997 0.9964 0.0795675 -0.0292599 -0.973206 0.227119 0.0358728 -0.897984 0.132957 0.41946 -0.864822 0.0526897 -0.499307 0.515839 0.0662261 -0.854122 0.866025 0 -0.500001 0.866026 0 -0.499999 0.866026 0 -0.499999 -0.866026 0 -0.499999 -0.866026 0 -0.499999 -0.824425 0.106107 0.555936 -0.568351 0.104168 0.816166 0.558891 0.14041 -0.817267 0.837688 0.0759199 0.540846 -0.866025 0 0.500001 -0.866025 0 0.500001 -0.936298 -0.0166456 0.350813 -0.866025 0 0.500001 -0.866026 0 -0.499999 -0.584379 0.100233 0.805267 0.866026 0 -0.499999 0.866026 0 -0.499999 0.865922 -0.0153944 0.499942 0.954973 0 0.296691 0.866025 0 0.500001 0.866025 0 0.500001 -0.0812843 -0.389135 0.917588 0.054756 -0.285 0.956962 -0.989878 -0.138595 0.0305336 0.973202 -0.227118 0.0360055 -0.0077482 -0.999333 -0.0356942 -0.994687 -0.102326 0.0113056 0.997457 -0.0616162 0.0358325 -0.0647585 0.258608 -0.963809 -0.968225 -0.245988 -0.0450652 0.0647585 -0.258608 -0.963809 0.968225 0.245988 -0.0450652 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0.473199 -0.240362 -0.847531 0.501152 0.107713 -0.858629 -0.4441 0 -0.895977 -0.473199 0.240362 -0.847531 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.35154e-12 -1 -4.72418e-07 -3.47018e-07 -1 -3.11002e-11 0 1 0 5.20113e-06 1 7.08523e-06 0.268391 -0.945477 0.184498 0.63977 0.765261 0.0712 0.478496 -0.871013 0.111257 0.626856 0.773754 0.0914103 0.983205 0.182403 0.00605256 0.609611 -0.780787 0.136914 0.654419 0.749642 0.0988558 0.619059 -0.775187 0.125902 0.65677 0.748251 0.0936684 0.73424 -0.663695 0.14283 0.863702 0.485349 0.135849 0.882729 -0.464288 0.0722952 0.99156 0.129448 -0.00728314 0.665848 0.739949 0.0955101 0.733788 -0.663275 0.147044 0.861424 0.48963 0.134949 0.733788 -0.663275 0.147044 0.861424 0.48963 0.134949 0.479055 -0.872029 0.10036 0.652456 0.753042 0.0850217 0.861365 -0.431011 0.268849 0.422439 -0.872747 0.244659 0.797269 0.137641 -0.587722 0.91892 0.308758 -0.245467 -0.592769 0.805366 -0.00327476 0.666249 -0.745728 -0.00121991 -0.13396 0.90534 0.403007 0.0210741 0.217909 -0.975742 0.0329936 -0.364342 -0.930681 -0.00345467 0.921516 0.388325 0.00278646 0.127245 -0.991867 -7.29423e-07 -0.990237 -0.139398 0.000635332 0.00699651 0.999975 0.000110913 -0.00840774 0.999965 4.09963e-05 -0.016067 0.999871 -0.00289675 0.0282083 0.999598 0.0030021 0.0223138 0.999747 0.00140096 0.0148496 0.999889 1.69667e-05 -0.00622963 0.999981 -0.0173702 0.0716804 0.997276 0.515099 0.79862 0.311254 5.16314e-05 0.000552358 1 1.50997e-07 -0.000351925 1 -0.0155042 0.142253 0.989709 0.0366091 0.193469 0.980423 0.000119315 0.000630547 1 0.000313075 -0.00672776 0.999977 -0.0002794 0.00533016 0.999986 0 -0.00157046 0.999999 -8.32214e-05 0.00200606 0.999998 -2.52533e-05 0.000481761 1 -7.94217e-05 0.0021248 0.999998 -0.0705192 0.944459 0.320973 0.000797433 -0.0366983 0.999326 -0.00223994 0.0125961 0.999918 0.0104265 0.199534 0.979835 -0.0355683 -0.0338815 0.998793 0.00296486 0.0413004 0.999142 -0.049878 0.676374 0.734868 -0.426417 -0.903293 -0.0472211 -0.476945 -0.863605 0.163429 0.585791 -0.506547 0.632661 0.823492 0.03034 0.566516 -0.834465 0.0212683 0.55065 0.000961076 -0.0187365 0.999824 0.293754 -0.478103 0.827724 0.333856 -0.457094 0.824382 0.000676087 0.0301882 -0.999544 -7.35544e-05 -0.0031765 0.999995 -0.00113057 -0.00958869 0.999953 -0.00470568 -0.0519514 0.998639 -0.0745711 -0.843129 0.532516 0.00388807 0.0542797 0.998518 -0.00394755 -0.019713 0.999798 0.00421139 0.0591976 0.998237 0.000938217 0.0870865 -0.9962 0.000757013 0.00835754 0.999965 -0.000880363 -0.0110323 -0.999939 -9.26571e-05 -0.00450004 0.99999 -3.34819e-11 -0.00033253 1 -0.661895 -0.738734 0.127153 0.00381421 -0.0197393 0.999798 0.00365874 -0.0184809 0.999822 0.000894445 0.0161823 0.999869 -0.00124146 0.000851507 0.999999 0.00307731 -0.00578602 0.999979 -0.000135755 0.014093 0.999901 0.000239702 -0.00485598 0.999988 -6.42683e-06 0.0125057 0.999922 -9.02439e-05 -0.00230177 0.999997 4.77421e-06 -0.000165937 1 -2.96443e-06 0.000155733 1 -7.96463e-07 1.01108e-05 1 0.0666487 -0.846081 0.528871 -0.273615 -0.672553 0.68761 -0.00470751 0.0473475 0.998867 -0.00886875 -0.797565 0.603168 0.000825992 -0.798251 0.602325 -0.0708524 -0.836555 0.543282 -0.0150931 0.75634 -0.654004 0.257262 -0.754417 0.60388 0.000229056 -0.798791 0.601609 -0.021033 0.898071 -0.439347 7.08175e-05 -0.799191 0.601077 -2.16367e-06 -0.799752 0.60033 5.09405e-05 -0.79847 0.602035 -0.00773677 -0.811679 0.584053 0.00362376 -0.794592 0.607133 0.0200112 -0.813565 0.58113 0.000446842 -0.79977 0.600307 0.0001831 0.797151 -0.60378 -0.0101764 -0.807013 0.590446 0.0282699 -0.773507 0.633157 0.326552 -0.842391 0.42865 -0.12772 -0.417861 0.899489 -0.207341 -0.349834 0.913579 4.67898e-06 -0.799073 0.601235 0.997317 -0.0683632 -0.0261804 -0.898883 -0.380019 0.218165 -0.158058 -0.788564 0.594293 1 0 1.70997e-06 0.998304 0.00869055 0.0575559 0.100451 0.794595 0.598772 1 -1.87206e-05 5.36538e-05 1 -2.25693e-05 -1.70072e-05 1 4.6792e-06 0.000126387 0.00249762 -0.87108 0.491134 0.99093 -0.13237 0.0231373 0.998973 -0.0424832 -0.0157683 0.999883 -0.000823818 0.0152934 0.962403 -0.255279 0.0928094 1 0 0 1 0 0.000427759 1 1.88047e-05 0.000295279 -1 -3.78158e-06 -0.000191653 0.999999 6.99853e-05 0.00131996 1 3.39913e-06 0.000106468 -0.789332 0.558746 0.254477 -0.997315 0.0683625 -0.0262664 -0.999999 0.00010045 0.00134398 -1 4.67575e-05 -0.000107408 -0.364376 -0.828648 0.424938 -1 2.90689e-05 7.70481e-06 -1 0 0.000178736 -1 -5.11075e-06 0.000352237 -0.999999 0.00165253 -4.74128e-05 -1 3.72368e-05 0.000204091 -1 0 0 -1 0 0 -1 0 0 -1 -6.37541e-06 0.000172203 -1 2.65662e-05 5.36543e-05 -2.8987e-05 0.124599 0.992207 -0.974904 -0.222533 0.0063847 -0.99991 0.000708128 0.0133996 -0.962354 0.255408 0.0929613 -1 1.50561e-05 0.000634535 -1 -8.33526e-05 -2.30625e-05 -0.999999 -0.00126793 -0.000350819 -0.996918 -0.0737199 0.0268318 0 -0.000571364 1 8.53836e-07 -0.000873336 1 0 1 0 0 1 0 0.5837 -0.77987 -0.226045 0.113511 0.992139 0.0526826 -0.404009 0.908792 -0.104272 0 0 1 -0.0963281 -0.995122 0.0213087 -0.140652 0.900558 0.411354 0.00261292 0.0401168 0.999192 0 0 1 0.00016913 -0.000694608 -1 0.0432411 -0.276079 0.960162 -3.71218e-06 5.02118e-05 1 0 0 -1 0 0 -1 0 0 1 3.25601e-06 -3.52065e-05 -1 -4.77731e-08 1.90625e-06 1 2.4072e-06 -3.93997e-05 -1 4.77731e-08 -1.90625e-06 -1 -2.4072e-06 3.93997e-05 1 -3.37278e-07 1.0489e-05 1 0 0 -1 -2.47192e-07 1.25794e-05 -1 2.0233e-07 -8.07339e-06 1 2.25882e-07 -1.59297e-06 -1 -2.75515e-07 1.09891e-05 1 0 0 -1 6.85874e-07 -2.73819e-05 -1 -6.85561e-07 2.73553e-05 1 3.45834e-07 -1.77641e-05 -1 7.26539e-08 -4.84292e-06 -1 1.14286e-07 -5.81447e-06 1 -2.54525e-07 1.01561e-05 -1 -5.51562e-08 2.68455e-06 1 0 0 1 0 0 -1 -1.06289e-06 -2.42561e-05 1 0 2.90863e-06 1 9.41273e-07 2.02967e-08 1 -5.62003e-07 -1.49438e-05 1 4.66548e-08 -1.86162e-06 1 -1.47116e-06 1.83566e-05 -1 -1.02112e-05 -2.20183e-07 -1 -3.65209e-05 0.000320225 1 0.421897 0.902081 -0.0908449 -0.000123098 -0.000686376 1 -7.70601e-05 -0.000409215 1 2.36059e-06 -1 0.00025732 0 -1 0 0 -0.00099988 1 0 1 0 0 1 0 0.611005 -0.777666 -0.148013 -0.425403 0.89515 -0.133187 8.89457e-06 1.91794e-07 -1 -2.675e-05 0.000130528 -1 -0.0771079 -0.993561 0.0830068 -0.159868 0.848495 0.504478 4.90301e-05 -0.000127619 1 -7.23256e-05 -0.0013427 0.999999 0 0 1 0 0 1 -2.68382e-06 8.02824e-05 1 3.52743e-06 7.60622e-08 1 0 0 -1 0 0 1 0 0 -1 0 0 1 -4.32119e-08 -6.40335e-06 1 -3.98197e-07 -2.00354e-05 -1 9.86115e-07 3.9348e-05 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 -1.24469e-06 -3.98133e-05 -1 0 0 -1 0 0 1 1.06243e-06 2.56579e-05 1 0 0 -1 4.30882e-07 -9.29166e-09 -1 -4.30882e-07 9.29114e-09 1 1.17064e-07 -2.52426e-09 1 -1.17064e-07 2.52426e-09 -1 -9.07607e-05 0.000391345 1 3.33099e-05 -7.18263e-07 -1 0.388344 0.916227 -0.0985748 -0.000240499 -0.00109226 0.999999 3.74453e-05 -0.00026698 1 0 -1 0 0 -1 0 -8.53816e-07 0.000873336 1 0 0.000571369 1 1 -1.12057e-05 0.000158198 1 0 0 -1 8.05438e-06 0.00016052 -1 0 4.20739e-05 -0.681863 -0.681861 -0.264816 0 0 -1 0 0 -1 0.600168 -0.600166 -0.528772 -0.000131829 -4.25255e-06 -1 0 0 -1 0 0 -1 -3.94113e-05 1.27133e-06 -1 0.99999 0.000486644 -0.00446017 0.999998 7.48232e-05 -0.00222587 -0.99999 -0.000486644 -0.00446017 -0.999999 0.000111785 -0.00121344 0 0 -1 0 0 -1 -0.0322293 0.00165127 -0.999479 -0.0146779 0 -0.999892 0.0322293 -0.00165127 -0.999479 0.0146779 0 -0.999892 0 0 1 0 0 1 -0.00279498 0.000321766 0.999996 0.0018885 -0.000202296 0.999998 -0.0020019 -0.000214443 0.999998 0 0 1 0 0 1 0.00222509 0.000256218 0.999997 -0.000349182 0.00207922 0.999998 0 0 1 0 0 1 0.192626 0.192624 0.96218 8.10167e-05 0.795675 0.605724 -0.00103403 0.797015 0.603959 0.000254462 0.801176 0.598429 -0.00151536 0.799835 0.600218 -0.00850726 0.803015 0.595898 -0.000669546 0.799461 0.600717 0.000435394 0.793707 0.6083 0.00245133 0.786937 0.617029 0.000349187 -0.00208244 0.999998 0 0 1 0 0 1 -0.192626 -0.192624 0.96218 0.44643 -0.428689 0.785447 0.352681 -0.480542 0.802929 -0.927731 -0.231311 0.292936 -0.279142 -0.328513 0.902308 -0.856802 0.0189882 0.515296 0.979245 0.0990669 0.176818 -0.968994 -0.124565 0.213386 0.851566 -0.375207 0.366134 -0.0110573 -0.964098 -0.265315 -0.516689 -0.678277 0.522468 0.634538 -0.683076 0.361621 -0.0689271 -0.96183 0.264823 -0.168571 -0.971764 0.165099 0.422332 0.510074 0.749307 0.466562 0.472884 0.747463 -0.308918 0.199545 0.92992 0.97829 0.118542 0.169987 -0.934976 -0.289665 0.204728 0 0 -1 0 0 -1 0 0 -1 0.00034868 -0.00034868 1 -1.8479e-07 1.57432e-05 -1 0 3.72476e-06 -1 0 0 -1 -1.56723e-06 -1.45758e-07 1 0 0 -1 0 0 -1 0 0 -1 -1.22073e-06 -5.75058e-07 -1 4.64706e-06 -5.7607e-07 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.00025779 -0.000252433 -1 0 0 1 -7.14669e-07 5.52914e-06 -1 -1.6693e-05 -0.000224006 -1 0 0 1 0 0 -1 0 0 -1 2.37235e-05 -0.000244232 -1 0.00652481 -0.0355653 -0.999346 -0.00238478 -0.00261383 -0.999994 -0.00122106 0.00224009 -0.999997 -3.63727e-06 2.88383e-05 -1 -1.26648e-05 -7.71473e-05 -1 0 0 -1 0.000603027 0.00094707 -0.999999 1.30242e-06 1.72802e-05 -1 -2.65846e-07 -1.79923e-05 -1 6.46562e-06 8.57841e-05 -1 -1.13036e-05 5.9314e-05 -1 1.00548e-05 -0.000176145 -1 -2.15032e-05 0.000248 -1 6.59237e-05 0.00013218 -1 0 0 -1 0 0 1 0 0 -1 1.04402e-05 4.54936e-05 -1 3.36821e-05 -0.000205171 -1 -0.00021017 0.000309765 -1 0.0352021 0.0606621 -0.997537 -0.00602454 0.0514348 -0.998658 0 0 -1 0 0 1 -4.01421e-05 -6.0776e-05 -1 0 0 -1 1.27444e-05 -5.83706e-05 -1 3.962e-05 0.000236895 -1 -0.000145111 -0.00269211 -0.999996 -2.4961e-07 -1.56054e-05 -1 0 0 -1 3.12495e-06 -0.000244299 -1 0.000150688 0.00114413 -0.999999 0.959066 -0.281609 0.0298067 -0.000669507 4.76806e-05 -1 -1.55673e-06 2.11765e-05 -1 -0.0232245 -0.174149 -0.984446 -0.286533 0.434606 -0.853824 0 0 -1 -1.7767e-05 0.000359417 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.000109773 -1.82266e-05 -1 0 0 -1 4.09125e-07 5.83619e-08 -1 0 0 -1 -0.00122663 0.000201897 0.999999 0 0 -1 0.00102731 8.91325e-07 -0.999999 0 0 -1 -0.000688516 0.00136178 -0.999999 0 0 -1 0.000938713 -0.000180314 -1 -0.000811794 -6.07408e-08 -1 -6.36544e-05 7.44985e-05 -1 0.000929813 -3.13767e-05 -1 0 0 -1 1.07935e-06 -2.69449e-08 -1 1.87392e-06 -7.35117e-09 -1 0.000839027 4.39702e-05 -1 -0.000401272 0.79984 0.600214 0.000149227 0.799462 0.600717 0.000443782 0.799194 0.601073 -0.00561678 0.816048 0.577956 -0.0196792 0.799114 0.600858 9.82155e-05 0.79853 0.601955 -4.82738e-05 0.798321 0.602233 -3.15779e-06 0.795875 0.605461 -0.0186599 0.839061 0.543717 -3.78508e-06 0.801159 0.598451 0.99999 0.000486644 -0.00446017 0.999999 -0.000111785 -0.00121344 0 1 0 0 1 0 -0.99999 -0.000486644 -0.00446017 -0.999999 0.000111785 -0.00121344 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0.0322293 -0.00165127 -0.999479 0.0146779 0 -0.999892 -0.0322293 0.00165127 -0.999479 -0.0146779 0 -0.999892 0.32999 -0.943985 0 0.468115 -0.881231 -0.0655811 0.924401 -0.370903 0.0889651 -0.462357 -0.886355 0.0245012 -0.424648 -0.905359 0 -0.424361 0.905493 0 -0.472809 0.880456 -0.035335 0.462357 0.886355 0.0245012 0.424648 0.905359 0 -0.998552 -6.98841e-05 0.0538013 -0.598396 -0.508533 0.619125 0.0443579 -0.0657082 0.996852 0.0129525 -0.0623534 0.99797 -0.816574 -0.35257 0.457058 0.176198 0.4559 0.872416 0.0795604 0.978923 -0.188096 0.25044 0.954493 0.161933 -0.175073 0.289344 0.941079 0.443667 0.884878 0.141954 -0.447287 -0.394345 0.802762 0.318975 0.910465 -0.263265 0.679819 -0.346561 0.646329 0.794006 0.147682 0.589698 0.389672 -0.536731 0.748382 0.130644 -0.454306 0.881214 -0.91892 -0.308758 0.245467 0.671638 0.452509 0.586633 -0.155549 -0.100885 0.982663 -0.797269 -0.137641 0.587722 -0.102153 0.150624 0.983299 -0.422439 0.872747 -0.244659 -0.861365 0.431011 -0.268849 -0.887874 -0.221322 0.403356 -0.325738 0.944991 -0.0297731 -0.825663 0.413539 0.383753 0.450995 0.62194 0.640152 -0.817341 0.400021 0.414654 0.646822 0.465946 0.603751 0.677292 -0.453259 0.57951 -0.494192 -0.635174 0.593573 -0.834823 -0.395213 0.383245 -0.591738 -0.80386 0.0604598 0 -1 0 -1.00689e-07 -1 -5.96157e-06 8.83341e-06 -1 -0.000261142 -1.9124e-05 -0.999999 0.00135787 -1.90994e-05 -1 -3.22358e-05 0 1 0 1.00688e-07 1 -5.96151e-06 0 1 0 0 1 0 0 1 3.1458e-05 8.73522e-06 1 0 0.50474 -0.807566 0.305082 -0.486783 -0.705993 0.514409 0.59354 0.799006 0.0964355 -0.501334 -0.710425 0.493923 0.655477 0.585697 0.476771 0.0338016 0.704637 0.708763 0.744577 0.550572 0.377461 -0.0713351 0.945522 0.317647 0.723154 -0.503856 0.472417 -0.0504553 0.667993 0.742455 -0.195961 0.98053 0.0126242 0.80041 -0.525176 -0.289021 0.995219 0.097667 0 0.999189 0.0355831 -0.0188348 0.998238 0.0474579 -0.0356071 -0.875408 0.292218 -0.385058 -0.999761 0.0218445 0 -0.267414 -0.96223 -0.0510235 -0.93807 -0.346446 0 0.504705 0.594601 0.625878 -0.26399 0.963168 -0.0511536 -0.809993 0.586195 -0.0169621 -0.981763 0.190077 0.00360366 -0.995219 -0.097667 0 -0.999161 -0.0365038 -0.0185564 -0.832495 -0.364806 -0.416976 0.92299 -0.235926 -0.30402 0.999758 -0.0219977 0 0.28137 0.95827 -0.0504849 0.93807 0.346446 0 -0.63149 0.771732 -0.075171 -0.549318 0.835613 0 0.630507 0.773639 -0.0628038 -0.895846 -0.33408 -0.293003 -0.33044 0.895978 0.296702 0.525016 -0.850714 -0.025359 -0.0462969 0.847399 0.528934 -0.25278 -0.481522 0.839189 -0.00258278 0.990265 -0.139173 -0.980503 3.69288e-06 -0.196507 -0.981182 0 -0.193083 0.907389 0.185533 0.377124 -0.958006 -0.216063 -0.188523 0.680311 0.732017 0.0364281 -0.00877308 0.0927593 0.99565 0.669807 -0.742535 -0.000440192 0.00260328 -0.999952 0.00939505 -0.937238 0.166689 0.306267 -0.678132 -0.734282 0.0310807 0.795918 0.584793 -0.156626 0.981182 0 -0.193083 0.981182 0 -0.193083 0.762854 -0.628903 -0.150119 0 0.939693 0.342019 2.14415e-08 0.939692 0.342021 5.34425e-07 -0.939694 0.342016 -2.22882e-06 -0.939693 0.34202 0 -0.939693 0.34202 -4.28407e-07 0.939692 0.342021 3.50243e-06 0.939692 0.342021 0 -1 8.76539e-06 -5.15529e-07 -1 2.68695e-05 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0.52117 -0.796526 -0.306477 0.794066 -0.523971 -0.308082 0.424649 0.905358 0 0.462357 0.886355 0.0245005 0.564928 -0.711215 -0.418366 -0.760968 0.469654 -0.447608 -0.47281 0.880455 -0.0353349 -0.424362 0.905492 0 -0.462356 -0.886356 0.0245005 -0.424648 -0.905359 0 -0.958206 0.273114 -0.0851455 -0.410409 0.911844 0.0102323 -0.424744 0.905313 0 0.424362 -0.905492 0 0.47281 -0.880456 -0.0353349 0.371009 0.928629 0 0.696205 0.696205 0.17492 0.957726 0.287681 0 -0.985859 -0.153345 0.0675754 -0.822045 0.560706 0.0992541 -0.515145 -0.850024 0.109931 -0.83435 0.542997 0.0949496 -0.413446 -0.902066 0.123848 -0.889466 0.439792 0.124232 -0.0149502 -0.999207 0.036893 -0.99156 -0.129448 0.00728314 -0.191774 0.976182 0.101443 -0.853487 -0.51019 0.106142 -0.746567 0.657679 0.100478 -0.392871 -0.91121 0.123886 -0.991671 -0.11669 0.0545109 -0.984028 -0.173499 0.0398445 -0.983205 -0.182403 -0.00605256 -0.983399 -0.17106 0.0605423 -0.979513 -0.200726 0.0162092 0.370942 -0.880051 0.2965 0.813694 0.581294 0 -0.171956 0.651747 0.738686 -0.000206717 -0.935133 0.354297 4.50316e-05 -0.673225 0.739438 0 0.133507 0.991048 0.00537927 -0.767734 0.640746 -4.50163e-05 0.673225 0.739438 0.000206739 0.935133 0.354297 0.707107 0 -0.707107 0.698801 0.000137631 -0.715316 0.553913 -0.621579 -0.553913 0.621958 -0.553703 -0.553699 0.103966 0.703278 -0.703272 0 -0.707109 -0.707104 0 -0.707109 -0.707104 0 0.707109 -0.707104 0 0.707109 -0.707104 -0.864287 -0.355676 -0.355673 -0.350057 -0.868862 -0.350057 -0.137989 0.700345 -0.70034 -0.70542 0 -0.70879 -0.707107 2.74082e-05 -0.707107 0.256083 -0.683533 -0.683523 0.195467 0.693467 -0.693467 0 -0.707112 -0.707102 0 -0.707112 -0.707102 0 0.707107 -0.707107 0 0.707107 -0.707107 -0.195469 -0.693472 -0.693461 -0.256081 0.683529 -0.683529 0.256081 -0.683529 -0.683529 0.195469 0.693472 -0.693461 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 0.707112 -0.707102 0 0.707112 -0.707102 -0.195466 -0.693467 -0.693467 -0.256083 0.683533 -0.683523 -0.457707 0.888418 0.0348911 -0.500512 -0.851243 0.157712 -0.708172 0.00589516 0.706016 0.00084833 -0.377249 0.926112 -1.00298e-06 -0.707436 0.706777 -0.694371 -0.00651947 0.719588 0.582932 -0.805691 0.10513 0.486181 0.869063 -0.0914216 -0.707924 -0.0045015 0.706275 -0.00084833 0.377249 0.926112 1.00298e-06 0.707436 0.706777 0.69436 0.00652501 0.719598 0.484272 0.874881 -0.00802906 0.379669 0.905508 0.189489 0.426417 0.903293 0.0472211 0.111147 0.949575 0.293177 -0.448743 -0.0168589 0.893502 -0.00422378 0.0339925 0.999413 -0.0180361 -0.000740349 0.999837 0.00155513 0.999999 -0.00057816 -0.111762 0.951531 0.286529 0.000578347 -4.71634e-05 1 0.0138512 0.0223838 0.999654 0.025178 0.999213 -0.0306382 0.0127693 0.999892 0.00725443 0.790541 0.611982 -0.0228892 -0.776048 0.621841 -0.105179 0.392238 0.223321 0.892344 -0.00109724 -0.900909 0.434007 0.0245278 0.91757 0.396818 0.480225 -0.195082 0.855176 -0.662069 -0.155458 0.733142 -0.0883937 0.922781 0.375048 0.686296 0.113791 0.718366 -0.648802 -0.108852 0.753132 0.348414 -0.934609 0.0715142 -0.492563 -0.135826 0.859612 0.20535 0.0495513 0.977433 -0.795192 -0.00769386 0.606309 0.0311243 0.0531989 0.998099 -2.51527e-06 -2.43365e-08 1 0.00251619 -0.999951 0.00958089 -0.00155631 -0.999998 -0.000938501 -0.998428 -0.00227582 -0.0559998 0.0385978 0.068941 0.996874 1.05072e-05 0.00301159 0.999996 0.00233378 -0.999976 0.00656208 -0.00104145 -0.999995 -0.00292831 0.985869 -0.0503205 -0.159783 0.476558 -0.862247 -0.17153 -0.698563 -0.713528 -0.0537435 0.000446118 -0.789367 0.613921 -0.417912 0.171419 0.892169 0.0368189 -0.703569 0.709673 0.00439144 -0.79171 0.610881 -0.00408563 -0.773736 0.633495 -0.017455 -0.723526 0.690077 -0.0274926 -0.696396 0.717131 -1.73925e-05 -0.793519 0.608545 -0.0263221 -0.728256 0.6848 0.0264516 -0.679819 0.732903 0.00195338 -0.127983 0.991774 0.130828 0.0144881 0.991299 0.461112 -0.53704 0.706374 -0.000506636 0.795649 0.605758 -0.421177 -0.108352 0.900483 -0.00284639 0.0268879 0.999634 -0.0791213 0.751179 0.65534 0.0993508 0.221856 0.970005 0.420005 0 -0.907522 0.00191 -0.880444 0.474146 -0.159222 -0.318443 -0.934475 0.14395 0.261224 -0.954484 -0.0509922 0.551916 -0.832339 -0.00249526 -0.911824 0.410573 -0.213672 -0.356119 -0.909683 -0.129164 0.189647 -0.973319 -0.703642 0.70364 -0.0988903 -0.316559 -0.470398 -0.823721 -0.554333 -0.534098 -0.638322 -0.556744 -0.563062 -0.610735 -0.773726 0.228532 0.590865 -0.847338 0.458313 0.268267 -0.221562 0.515715 -0.827616 -0.476257 -0.749747 -0.459411 -0.804611 -0.491847 0.332697 -0.481857 0.805884 -0.344043 -0.476643 -0.327677 -0.815745 -0.714882 0.608496 -0.344495 0.71848 -0.0397527 0.694411 0.00798113 -0.0209835 0.999748 -0.0703001 0.993305 -0.0916698 -0.696957 0.714671 -0.0591345 -0.623523 0.462318 0.630461 -0.692158 -0.301852 0.655594 -0.598607 -0.746467 -0.290616 -0.216508 -0.918035 0.332168 -0.0644087 -0.912772 0.403359 -0.392747 -0.897101 -0.202382 -0.714019 -0.689155 0.123456 -0.930507 -0.222548 -0.290909 -0.705957 0.557949 0.436254 -0.841349 0.528538 0.113046 -0.279147 0.957427 -0.0735541 0.00809601 0.873961 0.485928 -0.330948 0.810522 -0.483247 -0.0979616 0.830232 0.548743 -0.697589 0.22421 0.680514 -0.34855 0.384191 -0.854933 -0.946454 -0.243394 0.212096 -0.667031 -0.744901 0.0138588 -0.199876 -0.971247 -0.129343 -0.200971 -0.969953 -0.13712 0.3249 -0.917202 -0.230609 0.23172 -0.94733 0.221071 0.996935 -0.0260749 0.0737615 0.803108 -0.242808 0.544116 0.599414 -0.426848 -0.677129 0.653091 -0.753832 0.0721776 0.644401 0.420421 -0.638743 0.854469 0.207638 0.476202 0.637706 0.721561 0.269594 0.193283 0.935105 -0.297019 0.0505222 0.890725 0.451727 0.001416 0.00435165 -0.99999 0.00107835 -0.0522559 -0.998633 -0.0136845 -0.0056698 -0.99989 0.00480489 0.00136652 -0.999988 -0.00227938 -0.00905159 -0.999956 -0.0120133 -0.0147444 -0.999819 0.0265724 -0.0134989 -0.999556 0.000514358 -0.00997163 -0.99995 -0.0216326 -0.0129151 -0.999683 -0.012366 0.00568793 -0.999907 -0.0118323 -0.0147954 -0.999821 0.00692893 0.00571567 -0.99996 0.0103448 0.00297136 -0.999942 0.0162318 -0.0097326 -0.999821 -0.00346792 -0.000666726 -0.999994 0.00142085 -0.00204306 -0.999997 0.869108 0.442202 0.221607 -0.213459 0.296871 0.930754 -0.698281 -0.576169 0.424774 0.970339 -0.240394 -0.0255572 0.756872 0.588524 -0.284226 0.452201 0.88997 0.0588891 0.0935564 0.504875 0.858108 -0.0291305 0.00826729 0.999541 -0.0020625 -0.00258377 0.999995 0.00188767 0.00602119 0.99998 0.0576936 -0.029737 0.997891 -0.303351 0.469922 0.828946 -0.00198917 -0.064651 0.997906 -0.753131 -0.0830406 -0.652608 -0.00296749 -0.000187211 0.999996 0.0157154 0.0179476 0.999716 0.0044063 0.02397 0.999703 0.00254805 -0.0147828 0.999888 -0.00529059 0.030271 0.999528 0.281318 -0.365138 0.887431 -0.331284 -0.456564 0.825712 0.00676509 -0.00224598 0.999975 0.0214019 0.00431022 0.999762 0.0125075 -0.00308074 0.999917 0.00861133 -0.00294261 0.999959 0.0053286 -0.00957175 0.99994 -0.0108655 -0.00128864 0.99994 0.00360638 0.000354222 0.999993 -0.0139398 0.000778971 0.999903 0.22573 -0.789504 0.570728 0.536463 -0.756834 0.373376 0.526031 -0.430161 0.733657 0.0681316 -0.971056 0.228928 0.587252 -0.663055 0.464213 0.801807 -0.596897 0.0286448 0.796712 -0.190558 0.57353 0.824549 0.362361 0.434527 0.227989 0.965563 0.125333 -0.454355 -0.0151523 -0.890692 0.870739 0.0345428 -0.49053 0.804611 0.491847 -0.332697 0.476257 0.749747 0.459411 0.847338 -0.458313 -0.268267 0.773726 -0.228532 -0.590865 0.574596 0.551615 0.604616 0.541976 0.548274 0.636913 0.410404 -0.464618 -0.784664 0.833148 -0.0102545 -0.552955 0.236273 0.405836 -0.882877 -0.32698 -0.470185 -0.819762 -0.685853 -0.644901 -0.337206 -0.572663 -0.148254 -0.806274 -0.79168 0.295639 0.53464 -0.831995 0.484858 0.269623 -0.240092 0.511851 -0.824842 -0.698901 -0.597434 0.393204 -0.514662 0.235248 -0.824489 -0.476642 -0.327676 -0.815746 -0.714882 0.608496 -0.344495 -0.758313 0.574329 0.308396 0.0164687 0.0108567 0.999805 0.0172321 0.466698 0.884249 -0.321437 -0.63462 0.702805 -0.469534 0.809382 -0.352758 -0.612176 0.707082 -0.353943 -0.675113 0.550899 0.490646 -0.879369 0.0381731 0.474608 -0.7044 -0.345087 0.62027 -0.587929 -0.720236 0.368238 -0.0829621 -0.888778 0.450767 -0.732564 -0.506338 -0.454941 -0.855028 -0.29985 0.423104 -0.857946 0.494966 -0.137611 -0.295348 0.930296 0.217528 -0.330947 0.81052 -0.48325 -0.0463396 0.741964 0.668837 -0.69759 0.22421 0.680513 -0.348552 0.384192 -0.854932 -0.946455 -0.243394 0.212092 -0.667031 -0.744901 0.0138575 -0.199876 -0.971247 -0.129342 -0.200971 -0.969953 -0.137121 0.323919 -0.919306 -0.223501 0.23172 -0.947329 0.221072 0.996935 -0.0260752 0.0737642 0.803107 -0.242808 0.544116 0.543337 -0.413419 -0.730664 0.651395 -0.751264 -0.106241 0.644403 0.420422 -0.638741 0.854469 0.207637 0.476204 0.637707 0.72156 0.269595 0.193283 0.935106 -0.297016 -0.00463188 0.760972 0.648768 0.00493243 0.00794391 -0.999956 0.00734194 -0.132654 -0.991135 -0.0298295 -0.013151 -0.999469 -0.00227909 -0.00905229 -0.999956 -0.0139194 -0.0160331 -0.999775 0.103907 -0.0428172 -0.993665 0.000792348 0.00168966 -0.999998 -0.008195 -0.00888132 -0.999927 -0.00826095 0.00266432 -0.999962 -0.00163969 -0.0204446 -0.99979 0.000562595 0.000647247 -1 0.0057949 0.00683495 -0.99996 0.0131896 -0.00714852 -0.999887 -0.0109526 0.00403917 -0.999932 0.0154837 -0.00451952 -0.99987 0.00196017 -0.00786244 -0.999967 0.266412 0.899541 -0.346195 0.779544 0.394646 0.48638 0.998134 -0.0538827 -0.0287268 0.946851 -0.220354 0.234342 0.872888 -0.228439 -0.43114 0.636437 0.265167 0.724317 0.73842 0.597375 -0.312857 0.329858 0.817952 0.471326 0.355273 0.791883 0.496691 -0.0291305 0.00826728 0.999541 -0.00206294 -0.00258378 0.999995 -0.00114017 -0.000573616 0.999999 0.253443 -0.138719 0.957352 -0.00157871 -0.308393 0.951258 -0.974235 -0.10733 -0.198361 -0.00296862 -0.000187337 0.999996 0.0115863 0.013337 0.999844 0.00320351 0.0181675 0.99983 0.00122883 -0.0112951 0.999935 -0.00529059 0.030271 0.999528 0.341123 -0.448519 0.826115 -0.323912 -0.465292 0.823762 0.0157526 -0.00190195 0.999874 0.000883157 -0.00068678 0.999999 0.00195575 0.000114545 0.999998 0.00993238 -0.000274619 0.999951 0.00532859 -0.00957174 0.99994 -0.0108655 -0.00128864 0.99994 0.00360689 0.000354278 0.999993 -0.0139394 0.000778714 0.999903 0.304384 -0.852422 0.42512 0.542336 -0.764206 0.349085 0.477722 -0.358713 0.801939 -0.0347687 -0.958254 0.283795 0.631706 -0.690075 0.353191 0.780248 -0.625187 0.0188492 0.453387 0.861442 0.228821 -0.333499 0.891614 0.306274 -0.454355 -0.0151501 -0.890692 0.870737 0.0345384 -0.490535 0.802845 0.454426 0.385924 0.698901 0.597434 -0.393204 0.831995 -0.484858 -0.269623 0.79168 -0.295639 -0.53464 0.572663 0.148254 0.806274 0.685853 0.644901 0.337206 0.42212 -0.462602 -0.779624 0.88162 0.411738 0.230689 0.184844 0.410121 -0.893104 -0.678434 0.717645 0.157202 -0.832231 0.553273 0.035772 -0.555926 0.77952 -0.288609 0.508295 0.835323 0.209457 -0.924196 -0.381161 -0.0240429 -0.949757 -0.284735 0.129955 -0.979866 -0.144774 0.137491 -0.916659 -0.369835 -0.151524 -0.979857 -0.14494 0.137378 -0.916587 -0.370016 -0.151513 0.319998 0.947405 0.00495877 -0.248326 -0.966653 0.0625855 0.146919 -0.921341 0.359924 0.233224 -0.9716 -0.0400001 0.725893 0.68748 -0.0212079 -0.770751 0.636963 -0.0148557 -0.856541 0.516007 -0.00858606 0.731934 0.681358 0.0048356 -0.545774 0.651443 -0.527022 0.545774 -0.651443 0.527022 0.517075 0.850945 -0.0923352 0.194171 -0.860022 -0.471868 0.370632 0.873671 -0.315169 -0.0329309 -0.799686 0.599515 0.141196 -0.60922 0.78033 -0.519325 -0.563455 0.642511 -0.361653 0.49058 0.792804 -0.584402 -0.368088 0.723177 0.705634 0.708438 0.0140249 0.0212776 -0.675854 0.736728 0.255774 0.713495 0.652307 0.0342218 0.995833 0.084533 -0.414974 0.80938 0.415572 -0.942398 -0.313648 0.116236 -0.924192 -0.381171 -0.02404 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 0.258822 0.965925 0 0.258822 0.965925 0 0.706557 0.707657 8.92026e-06 0.707106 0.707107 7.69136e-05 0.967622 0.252403 0 0.965926 0.258819 -0.00762894 -0.999834 -0.0165708 -0.00261983 -0.998925 -0.0462832 -7.80462e-09 -1 1.87835e-05 0.000273266 -1 -0.000179908 0.0013129 -0.999999 1.12086e-06 -0.00161965 -0.999999 -2.25821e-06 -0.0187722 -0.999819 -0.00299071 -0.00116473 -0.999999 0.00101923 0 -1 0 0 -1 0 0 -1 0 -2.93753e-08 -1 6.29471e-08 -0.00214503 0.99999 -0.00397728 0.000794516 1 1.06369e-06 0.000337152 1 7.54227e-05 0 1 0 0 1 0 -0.0019512 0.999998 0.000836228 -0.00375509 0.999993 -7.48475e-06 -0.00136131 0.999999 -0.000490436 0.000211758 1 0.000399846 3.31357e-05 1 0.000774552 -6.01341e-08 1 0.000367293 -0.000351571 1 0.000257569 -0.000857566 0.999999 0.000887998 1 0.000507765 0.00058039 1 0.000235913 -0.000362957 -0.999998 -0.00126715 0.0015114 1 0.000277561 -0.000247057 1 8.35373e-06 0.000203319 1 -0.000216511 0.000352489 -1 0.000435142 -2.17508e-05 -1 -0.000963507 0.000115698 -0.999973 -0.00603014 0.00420331 0.999999 0.000839014 0.00116716 0.999998 0.00116843 -0.00177521 1 -7.04354e-05 -0.000271461 1 -9.38702e-05 2.01497e-05 1 2.75143e-05 1.20814e-05 0.999994 0.00338852 0.000724646 0.999997 0.00206038 0.00123125 -0.999987 0.00264243 -0.00433715 1 -7.23939e-05 -5.05885e-05 1 -2.16102e-05 0.00025268 1 1.58176e-05 6.39118e-06 1 -0.000145228 8.41133e-05 1 -3.56819e-05 5.18832e-06 1 -6.12792e-05 -4.86869e-05 -0.194171 0.860022 0.471868 0.906648 -0.109351 0.407471 -0.906648 0.109351 -0.407471 1 8.21266e-05 -0.000255296 1 -0.000235314 -0.000336629 1 0.000208743 -5.56393e-05 0.999997 0.000577385 0.00254493 0.999998 0.0011089 0.00147885 -0.00162233 0.00806798 0.999966 1.05044e-05 -5.22394e-05 1 -0.00299222 0.999841 0.0176029 0.000503227 0.999993 -0.00375416 0.00166814 -0.999953 0.00951205 9.3682e-05 -1 -0.000107091 0.982695 -0.0423426 -0.180329 0.947619 0.26113 0.183926 -0.00164281 0.00816987 0.999965 0.0015315 -0.00761632 0.99997 -0.00204526 0.999926 0.0119764 -5.46692e-05 1 -0.000108104 0.00378721 -0.999738 0.0225952 -0.000121312 -1 -0.000723766 0.941926 0.334925 -0.0244954 -0.997845 -0.0319802 0.0572994 -1.97905e-05 -3.75426e-05 -1 8.33112e-06 8.27788e-05 -1 0.986805 -0.0508509 -0.153717 -0.750346 0.138365 -0.646402 1.29336e-05 -1.70799e-05 -1 -1.23813e-05 8.15927e-05 -1 1.26096e-05 -0.000670298 1 -0.316814 0.944969 -0.0816278 -2.77745e-06 0.000178939 1 7.52663e-06 -0.000484907 1 -7.28632e-06 0.00024265 1 -0.338175 -0.64753 0.682893 0.428178 -0.889578 -0.159102 0.206009 0.674791 0.708673 3.71108e-05 0.00349599 0.999994 6.29181e-05 -0.000289221 1 0.00040324 -0.00101052 0.999999 0 0 1 -2.95397e-06 -0.000164826 1 1.40551e-05 -0.000474437 1 -2.708e-05 0.00062053 1 -0.286886 -0.642574 0.710489 0.461686 -0.875274 -0.144019 0.207825 0.679087 0.704024 0.000170435 -0.000783453 1 -2.82689e-05 -3.16578e-06 1 -5.24819e-06 0.000129422 1 -4.94772e-06 -0.000199957 1 2.06301e-07 -0.000127662 -1 -8.60975e-06 0.000482833 -1 -6.05455e-07 -0.000298134 1 -5.67781e-05 0.000168208 -1 -0.379086 0.917094 -0.123417 -1.56064e-05 -0.000562267 1 0.000179511 0.00225322 -0.999997 -0.00240615 -0.0073633 0.99997 -0.00793411 0.00611892 0.99995 0.0031412 -2.0514e-07 -0.999995 -1.22095e-06 3.75952e-05 -1 -0.00789068 -0.00906977 -0.999928 -1.1583e-06 -9.01121e-06 -1 2.14703e-06 0 -1 1.0658e-07 -4.51188e-05 -1 -0.00330331 0.00451371 -0.999984 1.14367e-06 -5.65371e-05 -1 -5.15442e-07 2.29888e-05 -1 1.03636e-06 3.14084e-06 -1 0.00222508 -0.457736 -0.889085 -0.000710669 -0.713419 -0.700738 4.43984e-05 -0.957994 -0.286788 0 -0.286611 -0.958047 -0.000455679 0.270914 -0.962603 -0.00506626 0.648026 -0.761601 0 0.962153 -0.272509 0.790658 -0.612258 -0.000160943 0.746062 -0.665871 -0.00288055 0.209162 -0.977874 0.00363265 0.605197 0.796056 -0.00563131 1.74895e-05 -6.63805e-05 -1 2.59492e-05 -0.00108756 -0.999999 2.37242e-07 2.67241e-05 -1 -5.3109e-06 -4.66322e-06 -1 -0.000107424 -0.000170495 -1 -4.00559e-05 -0.00100033 -1 -1.20193e-06 -3.00164e-05 -1 1.10098e-07 -6.86507e-05 -1 2.21807e-06 4.32263e-06 -1 8.4555e-06 7.04655e-05 -1 0.0210635 0.0314096 -0.999285 0.00808468 -0.0055049 -0.999952 2.48358e-05 -0.000134575 -1 -8.46336e-08 0 -1 0 9.24538e-07 -1 6.25408e-07 2.04359e-05 -1 -1.00696e-06 -8.92305e-06 -1 -2.54541e-06 0.000917911 -1 -2.51828e-05 0.000354795 -1 5.4301e-07 1.46067e-05 -1 2.77575e-05 -1.78812e-06 -1 0.0062318 -0.0134427 -0.99989 1.90109e-05 0.000141474 -1 -1.164e-06 -8.79326e-06 -1 2.23654e-07 0.000952333 -1 8.49602e-06 -0.000117215 -1 -0.694611 -0.0015859 0.719384 -0.694771 0.000855233 0.71923 -0.69462 0.00083428 0.719376 1 0.000506206 -0.000115869 1 -0.000479907 3.20222e-05 1 -0.000884552 2.43503e-05 0.999289 0.00450642 0.0374264 0.999853 -0.0164082 -0.00496856 1 -6.35773e-05 0.000171993 1 -0.000549235 -4.58075e-05 1 0.000612324 -1.88296e-05 1 -0.00037158 -7.3062e-06 0.999993 -0.00202478 0.00308522 0.999975 0.00706499 0.000625772 0.970806 0.123522 0.205619 0.999999 -0.00108768 -0.000487066 5.63075e-05 -0.00222654 0.999998 -2.68926e-06 -0.000146841 1 -0.465612 0.873025 -0.145025 -0.215443 -0.680629 0.700235 2.46032e-06 -0.000203245 -1 1.33828e-05 0.000939707 1 -0.00016164 0.000246342 1 0.0002189 0.00283478 0.999996 -0.00476253 -0.00263843 0.999985 2.65013e-06 -1.62393e-05 1 -0.000123713 0.000463228 1 -1.52872e-05 -0.000559322 1 -0.222503 -0.681294 0.697374 -0.45718 0.877962 -0.142018 0 0 1 -2.82172e-06 0.000157749 1 0.327297 0.640091 0.695098 0.29603 -0.950725 -0.0921363 -0.00169502 0.0103866 0.999945 -2.56882e-05 -8.28896e-05 1 -8.16521e-05 0.000445387 1 -1.34364e-05 2.36976e-06 1 -1.78204e-06 0.000216695 1 -2.31256e-06 -0.000128355 1 6.81701e-06 0.000202074 -1 -4.4482e-06 0.000160586 1 3.63905e-06 -0.000151116 -1 4.07738e-06 -4.38764e-05 1 -0.000123863 -0.000967761 -1 -0.00272062 -0.00699552 0.999972 -0.00729674 -0.999713 -0.0228246 -0.00764165 -0.988733 0.149495 0.00646841 -0.999893 0.0131275 0.000637291 -1 -4.57722e-05 0.118022 -0.992733 0.0234882 1.60718e-07 -1 -2.99337e-06 0.00110993 -0.999999 3.47433e-05 -0.000105505 -1 -1.01076e-05 -0.000324725 -1 -0.000811855 0 -1 0 -5.04245e-05 0.000751147 -1 -1.38178e-05 -0.000185017 -1 6.50965e-05 8.16317e-05 -1 2.44857e-05 0.000424972 -1 2.36195e-05 0.000443997 -1 -2.4666e-05 2.10025e-05 -1 -0.000290512 0.000247363 1 -6.05218e-05 5.25862e-06 -1 0.073553 0.0507175 -0.996001 -0.00431871 -0.0045625 0.99998 0.000378411 -0.000111207 -1 1.77723e-05 0.000762575 -1 -0.00168816 0.000183405 -0.999999 -0.00133767 0.000271546 -0.999999 0.00281378 -0.000636828 -0.999996 -3.81826e-05 -0.00161187 -0.999999 2.04191e-05 -0.000353932 -1 6.66413e-06 -0.000115512 -1 9.98876e-05 0.00089709 1 0.00299853 -0.00402473 -0.999987 0.103159 -0.068838 -0.99228 3.70124e-05 -0.000199959 1 2.55913e-05 0.000153488 -1 0.000322616 0.000711914 -1 0.000613703 -4.51588e-05 -1 0.000620033 0.00374432 -0.999993 -0.00867984 0.00514932 -0.999949 -2.5847e-05 -5.60274e-05 -1 4.66502e-06 -7.75872e-05 -1 -2.53228e-05 6.56882e-05 -1 9.51267e-05 5.65871e-05 -1 -3.81636e-05 -0.000321448 1 1.43357e-05 7.4401e-06 1 -2.58344e-05 3.46552e-05 -1 2.22545e-06 -2.21816e-05 -1 -0.000172315 1 -0.000430792 -0.0351242 0.998168 -0.0492688 0.000368808 1 8.01619e-05 -3.18862e-05 1 -6.93059e-06 2.41522e-06 1 -4.49835e-05 0 1 0 0.000269722 1 -2.02775e-05 1 -8.43725e-06 -2.6446e-07 0.999973 0.00730907 -0.000270473 1 0.000736826 -6.75309e-06 1 0.000893363 -0.000153981 1 0.00072283 -0.000110693 0.966706 -0.216229 0.136841 1 -1.90406e-06 3.52823e-06 1 -3.94563e-06 0.000155545 1 0.000757193 -3.53887e-05 1 -0.000496192 -5.78794e-06 1 -0.000271953 5.35575e-06 1 -0.000432019 -7.57418e-05 0.999999 0.00106156 0.00013435 -1 -0.000481525 1.4304e-05 -1 -8.73755e-06 0.000249727 -1 -8.23836e-06 0.000408985 -1 -5.91423e-05 -3.54324e-05 -1 -6.91647e-06 -0.000266284 -1 2.90989e-07 0.000147914 -1 8.78419e-05 -0.000161567 -1 0.000108145 -0.000201372 -1 7.68169e-05 6.7933e-06 -1 -0.000277937 6.73827e-05 -0.222746 -0.912868 -0.342135 -0.999999 -0.00101485 0.000561126 -1 0.000428122 -9.26595e-05 1 9.01838e-05 5.82296e-06 -1 -9.42627e-05 -6.90733e-06 -1 0.000162485 1.07906e-05 -1 -5.07986e-05 0.000303604 -0.999999 0.00123965 -7.85857e-05 -1 -0.00045403 -6.07663e-05 -0.999999 0.00126111 0.00108434 -1 0.000215272 7.27654e-05 -1 3.19678e-05 1.7543e-06 -1 6.22003e-07 1.9075e-06 -1 -7.2299e-06 -1.18787e-06 -1 1.22183e-05 3.21265e-05 -1 0.00013337 -2.86452e-06 -1 -1.28995e-05 -2.11939e-06 -0.00435671 0.93142 -0.36392 -1 -0.000122371 6.56171e-07 -1 -6.44166e-05 2.58197e-06 -9.13412e-05 0.0019867 0.999998 -3.22613e-06 -0.000187796 1 9.09766e-06 2.94723e-05 1 -0.000216042 0.000345168 1 0.000208186 0.0133404 0.999911 0.000650315 0.00516462 0.999986 0.000189686 1 -0.000239528 -1.72742e-07 1 1.63028e-07 7.99562e-09 1 2.36124e-07 1.64595e-08 1 1.1641e-07 -0.0715449 -0.995493 0.0622563 -2.49177e-13 -1 1.1641e-07 1.60047e-08 -1 -1.0997e-07 4.85996e-06 -1 1.8485e-06 -1.34751e-05 -4.48863e-05 1 -0.000154552 -0.00169721 0.999999 0.000287823 -0.000363602 1 -3.73936e-06 -0.00675092 0.999977 -2.14052e-06 0.000276811 1 0.000114262 -0.0017701 0.999998 0.00207025 0.935268 -0.353935 -0.0453283 -0.996088 -0.0758611 -0.0342218 -0.995833 -0.084533 -0.255774 -0.713495 -0.652307 -0.0212776 0.675854 -0.736728 -0.60984 0.147652 -0.778649 -0.999999 -0.000992597 -0.000189798 -0.999991 0.0040931 -0.00146532 1 -1.36259e-05 0.000862987 0.999997 -0.0018368 0.00133879 1.24443e-06 0 1 -0.00095062 -0.000308526 1 -0.000129841 0.000701028 1 9.12224e-06 0.00247135 0.999997 -0.000163727 -0.00243838 0.999997 -1.16759e-06 -1.30963e-05 1 0.740082 0.0803137 -0.667704 0.70092 0.00268823 -0.713235 0.694651 4.26263e-06 -0.719347 0.694651 6.66373e-06 -0.719347 0.694654 1.65882e-05 -0.719344 0.694656 1.05216e-05 -0.719342 0.694655 -1.01371e-06 -0.719343 0.694666 -0.000118843 -0.719333 0.694656 -1.47099e-05 -0.719342 0.732855 -0.0688935 -0.676888 0.694684 0.000141791 -0.719316 -0.694844 -7.69074e-06 0.71916 -0.694672 0.00190249 0.719324 -0.694673 -0.0019027 0.719324 -0.694504 -2.80039e-06 0.719489 -0.900582 0.434239 -0.0197224 -1 -0.000635713 -0.000316203 -0.138226 -0.892877 -0.428561 -0.900418 0.434644 -0.0182141 -0.999963 -0.00833655 -0.00188614 -0.909473 -0.415286 -0.0199109 -0.999309 -0.0371341 0.001516 -0.999988 -0.00481679 -0.00112121 -0.999747 -0.0218898 0.00523714 -0.564201 -0.579378 0.588216 -0.444963 -0.770566 0.45633 -0.188826 -0.961751 0.198442 -0.00074459 -0.567514 0.823363 0.000946185 -0.638168 0.769896 -0.000573263 -0.963184 0.268842 0 -0.973753 0.227606 -0.634779 -0.77267 0.00607046 -0.979628 0.198477 -0.030587 -0.803342 0.0356663 0.594449 -0.696226 0.0325185 0.717086 -0.584651 0.537014 0.608112 -0.266762 0.922239 0.279844 -0.431491 0.785457 0.443704 -0.988949 0.14751 -0.0148349 -0.692142 0.721694 0.0098537 -0.000151665 0.871483 0.490426 0.000221354 0.858326 0.513105 -0.000302999 0.533308 0.845921 -0.00010336 0.521987 0.852954 0.419288 0 0.907853 0.467485 -0.0476499 0.882716 -0.418221 0 -0.908346 -0.468278 -0.0492425 -0.882208 0.117022 0.0820263 -0.989736 -0.141196 0.60922 -0.78033 0.162796 0.610071 -0.775442 -0.276396 -0.211531 -0.937475 -0.157175 0.797193 0.582906 0.157175 -0.797193 -0.582906 0.753615 -0.620244 -0.217626 0.978992 0.109649 0.171905 -0.0122402 0.948625 -0.316166 -0.519427 -0.853727 0.0366895 -0.517075 -0.850945 0.0923352 -0.731934 -0.681358 -0.0048356 0.856541 -0.516007 0.00858605 0.770751 -0.636963 0.0148557 -0.725893 -0.68748 0.0212078 0.00193225 0.999998 0.000213128 0.00872617 0.999961 0.00117591 -0.0385245 -0.00532529 0.999243 -0.041736 0.000161727 0.999129 -0.03885 0.00145781 0.999244 0.0343378 0.0184649 0.99924 -0.00468016 -0.999989 6.04171e-05 0.00156336 -0.999998 0.000909346 -0.0367039 -0.999199 0.0159485 -0.399352 0.87406 0.276652 0.282219 0.934688 -0.216125 -0.693152 -0.696231 0.186554 -0.827457 -0.39706 0.397061 -1 0 0 -1 0 0 -1 0 0 -0.7835 -0.16083 0.600218 -0.870566 -0.329174 0.365732 -1 0 0 -1 0 0 -1 0 0 0.000671371 -0.000192677 1 -0.000159191 -0.000328988 -1 0.00965863 -0.0193172 0.999767 0 0 1 0 0 1 -5.5641e-05 0.000103237 1 1.54644e-07 3.1959e-07 1 -5.1331e-07 0 1 1.85997e-07 1.96196e-06 1 0 0 1 0 0 1 -8.98449e-10 -7.48856e-07 1 0 -7.3822e-07 1 9.03839e-10 7.53349e-07 1 0.0526078 -0.973998 -0.220363 0 -1 0 0 -1 0 -0.000417207 -0.999988 -0.00486676 0 1 0 0.000175255 1 0.000766521 -0.0551782 0.992256 -0.111282 0 1 0 0 1 0 -0.15534 0.953474 -0.258374 0.000548382 -0.965291 0.261178 0.248326 0.966653 -0.0625855 -0.319998 -0.947405 -0.00495877 -0.991856 -0.127362 -0.000273672 0.991856 0.127362 0.000273672 -0.000755445 0.999995 -0.00316812 -0.000299421 0.999981 -0.00622615 0.00165068 -0.999927 -0.0120148 -0.000382917 -0.999999 0.00153563 1.02739e-05 3.61993e-05 -1 3.24579e-06 6.03049e-06 -1 0.000876067 0.999988 -0.00478667 0.000449268 0.999998 -0.00214143 -0.000120662 -0.999991 -0.00418768 0.000685804 -0.999999 0.00144107 -4.32944e-06 7.08182e-06 -1 -2.07214e-06 1.60798e-05 -1 0.000279895 0.999997 -0.00235789 -0.00061392 0.999992 0.00390329 -0.00116744 -0.999963 -0.00856512 0.000862786 -0.999989 0.0046309 -0.000682738 0.999998 -0.00179847 -0.0001846 0.999985 -0.00540423 0.00207141 -0.999859 -0.016653 -0.000668343 -0.999994 0.00340997 -0.969229 -0.167176 -0.180686 0.969111 0.19111 -0.155885 0.966735 0.195842 -0.164528 0.963781 -0.129379 -0.233209 -0.970976 -0.0899956 -0.2216 -0.822153 -0.554214 0.130046 0.923235 0.15452 -0.351795 0.933348 -0.214636 0.287736 0.960471 0.165664 0.223722 -0.745603 0.495766 -0.4453 -0.922911 -0.164626 -0.348042 0.854693 0.134268 -0.50147 0.44712 0.876361 0.179096 0.598602 -0.749949 0.281517 -0.995106 -0.0942451 0.0296935 -0.985468 -0.152846 -0.0740942 0.969163 -0.194005 0.151939 0.968378 0.11765 -0.220006 4.61162e-05 -0.999999 -0.00116229 0.00027569 -1 0.000297988 -0.000258648 1 -3.56784e-05 -0.000677361 0.999996 0.00279695 2.4729e-09 -5.36231e-05 1 3.40523e-05 -0.000237178 1 0.974734 -0.127542 -0.183378 0.9794 0.144706 0.140841 0.000748262 -0.999992 0.0039793 0.000154193 -1 0.000278078 -0.000748432 1 -0.000105645 -0.000253948 0.999994 -0.00335354 4.05352e-05 -0.000211135 1 -4.05352e-05 0.000211135 1 0.924151 0.38127 -0.0240362 0.00299871 -0.99984 0.0176124 -3.81779e-05 -1 -0.000942144 -0.00254202 0.999882 0.0151662 1.84376e-05 1 -0.000110002 -0.00305635 0.0151995 0.99988 0.00199796 -0.00993605 0.999949 0.949635 0.285151 0.129934 0.00253064 -0.999883 0.0150983 -1.8469e-05 -1 -0.000110189 -0.00299212 0.999841 0.0175715 3.81195e-05 1 -0.000942146 -0.00162233 0.00806799 0.999966 0.00230285 -0.0114523 0.999932 0.87499 0.167432 -0.454268 0.924689 -0.101465 -0.366954 0.242091 -0.137648 -0.96044 0.941521 0.262306 -0.211503 0.94268 0.00191556 -0.333693 0.29068 0.0918455 -0.952402 0.54857 -0.155091 -0.821595 -0.120743 0.908558 -0.399929 0.467477 -0.189423 0.863472 -0.234078 -0.71364 -0.660246 -0.00207025 -0.935268 0.353935 -0.0158624 0.720267 -0.693515 -0.300401 -0.951466 -0.0668686 0.913153 0.00670412 0.407561 0.897072 -0.195856 0.396109 0.869052 -0.494721 0 -0.133864 0.991 0 0.819078 0.191981 0.540606 0.851233 -0.137049 0.506577 0.882095 -0.45502 0.121922 0.838151 -0.385683 0.385684 0.516655 -0.221602 0.827019 0.657837 0.194934 0.727496 0.412765 0.172563 -0.894342 0.983403 -0.022655 -0.180013 -0.708949 -0.000837303 -0.70526 -0.695787 0.00486226 -0.718232 -0.706838 0.000214341 -0.707375 -0.707002 -1.49813e-05 -0.707211 -0.711575 0.00011059 -0.70261 -0.706851 0.000103897 -0.707362 -0.707389 -1.66888e-06 -0.706825 0.707743 -0.000181042 0.70647 0.707373 -0.000185447 0.70684 0.707243 2.46792e-05 0.706971 0.708104 -6.22485e-05 0.706108 -0.786795 0.160565 -0.595963 -0.635122 -0.156191 -0.756455 -0.0260739 0.999637 -0.00683075 0.0260739 -0.999637 0.00683075 -0.999496 0.0309568 -0.00698321 -0.82726 0.0595539 -0.558654 -0.968913 -0.0496289 -0.242372 -0.197243 0.0134382 -0.980262 -0.107004 0.0645935 -0.992158 -0.497133 -0.00316282 -0.867669 -0.0049515 0.800225 -0.59968 -0.00387136 0.603712 -0.797193 -0.980174 0.19798 -0.00796396 -0.780146 0.081875 -0.620217 -0.133175 0.962991 -0.234334 -0.614317 0.166697 -0.77125 -0.796954 -0.0188433 -0.603747 -0.641814 -0.128851 -0.755958 -0.474962 0.00670647 -0.879981 -0.460283 0.292934 -0.838051 0.148108 -0.107441 0.983118 -0.902369 -0.0356518 -0.429487 -0.961292 0.0386368 -0.27281 -0.895442 -0.0239121 -0.444535 -0.0478702 -0.0259479 -0.998516 -0.098638 -0.00589286 -0.995106 -0.132142 -0.937872 -0.320835 -0.525296 -0.850916 -0.00246804 -0.00262113 -0.998923 -0.0463242 -0.0500142 -0.812748 -0.580465 0.00341842 -0.778838 -0.627216 -0.139461 -0.702969 -0.697413 -0.000259027 -0.999999 -0.00148223 0.00652214 -0.999979 -0.000570332 0.0492359 0.998766 -0.00646349 0.0056282 0.999984 -0.000922665 -0.00219561 0.924563 -0.381024 -0.0655555 0.725049 -0.68557 0.21872 0.842317 -0.49261 -0.113601 0.924621 -0.363553 0.242852 -0.843 -0.479973 -0.536582 0.0488617 -0.842432 -0.70765 -0.706562 0.000847636 -0.748052 0.663632 -0.00324786 0.0183711 -0.999824 -0.00379278 -0.0162915 -0.99985 0.00583818 0.0106236 -0.00249786 0.99994 -0.00262968 0.000613574 0.999996 0.0278744 0.999596 0.00563977 0.0116473 0.999932 0.00117076 0.0224492 0.00171167 -0.999747 -0.0312033 -0.0164375 -0.999378 1 3.49637e-06 -4.09078e-06 1 2.3251e-06 -2.72039e-06 -0.304253 0.246786 -0.920069 0.756644 0.653817 0.00371132 0.494697 0.791884 0.358043 -0.00294631 0.861866 0.507128 0.948561 0.20383 0.242252 0.0611694 0.737714 0.672337 0.289272 0.806593 0.51549 0.558069 -0.782549 -0.276 -0.494253 -0.811869 0.310778 0.832231 -0.553273 -0.035772 0.678434 -0.717645 -0.157202 0.678434 -0.717645 0.157202 0.832231 -0.553273 0.035772 0.555926 -0.77952 -0.288609 -0.508295 -0.835323 0.209457 0.924196 0.381161 -0.0240429 0.949757 0.284735 0.129955 0.979866 0.144774 0.137491 0.916659 0.369835 -0.151524 0.979857 0.14494 0.137378 0.916587 0.370016 -0.151513 -0.319998 -0.947405 0.00495877 0.248579 0.966659 0.0614686 -0.233224 0.9716 -0.0400001 -0.725893 -0.68748 -0.0212079 0.770751 -0.636963 -0.0148557 0.856541 -0.516007 -0.00858606 -0.731934 -0.681358 0.0048356 0.545774 -0.651443 -0.527022 -0.545774 0.651443 0.527022 -0.517075 -0.850945 -0.0923352 -0.194171 0.860022 -0.471868 -0.370632 -0.873671 -0.315169 0.0329309 0.799686 0.599515 0.195105 0.664746 0.721143 0.234444 -0.968896 0.0792264 0.309155 0.760556 0.570945 0.548918 -0.681893 0.483437 0.565115 -0.589819 0.576853 0.586905 0.371788 0.719247 -0.705669 -0.708401 0.0140985 -0.0212776 0.675854 0.736728 -0.255774 -0.713495 0.652307 -0.0342218 -0.995833 0.084533 0.414974 -0.80938 0.415572 0.942398 0.313648 0.116236 0.924192 0.381171 -0.02404 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707106 0.707107 0 0.707106 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.706557 0.707657 -8.92026e-06 -0.707106 0.707107 -7.69136e-05 -0.967622 0.252403 0 -0.965926 0.258819 0.00762894 0.999834 -0.0165708 0.00261983 0.998925 -0.0462832 7.80462e-09 1 1.87835e-05 -0.000273266 1 -0.000179908 -0.0013129 0.999999 1.12086e-06 0.00161965 0.999999 -2.25821e-06 0.0187722 0.999819 -0.00299071 0.00116473 0.999999 0.00101923 0 1 0 0 1 0 0 1 0 2.93753e-08 1 6.29471e-08 0.00214503 -0.99999 -0.00397728 -0.000794516 -1 1.06369e-06 -0.000337152 -1 7.54227e-05 0 -1 0 0 -1 0 0.0019512 -0.999998 0.000836228 0.00375509 -0.999993 -7.48475e-06 0.00136131 -0.999999 -0.000490436 -0.000211758 -1 0.000399846 -3.31357e-05 -1 0.000774552 6.01341e-08 -1 0.000367293 0.000351571 -1 0.000257569 0.000857566 -0.999999 0.000887998 -1 -0.000507765 0.00058039 -1 -0.000235913 -0.000362957 0.999998 0.00126715 0.0015114 -1 -0.000277561 -0.000247057 -1 -8.35373e-06 0.000203319 -1 0.000216511 0.000352489 1 -0.000435142 -2.17508e-05 1 0.000963507 0.000115698 0.999973 0.00603014 0.00420331 -0.999999 -0.000839014 0.00116716 -0.999998 -0.00116843 -0.00177521 -1 7.04354e-05 -0.000271461 -1 9.38702e-05 2.01497e-05 -1 -2.75143e-05 1.20814e-05 -0.999994 -0.00338852 0.000724646 -0.999997 -0.00206038 0.00123125 0.999987 -0.00264243 -0.00433715 -1 7.23939e-05 -5.05885e-05 -1 2.16102e-05 0.00025268 -1 -1.58176e-05 6.39118e-06 -1 0.000145228 8.41133e-05 -1 3.56819e-05 5.18832e-06 -1 6.12792e-05 -4.86869e-05 0.194171 -0.860022 0.471868 -0.906648 0.109351 0.407471 0.906648 -0.109351 -0.407471 -1 -8.21266e-05 -0.000255296 -1 0.000235314 -0.000336629 -1 -0.000208743 -5.56393e-05 -0.999997 -0.000577385 0.00254493 -0.999998 -0.0011089 0.00147885 0.00162233 -0.00806798 0.999966 -1.05044e-05 5.22394e-05 1 0.00299222 -0.999841 0.0176029 -0.000503227 -0.999993 -0.00375416 -0.00166814 0.999953 0.00951205 -9.3682e-05 1 -0.000107091 -0.982695 0.0423426 -0.180329 -0.947619 -0.26113 0.183926 0.00164281 -0.00816987 0.999965 -0.0015315 0.00761632 0.99997 0.00204526 -0.999926 0.0119764 5.46692e-05 -1 -0.000108104 -0.00378721 0.999738 0.0225952 0.000121312 1 -0.000723766 -0.941926 -0.334925 -0.0244954 0.997845 0.0319802 0.0572994 1.97905e-05 3.75426e-05 -1 -8.33112e-06 -8.27788e-05 -1 -0.979022 0.0504505 -0.197409 0.750347 -0.138365 -0.646401 -1.29336e-05 1.70799e-05 -1 1.23813e-05 -8.15927e-05 -1 -1.26096e-05 0.000670298 1 0.316814 -0.944969 -0.0816278 2.77745e-06 -0.000178939 1 -7.52663e-06 0.000484907 1 7.28632e-06 -0.00024265 1 0.338175 0.64753 0.682893 -0.428178 0.889578 -0.159102 -0.206009 -0.674791 0.708673 -3.71108e-05 -0.00349599 0.999994 -6.29181e-05 0.000289221 1 -0.00040324 0.00101052 0.999999 0 0 1 2.95397e-06 0.000164826 1 -1.40551e-05 0.000474437 1 2.708e-05 -0.00062053 1 0.286886 0.642574 0.710489 -0.461686 0.875274 -0.144019 -0.207825 -0.679087 0.704024 -0.000170435 0.000783453 1 2.82689e-05 3.16578e-06 1 5.24819e-06 -0.000129422 1 4.94772e-06 0.000199957 1 -2.06301e-07 0.000127662 -1 8.60975e-06 -0.000482833 -1 6.05455e-07 0.000298134 1 5.67781e-05 -0.000168208 -1 0.379086 -0.917094 -0.123417 1.56064e-05 0.000562267 1 -0.000179511 -0.00225322 -0.999997 0.00240615 0.0073633 0.99997 0.00793411 -0.00611892 0.99995 -0.0031412 2.0514e-07 -0.999995 1.22095e-06 -3.75952e-05 -1 0.00789068 0.00906977 -0.999928 1.1583e-06 9.01121e-06 -1 -2.14703e-06 0 -1 -1.0658e-07 4.51188e-05 -1 0.00330331 -0.00451371 -0.999984 -1.14367e-06 5.65371e-05 -1 5.15442e-07 -2.29888e-05 -1 -1.03636e-06 -3.14084e-06 -1 -0.00222508 0.457736 -0.889085 0.000710669 0.713419 -0.700738 -4.43984e-05 0.957994 -0.286788 0 0.286611 -0.958047 0.000455679 -0.270914 -0.962603 0.00506626 -0.648026 -0.761601 0 -0.962153 -0.272509 -0.790658 0.612258 -0.000161369 -0.746069 0.665862 -0.00288066 -0.209162 0.977874 0.00363265 -0.605196 -0.796057 -0.00563131 -1.74895e-05 6.63805e-05 -1 -2.59492e-05 0.00108756 -0.999999 -2.37242e-07 -2.67241e-05 -1 5.3109e-06 4.66322e-06 -1 0.000107424 0.000170495 -1 4.00559e-05 0.00100033 -1 1.20193e-06 3.00164e-05 -1 -1.10098e-07 6.86507e-05 -1 -2.21807e-06 -4.32263e-06 -1 -8.4555e-06 -7.04655e-05 -1 -0.0210635 -0.0314096 -0.999285 -0.00808468 0.0055049 -0.999952 -2.48358e-05 0.000134575 -1 8.46336e-08 0 -1 0 -9.24538e-07 -1 -6.25408e-07 -2.04359e-05 -1 1.00696e-06 8.92305e-06 -1 2.54541e-06 -0.000917911 -1 2.51828e-05 -0.000354795 -1 -5.4301e-07 -1.46067e-05 -1 -2.77575e-05 1.78812e-06 -1 -0.0062318 0.0134427 -0.99989 -1.90109e-05 -0.000141474 -1 1.164e-06 8.79326e-06 -1 -2.23654e-07 -0.000952333 -1 -8.49602e-06 0.000117215 -1 0.694611 0.0015859 0.719384 0.694771 -0.000855233 0.71923 0.69462 -0.00083428 0.719376 -1 -0.000506206 -0.000115869 -1 0.000479907 3.20222e-05 -1 0.000884552 2.43503e-05 -0.999289 -0.00450642 0.0374264 -0.999853 0.0164082 -0.00496856 -1 6.35773e-05 0.000171993 -1 0.000549235 -4.58075e-05 -1 -0.000612324 -1.88296e-05 -1 0.000371582 -7.30661e-06 -0.999999 0.000918275 0.00101555 -0.999998 -0.00192791 0.000237128 -0.971401 -0.122267 0.203544 -1 0.000882917 -0.000148314 -5.63075e-05 0.00222654 0.999998 2.68926e-06 0.000146841 1 0.465612 -0.873025 -0.145025 0.215443 0.680629 0.700235 -2.46032e-06 0.000203245 -1 -1.33828e-05 -0.000939707 1 0.00016164 -0.000246342 1 -0.0002189 -0.00283478 0.999996 0.00476253 0.00263843 0.999985 -2.65013e-06 1.62393e-05 1 0.000123713 -0.000463228 1 1.52872e-05 0.000559322 1 0.222503 0.681294 0.697374 0.45718 -0.877962 -0.142018 0 0 1 2.82172e-06 -0.000157749 1 -0.327297 -0.640091 0.695098 -0.29603 0.950725 -0.0921363 0.00169502 -0.0103866 0.999945 2.56882e-05 8.28896e-05 1 8.16521e-05 -0.000445387 1 1.34364e-05 -2.36976e-06 1 1.78204e-06 -0.000216695 1 2.31256e-06 0.000128355 1 -6.81701e-06 -0.000202074 -1 4.4482e-06 -0.000160586 1 -3.63905e-06 0.000151116 -1 -4.07738e-06 4.38764e-05 1 0.000123863 0.000967761 -1 0.00272062 0.00699552 0.999972 0.00729674 0.999713 -0.0228246 0.00764165 0.988733 0.149495 -0.00646841 0.999893 0.0131275 -0.000637291 1 -4.57722e-05 -0.118022 0.992733 0.0234882 -1.60718e-07 1 -2.99337e-06 -0.00110993 0.999999 3.47433e-05 0.000104042 1 -1.00536e-05 0.000324725 1 -0.000811855 0 1 0 5.04245e-05 -0.000751147 -1 1.38178e-05 0.000185017 -1 -6.50965e-05 -8.16317e-05 -1 -2.44857e-05 -0.000424972 -1 -2.36195e-05 -0.000443997 -1 3.44954e-05 -0.000163476 -1 0.00240626 -0.000123018 -0.999997 7.03045e-05 1.37719e-05 -1 0.00163589 0.000238596 -0.999999 -0.0759791 -0.0507083 -0.995819 -0.00321631 -0.00209478 0.999993 -0.000378871 0.000110451 -1 -1.77723e-05 -0.000762575 -1 0.000470586 9.31009e-05 -1 -0.00281378 0.000636828 -0.999996 3.81826e-05 0.00161187 -0.999999 -2.04191e-05 0.000353932 -1 -6.78105e-06 0.000117538 -1 -9.98876e-05 -0.00089709 1 -0.00299853 0.00402473 -0.999987 -0.101056 0.0688528 -0.992495 -3.68498e-05 0.000197602 1 -2.55913e-05 -0.000153488 -1 -0.000322616 -0.000711914 -1 -0.000613703 4.51588e-05 -1 -0.000620033 -0.00374432 -0.999993 0.00867984 -0.00514932 -0.999949 2.43454e-05 5.70885e-05 -1 -4.66502e-06 7.75872e-05 -1 2.38153e-05 -6.59855e-05 -1 -9.84071e-05 -5.71819e-05 -1 4.77546e-05 0.000328951 1 8.53826e-06 -1.19649e-05 -1 -9.41764e-06 -4.10469e-05 -1 2.92559e-06 2.59779e-05 1 0.000172315 -1 -0.000430792 0.0351242 -0.998168 -0.0492688 -0.000368808 -1 8.01619e-05 3.20723e-05 -1 -6.97105e-06 -2.41522e-06 -1 -4.49835e-05 0 -1 0 -0.000268654 -1 -2.02775e-05 -1 8.43725e-06 -2.6446e-07 -0.999988 -0.00492269 -0.000181036 -1 -0.000741716 -1.36284e-05 -1 -0.000893356 -0.00015398 -1 -0.000704358 -9.90316e-05 -0.966706 0.216229 0.136841 -1 1.90406e-06 3.52823e-06 -1 3.94563e-06 0.000155545 -1 -0.000757193 -3.53887e-05 -1 0.000489838 -1.27144e-05 -1 0.000169886 3.17889e-06 -1 0.000432019 -7.57418e-05 -0.999999 -0.00102235 6.71159e-05 1 0.000514724 2.64716e-05 0.999981 0.000842613 0.00609274 1 6.73394e-05 -0.000556112 1 0.000255289 -0.000115356 0.999999 -2.4389e-05 -0.00114635 -0.999994 -0.000971204 0.00340763 1 -3.5745e-07 0.000110215 1 -0.000110751 -0.00020251 1 -9.49765e-05 -0.000254192 1 -7.68205e-05 6.79268e-06 1 0.000277937 6.73827e-05 0.222746 0.912868 -0.342135 0.999999 0.00101485 0.000561126 1 -0.000428122 -9.26595e-05 -1 -0.000311025 1.95184e-05 1 -0.000222379 9.12893e-05 0.999908 0.00285523 -0.0132821 1 -9.09817e-06 3.63308e-06 1 0.000103865 -0.000437543 0.999996 0.00295909 9.98896e-05 1 0.000467422 -6.34381e-05 0.999999 -0.00126111 0.00108434 1 -0.000215272 7.27654e-05 1 -3.19727e-05 1.75427e-06 1 -4.8251e-07 1.90818e-06 1 -0.000137239 5.38598e-05 1 -1.12901e-05 3.33046e-05 1 -0.00012162 -3.078e-06 1 0.00017182 2.30199e-05 1 4.92173e-05 6.56965e-07 1 8.40673e-05 -1.09839e-06 9.13412e-05 -0.0019867 0.999998 3.22613e-06 0.000187796 1 -9.09766e-06 -2.94723e-05 1 0.000216042 -0.000345168 1 -0.000208186 -0.0133404 0.999911 -0.000650315 -0.00516462 0.999986 -0.000189686 -1 -0.000239528 1.72742e-07 -1 1.63028e-07 -7.99562e-09 -1 2.36124e-07 -1.64595e-08 -1 1.1641e-07 0.0715449 0.995493 0.0622563 2.49177e-13 1 1.1641e-07 -1.60047e-08 1 -1.0997e-07 -4.85996e-06 1 1.8485e-06 1.34751e-05 4.48863e-05 1 0.000154552 0.00169721 0.999999 -0.000287823 0.000363602 1 3.73936e-06 0.00675092 0.999977 2.14052e-06 -0.000276811 1 -0.000114262 0.0017701 0.999998 -0.00207025 -0.935268 -0.353935 0.0453283 0.996088 -0.0758611 0.0342218 0.995833 -0.084533 0.255774 0.713495 -0.652307 0.0212776 -0.675854 -0.736728 0.604709 -0.155377 -0.781143 0.999999 0.000992597 -0.000189798 0.999991 -0.0040931 -0.00146532 -1 1.36259e-05 0.000862987 -0.999997 0.0018368 0.00133879 -1.24443e-06 0 1 0.00095062 0.000308526 1 0.000129841 -0.000701028 1 -9.12224e-06 -0.00247135 0.999997 0.000163727 0.00243838 0.999997 1.16759e-06 1.30963e-05 1 -0.740082 -0.0803137 -0.667704 -0.70092 -0.00268823 -0.713235 -0.694651 -4.26263e-06 -0.719347 -0.694651 -6.66373e-06 -0.719347 -0.694654 -1.65882e-05 -0.719344 -0.694656 -1.05216e-05 -0.719342 -0.694655 1.01371e-06 -0.719343 -0.694666 0.000118843 -0.719333 -0.694656 1.47099e-05 -0.719342 -0.732855 0.0688935 -0.676888 -0.694684 -0.000141791 -0.719316 0.694844 7.69074e-06 0.71916 0.694672 -0.00190249 0.719324 0.694673 0.0019027 0.719324 0.694504 2.80039e-06 0.719489 0.900582 -0.434239 -0.0197224 1 0.000635713 -0.000316203 0.138226 0.892877 -0.428561 0.900418 -0.434644 -0.0182141 0.999963 0.00833655 -0.00188614 0.909473 0.415286 -0.0199109 0.999309 0.0371341 0.001516 0.999988 0.00481679 -0.00112121 0.999747 0.0218898 0.00523714 0.564201 0.579378 0.588216 0.444963 0.770566 0.45633 0.188826 0.961751 0.198442 0.00074459 0.567514 0.823363 -0.000946185 0.638168 0.769896 0.000573263 0.963184 0.268842 0 0.973753 0.227606 0.634779 0.77267 0.00607046 0.979628 -0.198477 -0.030587 0.803342 -0.0356663 0.594449 0.696226 -0.0325185 0.717086 0.584651 -0.537014 0.608112 0.266762 -0.922239 0.279844 0.431491 -0.785457 0.443704 0.988949 -0.14751 -0.0148349 0.692142 -0.721694 0.0098537 0.000151665 -0.871483 0.490426 -0.000221354 -0.858326 0.513105 0.000302999 -0.533308 0.845921 0.00010336 -0.521987 0.852954 -0.419288 0 0.907853 -0.467485 0.0476499 0.882716 0.418221 0 -0.908346 0.468278 0.0492425 -0.882208 0.0817774 -0.156364 -0.984308 0.405103 0.46413 -0.787702 -0.162796 -0.610071 -0.775442 0.276396 0.211531 -0.937475 0.157175 -0.797193 0.582906 -0.157175 0.797193 -0.582906 -0.753615 0.620244 -0.217626 -0.978992 -0.109649 0.171905 0.0122402 -0.948625 -0.316166 0.519427 0.853727 0.0366895 0.517075 0.850945 0.0923352 0.731934 0.681358 -0.0048356 -0.856541 0.516007 0.00858605 -0.770751 0.636963 0.0148557 0.725893 0.68748 0.0212078 -0.00225707 -0.999997 0.00085764 0.00325709 -0.999995 7.42181e-05 0.000928972 0.0121594 0.999926 -0.000677216 0.0113962 0.999935 0.0198167 -2.43561e-05 0.999804 0.0172865 -0.00251196 0.999847 0.0046562 0.999989 0.000128987 -0.0119343 0.999926 0.00238942 0.0367039 0.999199 0.0159485 0.39446 -0.8774 0.273076 -0.282219 -0.934688 -0.216125 0.693152 0.696231 0.186554 0.827457 0.39706 0.397061 1 0 0 1 0 0 1 0 0 0.7835 0.16083 0.600218 0.870566 0.329174 0.365732 1 0 0 1 0 0 1 0 0 -0.000671371 0.000192677 1 0.000159191 0.000328988 -1 -0.00965863 0.0193172 0.999767 0 0 1 0 0 1 5.5641e-05 -0.000103237 1 -1.54644e-07 -3.1959e-07 1 5.1331e-07 0 1 -1.85997e-07 -1.96196e-06 1 0 0 1 0 0 1 8.98449e-10 7.48856e-07 1 0 7.3822e-07 1 -9.03839e-10 -7.53349e-07 1 -0.0526078 0.973998 -0.220363 0 1 0 0 1 0 0.000417207 0.999988 -0.00486676 0 -1 0 -0.000175255 -1 0.000766521 0.0551782 -0.992256 -0.111282 0 -1 0 0 -1 0 -0.0017862 -0.964574 -0.263807 0.00178624 0.964574 0.263807 -0.248579 -0.966659 -0.0614686 0.319998 0.947405 -0.00495877 0.991856 0.127362 -0.000273672 -0.991856 -0.127362 0.000273672 0.000755445 -0.999995 -0.00316812 0.000299421 -0.999981 -0.00622615 -0.00165068 0.999927 -0.0120148 0.000382917 0.999999 0.00153563 -1.02739e-05 -3.61993e-05 -1 -3.24579e-06 -6.03049e-06 -1 -0.000876145 -0.999999 0.00073823 -0.0012393 -0.999998 -0.00167087 0.000120662 0.999991 -0.00418768 -0.000685804 0.999999 0.00144107 4.32944e-06 -7.08182e-06 -1 2.07214e-06 -1.60798e-05 -1 -0.000279897 -0.999997 -0.00235788 0.00061392 -0.999992 0.00390327 0.00116744 0.999963 -0.00856512 0.00046385 0.999992 -0.00399198 0.000682738 -0.999998 -0.00179847 0.0001846 -0.999985 -0.00540423 -0.00207141 0.999859 -0.016653 0.000668343 0.999994 0.00340997 0.969229 0.167176 -0.180686 -0.969111 -0.19111 -0.155885 -0.966735 -0.195842 -0.164528 -0.963781 0.129379 -0.233209 0.970976 0.0899955 -0.2216 0.822153 0.554214 0.130046 -0.923236 -0.15452 -0.351793 -0.807233 0.389949 0.443075 -0.933348 0.214637 0.287736 0.745604 -0.495765 -0.4453 0.922911 0.164626 -0.348042 -0.854693 -0.134268 -0.50147 -0.447119 -0.876361 0.179096 -0.598602 0.749949 0.281517 0.995106 0.0942451 0.0296935 0.985468 0.152846 -0.0740942 -0.969163 0.194005 0.151939 -0.968378 -0.11765 -0.220006 -4.61162e-05 0.999999 -0.00116229 -0.00027569 1 0.000297988 0.000258648 -1 -3.56784e-05 0.000677361 -0.999996 0.00279695 -2.4729e-09 5.36231e-05 1 -3.40523e-05 0.000237178 1 -0.974734 0.127542 -0.183378 -0.9794 -0.144706 0.140841 -0.000748262 0.999992 0.0039793 -0.000154193 1 0.000278078 0.000748432 -1 -0.000105645 0.000253948 -0.999994 -0.00335354 -4.05352e-05 0.000211135 1 4.05352e-05 -0.000211135 1 -0.924151 -0.38127 -0.0240362 -0.00299871 0.99984 0.0176124 3.81779e-05 1 -0.000942144 0.00254202 -0.999882 0.0151662 -1.84376e-05 -1 -0.000110002 0.00305635 -0.0151995 0.99988 -0.00199796 0.00993605 0.999949 -0.949635 -0.285151 0.129934 -0.00253064 0.999883 0.0150983 1.8469e-05 1 -0.000110189 0.00299212 -0.999841 0.0175715 -3.81195e-05 -1 -0.000942146 0.00162233 -0.00806799 0.999966 -0.00230285 0.0114523 0.999932 -0.87499 -0.167432 -0.454268 -0.924689 0.101465 -0.366954 -0.242091 0.137648 -0.96044 -0.941324 -0.263049 -0.211458 -0.942707 -0.00193728 -0.333616 -0.29068 -0.0918455 -0.952402 -0.54857 0.155091 -0.821595 0.117948 -0.912777 -0.391059 -0.408128 -0.140211 0.902093 0.234078 0.71364 -0.660246 0.00207025 0.935268 0.353935 0.0158624 -0.720267 -0.693515 0.300401 0.951466 -0.0668686 -0.913153 -0.00670412 0.407561 -0.897072 0.195856 0.396109 -0.869052 0.494721 0 0.133864 -0.991 0 -0.819078 -0.191981 0.540606 -0.851233 0.137049 0.506577 -0.882095 0.45502 0.121922 -0.838151 0.385683 0.385684 -0.516655 0.221602 0.827019 -0.657837 -0.194934 0.727496 -0.412765 -0.172563 -0.894342 -0.983403 0.022655 -0.180013 0.708949 0.000837303 -0.70526 0.695787 -0.00486226 -0.718232 0.706838 -0.000214341 -0.707375 0.707002 1.49813e-05 -0.707211 0.711575 -0.00011059 -0.70261 0.706851 -0.000103897 -0.707362 0.707389 1.66888e-06 -0.706825 -0.707564 0.000271898 0.706649 -0.707373 0.000185447 0.70684 -0.707243 -2.46792e-05 0.706971 -0.708179 6.9787e-05 0.706033 0.786795 -0.160565 -0.595963 0.635122 0.156191 -0.756455 0.0260739 -0.999637 -0.00683075 -0.0260739 0.999637 0.00683075 0.999496 -0.0309568 -0.00698321 0.82726 -0.0595539 -0.558654 0.968913 0.0496289 -0.242372 0.197243 -0.0134382 -0.980262 0.107004 -0.0645935 -0.992158 0.497133 0.00316282 -0.867669 0.0049515 -0.800225 -0.59968 0.00387136 -0.603712 -0.797193 0.980174 -0.19798 -0.00796396 0.780146 -0.081875 -0.620217 0.133175 -0.962991 -0.234334 0.614317 -0.166697 -0.77125 0.796954 0.0188433 -0.603747 0.641814 0.128851 -0.755958 0.474962 -0.00670647 -0.879981 0.460283 -0.292934 -0.838051 -0.148108 0.107441 0.983118 0.902369 0.0356518 -0.429487 0.961292 -0.0386368 -0.27281 0.895442 0.0239121 -0.444535 0.0478702 0.0259479 -0.998516 0.098638 0.00589286 -0.995106 0.132142 0.937872 -0.320835 0.525296 0.850916 -0.00246804 0.00262113 0.998923 -0.0463242 0.0500142 0.812748 -0.580465 -0.00341842 0.778838 -0.627216 0.139461 0.702969 -0.697413 0.000259027 0.999999 -0.00148223 -0.00652214 0.999979 -0.000570332 -0.0492359 -0.998766 -0.00646349 -0.0056282 -0.999984 -0.000922665 0.00219561 -0.924563 -0.381024 0.0655555 -0.725049 -0.68557 -0.21872 -0.842317 -0.49261 0.113601 -0.924621 -0.363553 -0.242852 0.843 -0.479973 0.536582 -0.0488617 -0.842432 0.70765 0.706562 0.000847636 0.748052 -0.663632 -0.00324786 -0.0183711 0.999824 -0.00379278 0.0162915 0.99985 0.00583818 -0.0106236 0.00249786 0.99994 0.00262968 -0.000613574 0.999996 -0.0278744 -0.999596 0.00563977 -0.0116473 -0.999932 0.00117076 -0.0224492 -0.00171167 -0.999747 0.0312033 0.0164375 -0.999378 -1 -3.49637e-06 -4.09078e-06 -1 -2.3251e-06 -2.72039e-06 0.304253 -0.246786 -0.920069 -0.756644 -0.653817 0.00371128 -0.494697 -0.791884 0.358043 0.00294631 -0.861866 0.507128 -0.948561 -0.20383 0.242252 -0.0611694 -0.737714 0.672337 -0.289272 -0.806593 0.51549 -0.558069 0.782549 -0.276 0.494253 0.811869 0.310778 -0.832231 0.553273 -0.035772 -0.678434 0.717645 -0.157202 0.635216 -0.762668 -0.121813 0.689674 -0.0102633 -0.724047 0.655552 -0.753197 0.0542772 -0.626497 -0.765931 -0.1444 -0.703051 0.112525 -0.70218 0.162262 -0.61822 0.769074 0.253139 -0.958042 0.13445 -0.790049 0.576663 -0.208044 0.790049 -0.576663 0.208044 -0.119423 -0.758957 0.640096 0.493513 -0.664253 0.561438 0.106786 -0.906833 -0.407739 0.28598 -0.490706 0.823057 0.0318762 -0.559018 -0.828543 0.204235 -0.355344 0.912151 -0.124061 -0.873631 0.470509 -0.180841 -0.462888 0.867774 0.00527369 -0.318394 -0.947944 -0.476941 0.300182 0.826086 -0.844069 -0.0855818 0.529361 -0.419556 0.219101 0.88089 -0.593329 0.035523 0.804176 0.4935 -0.299254 0.816642 -0.381221 0.408139 0.829514 0.255063 -0.169693 0.951918 0.581949 0.805027 -0.115182 0.194452 0.976329 0.0947106 0.809463 -0.580566 -0.08782 0.296063 -0.952864 0.0663124 0.822857 -0.560656 -0.0925757 0.734303 -0.678536 -0.0196895 0.999526 0.00310201 0.0306417 0.598855 0.794326 -0.10207 0.188273 0.979464 0.0721333 1 -8.12299e-06 -1.50232e-05 1 -4.06154e-05 5.34438e-05 1 -1.04558e-05 -2.33545e-06 1 1.83026e-07 3.27707e-06 1 9.19839e-07 1.66352e-06 1 -1.74895e-06 0.000278383 1 5.58206e-06 0.000161159 1 7.566e-05 -0.000135835 1 -0.000116412 -0.00021456 1 2.03219e-06 3.74555e-06 1 -8.60354e-10 1.16898e-06 1 -0.000162855 -0.000225838 1 1.31461e-06 1.82302e-06 1 1.30889e-06 1.73539e-06 1 2.44366e-06 1.08389e-05 1 7.40066e-07 -1.73695e-05 1 0.000219285 -0.000335261 -1 1.04935e-06 0.000385078 -1 -1.38032e-05 5.35103e-06 -1 9.16118e-07 4.06011e-06 -1 2.30987e-06 2.68686e-06 -1 -4.06174e-05 -1.07804e-06 -1 9.21175e-07 -1.6693e-06 -1 7.42062e-06 9.9341e-06 -1 1.00255e-06 1.84781e-06 -1 -1.96105e-07 2.84079e-06 -1 -1.27288e-06 5.96046e-06 -1 0.000135121 -0.000245428 -1 -8.1876e-07 0.000238154 -1 -0.000101624 -0.000187303 -1 0.000198741 -0.000305391 -1 7.40066e-07 -1.73709e-05 -1 2.44355e-06 1.08382e-05 -1 1.30887e-06 1.65646e-06 -1 1.32836e-06 1.9329e-06 -1 -0.000226873 -0.000330124 -0.571335 0.116973 -0.812339 -0.552723 0 -0.833365 -0.552718 5.00034e-07 -0.833369 -0.552712 0 -0.833372 -0.552717 3.7407e-07 -0.833369 -0.552723 -7.95608e-08 -0.833365 -0.552722 0 -0.833365 -0.887042 0 -0.461689 -0.589823 0.101195 -0.801167 -0.548756 -0.610376 -0.571234 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.00131064 0.000172332 -0.999999 0.021525 0.0344655 -0.999174 -0.0370025 -0.0340893 -0.998734 0.00840875 -0.0358931 -0.99932 0 0 -1 0.235848 0.323177 -0.916478 0.485708 -0.000394919 -0.874121 0.489777 -3.98347e-07 -0.871848 0.489774 0 -0.87185 0.489773 0 -0.87185 0.489781 8.21468e-07 -0.871846 0.489777 0 -0.871848 0.80455 0 -0.593884 0.528735 -0.162756 -0.833036 -2.85561e-07 0.890061 -0.455841 -0.325979 0.60311 -0.728008 -2.12106e-06 0.890059 -0.455845 0 0.89006 -0.455844 0 0.89006 -0.455844 8.47466e-08 0.89006 -0.455843 -0.339759 0.531459 -0.775961 0 0 -1 0 0 -1 0 0 -1 8.31205e-07 -1.62869e-06 -1 0 0 -1 0 0 -1 8.84096e-07 -1.44688e-06 -1 0 0 -1 0 0 -1 -0.569002 -7.25142e-06 -0.822336 -0.569212 0.000205682 -0.82219 -0.569644 0 -0.821892 -0.269057 -0.630127 -0.728387 -0.265618 -0.766825 -0.584318 0 -0.89006 -0.455844 0 -0.89006 -0.455844 2.39226e-07 -0.890061 -0.455842 -2.8889e-07 -0.89006 -0.455843 -0.332903 -0.520734 -0.786137 6.57141e-07 1.95443e-06 -1 7.73952e-07 1.73249e-06 -1 1.06092e-06 5.6427e-07 -1 9.19095e-07 3.58285e-07 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.569105 -0.000583696 -0.822265 -0.569935 -0.000422824 -0.82169 -0.57083 0 -0.821068 1.11162e-06 0.210817 -0.977526 9.52103e-07 0.210817 -0.977526 -1.30632e-05 0.953292 -0.302052 -1.16194e-06 0.953292 -0.302049 -3.79249e-07 0.953292 -0.30205 -4.45824e-06 0.953292 -0.302051 0.400578 0.420277 -0.81419 0.400568 0.420268 -0.814199 0.400563 0.420269 -0.814201 0.351409 0.935167 -0.0444254 0.351419 0.935164 -0.0444246 -2.37743e-07 0.890502 -0.454979 -2.57592e-07 0.890502 -0.454979 -0.351417 0.935164 -0.0444273 -0.351406 0.935169 -0.0444283 -9.18678e-07 0.645742 0.763555 5.32044e-07 0.645729 0.763566 4.45824e-06 0.953292 -0.302051 3.79249e-07 0.953292 -0.30205 1.56814e-06 0.953293 -0.302048 1.22948e-05 0.953292 -0.302051 0.569018 -1.84365e-07 -0.822325 0.569217 -0.000201694 -0.822187 0.569641 0 -0.821894 0.338427 -0.529374 -0.777965 2.85561e-07 -0.890061 -0.455841 0.323305 -0.60656 -0.726333 2.96955e-06 -0.890059 -0.455846 0 -0.89006 -0.455844 0 -0.89006 -0.455844 -8.47466e-08 -0.89006 -0.455843 0.552723 0 -0.833365 0.552718 0 -0.833368 0.552723 9.10176e-07 -0.833365 0.552712 0 -0.833372 0.552717 3.74784e-07 -0.833369 0.552722 -4.19613e-08 -0.833365 0.548756 0.610376 -0.571234 0.902041 -0.113116 -0.416565 0.788807 0 -0.614641 0.0342282 -0.0374213 -0.998713 0 0 -1 0 0 -1 0 0 -1 -0.0711655 -0.060067 -0.995654 0 0 -1 0 0 -1 0 0 -1 0.0527016 0.0354681 -0.99798 -0.014072 0.0813553 -0.996586 0 0 -1 -0.489781 0 -0.871845 -0.489777 0 -0.871848 -0.489781 -8.21468e-07 -0.871846 -0.489774 0 -0.87185 -0.489774 0 -0.87185 -0.489777 3.98347e-07 -0.871848 -0.780061 0 -0.625704 -0.527781 -0.157876 -0.83458 -0.529956 0.169096 -0.830996 -1 0 -2.30943e-06 -1 0 -2.30943e-06 0 0 1 -1.65786e-05 -0.000173773 -1 -0.11285 -0.853646 -0.508481 3.61155e-06 1.71776e-05 1 -5.54873e-06 -3.00744e-05 -1 0 0 1 0 0 1 6.25227e-07 6.82877e-06 1 0.73163 -0.498298 -0.465206 1.08716e-06 6.51416e-06 1 0 0 -1 0 0 1 0 0 1 -1.02707e-05 5.39007e-05 1 0 0 1 0 0 1 -4.31597e-05 -9.46272e-06 1 -9.32187e-06 -5.1781e-05 1 2.42947e-07 -2.14776e-07 -1 -0.275758 -0.907607 0.316555 4.09929e-07 -4.15062e-06 -1 -4.30651e-07 4.3433e-06 1 4.39252e-07 -4.44752e-06 -1 0.000371836 0.000265758 -1 -0.194078 -0.917215 -0.347924 -0.000371836 -0.000265758 1 0 0 1 0 0 1 4.00628e-05 -1.59903e-06 -1 -0.493513 0.664253 -0.561438 0 0 1 -4.00628e-05 1.59903e-06 1 9.12767e-05 -7.91255e-06 1 0 0 1 0 0 1 0.0524318 -0.987501 0.148637 0 -1.733e-06 1 -2.32548e-07 -3.19789e-07 1 0 0 -1 -0.0524318 0.987501 -0.148637 0 0 1 -2.26865e-05 2.22524e-06 1 2.64891e-06 2.16282e-06 1 -4.03578e-07 -8.40696e-08 -1 0 0 1 0 0 1 2.66675e-06 -1.27744e-05 1 2.16994e-12 1.4844e-06 1 -2.29778e-07 -1.23421e-07 1 -2.27793e-07 -1 3.08742e-07 -2.29622e-07 -1 -5.90161e-06 -1.82291e-06 -1 8.27656e-05 7.07335e-08 1 -8.9407e-06 -1.15191e-06 1 -1.25046e-06 1.76834e-06 1 -0.000243629 0 1 0 1.51244e-07 1 7.08755e-06 1.67362e-06 1 -0.000265698 7.81633e-06 1 1.14356e-06 3.46786e-06 1 -8.04663e-05 0 0 1 0 0 1 -1.97089e-06 3.44699e-12 1 0.457463 1.13535e-06 0.889229 -1.9708e-06 -4.89455e-12 1 -1.97084e-06 -2.5796e-12 1 -4.02075e-07 -2.98024e-08 1 -2.65844e-06 2.79079e-06 1 -0.000135298 -1.00285e-05 1 0.44504 -1.56784e-05 0.895511 0 2.06955e-06 1 2.35779e-08 -2.47508e-08 1 0 0 1 0.113273 0.0764377 0.990619 0 0 1 0 0 1 -0.448912 5.57502e-07 0.893576 -0.0670396 -0.107616 0.99193 0 0 1 0 0 1 -1.20315e-06 3.65557e-05 1 1.32763e-07 4.76168e-07 1 0 2.03092e-05 1 6.01544e-07 3.65557e-05 1 4.31404e-07 -0.64573 0.763566 -9.18676e-07 -0.645742 0.763556 1.37075e-05 -0.953292 -0.302052 1.16193e-06 -0.953292 -0.302049 3.79249e-07 -0.953292 -0.30205 4.45824e-06 -0.953292 -0.302051 0.569092 0.000605184 -0.822273 0.569963 0.000435878 -0.82167 0.538549 0.0151064 -0.842459 0.35665 0.370481 -0.857639 0.274345 0.622867 -0.732647 0.272395 0.762423 -0.586952 0 0.89006 -0.455844 0 0.89006 -0.455844 -2.39226e-07 0.890061 -0.455842 2.8889e-07 0.89006 -0.455843 -8.28583e-07 -1.62869e-06 -1 0 0 -1 1.29337e-07 1.22029e-06 -1 -7.73952e-07 -1.73249e-06 -1 -8.84096e-07 -1.28409e-06 -1 0 0 -1 -0.463037 -0.180503 -0.867765 -0.145673 0.216521 -0.965349 -0.441446 -1.31761e-06 -0.897288 -0.441446 -1.17334e-06 -0.897288 -0.441446 5.57643e-07 -0.897288 0 0.649376 -0.760467 0 0.649376 -0.760468 0 -1.82723e-06 -1 0 0 -1 2.81187e-07 -9.77213e-07 -1 -4.6412e-07 -5.02766e-06 -1 0 0 -1 1.77137e-07 2.74625e-06 -1 0 0 -1 -2.76691e-07 -9.77213e-07 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.72646e-07 -9.88392e-07 -1 -2.90107e-07 -8.98769e-07 -1 8.69883e-08 -8.15265e-07 -1 1.09113e-07 -3.78067e-06 -1 0.441446 -1.16443e-06 -0.897288 0.441446 -1.32313e-06 -0.897288 0.441446 5.57643e-07 -0.897288 0.400564 -0.420289 -0.81419 0.400576 -0.420266 -0.814196 0.400563 -0.42027 -0.814201 -4.45824e-06 -0.953292 -0.302051 -3.79249e-07 -0.953292 -0.30205 -1.16193e-06 -0.953292 -0.302049 -1.49836e-05 -0.953291 -0.302052 1.04203e-06 -0.645742 0.763556 -4.3195e-07 -0.645728 0.763567 0.351419 -0.935164 -0.0444246 0.351409 -0.935167 -0.0444254 -2.57592e-07 -0.890502 -0.454979 -2.38414e-07 -0.890502 -0.454979 -0.351406 -0.935169 -0.0444283 -0.351417 -0.935164 -0.0444273 -0.400576 -0.420275 -0.814192 -0.400568 -0.420268 -0.814199 -0.400563 -0.42027 -0.814201 -9.38779e-07 -0.210817 -0.977526 -9.52103e-07 -0.210817 -0.977526 0 -0.658486 -0.752593 -2.38022e-07 -0.65849 -0.752589 9.5186e-07 -0.210817 -0.977526 9.38779e-07 -0.210817 -0.977526 0.98885 0.0978095 0.11229 0.304387 0.943012 -0.134449 0.319778 0.939454 -0.123162 -0.667683 0.738659 0.0926374 -0.961401 0.249874 -0.115201 -0.990614 -0.135233 -0.0199199 -0.649233 -0.7488 -0.133399 -0.688605 -0.717073 -0.107839 0.294935 -0.949234 0.109395 0.814477 -0.537749 -0.217837 0.4069 -0.911621 0.0581284 0.0178737 -0.991073 -0.132116 -0.480328 -0.874663 0.0651868 -0.988071 -0.0747258 -0.134655 -0.975382 0.220519 -0.0012849 -0.429747 0.887202 -0.1679 -0.0983195 0.994001 0.047901 0.972228 0.226222 -0.0599724 0.981709 0.188587 -0.0261414 0 1 0 0 1 0 0 1 0 0 1 0 1 0 -2.30943e-06 1 0 -2.30943e-06 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.649376 -0.760467 0 -0.649376 -0.760467 -0.441445 1.45671e-06 -0.897288 -0.441446 1.74753e-06 -0.897288 -0.441446 -5.57643e-07 -0.897288 0 0 -1 -9.85417e-07 1.95443e-06 -1 0 0 -1 -1.06092e-06 1.70494e-06 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -9.51861e-07 0.210817 -0.977526 -1.11162e-06 0.210817 -0.977526 -0.400565 0.420283 -0.814193 -0.400574 0.420266 -0.814197 -0.400563 0.420269 -0.814201 -2.3842e-07 0.65849 -0.75259 0 0.658485 -0.752594 -1.77137e-07 -2.74625e-06 -1 2.48451e-07 -1.77142e-06 -1 0 2.2206e-06 -1 -1.02944e-07 -2.33027e-06 -1 0 0 -1 8.88733e-08 1.93164e-06 -1 3.16393e-07 1.30295e-06 -1 -2.21249e-07 1.30295e-06 -1 -1.46131e-07 1.04189e-06 -1 7.68339e-07 -1.55585e-06 -1 -2.05925e-07 5.47721e-06 -1 -3.17964e-08 3.42775e-06 -1 0 2.8312e-06 -1 -2.29434e-07 1.25847e-06 -1 8.73357e-08 -8.07028e-08 -1 7.09764e-08 -1.74929e-06 -1 0 0 -1 0.441445 1.75368e-06 -0.897288 0.441446 1.47292e-06 -0.897288 0.441446 -5.57643e-07 -0.897288 -0.981869 0.189547 0.00219213 -0.611175 0.788668 0.0668425 0.150362 0.965369 -0.213202 0.411836 0.90995 -0.0488113 0.981745 -0.180625 -0.05959 0.974958 -0.220424 -0.0295052 0.179048 -0.982094 0.0585878 -0.0982082 -0.992875 -0.0674837 -0.686222 -0.721228 0.0944981 -0.985591 -0.100127 -0.136324 -0.984707 -0.0973994 0.144448 -0.305487 -0.946422 -0.104709 -0.196792 -0.962948 -0.184403 0.734446 -0.678667 -0.00093022 0.955609 -0.00869486 -0.294509 0.80755 0.579192 0.111356 -0.296651 0.954756 0.0209778 -0.648194 0.698031 -0.304298 0.951772 -0.294554 -0.0858419 -0.87325 0.480323 -0.0819985 -0.982706 0.170912 0.0712631 -0.443563 -0.893085 -0.0751691 -0.127358 -0.988089 0.086373 -0.361362 -0.931562 0.0401298 -0.685966 -0.719309 -0.109749 -0.995349 0.0963034 0.00243103 -0.848033 0.519684 -0.103774 -0.296063 0.952864 0.0663124 0.393787 0.91496 -0.0882006 0.809047 0.580265 0.0934635 -1.20316e-06 -3.24939e-05 1 1.32762e-07 3.58553e-06 1 0 -1.62473e-05 1 7.51953e-07 -3.6556e-05 1 -4.31404e-07 0.645728 0.763567 9.6264e-07 0.645741 0.763557 0 -1 0 1.02285e-07 1 -9.63123e-06 2.22676e-08 -1 3.67046e-06 -2.49145e-06 -1 -0.000410675 -9.27399e-06 -1 -3.33918e-06 -8.23911e-06 -1 -2.38425e-05 -1.46183e-06 -1 0.000145372 2.22909e-07 -1 2.6999e-05 -1.31539e-06 1 -6.54645e-06 8.76878e-07 -1 1.86412e-05 0.937071 -0.337408 -0.0897381 0.370285 -0.923667 -0.0986343 1 -2.94421e-08 -7.81649e-06 -1 -1.3422e-05 9.59169e-05 1 1.22139e-05 4.86889e-05 1 8.06845e-06 -0.000129223 1 3.15045e-07 4.66941e-07 1 2.58368e-06 -5.44594e-05 1 -2.72346e-05 -0.000982007 1 3.0457e-06 -3.40234e-06 1 -2.71033e-05 0.000239139 1 1.81331e-05 -2.38433e-05 1 -3.73597e-05 8.68647e-05 0.999999 -5.54323e-06 0.00131564 1 8.8151e-07 0.000234029 -1 1.52061e-05 -0.000173395 -1 -9.61578e-06 8.5765e-05 -1 -1.51443e-05 -0.000146912 -1 1.78827e-07 -0.000403203 -1 -2.21213e-05 -7.74866e-05 -1 -7.9579e-07 -0.000474156 -1 1.02522e-07 3.83259e-06 1 -5.19392e-05 0.000437071 -1 1.93151e-05 -0.00011921 -1 5.19531e-05 -0.000444421 -1 1.08289e-06 4.0482e-05 -1 -1.07289e-06 0.00057168 -0.764527 -0.598595 -0.239127 -0.986307 -0.151511 -0.0651462 -0.0983973 -0.9948 -0.0262903 0.202901 -0.966582 0.156687 0.94148 -0.292523 -0.16747 0.785177 0.610489 0.103925 0.58239 0.812011 -0.0382199 -0.636092 0.770483 0.0417442 -0.782808 0.611455 -0.115477 -0.209574 -0.976665 -0.0469406 -0.810992 -0.58166 0.0629541 -0.974081 -0.215648 -0.0682729 -0.760711 0.647867 -0.039842 -0.734303 0.678536 -0.0196895 0.306957 0.950967 0.0379284 0.651641 0.752965 -0.0916954 0.991299 0.0980528 0.0878195 0.663205 -0.739798 -0.113391 0.957182 -0.26449 0.117675 -0.94171 0.322925 -0.094352 -0.999373 0.0180242 0.0304917 -0.704438 -0.704737 -0.0843382 -0.236913 -0.969274 0.0661814 -0.963687 0.0588159 -0.260476 -0.615769 0.787397 0.028878 0.107821 0.987716 -0.1131 0.605016 0.794233 0.0561209 0.91464 0.352576 -0.197795 0.6753 -0.737359 0.0164796 0.215462 -0.957264 -0.19293 -0.649304 -0.742443 0.164871 0.578064 -0.180744 -0.795722 -1 0.000872438 -9.93409e-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 -3.69041e-07 3.97364e-06 1 9.11062e-07 1.68498e-06 -1 3.24962e-05 -5.60586e-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.840808 0.448766 -0.30274 -0.231207 -0.449419 -0.862882 0.857407 0.411761 0.308716 -0.451646 -0.487276 -0.747381 0.374341 0.443143 -0.814551 -0.677531 -0.00147331 -0.735493 -0.533332 0.131464 -0.835628 0.959878 -0.155799 -0.233154 0.961464 -0.203289 -0.185096 0.844069 0.0855818 -0.529361 0.476941 -0.300182 -0.826086 -0.178693 0.982858 -0.0453748 -0.068641 0.163261 -0.984192 -0.177976 0.908148 0.378934 0.154261 0.987871 -0.0177379 0.227993 0.753497 0.616653 0.092537 0.55844 -0.824367 0.00506649 -0.00565162 -0.999971 0.00361668 0.00500306 -0.999981 -6.17673e-05 -0.000322297 -1 -0.000221678 0.000282957 -1 -0.00868154 -0.00202006 -0.99996 -0.000191845 0.0106376 -0.999943 0.00150521 0.00349735 -0.999993 0.00272152 -0.00185432 -0.999995 0.0120432 -0.0367468 -0.999252 -0.0465505 0.00646144 -0.998895 0.0113148 -0.00622362 -0.999917 0.00588409 0.0118472 -0.999913 0.00717229 -0.00772374 -0.999944 -0.00015332 -0.00155005 -0.999999 0.00190944 -0.00421774 -0.999989 0.00590965 0.00682854 -0.999959 0.00565002 -0.00405233 -0.999976 -0.00285762 -0.0133172 -0.999907 0.00122728 0.00170952 -0.999998 0.0014667 -0.000454681 -0.999999 -0.000291575 -0.00294783 -0.999996 0.148729 0.954069 -0.260062 -0.579635 0.39477 -0.712868 0.805187 0.531201 0.263628 -0.466073 0.489908 0.736726 0.194078 0.917215 0.347924 0.731405 0.289727 0.617336 -0.710835 0.493488 -0.501182 -0.253139 0.958042 -0.13445 -0.719814 -0.0371564 -0.693172 -0.620752 0.770656 -0.144071 -0.703187 0.695888 0.145837 0.610241 0.778714 -0.145637 0.686711 -0.0543601 -0.724895 0.657587 0.751577 0.0520753 0.839961 0.0137401 0.542473 0.721394 0.674889 0.155291 0.34788 0.926926 0.140666 0.35237 0.926736 0.130371 0.262159 0.216921 0.940329 0.64405 -0.295107 -0.70577 0.111661 0.85762 -0.502016 -0.573195 0.761669 -0.302172 -0.945825 -0.152557 -0.286602 -0.287133 -0.605574 -0.742183 -0.581906 -0.80741 0.0973349 0.140812 -0.95387 -0.265148 0.344189 -0.852038 0.394417 0.134206 -0.710196 0.691094 0.93071 -0.25055 0.266467 -0.220859 0.219434 -0.9503 -0.0643654 0.363517 -0.929361 0.784054 0.145344 -0.603436 0.837904 0.0365195 -0.544595 0.959471 -0.161416 -0.230997 0.651024 -0.708628 -0.272056 0.755751 -0.204514 -0.622105 0.634091 -0.31748 -0.705078 0.59171 -0.133264 -0.795059 0.480243 -0.211912 -0.851152 0.640018 -0.000155492 -0.76836 0.0530753 0.886437 -0.459796 0.414945 0.907769 0.0614588 -0.369187 -0.789071 -0.490987 -0.577352 -0.210272 -0.788955 0.116478 -0.229119 -0.966404 0.979554 0.0601669 0.191975 0.0601128 -0.322152 -0.944777 -0.399453 -0.373903 -0.837039 0.736485 -0.483057 -0.473546 0.778977 -0.456571 0.429812 0.18851 -0.629281 -0.753969 0.535269 -0.660948 -0.525961 0.812851 -0.486123 -0.32087 0.690841 -0.715832 0.101601 0.497235 -0.860188 0.113282 0.299141 -0.931764 -0.205745 0.0627511 -0.971002 -0.23069 -0.131097 -0.85906 -0.494803 0.622309 0.782332 0.0262305 0.411491 0.715975 -0.563963 0.709396 0.677417 -0.194585 0.730328 0.547328 0.408721 0.841058 0.389917 0.374948 -0.48743 0.466015 -0.738405 0.900184 0.392607 -0.188488 0.952364 0.299305 -0.0584734 0.842278 0.247755 0.478733 -0.233148 0.557456 -0.796797 0.0794558 0.827428 -0.555923 0.133992 0.192972 -0.972012 0.48492 0.281238 -0.828105 0.68493 0.0710298 -0.725139 0.683527 -0.0247065 -0.729507 -0.696221 -0.000708469 0.717827 -0.695 -0.00124682 0.719009 -0.695831 -0.00139223 0.718204 -0.692329 0.00252585 0.721577 -0.179206 -0.169594 0.969084 0.242313 0.345471 0.906606 -0.330151 0.56423 0.756733 0.197478 0.917304 0.345767 0.10012 0.952213 0.288559 -0.330819 -0.906044 0.263899 0.438776 -0.647762 0.6228 0.42715 -0.679268 0.596773 0.835462 0.542819 -0.0857444 0.343163 0.924069 -0.16833 0.495213 0.380606 -0.780963 -0.220897 -0.19061 -0.95649 0.433277 -0.415853 -0.799586 0.538528 -0.608148 -0.583218 -0.112976 -0.894967 -0.431591 0.275783 -0.953787 -0.119311 -0.500515 -0.270436 0.822404 0.915582 0.229246 -0.330389 0.990154 0.0668847 0.122966 0.958411 0.0806954 0.273746 0.694512 0.300781 0.653593 0.972373 -0.0591226 0.22582 0.989051 -0.121651 0.0835387 0.599591 -0.376309 -0.706316 0.1027 0.8057 0.583352 -0.00846358 -0.53989 0.841693 0.0887443 -0.980623 0.174654 0.381982 -0.658531 -0.648403 0.41761 -0.908623 -0.00249823 0.680597 0.0382191 -0.73166 0.487686 -0.0316034 0.872447 0.846437 -0.385533 -0.367299 0.75586 -0.445575 0.479727 0.410165 -0.315249 -0.855794 0.718202 -0.515847 0.466999 0.695689 0.208495 0.68742 0.406928 -0.640449 -0.651333 0.654522 -0.643596 -0.396717 0.23032 -0.760718 0.606845 0.42553 -0.904937 -0.00360995 0.734012 0.425647 0.529199 0.226258 0.94479 0.237023 0.482711 0.855821 0.185904 0.105896 0.945608 -0.307591 0.294742 0.464427 0.835126 0.757704 0.551823 0.34839 0.646597 -0.0812461 -0.758493 0.329344 0.506487 -0.796871 0.840581 0.503113 -0.20075 0.728171 0.625224 -0.280824 0.775521 0.344506 0.52904 0.188033 0.296223 0.936427 0.460212 0.682095 -0.568289 0.895654 0.390987 -0.211972 0.995625 -0.0296143 0.0886179 -0.711679 0.537352 -0.452511 -0.996083 0.00371801 -0.0883428 -0.996071 0.00088173 -0.0885547 -0.996161 -0.00127741 -0.0875256 -0.996148 -0.00113606 -0.0876789 -0.996358 -0.00234419 -0.0852412 -0.88534 -0.158505 -0.437092 0.763449 0.611002 0.209338 0.222767 0.97132 -0.0831403 -0.363986 0.809693 0.460339 -0.250327 -0.088189 0.964137 -0.979086 -0.06304 -0.193435 -0.87757 0.239789 -0.415178 -0.843079 0.494735 -0.210842 -0.494113 0.733222 -0.46716 -0.517518 0.424384 -0.743016 -0.0650717 0.944125 -0.323099 -0.845389 0.295796 0.444772 -0.531669 0.567787 0.628447 -0.43508 0.763999 0.476456 -0.503074 0.460121 0.731577 -0.22002 0.858787 0.462684 -0.839246 0.157502 0.520441 -0.901505 0.40741 0.145967 -0.974386 0.0665406 -0.214813 -0.96071 0.0185271 -0.276934 -0.994947 0.0851821 -0.0531431 -0.997032 0.0724883 0.0259355 -0.991827 0.103498 -0.0746103 0.272552 0.706075 0.653585 0.298166 0.596752 0.744973 0.631685 0.580977 0.513263 0.912687 0.316624 0.258364 0.0681087 0.997458 0.0209683 0.920906 0.388414 -0.0326778 0.712722 0.433631 -0.551355 0.627266 0.703675 -0.333735 0.365599 0.730824 -0.576397 0.338819 0.653949 -0.676426 0.950668 0.292712 -0.102711 0.981101 0.00858058 0.193306 0.990465 0.0656439 0.121118 0.990471 0.0621592 0.122893 0.991751 0.0979914 0.0826283 0.996145 0.082418 0.0300242 0.888867 0.26556 0.373354 -0.138142 0.608017 0.781813 -0.14512 0.60266 0.784692 -0.115972 0.58019 0.806182 -0.113995 0.584233 0.803541 -0.102242 0.564733 0.818916 0.358386 -0.50664 -0.78414 0.00228184 -0.607871 -0.794033 0.012316 -0.607421 -0.794285 0.00743714 -0.578029 -0.815982 0.0288218 -0.582605 -0.812244 0.0225847 -0.60871 -0.793071 -0.131145 -0.557208 0.819951 -0.0443276 -0.729382 0.682669 -0.0557922 -0.780965 0.622078 -0.0533666 0.771806 0.633615 -0.0294632 0.823441 0.566636 -0.977969 -0.0472553 -0.203332 -0.979284 0.0872401 -0.182736 -0.0672112 0.698871 0.712083 -0.736436 0.0792172 0.671853 0.0588265 -0.78321 -0.618968 0.0601129 0.781371 -0.621165 -0.987317 0.016314 0.157919 -0.994657 -0.0734802 -0.0725073 -0.991979 0.126396 0.00133347 -0.989621 0.0563676 0.132184 0.0546157 0.658179 -0.750878 -0.0606886 0.789179 0.611157 -0.0660455 0.772189 0.631951 -0.0599496 0.775597 0.628375 0.0420413 0.787092 -0.615401 0.0499535 -0.759042 -0.649122 0.135208 -0.806649 -0.575357 0.996655 -0.0690068 0.0437825 0.974441 0.0324454 0.222289 0.407421 -0.757021 -0.51081 0.374683 -0.664614 -0.646452 0.728554 -0.554605 -0.402023 0.943444 -0.314723 -0.104222 0.992947 -0.0834843 0.0841843 0.917985 -0.343725 0.197878 0.720801 -0.100632 0.685799 0.680095 -0.62946 0.375834 0.402054 -0.510692 0.759965 0.280437 -0.887588 0.365436 0.273464 -0.890697 0.363149 0.996807 -0.0431739 -0.0671633 0.990256 -0.107569 0.0884473 0.943886 -0.305672 -0.125075 -0.0671148 -0.792478 0.606197 -0.123826 -0.809105 0.57447 -0.0719411 -0.837838 0.541158 -0.998974 -0.0420848 -0.0167313 -0.939521 -0.265732 0.21607 -0.645121 -0.595759 0.478425 -0.65392 -0.549257 0.520294 -0.734991 -0.565065 -0.374819 0.0212709 -0.914233 0.404631 -0.941984 -0.284319 0.178405 -0.988168 -0.119148 -0.0965771 -0.170559 -0.767232 -0.618276 -0.35519 -0.735806 -0.576567 -0.360507 -0.704532 -0.611285 -0.764217 -0.214458 -0.60826 -0.862737 -0.403703 -0.304482 -0.985705 -0.111521 -0.12629 -0.996866 -0.0691515 -0.0384198 -0.99798 -0.0616636 0.0153044 -0.117841 -0.990218 -0.0747113 0.0521995 -0.996747 0.061409 -0.0571654 0.994738 -0.0850154 -0.0394382 0.0138545 0.999126 0.0432523 -0.33667 -0.940629 0.31878 -0.0486165 -0.946581 -0.0932638 0.354566 -0.930368 -0.228483 0.837876 0.495741 0.998703 0.0502251 -0.00832635 0.635101 0.693673 -0.339801 0.97386 -0.179611 -0.13906 0.808174 -0.41711 0.41578 0.942346 0.312053 -0.120861 0.956143 0.274322 0.102658 0.950387 -0.134055 0.280702 0.0763481 -0.822681 -0.563353 0.891815 -0.341911 0.296249 0.246594 -0.963565 0.10361 -0.173104 -0.835196 -0.521998 -0.97386 0.179611 0.13906 -0.635101 -0.693673 0.339801 0.108941 0.425434 -0.898408 -0.0799224 -0.626114 0.775625 -0.104133 -0.62499 0.773656 -0.127588 -0.685487 0.716819 -0.0952357 -0.681217 0.725861 -0.0919888 -0.693516 0.714544 -0.0674653 -0.689726 0.720921 -0.0652238 -0.681678 0.72874 0.0158218 0.55509 -0.83164 0.0036255 0.570443 -0.821329 0.0458306 0.586742 -0.808476 0.0178738 0.613445 -0.789535 0.0168079 0.613468 -0.789541 0.0700445 0.55829 -0.826684 0.0743427 0.571776 -0.817035 -0.0661714 0.695345 0.715623 -0.134742 0.699083 0.70223 -0.125359 0.646088 0.752898 -0.126819 0.647322 0.751592 0.0698118 -0.575338 -0.814931 0.0732597 -0.545601 -0.834837 -0.000564862 0.650682 -0.75935 0.0120618 0.652701 -0.75752 -0.00635305 0.675902 -0.736964 0.0387859 0.67706 -0.734905 0.0389071 0.688663 -0.724037 0.0622975 0.686177 -0.724762 -0.142443 -0.544791 0.826385 -0.13787 -0.572339 0.808344 -0.101796 -0.580104 0.808156 -0.156884 -0.606132 0.779738 -0.123309 -0.606117 0.785759 -0.0714689 -0.563523 0.823003 -0.0711881 -0.564249 0.82253 -0.074046 0.572048 0.816871 -0.0715306 0.553059 0.830066 0.0636023 -0.687574 -0.723324 0.032298 -0.707076 -0.7064 0.0251442 -0.668329 -0.743441 0.00605938 -0.674685 -0.738081 -0.0027928 -0.648663 -0.761071 -0.0686405 -0.638708 -0.766382 -0.996066 0.0270227 -0.084393 -0.996234 0.00738574 -0.0863847 0.995613 -0.0290657 0.0889436 0.996203 -0.00214031 0.0870322 -0.709703 0.695704 -0.110987 -0.0594219 0.998179 -0.0103915 0.0122039 -0.999913 0.00510235 -0.995779 -0.032333 -0.0858961 -0.996106 -0.0052664 -0.0880119 0.996353 -0.00784013 0.0849639 -0.0870419 -0.569639 0.817273 -0.245229 -0.96943 -0.00830259 0.00146769 -0.999991 -0.00392046 0.0285068 0.999591 0.00249388 0.0595639 0.998196 0.00759414 0.25323 -0.967351 0.0103359 -0.727696 -0.681153 -0.0805532 0.703617 0.707594 0.0650629 -0.835115 0.545201 -0.0730629 -0.834843 0.54562 -0.0730577 0.752916 -0.654018 0.0733366 0.634028 0.77085 0.0616423 0.452417 0.280556 -0.846527 0.994979 0.0442779 0.0897529 0.856167 0.201665 0.47572 0.00658779 0.347881 -0.937516 0.0411998 -0.68395 -0.728365 0.638104 0.536285 0.552469 -0.058081 0.644372 0.762504 0.0878431 -0.7034 -0.705345 0.0817177 -0.69905 -0.710388 -0.13555 -0.499759 0.855492 0.036954 -0.837424 -0.545303 0.759496 -0.386387 -0.523327 -0.0727653 -0.0730849 -0.994668 -0.0924427 0.684133 0.723475 -0.0465559 0.7028 0.709863 -0.0361712 0.750977 0.659336 0.0580241 0.715151 -0.696558 0.0821386 0.770963 -0.631561 -0.81068 -0.21334 -0.545238 0.698536 0.501867 -0.510076 -0.851849 0.190288 0.488 -0.86051 0.29689 -0.413978 -0.0988253 0.851138 -0.515555 0.712586 -0.00965354 0.701519 0.564547 -0.0996857 0.819359 -0.561397 0.0957747 0.821986 -0.956083 0.129077 0.263143 -0.397425 0.862965 0.312003 -0.837752 0.4629 -0.289645 -0.824696 0.486478 -0.288471 -0.772101 0.567054 -0.286896 -0.256503 0.816643 0.517011 -0.110693 0.88103 0.459927 0.210863 0.230469 0.949958 -0.547033 0.575277 0.608122 -0.423257 0.214652 0.880215 -0.616163 0.0589193 0.785412 -0.717988 0.0996127 0.688891 -0.715492 0.103851 0.690859 -0.818506 0.0295205 0.573738 0.838058 0.470377 0.276414 0.529207 0.827033 -0.189622 0.774511 0.340028 -0.533398 0.696569 -0.0140502 -0.717352 0.00637951 0.41699 -0.908889 0.129507 0.81052 -0.571213 -0.367552 0.537974 -0.75861 0.461186 0.201663 -0.864083 0.760375 -0.00590994 -0.649458 0.726372 0.0867508 -0.681805 0.66586 0.130495 -0.734576 0.637686 0.0212805 -0.770002 0.641407 0.0251807 -0.766788 0.955631 0.157427 -0.248969 0.584116 0.580972 -0.566816 0.53192 0.647741 0.54543 0.522371 0.603183 0.602743 0.548089 0.604404 0.578183 0.571699 0.581525 0.578782 0.562504 0.562987 0.605504 -0.604184 0.550267 -0.576339 -0.875204 -0.326582 -0.356879 -0.616797 -0.611198 -0.495982 -0.628774 -0.578298 -0.519821 -0.614307 -0.584714 -0.529846 -0.622846 -0.560106 -0.546209 0.583821 -0.555641 0.591959 -0.611354 0.534951 -0.583159 0.465758 -0.764103 0.446336 0.428795 -0.798316 0.42288 0.467915 0.75891 0.452892 0.437029 0.804466 0.402294 -0.736562 0.1371 0.662329 -0.721135 -0.0932875 0.686485 -0.760995 0.156762 0.629534 -0.780927 -0.107917 0.615229 0.364829 -0.819282 0.442353 0.527534 -0.678972 0.510594 0.518903 0.689966 0.504665 0.523377 0.685243 0.506477 -0.419803 -0.820709 -0.38756 -0.456323 -0.771015 -0.44419 -0.403173 0.829352 -0.386816 -0.433099 0.792659 -0.429088 -0.648489 -0.12613 0.750702 -0.642946 0.053541 0.764038 -0.328687 -0.15791 0.931144 -0.695231 0.0507597 0.716992 -0.482822 0.848656 -0.216023 -0.42131 -0.822485 -0.382121 -0.525093 0.685028 -0.50499 -0.541632 0.666473 -0.512297 -0.522852 -0.688292 -0.502872 -0.524163 -0.685152 -0.505787 0.465119 0.74987 0.470488 0.450434 0.770792 0.450542 0.460208 0.804706 0.375042 -0.406919 0.826203 -0.389622 -0.433268 -0.801716 -0.41174 -0.466203 -0.770624 -0.434504 -0.490898 -0.757902 -0.429656 0.638098 0.0233486 -0.769601 0.0829456 -0.115828 -0.9898 -0.281429 -0.553228 -0.784051 -0.184679 -0.813754 -0.551088 0.570454 -0.377421 -0.729476 0.697174 -0.132509 -0.70455 0.695888 -0.131459 -0.706016 0.71791 -0.108326 -0.687656 0.789506 -0.294549 -0.538443 0.751259 -0.605395 -0.262883 0.842574 -0.524853 -0.120823 0.674421 -0.709329 0.20496 0.630632 -0.764627 0.132853 0.746349 -0.0227469 -0.665165 0.900852 -0.210824 -0.379498 0.401998 -0.819276 0.408883 0.463711 -0.832264 0.303825 0.449669 -0.778146 0.438505 -0.211429 -0.137447 0.967681 -0.387309 -0.725865 0.568429 0.305646 -0.481169 0.821619 0.312527 -0.3321 0.889964 0.311234 -0.567636 0.762183 0.184767 -0.599256 0.778944 -0.423656 -0.245379 0.871954 -0.648942 -0.0661171 0.75796 -0.68525 -0.114741 0.719212 -0.812592 -0.557231 -0.170843 -0.79197 -0.572455 -0.212318 -0.74236 -0.644139 -0.184355 -0.626617 -0.632402 0.455433 -0.91186 -0.300657 0.279494 -0.750028 -0.0782888 0.656756 -0.65384 -0.080743 0.752312 -0.625184 -0.0554057 0.778509 -0.0683049 -0.978804 0.193074 -0.0104148 -0.995198 -0.0973277 0.0926168 0.96979 -0.225675 0.0523553 0.996289 0.0683097 -0.642127 -0.402745 -0.65228 -0.679597 0.358961 -0.639762 0.301404 0.812175 0.499528 0.479203 0.192399 -0.856357 0.486558 0.168768 -0.857192 0.477 0.370378 -0.797052 0.741161 0.0617631 -0.66848 0.851319 -0.197779 -0.485941 0.851849 -0.190288 -0.488 0.447994 -0.298338 0.842791 0.513651 -0.854446 0.0780025 0.851849 -0.190288 -0.488 0.497889 -0.649314 0.574889 0.501156 -0.648801 0.572625 0.500406 -0.684957 0.529554 0.499409 -0.686158 0.528941 0.519211 -0.687993 0.507037 -0.616846 0.577835 -0.534423 -0.606642 0.599688 -0.521881 -0.625129 0.572187 -0.530863 -0.634764 0.596101 -0.491668 -0.592447 0.566512 -0.572775 0.502514 0.684991 0.52751 0.559622 0.644195 0.521379 0.497453 0.648701 0.575958 0.196998 0.768725 0.608485 -0.599799 -0.555825 -0.575586 -0.589133 0.639888 -0.493422 -0.592904 0.664805 -0.454422 -0.562046 0.655328 -0.504628 -0.53709 0.697128 -0.474917 0.540061 -0.568594 0.620511 0.567207 -0.587901 0.576757 0.562185 -0.573691 0.595673 0.520196 -0.60441 0.603395 0.531678 -0.604203 0.593513 0.594703 -0.564705 0.572221 0.595303 -0.562427 0.573838 0.592032 0.565323 0.574377 0.597305 0.55707 0.576974 -0.545563 -0.685725 -0.481812 -0.544913 -0.674012 -0.498776 -0.571172 -0.688144 -0.447459 -0.586094 -0.649944 -0.483805 -0.595898 -0.64815 -0.474139 -0.694685 0.00925156 0.719254 -0.691016 0.0539635 0.720822 0.695453 0.0102754 -0.718498 -0.560207 0.756437 -0.337596 0.0583515 0.996816 -0.0543432 0.0330853 0.998936 -0.0321311 0.0155745 -0.999749 -0.0161278 0.0389261 -0.998555 -0.0370456 -0.694343 -0.027062 0.719136 -0.694723 -0.0388003 0.71823 0.693134 -0.0275576 -0.720282 0.0189772 -0.999681 -0.0166604 -0.0144555 -0.999815 0.0126857 0.0373582 0.998723 -0.0340252 -0.587715 -0.533105 0.608597 -0.579328 -0.550601 0.601014 -0.411484 0.816028 0.405931 -0.580711 0.549891 0.600329 0.697899 0.0757849 -0.712175 0.267923 0.917464 -0.294071 0.411752 -0.225047 -0.883071 0.949752 -0.257347 -0.178167 0.691612 -0.0352505 -0.721408 -0.786991 -0.159991 -0.59586 0.404194 0.036547 0.913943 0.485755 0.664932 0.567369 -0.503298 -0.716214 -0.483454 -0.481133 -0.7253 -0.492394 -0.391699 -0.796204 -0.46112 0.321377 -0.747397 -0.581476 0.592046 -0.501683 0.63071 -0.695658 0.343414 -0.630973 0.571811 0.58161 0.578587 0.594682 0.558992 0.577825 0.566256 0.572183 0.593263 -0.557517 0.626243 -0.544972 0.843962 0.535453 -0.0319061 -0.886366 0.453647 -0.092524 0.221785 0.949464 -0.222101 0.998466 0.0552523 0.00362543 0.253957 0.967149 0.0113569 0.120915 0.992601 -0.0110584 -0.984251 0.175892 0.017686 -0.98006 0.19748 0.0220041 0.34292 0.937997 0.0506787 -0.459234 -0.88816 -0.0166435 0.392236 -0.919849 -0.00533459 0.088906 -0.995657 0.0276174 -0.0326278 0.00694767 0.999443 0.995827 -0.088092 0.0238344 0.184579 -0.233601 0.954652 0.350363 -0.926068 0.140158 -0.495155 0.217168 0.841225 -0.430348 -0.894158 0.123622 -0.542637 0.836055 0.0809776 0.0621914 0.988982 0.13434 0.993164 0.0335422 0.111804 0.595247 -0.8019 0.0513532 -0.953591 -0.298448 0.0399176 0.519393 -0.685495 -0.510222 -0.993514 0.0254133 0.110836 0.178542 -0.543264 -0.820358 -0.287946 -0.377917 -0.879924 0.0429637 -0.086316 -0.995341 0.114819 0.157057 -0.980892 -0.763556 -0.645672 -0.00947618 0.785087 0.457912 -0.417078 -0.190426 0.876828 0.441486 0.271788 0.400399 0.875107 0.961581 -0.100524 0.255453 -0.511111 0.394016 -0.763883 -0.997741 -0.00746662 -0.0667657 0.19188 -0.399808 0.89629 0.556302 -0.830974 0.00313515 0.00943718 -0.966755 0.255531 -0.383399 -0.898565 -0.213508 -0.253576 -0.916541 -0.309278 -0.853522 -0.369617 -0.367265 -0.704448 -0.340263 -0.622876 -0.577959 0.181645 -0.795593 -0.895609 0.406667 -0.180298 -0.184273 0.9128 -0.364473 0.183838 0.906076 0.381091 0.234744 0.92034 0.31284 0.672471 0.366243 0.643155 0.567592 0.38517 0.727656 0.672043 -0.364804 0.64442 -0.74148 -0.563298 0.36456 0.200518 -0.895575 0.397161 -0.00823411 -0.956493 -0.291639 -0.287383 -0.889175 -0.356061 0.158654 -0.594937 -0.787959 -0.165117 -0.43502 -0.885152 0.305031 0.0150995 -0.952223 0.0141074 0.142239 -0.989732 0.126369 0.604641 -0.78641 -0.519363 0.640293 -0.565939 0.622255 0.767889 0.152134 -0.682809 0.50089 0.531866 0.213185 0.403291 0.889892 0.164116 -0.408524 0.897872 -0.315121 -0.0989728 0.943877 -0.0045753 0.113959 0.993475 0.109419 0.243479 0.963714 -0.157631 0.777306 0.609055 -0.208036 0.727235 0.654103 -0.024445 0.983235 -0.180696 -0.059772 0.985275 -0.160192 -0.0181677 -0.968842 -0.247013 0.0807148 -0.957316 0.277547 -0.20954 -0.750117 0.62723 0.205975 -0.423813 0.882019 0.994845 0.0984071 -0.0244725 0.992281 0.116807 -0.0416571 0.220377 0.974754 0.035895 -0.0178426 0.989228 -0.14529 -0.897868 0.406371 0.169399 -0.978107 -0.125453 -0.166039 -0.740967 -0.669761 0.04888 -0.0322981 -0.98307 -0.180364 0.295851 -0.952185 0.0762611 0.934639 0.324123 -0.146271 0.666182 0.711928 0.22217 -0.234737 0.952358 -0.19471 -0.850539 0.511729 0.121317 -0.981995 0.0322669 -0.186133 -0.666653 -0.721439 0.187349 0.220971 -0.949638 -0.222169 0.647362 -0.748016 0.146271 -0.0136735 0.84525 0.534197 0.0403252 0.358508 0.932655 0.0155988 0.416106 0.909182 -0.00316948 -0.17272 0.984966 -0.0669998 -0.818048 0.571234 0.0295113 -0.984223 0.174457 -0.0288791 -0.991279 -0.128579 0.0225636 -0.934565 -0.355077 -0.0265022 -0.797199 -0.603134 0.0385804 -0.598484 -0.800206 -0.0446472 -0.267914 -0.962408 0.0441723 0.164301 -0.985421 0.0242942 0.622437 -0.782293 -0.0354978 0.98421 -0.173406 0.756564 0.276194 0.592729 0.00502933 -0.332479 -0.943097 0.915297 0.389986 0.100714 0.86366 0.404287 -0.301072 0.819557 -0.0699898 -0.568708 0.866719 0.399606 -0.298518 0.859023 0.397597 -0.322484 0.850978 0.402502 -0.337386 0.849492 0.393357 -0.351616 0.860285 0.381803 -0.33784 0.853554 0.397316 -0.337024 0.862225 0.389609 -0.323687 0.861016 0.391716 -0.324361 0.859263 0.394996 -0.325032 0.831668 0.454935 -0.318374 0.406639 0.670436 -0.620613 -0.0626225 -0.871008 0.487261 -0.884488 -0.353632 0.304344 0.850516 0.406524 -0.333708 0.858169 0.395061 -0.327832 0.857032 0.397176 -0.32825 0.859541 0.400537 -0.317427 -0.696779 0.00177849 0.717284 -0.694635 0.00295679 0.719357 -0.69466 0.000527338 0.719338 -0.693401 -0.000265606 0.720551 -0.684488 -0.00451642 0.72901 -0.690767 -0.00392886 0.723067 -0.703756 0.0699898 0.706985 -0.69424 0.00029363 0.719743 -0.682459 0.0479017 0.729353 -0.668782 -0.0168893 0.743267 -0.607275 0.451943 0.653425 -0.0210654 0.999214 0.0335824 -0.022098 0.999431 0.0254905 -0.0224824 0.999427 0.0252946 -0.0189388 0.999493 0.0255784 -0.0244077 0.999417 0.02386 -0.0226529 0.999175 0.0337121 -0.0553427 0.996825 0.0572447 -0.0564841 0.996706 0.0582002 -0.027015 0.999331 0.0246537 -0.03718 0.998884 0.0291265 -0.0201801 0.0718618 0.99721 -0.000516214 0.000601659 1 5.63663e-06 0.000281598 1 -0.00950989 -0.00406593 0.999947 -0.00102268 3.94275e-05 0.999999 0.000820339 0.00129828 0.999999 0.000105542 0.000226928 1 -0.000809451 1 0.00052167 -0.000565317 1 0.000516864 6.87279e-05 1 0.000680477 -0.0618567 0.991157 0.117397 0.0681423 0.600373 0.796811 -0.999733 0.00944965 -0.0210842 -1 0 0 -1 1.87307e-05 3.57441e-05 -1 -6.04106e-05 8.09906e-05 -0.999996 -0.00168608 -0.00228479 -1 0 0 6.24748e-05 -0.412055 0.911159 -0.0054279 -0.408981 0.912527 -0.270998 -0.961409 -0.0474745 -0.996206 2.18293e-05 -0.0870246 -0.996178 -0.000140863 -0.0873462 0.426107 0.80855 0.405808 -0.860059 -0.280637 -0.426078 0.431776 0.891883 0.13459 -0.695694 -0.000123887 0.718338 -0.692977 -0.000321403 0.72096 0.173547 -0.932922 -0.315495 -0.096884 -0.463396 0.880839 -0.0764249 -0.398086 0.914159 -0.142138 -0.456248 0.878427 -0.0786246 -0.432032 0.898424 -0.0213671 0.880013 0.474469 -0.0434383 0.96322 0.26518 -0.106928 0.38999 0.91459 -0.0796928 0.425987 0.901213 -0.0786028 0.437697 0.89568 -0.0833554 0.433297 0.897388 -0.812131 0.447973 0.373851 -0.0302604 -0.997634 -0.0617236 -0.995634 0.0134652 -0.0923668 -0.996193 8.51245e-05 -0.0871782 -0.996197 3.96216e-05 -0.0871279 0.117998 -0.641046 -0.758377 -0.00554314 -0.832487 -0.554017 0.0668211 0.728823 -0.681433 0.0780234 0.743131 -0.664582 0.0199058 0.803367 -0.595151 0.0678776 0.848383 -0.525014 -0.020878 -0.00073515 -0.999782 -0.53202 0.00502802 -0.846717 -0.0756781 0.0909977 -0.992971 -0.192764 0.0151822 -0.981128 0.01632 -0.00750153 -0.999839 0.000242805 0 -1 -0.00406431 0.00236067 -0.999989 -0.00172454 -0.000240048 -0.999999 -0.00217218 -0.00024745 -0.999998 3.33394e-05 7.12574e-06 -1 0.00317543 -0.000551885 -0.999995 -0.160549 0.986881 -0.0170239 -0.0444192 0.951202 -0.305356 -0.0452658 -0.931356 -0.361286 -0.180589 -0.895779 0.406161 -0.0496417 0.612225 0.789124 -0.0611286 0.779484 0.623433 -0.0341856 0.824472 0.564869 -0.0588168 0.863993 0.500056 0.104396 0.89376 -0.436227 0.0713311 -0.8959 -0.438491 -0.0950138 -0.91859 0.38362 0.086143 -0.838009 -0.538813 0.037567 -0.809458 -0.585975 -0.215484 0.504897 0.83585 -0.412362 0.814236 -0.408628 -0.406014 -0.821856 -0.399632 -0.42625 -0.812754 -0.397168 -0.413371 0.827175 -0.380666 0.518415 -0.685264 0.511526 0.532766 -0.6701 0.516843 0.489426 -0.699777 0.520361 0.529667 -0.679471 0.507713 0.43802 0.719736 0.538626 -0.188671 0.588838 0.785922 -0.00569073 0.999975 0.00427334 -0.0215931 0.999636 0.0162057 -0.0211223 -0.999715 0.0111693 -0.0103405 -0.999941 0.00345577 -0.871523 0.108791 -0.478133 0 0 -1 -0.00124981 2.31493e-05 -0.999999 -0.933878 -0.104117 -0.342099 0.967653 -0.0478265 -0.247709 -0.0651941 0.563105 -0.82381 -0.319114 -0.947127 -0.0334054 -0.0482936 -0.899682 -0.433867 0.00130143 0.00531977 0.999985 0.0100068 0.0668883 0.99771 -0.000234795 0.00373662 0.999993 0.00149871 -0.000961812 0.999998 -0.00108776 -0.00899362 0.999959 0.00479403 0.00270926 0.999985 -0.00402256 -0.00256473 0.999989 -0.00245125 -0.0251186 0.999681 0.00249072 0.00173857 0.999995 -0.0241407 -0.0128209 0.999626 -0.000162432 -0.000366935 1 0.000288932 -8.55942e-05 1 5.02851e-05 2.12598e-05 1 0.00128749 -0.000639228 0.999999 -3.94904e-05 -1.6696e-05 1 -3.43641e-06 2.52795e-07 1 0 0 1 -0.000299119 -7.48759e-06 1 0.750255 -0.000646235 -0.661149 0.264551 -0.404455 -0.875459 0.214004 0.527349 -0.822256 0.278623 0.575182 -0.769113 0.110816 0.956018 -0.271568 0.253929 0.953678 -0.161303 0.302254 0.391702 -0.869029 0.308995 0.38861 -0.868046 0.298686 0.391147 -0.870512 0.30602 0.401073 -0.863419 0.305747 0.401979 -0.863094 0.295156 0.394893 -0.870025 0.294726 0.395475 -0.869906 0.28147 0.374247 -0.88358 0.296118 0.394225 -0.87 0.64925 0.360044 -0.669958 0.311434 -0.407274 -0.858567 0.312279 -0.404662 -0.859494 0.320933 -0.399194 -0.858863 0.304717 -0.385275 -0.87104 0.300805 -0.390756 -0.869958 0.304481 -0.391285 -0.868439 0.352301 -0.367779 -0.860594 0.32462 -0.417701 -0.848615 0.858545 -0.393839 -0.328316 0.85818 -0.394437 -0.328552 0.858978 -0.394826 -0.32599 0.860784 -0.391081 -0.325739 0.859355 -0.393876 -0.326145 0.856748 -0.392355 -0.334724 0.860107 -0.384591 -0.33512 0.859772 -0.393568 -0.325419 0.854023 -0.391116 -0.343035 0.85967 -0.3941 -0.325043 0.861857 -0.38475 -0.330409 0.858839 -0.395986 -0.324947 0.858812 -0.396066 -0.324921 0.846552 -0.426479 -0.318538 0.858277 -0.402882 -0.317878 0.86137 -0.395309 -0.319018 0.86374 -0.388815 -0.320586 -0.788111 0.393701 -0.47316 0.788513 -0.395259 0.471187 0.790676 -0.393977 0.46863 -0.76178 0.427021 -0.48718 0.788646 -0.400343 0.466651 0.789961 -0.402951 0.46216 0.789098 -0.396173 0.469438 0.786147 -0.409484 0.462921 0.784253 -0.413248 0.462788 0.789546 0.395155 0.469543 0.789588 0.395015 0.469588 0.788699 0.396899 0.469495 0.793797 0.393108 0.46406 0.791385 0.397025 0.464844 0.793192 0.391294 0.466621 0.787304 0.39554 0.472969 0.787779 0.395262 0.472411 0.789623 0.395342 0.469255 0.935124 0.000707132 -0.354319 0.58536 -0.111761 -0.803034 0.935231 -0.000264808 -0.354039 0.000808131 0.000405048 -1 0.000620944 0 -1 0.749213 -0.0305158 -0.661626 0.721012 0.00462849 -0.692907 0.3874 0.00256174 -0.921908 0.359692 -0.0227559 -0.932794 0.873762 0.0553545 0.483194 0.858948 0.00288053 0.512054 0.000350976 0.815967 -0.578099 0.000221301 0.816028 -0.578012 0.234474 0.787331 -0.570204 0.362707 0.77456 -0.518171 0.525169 0.703643 -0.478628 0.740641 0.588392 -0.324416 0.806352 0.507081 -0.30441 0.796124 0.522389 -0.305444 0.631412 0.775217 -0.0189113 0.84689 0.483961 -0.220362 9.60827e-06 0.99352 0.113658 0.000167154 0.993282 0.115722 0.000668439 0.993456 0.114212 -0.000255346 0.99354 0.113484 -6.48688e-05 0.993381 0.114868 -0.000635995 0.993521 0.113649 -0.000201501 0.993562 0.113291 0.00069947 0.993458 0.114198 -0.000321414 0.993512 0.113728 -0.000503648 0.993493 0.113893 -0.000306604 0.993459 0.114193 -0.00035327 0.993414 0.114583 0.762334 0.463091 0.452098 0.858762 0.417854 0.296521 0.760158 0.474145 0.444237 0.760171 0.471986 0.446507 0.0700227 0.699282 0.711408 0.564754 -0.057865 0.823228 0.303608 0.0317646 0.952267 0.934941 -0.00388214 -0.354781 0.935263 -0.000439079 -0.353953 0.978376 0.0114094 0.206518 0.982882 -0.00585905 0.184141 0.981851 -0.00259243 -0.189639 0.982123 -0.0035455 -0.188206 0.000830859 -0.000454133 -1 0.000620946 0 -1 0.74739 0.0465644 -0.662752 0.673039 -0.0357822 -0.738741 0.365972 0.0171963 -0.930467 0.359341 0.023169 -0.932919 0.860114 0.00103708 0.5101 0.858571 -0.00430244 0.512678 0.000322188 -0.8159 -0.578193 3.55544e-05 -0.816028 -0.578012 0.223182 -0.794182 -0.565212 0.207514 -0.798675 -0.564851 0.463659 -0.728426 -0.504398 0.521205 -0.716124 -0.464232 0.763271 -0.595141 -0.251445 0.785449 -0.513174 -0.346008 0.766523 -0.564106 -0.306964 0.786728 -0.53787 -0.30291 0.856236 -0.500149 0.129271 0.840772 -0.516349 0.162747 0.862626 -0.483229 -0.149555 0.760522 -0.473645 0.444147 0.761323 -0.465557 0.451268 0.692812 -0.462879 0.552951 0.575384 0.0667932 0.815152 0.226332 -0.041088 0.973183 0.640391 -0.368132 -0.674076 0.64842 -0.360961 -0.670268 0.927362 0.365087 0.0819187 0.318278 -0.00459152 -0.947986 0.933513 -0.00221899 -0.358538 0.932037 0.00548449 -0.362321 0.915949 0.202579 -0.346408 0.884739 0.313302 -0.345079 0.330511 0.00180808 -0.9438 0.693697 4.32221e-05 -0.720267 0.694223 -0.0001599 -0.71976 0.694555 -0.00011211 -0.71944 0.694577 0.000192736 -0.719419 0.694746 -0.00381947 -0.719245 0.695346 -0.000744083 -0.718675 0.695306 -3.57761e-06 -0.718714 0.571378 -0.0474257 -0.819315 0.694855 -0.000177143 -0.719149 0.695049 -0.000601619 -0.718962 0.69465 0.000248346 -0.719348 0.694173 -0.00104076 -0.719808 0.694466 -0.00124008 -0.719524 0.37871 0.334094 -0.863111 0.716244 0.157651 -0.679809 0.693627 -0.000525492 -0.720334 0.69439 -0.000876094 -0.719598 0.996142 0.00030957 0.0877594 0.996137 0.000408576 0.0878121 0.996287 0.00122825 0.0860831 0.996095 0.000427479 0.0882908 0.99616 -0.00113124 0.0875399 0.996139 0.000327419 0.0877934 0.996196 0.0039687 0.0870492 0.996256 -0.000256411 0.0864577 0.996183 0.000501961 0.0872837 0.996021 0.0157455 0.0877168 0.995814 -0.000160185 0.0914079 0.996761 0.00308777 0.0803572 0.996136 0.000401184 0.0878275 0.996147 0.000367242 0.0877016 0.996227 -0.000431562 0.0867856 0.996311 0.000348719 0.085818 0.996265 0.000205574 0.0863465 0.929119 -0.360275 0.0833018 0.854169 0.00286395 0.519988 0.856742 0.000416728 0.515745 0.806442 -0.372147 0.459519 0.832616 -0.401925 -0.38106 0.626916 0.380082 -0.680083 0.316558 0.395054 -0.862394 0.863822 0.388776 -0.320412 0.924626 -0.375159 0.0657463 0.864365 -0.396578 -0.309191 0.000549082 0.999998 -0.00185386 -0.000188987 0.999999 -0.00144969 0 1 0 0.000980815 0.999964 -0.00839894 0.00239894 0.999997 0.000960324 0.0113297 0.999858 -0.0124476 0.000292469 1 -3.40327e-05 -0.00122012 0.999999 0.00045992 -0.000879462 0.000303555 -1 0.00147727 -0.00215471 -0.999997 0.00065524 0.3597 -0.933068 -6.08809e-05 0.360172 -0.932886 -0.00321249 -0.357475 -0.933917 -0.000395657 -0.359812 -0.933025 0 -0.648347 -0.761345 0.0113387 -0.626851 -0.779057 0 0.648347 -0.761345 4.0942e-08 0.648347 -0.761345 0.732805 0.580549 -0.354909 0.751946 0.552283 -0.359945 0.563587 0.361204 -0.7429 0.660292 0.639129 0.394371 0.507165 0.558706 0.656226 0.695076 0.606053 0.386743 0.0122203 0.725049 -0.688588 0.000127577 0.698811 -0.715307 6.59803e-05 0.698861 -0.715257 0.00119965 0.698222 -0.71588 0.73749 -0.577164 -0.350699 0.753689 -0.541482 -0.372492 0.455546 -0.787657 0.414819 0.669583 -0.620483 0.40824 5.7214e-07 -0.698869 -0.71525 0.00759237 -0.684429 -0.72904 0.00543669 -0.69178 -0.722088 0.00887655 -0.68928 -0.724441 -1.29476e-06 -0.698872 -0.715247 0.000578291 -0.592414 0.805633 2.93303e-07 -0.59059 0.806972 0.000438673 -0.591832 0.806061 2.64122e-05 -0.993533 0.113548 -0.000140131 -0.993213 0.116314 -0.000546437 -0.993706 0.112015 -0.000264271 -0.99348 0.114004 -0.000779084 -0.99353 0.113568 -0.00141011 -0.992632 0.121163 -2.45987e-05 -0.993734 0.111775 0.000569098 -0.993433 0.114416 0.000966342 -0.993477 0.114028 0.00011531 -0.993568 0.113234 0.000949925 -0.993572 0.1132 -0.000782474 -0.99352 0.113657 0.124668 -0.117225 0.985249 0.35823 0.307624 0.881498 -0.0351146 0.701291 0.71201 0.230551 0.808142 0.54199 0.50919 -0.297317 0.807669 -0.315001 0.0452476 0.948012 9.71206e-05 0.819928 0.572466 0.000729798 0.822514 0.568744 0.00112499 0.820009 0.572349 -0.264363 -0.236435 0.934992 0.000947847 -0.819709 0.572779 0.00106326 -0.818973 0.573831 0.00120845 -0.819996 0.572368 -1.99389e-05 0.997567 0.0697204 -3.3772e-05 0.997566 0.069729 -0.000145838 0.997555 0.0698869 0.000143218 0.592491 0.805577 0.000910933 0.594504 0.804092 0.00011592 0.592385 0.805655 -6.94004e-06 -0.997564 0.06976 -6.97885e-05 -0.997558 0.0698442 -9.47689e-07 -0.997564 0.0697569 -0.496927 0.239784 0.834006 -0.594573 0.784372 -0.176758 -0.707849 5.62353e-05 0.706364 -0.707109 0 0.707105 -0.670474 -0.317699 0.670471 -0.702029 -0.355174 0.617257 5.08303e-06 -2.86094e-05 1 2.82561e-06 -3.21665e-05 1 3.46362e-05 4.44247e-06 1 -2.28282e-05 3.14917e-05 1 -4.00382e-05 7.65587e-06 1 1.05281e-05 -3.93586e-05 1 4.60879e-07 -2.5552e-05 1 0 0 1 0 0 1 1.76696e-05 5.01009e-05 1 -1.47202e-05 -4.29179e-05 1 -6.13729e-07 -1.70133e-05 1 0 0 1 0 0 1 0 0 1 0 0 1 -7.60242e-06 0 1 1.21458e-05 2.26342e-05 1 -0.00195868 -0.999992 0.00349053 -0.00364378 -0.999822 -0.0185093 -9.82542e-05 -1 0 0 -1 -0.000803668 0.000548826 -0.999999 -0.00110419 0.00118836 -0.999968 -0.00788671 0.00943705 -0.999908 -0.0097108 0.00366525 -0.999993 -0.000916515 0.000956125 -0.999999 -0.00118444 -0.00105421 -0.999999 0.000862055 0.00414098 -0.999991 0.000201765 -0.000201937 -1 6.53204e-05 0.000979317 -0.999999 -0.000316779 0.0017717 -0.999997 -0.00154888 0.000100595 -1 5.28793e-05 -6.00965e-05 -1 3.52646e-05 -0.00163359 -0.999998 -0.00110475 -6.50377e-05 0.999774 0.021265 -0.00148948 0.999995 0.00280082 0.273188 0.941438 0.197644 0.00913779 0.999958 0.000969362 0.000123528 1 4.86172e-05 -0.96721 0.253483 0.0158675 -0.908392 0.359445 0.213594 -0.373396 0.925162 0.06819 -0.411475 0.909179 0.0638932 -0.750155 0.659938 0.0418168 -0.875708 0.481538 0.0354583 -0.983478 -0.130541 -0.125422 -0.932453 -0.277282 0.231615 -0.967551 -0.252156 0.0161899 -0.750395 -0.65963 0.0423612 -0.877367 -0.478477 0.0358798 -0.149849 -0.986335 0.0684797 -0.329617 -0.941247 0.0735309 -0.45396 -0.888829 0.062472 -0.632574 0.718369 0.289476 -0.998841 -0.0401176 0.0266059 -0.999999 0 0.00139073 -0.999999 -2.16985e-06 0.00150842 -0.685289 -0.00620117 0.728245 -0.74203 -0.0282819 0.66977 -0.653298 -0.724403 0.220095 -0.998582 0.0520671 -0.0111098 -0.738918 0.0265878 0.673271 -0.999977 0.00435463 0.00515681 -0.688295 0.00630372 0.725403 -0.687863 0.671829 0.274756 -0.0262474 -0.882012 0.470496 -0.65095 0 -0.759121 -0.799217 -0.000542139 -0.601042 -0.0897906 0.995957 -0.00288089 -0.151855 -0.988335 -0.0115711 0.0651539 0.8651 0.49735 0.993662 0.110442 0.0209337 2.38419e-06 -0.599999 -0.800001 0 0.275002 -0.961444 0.998127 -0.0150612 -0.0592932 0.995257 0.000626774 -0.0972823 -0.500892 -0.498318 -0.707662 -0.501935 0.498419 -0.706852 0 -0.923209 0.384298 1 1.35539e-06 1.80718e-06 1 -2.98106e-05 0 0 -0.6 -0.8 -1 0 0 -1 0 0 -0.0743247 -0.293534 0.953055 0 -0.250945 0.968001 -0.010088 0.988285 -0.152284 -1 0 0 -1 0 0 -0.68694 -0.581372 -0.436028 0.0995051 0.874877 -0.474013 0.51052 0.515918 -0.687894 1 -7.59741e-06 -4.53576e-07 1 0 0 -0.45853 0.593953 0.661038 -1 0 0 -1 0.000159263 -9.50822e-06 0.220996 0.294029 0.929897 -0.681302 -0.0734171 0.728311 -0.68984 -0.177295 0.701917 0.0170329 -0.473253 0.880762 -0.0614025 -0.993682 0.0939416 -0.609411 -0.0811611 0.78869 -0.401261 -0.804414 0.438073 -0.0121116 -0.777853 0.62833 0.0108209 -0.999941 4.69224e-05 -0.0795316 0.96778 -0.238908 0.169823 0.386486 -0.906526 -0.915386 -0.397875 0.0613545 -0.0262888 -0.95136 0.306956 -0.605684 0.00167438 -0.795704 -0.21775 -0.000493742 -0.976005 0.00227434 -0.000189528 -0.999997 -0.537619 0.0160312 0.843036 -0.00479874 0.466222 -0.884655 -0.130688 0.193674 -0.972322 -0.00282992 -0.270984 -0.96258 -0.0305941 0.265237 -0.963698 0 0.855864 -0.517202 -0.0151777 0.997859 -0.0636216 -0.0611155 0.363158 -0.929721 -0.999589 0.02637 0.0112701 -0.0781068 0.996896 0.00985768 -0.0133738 0.728255 0.685175 -0.127881 0.869391 0.477289 -5.01562e-11 -1 1.68296e-05 -0.00135241 -0.999999 6.80832e-05 0.000710869 1 2.77683e-05 -0.000802449 1 -3.13456e-05 -0.99989 0.0110831 -0.00984451 -0.999963 -0.00824825 -0.00226913 -0.99995 0.00426902 -0.00904233 -1 -0.000629786 -0.000610392 -1 -7.24142e-05 -0.000664938 -0.999997 -0.000742071 -0.00236343 1 0 0 1 -5.13009e-07 -1.47419e-05 0.00324032 0.98865 -0.150202 -0.0511598 -0.919609 -0.389488 -0.853544 -0.0015352 -0.521018 0 1 0 0 1 0 -0.00142155 0.999985 -0.00521235 0 0.999977 -0.00674041 -0.00128465 0.999982 -0.00582202 -0.000958305 1 -5.91742e-05 -0.000381309 1 2.00528e-06 -0.999962 9.06232e-05 -0.0086685 -0.999889 -4.25893e-06 -0.0149152 -0.0814409 -0.969855 0.229671 -0.999642 0.0261796 0.00546794 -0.999569 0.0275628 -0.0100902 -0.999983 -0.00268867 0.00516627 -1 -0.00032953 0.000819433 -0.0180034 -0.834162 0.551226 -0.999988 -0.00301738 0.00384945 -0.999985 -0.00123988 0.0053884 -0.927383 -0.373468 0.0219681 -0.954258 -0.296548 0.0380939 -0.00171732 -0.999998 -0.000394845 -0.0321506 -0.999483 0 0.019829 -0.999787 0.00573744 -0.00071283 -1 -0.000206254 0 -1 -0.00051087 -0.000115928 -1 -0.000425067 0 -1 0 -1.81234e-05 -1 -5.24623e-06 0.125305 -0.425383 0.896297 -0.120092 0.723625 0.679665 -0.99894 -0.0174773 -0.0425891 -1 -0.000234077 -0.000609103 -1 -0.000362145 -0.000724174 -1 0.000148968 -0.000665019 -0.999999 -0.00133554 -0.000301987 0.99999 0.00434327 0.00106422 -0.999998 -0.00100087 -0.00171792 0 0 -1 0 0 1 0 0 -1 4.2781e-05 -8.92174e-06 -1 -1.08558e-05 1.25438e-05 -1 0.000599727 -0.000102864 -1 5.31411e-05 0.000210036 -1 0 0 -1 0 0 -1 0 0 -1 -5.46828e-05 -0.000241868 -1 -0.00053101 -0.000167617 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -3.20356e-05 1.55708e-05 -1 0 0 -1 -0.665559 -0.124178 0.735943 -0.0888952 -0.184771 -0.978753 -0.183146 -0.746083 0.64017 -0.0386056 -0.644903 -0.763289 -0.00671083 -0.987695 -0.156249 0.00976016 -0.957461 -0.288397 0.0292063 0.691862 -0.721439 -0.2159 0.448723 0.867199 0.0591387 0.146853 -0.987389 -0.0332725 0.602059 -0.797758 -0.0020136 -0.993038 -0.117774 9.49446e-06 0 -1 9.49478e-06 2.06023e-11 -1 -0.570706 -0.768239 0.290005 -0.998376 -0.0179531 -0.0540595 -0.998119 -0.0589936 0.0166624 -1 0 0 -0.999565 0.029091 0.00480807 -1 0 0 -1 -6.33623e-05 0 -1 -8.60133e-06 1.01004e-05 -1 -5.3685e-06 8.35549e-06 -1 0 0 -1 9.03138e-07 4.87325e-07 -1 6.74082e-07 1.74796e-06 -1 0 0 -1 9.07022e-07 7.78305e-07 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.999847 0.016978 0.00432865 -1 2.3267e-06 -2.04619e-06 -1 0 2.67835e-05 -1 -3.06094e-06 -6.90422e-06 -0.999548 -0.0296067 0.00522104 -0.999999 0.000161098 -0.0016162 -1 0 0 -1 0 0 -1 -4.90405e-06 2.84398e-05 -1 -2.92938e-05 8.45145e-07 -1 -1.51695e-06 -1.3966e-06 -1 -4.72411e-06 1.59203e-06 0.0113512 0.942971 -0.33268 -0.07489 0.643558 -0.761724 0.0200107 0.677798 -0.734976 -0.00596067 -0.636664 -0.771118 -0.0183116 0.98676 -0.161149 -0.0105433 0.991702 -0.128122 -0.0159022 -0.998807 -0.046174 -0.000188624 -3.48655e-05 1 0.000229032 -0.000773231 1 0.00118385 -0.000232286 -0.999999 0 -0.00098633 1 -0.000766706 -5.98507e-07 1 -0.00173727 -0.00272642 0.999995 -0.034781 -0.99939 -0.00310222 -0.0389274 -0.999238 -0.00281349 -0.0364118 -0.999335 -0.00218735 -0.0341302 -0.999413 -0.00298572 -0.0348648 -0.999387 -0.00304999 -0.0386022 -0.999252 -0.00247759 -0.123081 0.00031863 0.992397 0.0523394 4.24904e-06 -0.998629 0.0519111 0.000105982 -0.998652 -0.88357 -0.463971 -0.0635216 -0.36349 -0.93052 -0.04481 -0.929645 0.0644618 -0.362775 -0.912234 0.257927 -0.318282 0.784809 0.610879 0.104414 -0.163793 0.00947401 0.986449 -0.928217 0.0178489 0.37161 -0.915376 -0.0147348 0.40233 -0.939759 -0.22168 0.260215 -0.886258 -0.000554538 0.463193 -0.728541 0.0095979 -0.684935 -0.254021 -0.00823337 -0.967164 -0.034887 0.99939 -0.00133919 -0.0364175 0.999321 -0.00562982 -0.0343 0.999409 -0.00225583 -0.0445221 0.998981 0.00735912 -0.0338274 0.999419 -0.00408723 -0.0311594 0.999512 0.00230886 -0.0875665 0.996137 -0.00656983 -0.098738 0.995075 -0.00875853 -0.0510797 0.998607 -0.0132166 -0.041832 0.999103 0.00660718 -0.941849 0.215463 0.257868 -0.869442 0.489035 -0.0701063 -0.857014 0.509751 -0.0753715 -0.191816 0.570646 0.79848 -0.792421 0.180423 -0.58268 -0.115923 0.576513 -0.808823 -0.800549 0.00125183 -0.599266 -0.775367 0.00859697 -0.631452 -0.916028 -0.0829504 -0.392443 -0.861533 -0.501332 -0.08017 -0.849686 -0.5219 -0.0752 0.04353 -0.0499512 -0.997803 -0.0167997 -0.132717 -0.991012 0.00299299 -0.999028 -0.0439889 0.00103133 -0.0671756 -0.997741 -0.00511308 0.00478492 -0.999976 0.00844467 0.00380019 -0.999957 -0.999054 -0.0434539 0.00187288 0.0117901 -0.664491 -0.747204 -0.108421 0.000665952 0.994105 -0.111705 2.531e-05 0.993741 0.0602543 0.000805358 -0.998183 2.9517e-05 -1 -4.65295e-05 -3.68999e-05 -1 -7.50532e-05 -0.000726675 -1 -0.000202328 -0.999998 0.00120595 -0.00144273 -0.98631 -0.164835 -0.00477267 -0.341114 -0.940006 0.00553886 -0.000335661 1 -4.16144e-05 0.000145773 1 -0.000139957 9.36501e-07 1 -7.76469e-05 -0.999987 -0.00508861 0.000783 -0.999999 0.00123016 5.43667e-06 -0.192989 0.981201 0 -0.999912 -0.0132281 0.00105276 -0.737728 -0.00173402 -0.675095 -0.0254254 -0.999326 0.0264953 -0.00272462 -0.999694 0.0245905 -0.0254287 -0.999288 0.0278805 -0.024583 -0.999374 0.0254581 -0.0257749 -0.999311 0.0266924 0.69444 -0.000129219 0.719551 0.691661 0.000673972 0.722222 -0.956065 -0.0128552 0.292871 -0.611431 -0.439993 0.657691 -0.981965 0.0574025 0.180138 -0.276514 0.0171968 0.960856 -0.252918 -0.0134043 0.967395 -0.195272 -2.84099e-06 0.980749 -0.976918 0.00971434 0.213395 -0.978805 0.00779127 0.204648 -0.803502 -0.00517683 -0.595279 -0.399163 0.222584 0.889452 -0.607906 0.448103 0.65548 -0.594504 0.516661 0.616139 0.656901 0.454376 0.601684 -0.285668 -0.92158 0.262839 -0.338815 -0.173109 0.924791 0.5515 -0.508705 0.66111 0.163413 0.772166 0.614048 -0.61351 0.632844 -0.472349 -0.593209 0.518873 0.615527 -0.7588 0.00717173 -0.651285 -0.890205 0.152969 0.429111 -0.750309 0.00608219 -0.661059 -0.635477 -0.443336 0.632156 -0.594463 -0.517799 0.615222 -0.726658 -0.507129 -0.463453 -0.850442 -0.269285 0.451922 0.675461 -0.00344429 0.737387 0.062882 -0.689678 -0.72138 -0.0535004 -0.356562 -0.932739 -0.00434075 -0.968951 0.247213 0.943954 -0.32555 0.0544704 0.258625 -0.704812 -0.66057 0.198385 0.187679 -0.961988 0.0532682 0.690477 -0.72139 0.0680495 0.678419 -0.731517 0.0791967 0.864509 -0.496339 -0.10914 -0.705607 0.700148 -0.0325473 -0.781863 0.622601 -0.0621385 -0.794064 0.60465 -0.0567574 -0.713874 0.69797 -0.0509751 0.69094 0.721113 -0.060508 0.441739 0.895101 -0.0644304 0.67303 0.736804 -0.0757895 0.685679 0.723948 -0.0148755 0.835578 0.549171 -0.0947812 -0.67489 0.731806 -0.0501569 -0.648502 0.759559 -0.0471882 -0.639278 0.767527 -0.831887 -0.0012726 0.554943 -0.996194 -4.84659e-07 -0.0871635 -0.998872 0.00184274 -0.047444 0.521934 0.686956 0.505645 0.559899 0.599435 0.572006 0.533246 0.676345 0.508141 0.569082 -0.644568 0.510566 0.399159 -0.815027 0.420003 -0.0002598 1.58072e-06 1 -0.0167575 0.0133121 0.999771 -0.00157002 -0.000142474 0.999999 -0.0071529 0.000327007 0.999974 -0.0517262 -0.0389168 0.997903 8.40131e-05 0.0415961 0.999134 -0.676264 0.0086337 0.736609 -0.695194 -5.82527e-05 0.718822 -0.694627 3.7293e-05 0.71937 -0.694684 -0.000138978 0.719315 -0.662474 0.0848559 0.744263 0.378648 0.848187 0.370411 0.377823 0.848555 0.37041 0.892361 -0.451322 0.000797751 -0.0482255 -0.807321 0.588138 -0.0634633 -0.818406 0.571125 -0.0578697 0.817817 0.572562 -0.0509272 0.821495 0.567936 0.0279507 0.818946 -0.57319 0.0522689 0.83335 -0.550269 0.0847957 -0.441183 -0.893402 0.0786211 -0.432824 -0.898043 -0.093631 0.441267 0.892478 0.0785902 0.43218 -0.898356 0.06561 0.441667 -0.894777 0.0752188 0.426082 -0.901552 0.0646945 0.461367 -0.884848 -0.655496 -0.45171 -0.605214 -0.65789 -0.449651 -0.604148 0.384419 -0.856387 0.344709 -0.668993 0.428909 -0.60703 -0.64862 0.447561 -0.615615 0.0449746 0.98524 -0.165166 0.804967 0.538887 0.24825 -0.955243 -0.00296312 0.295808 -0.884523 -0.118085 -0.451304 0.667484 -0.265751 -0.695587 0.0253248 -0.969408 0.244146 -1 0 0 -1 -7.9063e-05 3.81816e-05 -0.999999 0.000572937 -0.000906129 -0.999995 0.00301246 0.000738864 -0.437056 -0.417764 0.796527 -0.0642254 0.372197 0.925929 0 0.405298 0.914185 0.00407049 -0.97342 -0.228992 -0.697487 -0.00107053 0.716597 -0.652526 -0.437676 -0.618587 -0.64866 -0.432514 -0.626237 -0.7861 0.147192 0.600318 -0.694876 4.01339e-05 0.71913 0.692362 -0.0394813 0.720469 -0.648162 0.434049 -0.625689 -0.646146 0.436426 -0.626121 -0.996045 0.00108498 -0.0888445 -0.296214 0.482104 0.82452 -0.996195 0.000157357 -0.0871533 -0.269223 -0.87373 -0.405111 -0.577378 -0.81622 0.0204812 -0.517428 0.855036 0.0343753 -0.996216 -0.000203861 -0.0869127 -0.99619 1.00594e-05 -0.0872146 -0.0790303 -0.431889 0.898458 -0.318524 -0.947609 0.0240686 -0.998793 0.048465 0.00799107 -0.00350031 0.999846 0.0171749 -0.543777 0.673391 -0.50085 -0.538836 0.650229 -0.535592 -0.528174 0.680821 -0.50746 -0.408164 -0.807584 -0.425687 -0.399975 -0.849301 -0.344541 0.194656 -0.975906 0.0985732 0.647073 -0.436211 0.625313 0.646091 -0.430268 0.630426 0.639744 -0.438538 0.631199 0.632011 -0.452522 0.629115 0.646397 0.42748 0.632007 0.645638 0.428935 0.631796 0.282963 0.932159 0.225857 -0.243483 0.956585 -0.16019 -0.427958 0.7963 -0.427502 -0.426368 0.808002 -0.406624 -0.482564 -0.724516 -0.492147 -0.539038 -0.679812 -0.497286 -0.539022 -0.679704 -0.497451 -0.432989 -0.786234 -0.440859 0.426294 -0.8093 0.404113 0.408043 -0.81809 0.405253 0.637853 0.438814 0.632918 -0.694314 4.279e-05 0.719672 -0.74538 -0.0358121 -0.665678 -0.474454 -0.876207 -0.0845822 -0.0544121 -0.301701 0.951849 0.649515 0.429781 0.627231 0.818793 -0.574089 0 0.0737276 0.978239 -0.193938 0.260892 -0.921979 0.286165 -0.0880706 0.000130276 0.996114 -0.0875823 -2.93453e-06 0.996157 -0.0862634 -0.0019697 0.99627 0.0866755 -0.000182919 -0.996237 0.077393 -0.00342213 -0.996995 0.0860841 0.000283675 -0.996288 0.0864085 0.000125176 -0.99626 -0.00652283 0.999976 0.00218075 -0.996177 0.00122665 -0.0873462 0.00564832 0.0506056 0.998703 0.719149 0.000601723 0.694855 0.719161 0.000564672 0.694843 0.719197 0.000475035 0.694806 0.719002 0.000130805 0.695008 0.719074 2.97831e-06 0.694934 -0.000605924 1 -1.80423e-05 -0.00114834 0.999999 -0.000232076 -0.719195 0.000878011 -0.694807 -0.71954 0.00126832 -0.69445 -0.719697 -4.72913e-07 -0.694289 -0.719623 6.66312e-05 -0.694365 -0.693748 0.000581188 0.720218 -0.695364 -0.00036444 0.718657 0.518384 0.711647 0.47417 0.0315218 0.998784 -0.0378949 -0.0651091 0.0213543 0.99765 0.0852347 0.00133937 0.99636 0.373172 0.0193618 0.92756 0.76628 0.57605 0.284572 0.979776 -0.0681335 -0.188143 0.980592 0.0819267 -0.17812 0.984848 -0.050779 -0.165822 0.990081 0.0454469 -0.132945 0.953111 0.277115 -0.121598 0.960558 -0.218389 -0.172145 0.984159 -0.152316 -0.090724 0.987414 -0.139136 0.0752006 0.913337 -0.234127 0.333167 0.984235 -0.17555 -0.0215272 0.956301 -0.289455 0.041283 -0.716467 0.604297 -0.348569 0.702451 0.710715 -0.0380295 0.677777 0.734759 -0.0273541 -0.246255 0.944442 -0.217689 0.070808 0.237645 0.968768 0.649604 0.759831 0.0259075 0.166833 0.985088 -0.0420652 -0.606411 0.794572 0.0303453 -0.208167 -0.97319 0.0978091 0.608873 -0.790799 0.0625332 -0.47908 -0.877568 -0.018903 -0.993658 0.11006 -0.0230315 -0.958738 -0.283843 0.0159643 -0.32758 -0.944568 -0.021982 -0.0181293 -0.999622 0.0206539 0.945008 -0.326913 -0.00938872 0.0666197 0.00860725 0.997741 0.925751 -0.378135 -0.000104088 0.24138 -0.259513 0.935088 -0.974743 0.111981 0.193226 0.899022 -0.119805 0.421196 -0.980483 0.129159 0.148226 -0.491433 0.870282 0.0332098 0.195151 0.69525 0.691769 -0.439894 -0.780197 0.444731 -0.992316 -0.1191 0.0335368 0.983114 0.174856 0.0539573 -0.579283 -0.583389 -0.569287 0.855247 -0.514271 -0.0638586 -0.412776 0.326776 -0.850196 0.0374061 0.109544 -0.993278 0.849244 -0.522441 -0.0764199 -0.437795 0.899074 0.0013262 0.491154 0.845716 -0.208644 0.905412 -0.339569 -0.254797 0.95822 -0.276957 0.0714845 -0.433247 0.081785 0.897557 0.0705055 0.910753 0.406887 0.0365012 -0.937511 0.346036 -0.136415 0.886397 0.442369 -0.164212 -0.0956084 0.981781 -0.137255 -0.170176 0.975808 0.165532 -0.845969 0.506889 -0.26792 0.465903 0.843299 0.0370558 -0.961897 0.270891 0.0685889 -0.912804 0.402596 0.175915 -0.868648 0.463146 -0.459014 0.870944 0.175392 -0.280612 0.141069 0.949398 0.566702 -0.396051 0.72249 0.384616 -0.132891 0.913461 -0.619014 0.785379 0.00130698 0.528459 -0.579267 0.620629 -0.0908303 0.814849 0.572512 -0.244764 0.664509 0.706059 -0.344649 0.294705 0.891272 0.154346 -0.0426964 0.987094 -0.804733 -0.0259435 0.59307 0.416767 -0.0147379 0.908894 -0.628369 0.628611 0.458258 -0.522802 -0.816261 -0.245758 0.0100552 0.99519 0.0974511 -0.318002 0.911807 0.259776 -0.859494 0.441191 0.258108 -0.987468 -0.147787 -0.0553679 -0.915353 0.0573598 0.398546 -0.790312 -0.330371 0.516005 -0.529831 -0.604554 0.594806 0.52257 -0.818585 0.238411 0.105938 -0.906423 0.40887 0.404479 -0.905434 -0.128789 -0.996109 0.0291195 -0.0831795 0.759926 -0.477144 -0.441414 0.723733 -0.576521 -0.379254 0.294311 -0.955011 -0.0365516 -0.0395483 -0.968998 0.243884 -0.327204 -0.859682 0.39228 -0.764481 -0.253539 0.592694 -0.785638 -0.200107 0.585432 0.127031 -0.62302 -0.771822 0.447309 0.345483 -0.824959 0.284093 0.493791 -0.821865 0.239492 -0.534419 -0.81058 0.401783 -0.148079 -0.903683 -0.792465 0.22237 0.567935 -0.564287 0.632384 0.530727 -0.35063 0.850466 0.392129 0.0944942 0.987426 0.126732 0.445465 0.877782 -0.17624 0.523853 0.82119 -0.22633 0.777574 0.448772 -0.440434 -0.108963 -0.952447 -0.284557 0.0769505 0.130695 -0.988432 0.1269 -0.566018 -0.814568 0.132349 0.942324 -0.307425 0.636048 0.76981 0.0532549 -0.913207 0.00527936 -0.407463 -0.382345 -0.299258 -0.874218 0.948105 0.272417 -0.163968 0.930485 0.334331 -0.149735 -0.105017 -0.794636 -0.597934 -0.795126 -0.461213 -0.393773 -0.794524 -0.461474 -0.394681 0.763369 0.553139 -0.333624 0.183197 0.277475 -0.943105 0.0995181 0.119639 -0.987817 0.862348 0.0117213 -0.506181 0.499567 -0.0091788 -0.866227 0.201984 0.00238361 -0.979386 -0.413166 0.00554188 -0.910639 -0.178517 0.952792 -0.2456 -0.163049 0.985844 0.039061 -0.164029 0.986199 0.0224897 -0.117608 0.891061 0.438382 0.00279108 0.388813 0.921313 0.0800318 -0.0411085 0.995944 0.0953021 -0.126673 0.987356 0.138304 -0.431064 0.891659 0.166876 -0.631736 0.757009 0.174878 0.76544 0.619289 0.168455 0.638281 0.751146 0.136758 0.420574 0.896892 0.0822558 0.0484517 0.995433 0.0777831 0.0239105 0.996684 0.0284551 -0.254823 0.966569 0.0044667 -0.393328 0.919388 -0.0470194 -0.621954 0.781641 -0.0933171 -0.825655 0.556404 -0.115853 -0.887252 0.4465 -0.159511 -0.980383 0.115781 0.69869 0.712623 0.0632502 0.44367 0.846142 0.295298 -0.126729 0.853034 0.506235 -0.46495 0.658152 0.592163 -0.90365 0.0177064 0.427905 -0.824178 0.272446 0.496492 -0.118155 -0.964509 0.236139 -0.0473092 -0.716327 0.696159 -0.163094 -0.363211 0.917321 0.0194907 0.919276 -0.393131 0.00472911 0.874086 -0.485749 0.0762155 -0.962895 -0.258891 0.000879234 -0.890864 -0.45427 -0.154342 -0.200347 0.967492 0.00959488 0.81389 -0.58094 -0.0270376 0.997128 -0.0707391 -0.0369457 0.407147 -0.912615 -0.0142983 -0.995666 0.0918991 -0.00108009 -0.852063 -0.523438 0.0497899 -0.92637 -0.373309 -0.222411 0.361996 0.905258 -0.149844 0.262775 0.953151 -0.0114739 0.9681 0.250299 -0.0365961 -0.00314291 0.999325 0.0813328 -0.324277 -0.942459 0.126874 -0.246474 -0.960809 -1.10752e-05 -0.00045631 -1 -0.0224427 -0.0579631 -0.998066 -1.14409e-05 0.997285 -0.0736424 0.0157909 0.978168 -0.207214 -0.0101661 -0.12476 0.992135 0.0773982 -0.197669 -0.977209 -0.0488241 0.131892 -0.990061 0.0948427 -0.185805 -0.977999 -0.0563307 0.106035 -0.992766 -0.016265 0.998807 0.0460332 -0.777131 -0.629086 -0.0178125 -0.872077 -0.467593 0.144354 0.152235 -0.833222 -0.531569 0.249074 -0.782402 -0.570797 -0.598188 -0.785043 -0.160869 0.861066 -0.159578 -0.482805 0.929831 0.0469043 -0.364986 -0.155145 -0.438347 -0.885315 -0.0757621 -0.00155901 -0.997125 -0.148334 -0.506595 -0.849328 -0.148318 -0.506403 -0.849445 -0.0779531 -0.0186003 -0.996783 0.0118212 0.442598 -0.896642 0.0448664 0.624248 -0.779937 0.192787 0.957643 -0.213898 0.19227 0.958256 -0.211606 0.113224 0.87048 -0.479005 0.0168189 0.447135 -0.894308 0.0220455 0.453936 -0.890761 -0.178509 -0.905883 -0.384071 -0.18078 -0.881197 -0.436818 0.175265 0.966239 0.188851 0.17192 0.982157 0.0762349 0.152267 -0.979463 -0.132164 0.312179 -0.946657 -0.0799028 -0.00344512 -0.361082 -0.932528 0.0531969 -0.673759 -0.737034 0.117466 -0.874589 -0.470422 -0.0822581 0.0264818 -0.996259 -0.0554652 0.550798 -0.832794 -0.122957 0.338212 -0.933003 -0.146648 0.486857 -0.861083 -0.0999158 -0.325242 -0.940338 -0.172645 0.759137 -0.627618 -0.184214 0.889702 -0.417726 0.177846 -0.964982 0.192823 -0.970251 -0.000890048 0.242099 -0.653554 -0.00892564 0.756827 -0.160024 0.00452536 0.987103 0.542517 -0.00230166 0.840042 0.988945 0.00635792 0.148148 0.998071 -0.00670859 -0.061721 0.0927791 0.0337629 0.995114 0.534861 0.595227 0.59969 -0.734069 -0.467235 0.492782 -0.774854 -0.599061 0.201813 0.49747 0.301354 0.813455 0.521707 0.336059 0.784147 -0.485934 -0.422409 0.76514 -0.12687 -0.105195 0.986325 -0.265198 -0.33716 0.903323 -0.203892 -0.746818 0.633001 -0.113671 -0.227728 0.967067 -0.232802 -0.587866 0.774737 -0.265609 -0.315796 0.910892 -0.160624 0.68557 0.710066 -0.160169 0.689772 0.706089 -0.236397 -0.856266 0.459266 -0.324076 -0.191954 0.926352 -0.151997 0.642707 0.750883 -0.0398203 0.837591 0.544844 -0.794733 -0.302643 0.526124 -0.569294 -0.788903 0.231379 -0.5735 -0.784309 0.236553 0.0676126 -0.973626 -0.217902 0.265205 -0.887708 -0.376351 0.786093 -0.217141 -0.578711 0.742464 -0.314524 -0.591458 0.015149 0.929382 0.368807 -0.311257 0.229668 0.922156 -0.444613 0.00765104 0.89569 -0.0635199 -0.950395 0.304491 -0.100366 -0.00477902 -0.994939 -0.0619431 0.0424876 -0.997175 -0.775611 0.300936 -0.554856 -0.803915 -0.0097031 -0.594666 -0.0746837 0.457456 -0.88609 0.207695 -0.917187 -0.340045 0.911577 -0.400525 -0.0927722 0.530594 -0.425632 -0.733013 0.439647 -0.833179 -0.335445 0.589081 -0.511628 -0.625476 -0.568657 0.622012 -0.538266 -0.231688 0.372971 -0.898451 -0.0154097 0.885952 -0.46352 0.440225 -0.0212514 -0.897636 0.432021 -0.438974 -0.78782 -0.256066 0.9402 -0.224621 -0.396329 0.329603 -0.856905 0.395067 -0.805804 -0.441137 -0.58907 0.767113 0.254036 0.215518 0.917046 -0.335527 0.187736 0.931003 -0.31303 0.735431 0.351985 -0.579006 0.739015 0.340745 -0.581162 0.0902796 -0.692201 -0.716036 0.541211 -0.506156 -0.671489 0.571526 -0.111445 -0.812981 0.46165 -0.626511 -0.627983 0.0222367 -0.161771 -0.986578 -0.000702784 -0.044554 -0.999007 -0.0412951 -0.0688772 -0.99677 0.541882 0.797815 -0.264302 -0.382842 -0.832752 0.399944 -0.428538 -0.893589 -0.133621 -0.690729 0.700148 0.180793 0.898207 0.10681 -0.426398 0.453909 0.654578 -0.604561 -0.619518 0.773044 -0.136383 0.216047 0.81237 -0.541644 -0.764683 0.642928 -0.0436325 -0.99813 -0.0324741 -0.0517956 0.029409 0.0439065 0.998603 -0.00946145 0.0726106 -0.997316 -0.0198056 0.0578282 -0.99813 -0.690083 -0.717262 0.0965442 0.151768 -0.988372 0.00931188 0.936879 0.314754 0.152274 -0.291798 0.116984 0.949299 -0.390387 0.00853331 0.920611 -0.999644 0.0108141 -0.0243869 -0.999935 0.00259502 -0.0111427 -0.999659 -0.021113 -0.0153458 -0.998521 -0.00217873 -0.0543264 -0.359228 0.11275 0.926414 -0.422672 -0.0742843 0.903233 0.41618 -0.890553 -0.183601 0.99813 0.0324741 0.0517956 0.852462 0.0409626 0.521182 -0.819111 -0.573083 -0.025146 0.527589 0.849399 0.013048 0.739773 0.593317 0.317351 0.283877 0.384904 -0.878215 0.213925 -0.253895 -0.943278 -0.40949 0.330346 0.850405 -0.779249 -0.616869 -0.110646 0.779249 0.616869 0.110646 -0.530018 -0.782646 -0.326414 0.517468 -0.717208 0.466733 -0.799472 -0.599976 0.0295549 0.799472 0.599976 -0.0295549 -0.726756 -0.684019 -0.0627982 0.726756 0.684019 0.0627982 0.00054133 -0.000983216 0.999999 -0.963435 0.080008 -0.25572 0.963435 -0.080008 0.25572 -0.927609 -0.153328 0.340635 0.763887 -0.631353 0.133679 0.276058 -0.896093 -0.347577 0.851448 -0.432182 0.297078 -0.0818204 -0.985201 -0.150615 0.57411 0.328373 0.750046 0.887011 -0.461678 -0.00803597 -0.00190542 -0.999957 -0.00904439 0.0020009 -0.999855 0.0168905 3.02158e-10 1.58571e-07 -1 -3.58491e-08 1.42305e-07 -1 -2.13507e-07 2.13398e-07 -1 -2.23792e-07 2.11254e-07 -1 -0.00551649 0.999485 0.031622 0.00275297 0.999807 -0.019453 -9.94294e-05 1 0.000277775 -4.50838e-05 0.999999 0.00112306 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 5.50603e-05 -6.10413e-05 -1 3.15837e-07 -1.30284e-08 -1 -1.41932e-05 5.85477e-07 -1 2.64268e-07 -1.28928e-07 -1 0 0 -1 -0.000104738 -0.999999 -0.00117074 0.000200678 -0.999994 0.00357818 0 0 -1 1.74218e-07 1.7212e-08 -1 0 0 -1 5.48363e-07 -1.56439e-07 -1 4.92904e-11 4.70463e-07 -1 -6.91123e-07 1.29508e-07 -1 -5.44094e-07 -5.12099e-07 1 5.44094e-07 5.12099e-07 -1 5.54235e-07 -1.07583e-06 -1 -1.82274e-07 -1.04919e-06 -1 -4.87645e-05 0.999999 -0.00166415 0.000386754 0.999992 0.0040855 -0.000411027 -0.999992 0.0040845 0.000268961 -0.999991 -0.00420603 1.22218e-07 -2.89091e-11 -1 3.41964e-11 -1.27142e-07 -1 -1 9.24194e-06 0.000371894 -1 1.07959e-10 -0.000214582 0 0 1 -1.76966e-07 5.057e-06 1 -0.539217 -0.441705 0.717037 2.42484e-05 -1.28308e-05 -1 0.00355699 -0.00525132 -0.99998 -0.00355699 0.00525132 0.99998 1.23817e-05 1.01426e-05 1 0.00186601 0.00126962 0.999997 -2.04886e-06 1.08413e-06 1 -0.00070166 -0.000978536 0.999999 4.13507e-06 -2.69751e-06 1 0.000443909 -0.000154552 1 -1.17358e-05 -4.193e-06 1 1.7144e-06 2.75055e-06 1 2.73014e-05 3.62664e-05 1 -0.00840242 0.00217254 0.999962 -0.000697264 0.00112625 0.999999 3.28618e-05 2.29926e-05 1 3.27293e-07 2.28999e-07 1 2.07415e-05 0.000252944 1 0 0 1 0 0 1 -6.50704e-06 -1.07557e-06 1 0.927609 0.153328 -0.340635 0 0 1 0 0 1 1.15793e-05 -0.000102451 1 0 0 1 2.8038e-06 5.01652e-06 1 5.39729e-06 -9.73412e-05 1 -0.763887 0.631353 -0.133679 0.90508 -0.3731 -0.204026 -2.14744e-06 1.46117e-06 1 -2.16983e-06 -3.46157e-06 1 -0.90508 0.3731 0.204026 2.61413e-06 -5.43366e-06 1 -2.3511e-05 -1.85064e-05 1 0 0 1 1.56028e-05 1.19307e-05 -1 -6.5165e-06 -2.62394e-06 1 2.67279e-05 2.04375e-05 -1 0 0 1 -7.96421e-07 9.0339e-06 1 1.72749e-05 -8.76846e-06 -1 -0.851448 0.432182 -0.297078 0 0 1 6.62609e-06 1.16665e-05 1 0 0 1 0 0 1 1.07187e-05 -0.000306418 1 -0.00028076 -0.000346285 1 5.6234e-07 -4.09367e-06 1 0.0139871 -0.000369653 0.999902 -0.0139871 0.000369653 -0.999902 0.930486 0.0994537 -0.35257 0 0 1 0 0 -1 0 0 1 -2.33001e-05 1.14245e-05 1 2.68062e-06 -4.03137e-06 1 0 0 1 -0.000220005 9.00814e-06 1 -0.000288062 -3.81218e-06 -1 4.38779e-06 0.000265096 -1 -8.39218e-06 -1.52139e-05 1 3.33414e-07 -1.37121e-05 -1 -0.00242458 -0.000209453 -0.999997 3.93271e-05 5.22703e-05 -1 -0.000100362 7.52882e-06 -1 -0.000268413 0.000307726 -1 -9.96908e-07 -0.000559736 -1 1.12432e-06 -4.45174e-05 -1 -4.13659e-06 3.82138e-05 -1 0.57787 -0.580092 -0.574073 2.41391e-05 1.38882e-05 -1 3.22893e-05 -1.28e-06 -1 -0.00347595 0.999984 -0.00456543 5.8479e-07 4.78101e-08 1 -5.07043e-05 -0.00158516 -0.999999 -2.83262e-05 -0.000153741 -1 -6.8418e-05 -6.24601e-05 -1 -0.000928854 0.0011509 -0.999999 0.000848766 0.000240975 -1 -0.630972 -0.720582 0.287466 -5.83239e-07 0.000184201 -1 -0.00011328 5.82536e-06 -1 -2.1166e-05 1.74536e-06 -1 -1.74509e-06 3.52026e-05 -1 0 0 -1 -4.7344e-06 -0.000185295 -1 0.000313123 -1.01375e-05 -1 -2.65748e-05 1.69626e-06 1 0 0 1 -3.83576e-05 -0.000132272 -1 2.2334e-08 7.70161e-08 -1 -0.000229341 -0.00162458 -0.999999 -0.00108011 -0.0013159 -0.999999 0.000709115 0.000551401 -1 0.000262538 0.00141114 -0.999999 -0.00083453 -0.00126785 -0.999999 -0.000989173 -3.63449e-05 -1 -2.8322e-07 -7.88352e-08 1 -2.18795e-07 -2.80951e-06 -1 7.31575e-05 0.000957468 -1 5.81997e-07 -1.49396e-07 1 -0.000421709 -2.65105e-06 1 0.000230889 -1.32183e-05 -1 -0.00205619 0.000183193 -0.999998 7.68647e-05 0.000314906 1 0 0 1 -2.19256e-07 -1.65828e-08 -1 -1.26384e-05 2.61236e-07 -1 1.35879e-05 7.94451e-07 1 -8.20508e-06 9.35227e-07 -1 9.78598e-06 -1.51159e-06 1 1.12887e-06 3.47978e-05 -1 3.9795e-06 -1.63724e-05 -1 4.78595e-06 1.39615e-05 -1 -2.03157e-05 1.08666e-05 -1 -0.820645 -0.289246 -0.492828 0.820645 0.289246 0.492828 -2.63841e-06 1.14121e-05 -1 0.828747 -0.294755 0.475709 -1.6865e-07 6.6006e-06 -1 5.16336e-07 -2.02083e-05 -1 6.19353e-07 -1.75567e-05 -1 -1.53293e-06 -1.30668e-07 -1 -0.828746 0.294755 -0.475709 -1.75583e-05 1.67185e-05 -1 1.57874e-05 4.81004e-05 -1 1.59158e-05 6.22506e-05 -1 -1.07575e-06 2.82616e-06 -1 -6.03275e-06 7.49846e-08 -1 -8.0635e-05 -6.34956e-05 -1 -1.7415e-05 3.08442e-07 1 2.51915e-06 -1.23497e-06 -1 1.83945e-07 2.04599e-07 1 0 0 -1 -9.70823e-07 4.16624e-06 1 -5.74383e-06 1.98797e-06 -1 1.58016e-06 -1.21551e-07 -1 -1.46313e-05 1.12549e-06 -1 0.999998 -0.00173753 -0.000664513 0 0.181118 0.983461 1 0 0 1 0 0 0.999995 0 -0.00304718 1 0 0 0 0.181118 0.983461 1 0 0 0.999998 0.00170012 -0.000650206 0.999998 0.000181234 0.00196432 0.999996 0.000329531 0.00294828 1 0.000454094 -0.000545245 1 0 0 1 0.000117752 -4.32474e-05 0.999995 -0.000334697 0.00307162 0.999997 -0.000528677 -0.00236886 1 0 0 1 0 0 1 -3.43879e-07 -8.75279e-06 1 0 0 0.009595 -0.812957 0.582245 3.49712e-05 -0.819315 0.573344 0 -0.819152 0.573577 -0.431507 -0.699631 0.56949 -0.441844 -0.673056 0.593101 -0.287793 -0.790652 0.540411 -0.136037 -0.786566 0.602335 -0.0952846 -0.815513 0.570841 -0.526541 -0.627507 0.573576 -0.526835 -0.628133 0.57262 -0.0140827 0.844659 0.53512 6.88494e-06 0.819381 0.57325 1.81113e-05 0.819523 0.573046 -6.37267e-05 0.819152 0.573577 -0.119166 0.813315 0.56949 -0.0941526 0.799595 0.593113 -0.28774 0.790675 0.540406 -0.401438 0.689947 0.602346 -0.451197 0.685945 0.570877 -0.526643 0.627629 0.573348 -0.534784 0.645859 0.544861 -0.415931 0.768698 0.485907 -0.0266688 0.990377 0.135805 -0.207346 0.962252 0.176292 -0.887011 0.461678 0.00803597 -0.544193 0.683344 0.486718 -0.276058 0.896093 0.347577 -0.930486 -0.0994537 0.35257 2.48615e-05 0.939693 0.342018 0 -1 0 0 -1 0 0 6.56914e-06 1 3.26237e-05 -0.000243088 1 -1.63645e-06 -0.000270211 1 -3.67924e-06 -0.000133961 1 -5.49955e-05 0 1 1.87369e-05 8.15485e-05 1 1.77133e-05 0.000383069 1 0 -2.34225e-05 1 7.04649e-06 -0.000343404 1 2.26347e-06 7.30586e-05 1 6.89161e-05 -0.000304696 1 -0.000151871 0 1 3.35191e-05 0.000103376 1 3.26582e-05 0.000447409 1 0 1 0 0 1 0 0 -0.181118 0.983461 0 -0.939693 0.34202 0 -0.939693 0.34202 2.57883e-06 -0.939693 0.34202 2.41765e-06 0.939693 0.34202 0 0.939693 0.34202 0 -1 0 0 -1 0 0 0 1 0 3.30921e-05 1 -1.0567e-06 -4.05396e-05 1 -3.39472e-06 2.39991e-06 1 9.9004e-07 0 1 -5.88178e-07 4.50612e-06 1 -4.00978e-06 -2.56964e-05 1 1.40099e-05 -0.000142179 1 -6.2448e-05 0 1 1.60076e-05 0.000146335 1 0 1 0 0 1 0 0 -0.181118 0.983461 -5.03674e-09 -0.939693 0.34202 0 -0.939693 0.34202 -1 2.01877e-06 4.31431e-05 -1 1.24498e-06 1.74661e-05 -2.35507e-05 5.03114e-07 -1 -1.02204e-05 -7.95694e-08 -1 -0.0511511 0.756397 -0.652109 -1.49241e-05 1.36323e-06 -1 -4.42169e-06 -7.22588e-07 -1 3.57097e-06 2.78013e-08 -1 -1.17587e-07 -1.37643e-07 -1 -0.707104 -1.07545e-05 0.707109 -0.707108 1.21635e-06 0.707106 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707108 -1.21635e-06 0.707106 -0.707104 -1.07545e-05 0.707109 -0.707108 1.21635e-06 0.707106 -0.707107 3.80692e-07 0.707107 -0.707108 0 0.707106 -0.707108 6.0774e-07 0.707106 -0.00440791 0.233826 0.972268 0.0121973 0.997733 -0.0661753 -0.00627988 0.213967 -0.976821 -0.00582704 -0.907817 -0.419327 -0.150662 -0.188545 0.970439 -0.0347843 -0.989605 -0.139543 -0.00823349 0.867453 0.497451 0 -0.181118 0.983461 0 -0.181118 0.983461 -0.00823012 0.867212 0.497871 -1 -5.6917e-07 0.000509991 -0.999999 -2.8444e-05 0.00109349 -0.000106388 -0.999994 0.00352385 0.000517707 -0.999992 -0.00408598 0.999998 0.000132419 0.00194518 0.999993 -0.000353113 -0.00374462 -0.000156 0.999975 -0.00713619 0.00548312 0.998085 0.0616203 0.181969 0.979255 -0.0891432 0.171059 0.984639 -0.0349937 0.641844 0.766825 0.00382621 0.641141 0.767298 0.0138861 2.44484e-07 2.5432e-07 -1 0 0 -1 0 -1 0 0 -1 0 0.998202 0.0150018 0.0580358 0.999984 -0.00140564 -0.00543785 -6.83294e-06 1 -0.000235053 1.76678e-05 1 0.000607772 -0.999805 -0.00140844 0.0197077 -2.98735e-07 4.40634e-06 -1 0 0 -1 0 0 -1 -0.000972676 0.000315205 -0.999999 0.000416864 0 -1 0.999993 0.00043137 0.00374495 0.999992 -0.000236536 -0.00408375 -0.00024472 0.999857 0.0168913 -1 -2.91763e-05 0.000610443 -1 2.91768e-05 -0.000610454 -0.002544 -0.999854 -0.0168906 0.00254405 -0.999854 0.0168909 0.641598 -0.767008 -0.00715761 0.641038 -0.767357 -0.0152919 0.182337 -0.977896 0.102335 7.17376e-06 2.70164e-06 -1 -1.1035e-06 -4.2695e-07 -1 -1.12312e-06 -4.22967e-07 -1 8.75152e-06 1.98428e-06 -1 0.999996 0.000441307 0.00295095 0.999994 -0.000127347 -0.0034015 -0.999993 -0.00050902 0.00373934 -1 -9.00164e-05 -0.000981341 -1 9.78273e-05 0.000855548 -0.999993 0.000486239 -0.00369874 0.999997 0.000173235 0.00224682 0.999993 -0.000356242 -0.00385521 -1 2.09492e-05 0 -0.999999 9.02652e-05 -0.00134109 1 -2.70166e-05 -0.000610492 0.999999 -4.98886e-05 -0.00108948 -1 -4.45166e-05 0 -0.999999 -0.000105663 0.00118303 1 -4.98885e-05 -0.000835349 1 -3.91334e-05 -0.000610287 -0.750154 0.661264 0 -0.353333 0.757725 -0.548642 0.836197 0.393296 0.382222 -0.785668 -0.618648 0 0.225891 -0.907853 0.353236 -0.388909 0.832884 -0.393769 -0.75675 -0.315312 -0.572632 -0.476769 -0.879029 0 -0.418492 0.881801 0.217467 -0.921896 0.184344 -0.340773 0.399149 0.840733 -0.365854 0.428748 -0.903424 0 0.475925 -0.877541 -0.058452 -0.396219 -0.827132 -0.398577 0.543128 0.801974 -0.248696 -0.551847 0.764857 0.332354 0.845678 0.52911 -0.0697999 -0.845678 -0.52911 0.0697999 -0.961044 -0.262194 0.08746 -0.26113 -0.794705 0.547955 0.0181549 -0.997444 0.0691066 0.949809 -0.302317 0.0804162 0.86016 0.494886 -0.123337 -0.114321 0.144911 0.982818 -0.141465 0.168592 -0.975482 -0.00106172 0.623027 0.782199 -0.00371871 0.252226 -0.967661 -0.22953 0.00747089 0.973273 -0.707112 -9.22068e-05 0.707102 -0.705996 -0.0001022 0.708215 -0.653099 -0.383323 0.653089 -0.610034 -0.365882 0.702843 0 -0.461754 0.887008 -0.00372402 -0.253476 -0.967335 -0.141538 -0.168678 -0.975456 -0.0276886 0.950483 0.309542 -0.0723419 -0.951169 0.300074 -0.00590967 -0.0121358 0.999909 0.713851 -0.00651179 0.700268 0.707112 0 0.707102 0.707112 0 0.707102 -0.120928 0.114529 -0.986032 -0.852723 -0.11245 0.510116 0.779266 0.133033 -0.61241 -0.90395 0.252521 -0.34512 -0.111639 -0.207261 0.971895 -0.513994 0 -0.857794 -0.879799 -0.205104 0.42882 -0.96279 -0.0818857 0.257546 0.293826 0.223348 0.929399 0.854603 -0.168368 0.491229 0.810335 0.086181 -0.579595 0.165433 -0.148796 -0.974932 0.0854298 -0.176421 -0.9806 0.034413 -0.154799 -0.987347 -0.494669 0.0159236 -0.868936 -0.888304 0.0454752 -0.456999 -0.637616 -0.522795 -0.565801 -0.731299 0 -0.682058 -0.980446 -0.155591 -0.120486 -0.290065 0.185818 0.938794 0.137763 -0.0710303 0.987915 0.914595 0.108992 0.389405 0.981858 -0.0596313 -0.179995 0.584181 0.0258967 -0.81121 -0.0635031 -0.141992 -0.987829 -0.105214 -0.126475 -0.986374 -0.721598 0.0451852 -0.690837 -0.302629 -0.100416 -0.947804 0.929824 0.0893958 -0.356982 -0.915196 0.177581 -0.361776 -0.560168 -0.196892 0.80464 0.948004 0.206513 0.242158 0.824102 0.305914 0.476732 0.42835 -0.0153906 -0.903482 -0.902806 0.0968114 -0.41901 -0.794334 0.272266 0.543051 -0.915488 0.201698 0.348137 0.573447 -0.20125 0.794139 0.860333 0.159849 -0.48402 0.728745 0.0946078 -0.678219 -0.0910619 -0.454773 -0.88594 -0.892536 0.169381 -0.41796 -0.945417 -0.173084 0.276094 -0.893131 -0.0755588 0.443405 -0.762498 0.00707306 0.646951 -0.29506 0.0216291 0.955234 -0.0346748 -0.0124809 0.999321 0.529026 -0.166887 0.832034 0.417958 -0.349298 0.838631 0.30129 -0.216409 0.92865 -0.781249 -0.0237073 0.623769 0.122257 -0.470626 -0.873821 -0.695502 0.184352 -0.694472 -0.956084 -0.2665 -0.121988 -0.119211 -0.266427 0.956455 0.0498265 -0.0936168 0.994361 -0.138523 -0.0549235 0.988835 -0.0429904 -0.0279638 0.998684 0.376908 0.0287794 0.925803 0.944228 -0.16429 0.285382 0.836769 -0.00345188 0.547545 0.808266 -0.0286348 0.58812 0.933423 0.118288 -0.338717 0.999609 -0.00349105 -0.0277566 0.213504 -0.932871 -0.290117 -0.436789 0.0431238 -0.89853 -0.693099 -0.0469703 -0.719311 -0.926774 0.0200212 -0.375086 -0.816883 -0.467163 0.338321 -0.994179 -0.0168987 -0.106405 0.80284 -0.386367 0.454058 0.251996 -0.0575521 -0.966016 0.598972 0.0504928 -0.799176 0.845133 -0.0234117 -0.534043 0.963849 0.012768 -0.266144 -0.999024 0.0118037 0.0425692 -0.955901 -0.0185401 0.293104 -0.618572 -0.409607 -0.670515 -0.94932 0.187063 -0.252584 0.131481 0.301139 -0.944472 -0.145859 -0.466152 -0.872598 0.552307 -0.405114 -0.728587 0.99969 0.0145045 0.0202369 0.973116 0.124514 -0.193757 0.871706 -0.0340316 0.488847 0.694511 0.0197706 0.71921 -0.176161 -0.0148059 0.98425 -0.148325 -0.0230731 0.988669 -0.737695 0.029443 0.674492 0.180675 -0.157682 -0.970821 0 0 -1 0 0 -1 0.00221067 -0.0224751 -0.999745 4.90195e-05 0.00204765 -0.999998 -0.0168933 0.000200256 -0.999857 0.228659 0.449557 0.863489 -6.8735e-06 0.800768 0.598975 0 0.800776 0.598964 -1.50714e-06 0.800787 0.598949 -3.58075e-08 0.800779 0.59896 4.45043e-07 0.800785 0.598952 1.51519e-05 0.800757 0.59899 -0.122879 0.622266 0.773102 0 0.800778 0.598961 4.27252e-06 0.80077 0.598971 3.07727e-06 0.800796 0.598937 4.8559e-06 0.800781 0.598957 0 0.703697 0.7105 -0.0014741 0.658131 0.752902 0.0003485 0.491989 0.870602 -0.000232305 0.438709 0.898629 0.00011941 0.316953 0.948441 5.29525e-05 0.313199 0.949688 0.000127235 0.112642 0.993636 0.000456942 0.135395 0.990792 0 0.0977908 0.995207 -0.000967797 0.167044 0.985949 -5.06647e-05 0.112553 0.993646 -0.00011703 0.315331 0.948982 0 0.658132 0.752903 0.00244441 0.70623 0.707978 -0.000295474 0.537682 0.843148 0.000495649 0.44788 0.894094 -0.000233049 0.320957 0.947094 0.201464 -0.849088 -0.488325 0.617871 -0.65465 -0.435511 -0.462331 -0.75319 -0.467926 0 -1 0 0 -1 0 0 -1 0 0.000804046 -0.999995 0.00299537 0.00191 -0.999996 -0.00196685 0.000194279 -1 -0.000203302 -0.000388514 -1 0.00040656 -0.000648654 -1 0.000159373 0 -1 5.89163e-05 0 -1 0 0 -1 0 0.000340458 -0.999997 -0.00254944 0.752665 -0.633883 0.178012 0.765723 -0.620865 0.167914 0.741199 -0.66628 0.081823 0.774498 -0.604031 0.18788 0.763557 -0.613269 0.202194 0.758284 -0.624957 0.185563 0.757667 -0.626744 0.182024 0.75995 -0.622585 0.186719 0.755508 -0.629089 0.182908 0.74133 -0.646109 0.181583 -7.79826e-06 1 -5.9787e-05 3.28279e-05 -1 0.000617452 0.000138612 -0.999999 0.00167637 0 -1 0 -2.47871e-06 1 -2.08447e-05 -0.15266 0.68582 -0.71158 -7.16291e-06 -1 -1.53665e-05 1.03753e-06 1 -4.203e-05 -0.0564397 -0.699648 -0.712255 -0.00678957 -0.121949 -0.992513 0.0815953 -0.995725 -0.0432898 0.00459897 -0.0152065 0.999874 0 -1 0 0 -1 5.54255e-05 -8.85195e-05 0.999999 -0.00119285 0 -1 5.51687e-05 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1.36962e-05 -0.999995 -0.00331077 -5.71017e-06 -1 0.00028082 -3.06723e-05 -1 -1.48029e-05 -2.33283e-07 -1 -1.08738e-06 0 -1 0 0.000120451 -1 5.52964e-05 0 -1 0 -0.000135317 -1 -0.000130259 0.000606628 -0.999999 -0.000992432 0.000176144 -0.999998 -0.00194862 -0.000461829 0.999995 -0.00310718 6.3164e-05 -0.999999 -0.00111903 -8.21827e-05 1 0.000198241 4.12681e-05 -0.999999 -0.00107224 2.52308e-05 -0.999997 -0.00226722 0 -1 0 0 -1 0 1.00008e-05 -1 8.87439e-06 4.22606e-06 -1 -0.000891614 0 -1 0 0 -1 0 0.571442 0.0440782 -0.819458 1.69739e-05 -0.999975 -0.00710216 6.34947e-05 -1 4.47531e-05 -9.33554e-06 -1 1.10716e-05 -0.00770109 -0.999956 -0.00537303 0.00697802 -0.999967 0.00422769 -2.02814e-06 -1 1.41487e-05 6.35366e-05 -1 4.43065e-05 8.73484e-05 -0.999987 -0.00513262 0.118137 -0.837143 0.534074 -6.86112e-05 -0.999941 -0.0109049 -0.0349331 -0.0569252 0.997767 0.0531131 0.193897 -0.979583 -0.120829 0.754515 0.645065 5.81932e-05 -0.999915 -0.0130206 -0.00340259 -0.999993 -0.00150716 0.479292 -0.0573294 0.875781 -1.04979e-07 -0.737322 0.675542 5.29768e-09 -0.737316 0.675548 6.0358e-09 -0.737318 0.675546 0 -0.737319 0.675545 -0.4474 -0.0720752 0.891425 -0.000104459 -1 0.000298883 0.19623 -0.865868 -0.460182 0 -0.800779 -0.598961 0.000238393 -0.800457 -0.59939 -0.000809552 -0.801113 -0.598513 5.75887e-09 -0.80078 -0.598958 2.76848e-08 -0.800779 -0.59896 4.36379e-08 -0.800779 -0.59896 6.09362e-05 -0.685491 -0.728081 -0.103357 -0.459116 -0.882343 0.0222208 -0.240404 -0.970419 -0.000890168 -0.764837 -0.644223 0 -0.725496 -0.688227 1.76982e-05 -0.798132 -0.602483 1.56939e-05 -0.798189 -0.602407 -0.000941482 -0.446205 -0.894931 -0.780706 -0.602881 0.164418 -0.757894 -0.625845 0.184161 -0.75382 -0.631095 0.182961 -0.759476 -0.623333 0.186153 -0.756672 -0.627976 0.181917 -0.758768 -0.624743 0.1843 -0.759887 -0.624026 0.182107 -0.762179 -0.619686 0.187276 -0.745449 -0.64118 0.182192 -9.30032e-05 -0.0847144 0.996405 0 -0.0871918 0.996192 -8.58656e-06 -0.083183 0.996534 -4.62667e-05 -0.0842136 0.996448 -0.00179735 -0.0208796 -0.99978 -5.07303e-06 0.000219831 -1 0 0 -1 0.00612618 -0.00600363 -0.999963 -0.108959 -0.0330657 -0.993496 -0.797375 0.0964468 -0.595727 0.798947 0.110846 -0.591099 0.970853 -0.017138 -0.239063 0.971079 0.0165387 -0.238185 -0.971129 0.00210958 -0.238546 -0.970244 -0.0362401 -0.239401 0 -0.706011 0.708201 -0.971117 6.78374e-06 0.238602 -0.971117 -1.73871e-06 0.238602 0.971117 6.54981e-06 0.238602 0.971117 -3.72193e-06 0.238602 0 -0.541238 0.840869 0.925237 0.375199 -0.0562272 0.311993 0.915244 -0.254929 -0.751489 0.498247 -0.432451 -0.72562 -0.673051 0.143103 -0.752199 -0.64367 0.141018 0.718303 -0.69021 0.0874771 0.308283 0.351077 -0.884142 -0.457797 0.481754 -0.747218 -0.705008 0.676233 -0.213712 -0.644068 0.748526 -0.157752 -0.637286 0.754533 -0.156672 -0.636655 0.75449 -0.159422 -0.750611 0.594358 -0.288654 -0.714645 0.619104 -0.325567 0.104779 0.938747 -0.328293 -0.115195 0.656072 -0.745855 -0.112795 0.993039 -0.0339266 -0.102042 0.994457 -0.025332 -0.113235 0.899763 0.421431 -0.168746 0.874426 0.454868 -0.0363916 0.179131 0.983152 -0.131686 0.036195 0.990631 -0.568798 0.574824 -0.588257 -0.540482 0.725532 -0.426007 -0.737751 0.563913 -0.371114 -0.758513 0.624398 -0.186506 -0.643426 0.76517 -0.0227775 -0.763081 0.61571 -0.19649 -0.766356 0.614586 -0.187037 -0.191627 -0.97994 -0.0547402 -0.205739 -0.612106 0.763543 -0.131293 -0.533023 0.835852 -0.182873 -0.701387 -0.688922 -0.182542 -0.701462 -0.688933 -0.00619443 0.706222 -0.707963 -0.016838 0.722429 -0.691241 0.00458227 0.722948 -0.690887 0.0159551 0.667647 -0.744307 -1.0414e-07 0.737314 -0.67555 1.48198e-06 -0.737315 0.67555 0 0.737318 -0.675546 -1.01645e-07 0.737314 -0.67555 0.755282 0.630258 -0.179789 0.758468 0.623659 -0.189144 0.760974 0.621141 -0.187356 0.72993 0.620126 -0.287482 0.561015 0.571051 -0.599301 0.760425 0.622093 -0.186424 0.75863 0.624289 -0.186394 0.742776 0.554916 -0.374635 0.520846 0.737232 -0.430358 0.10371 -0.541998 0.833956 0.200768 -0.642809 0.739249 0.135055 0.0262997 0.990489 0.0240639 0.170206 0.985115 0.149592 0.886005 0.438881 0.120133 0.898496 0.422225 0.100734 0.994598 -0.0250511 0.11519 0.992669 -0.0365865 0.1125 0.993541 -0.0148504 0.0254452 0.222442 -0.974614 0.64094 0.751275 -0.15742 0.641043 0.751184 -0.157437 0.651381 0.740101 -0.167191 0.666277 0.579852 -0.468878 0.725365 0.622965 -0.292849 0.649812 0.750741 -0.118882 -0.501256 0.654938 0.565507 -0.363438 0.833732 0.415696 -0.422834 0.782727 0.456673 -0.453854 0.763426 0.459563 -0.480935 0.721826 0.497663 -0.478719 0.723677 0.497111 -0.337725 0.869986 0.359259 -0.339771 0.870748 0.355464 0.357305 0.832206 0.423989 0.427611 0.76321 0.484417 0.473754 0.731413 0.490502 0.474526 0.719892 0.506538 0.496313 0.650213 0.575236 0.338219 0.870043 0.358654 0.337744 0.869885 0.359485 0.121171 0.986535 0.109849 0.0921496 0.990859 0.0985219 -0.131758 0.985206 0.109586 -0.0395554 0.988645 0.14497 0.00726054 -0.00391271 0.999966 -0.813234 0.127035 -0.567903 -0.812697 0.135449 -0.566724 -0.832648 0.333997 0.441751 -0.961643 0.160273 0.222611 0.0497488 0.171147 0.983989 0.606998 0.672561 0.423338 0.606912 0.672689 0.423258 0.0715498 0.420258 -0.90458 0.111904 0.11277 0.9873 0.114358 0.126985 0.98529 0.606706 0.673007 0.423047 0.606871 0.67276 0.423204 -0.812663 0.135759 -0.5667 -0.812329 0.140573 -0.566005 -0.734205 -0.556079 0.389512 0.00777842 0.0448305 -0.998964 0.049501 -0.0142263 0.998673 0.0629699 -0.0599002 0.996216 0.606664 0.673057 0.42303 0.605324 0.675046 0.421776 0.0717119 -0.215675 -0.973828 -0.812657 0.135994 -0.566652 -0.813135 0.128707 -0.567667 -0.562645 0.158038 0.811452 -0.760833 0.0119663 0.648838 0.00613594 -0.00201464 0.999979 0.0542107 0.195556 0.979193 0.621513 0.649528 0.43799 0.608085 0.671195 0.423945 -0.812518 0.136701 -0.566681 -0.821497 -0.210316 -0.53001 -0.560692 0.156677 0.813066 -0.758574 0.0111243 0.651492 0.606988 0.672568 0.423342 0.606594 0.673157 0.422969 0.138592 0.210545 -0.96771 0.280188 -0.00979657 -0.959895 -0.369345 0.0615576 -0.927251 -0.147129 -0.19978 -0.968732 -0.812703 0.13545 -0.566717 -0.812703 0.13545 -0.566717 0.0116264 -0.0177902 -0.999774 0.0304942 0.140039 0.989676 0.607053 0.672624 0.423159 0.607753 0.67158 0.423811 0.113823 0.502954 -0.856786 -0.812603 0.136077 -0.56671 -0.813338 0.12439 -0.568338 -0.829219 -0.200587 0.521691 0.00402716 -0.0025886 0.999989 0.0508653 0.18973 0.980518 -0.83307 0.33264 0.44198 -0.961158 0.160193 0.224754 0.189659 -0.698529 -0.689991 0.183281 -0.705638 -0.684458 4.69573e-06 -0.800751 -0.598998 -0.000786435 -0.799782 -0.60029 1.1353e-07 -0.800778 -0.598961 -4.19204e-05 -0.800362 -0.599517 0.00276439 -0.801895 -0.597459 -6.61683e-05 -0.764837 -0.644223 0 -0.685491 -0.728081 0.000404778 -0.7169 -0.697175 -0.0355098 -0.728853 -0.683749 0 -0.225759 -0.974183 0.107814 0.993613 -0.0332959 -0.0283676 0.999597 0.00132753 -0.20753 -0.975854 -0.0681155 -0.143176 0.981292 0.128714 0 1 0 0.144651 0.989289 0.0195997 -0.0448951 0.994256 -0.0971596 0 1 0 0 1 0 0 1 0 0 1 0 0.0283498 0.995415 -0.09135 -4.04072e-05 0.999999 -0.00133534 0 1 0 -0.25355 -0.854327 0.453693 -0.266952 -0.96371 0 -0.26778 -0.963478 -0.00206961 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.267649 -0.963516 0 0.266526 -0.963825 -0.00235316 0.257756 -0.869458 0.421432 -0.000261598 -0.86893 -0.494936 -0.00047128 -0.86829 -0.496057 -0.00164823 -0.868479 -0.495723 0.0130034 -0.867867 -0.496626 0 -0.868622 -0.495476 1.14724e-05 -1 2.81874e-06 0 -1 3.83085e-06 0 -1 1.91523e-06 -5.72756e-06 -1 1.40725e-06 0 -0.864028 -0.503444 0.000116013 -0.868687 -0.495361 0.00126616 -0.868823 -0.495122 0.00238059 -0.869 -0.494806 -0.0174797 -0.871049 -0.490884 0.00173835 -0.999999 -0.000328498 -0.0523313 -0.998572 0.0107104 -0.010388 -0.998788 -0.0481174 0.754571 -0.539301 0.373868 0.0513018 -0.998486 -0.019839 -0.0402684 -0.999109 -0.0126479 0.00639615 -0.999177 -0.0400493 0.946323 0.314157 0.0760119 -0.316583 0.87843 -0.357961 -9.94013e-06 -0.798635 -0.601815 0 -0.798409 -0.602115 0.358599 0 -0.933492 0.171818 -0.439569 -0.881622 0.0157506 -0.798536 -0.601741 -0.999994 0 -0.00351773 -0.999992 -0.00177215 -0.00355432 -0.751614 0.529792 -0.392934 -1.24575e-06 0 -1 5.35886e-08 -8.84157e-05 -1 0 0 -1 -3.74882e-09 6.54185e-06 1 0.00044443 -0.0236328 -0.999721 8.18842e-08 0 -1 0 -6.26143e-06 -1 0.00113105 -0.446205 -0.89493 -0.000407253 -0.0191239 -0.999817 0.0111837 0.0281366 -0.999542 0.0295956 0.0170095 -0.999417 0.606743 0.67295 0.423084 0.606596 0.673129 0.423012 -0.812676 0.135446 -0.566755 -0.81339 0.124004 -0.568348 0.120829 -0.754514 -0.645065 0.0660002 0.0732124 -0.99513 -0.0328247 0.135397 0.990248 -0.126917 -0.581911 0.803288 0.0457512 0.155636 0.986754 -0.952511 0.158752 0.259847 1.71905e-05 -1 4.87047e-05 -0.167212 -0.864638 -0.473753 0.20647 -0.976639 -0.0595443 0.195628 -0.979377 -0.0504966 -4.60648e-06 -1 0.000263396 -0.177776 0.891515 -0.41665 -0.00781924 -0.105159 0.994425 0.00838774 0.224097 -0.974531 2.57195e-05 1 6.65626e-06 1.37068e-05 -0.999999 -0.00169688 -9.5592e-06 0.999999 0.00119126 0.000132459 1 7.60391e-05 -4.14233e-05 1 -2.37794e-05 3.087e-05 -1 -2.65758e-06 8.99645e-05 -0.999997 -0.00238139 -0.00010353 0.999995 0.00315114 2.2971e-05 -0.999998 -0.00207131 0.000330972 1 -7.66168e-05 -1.59205e-05 0.999999 0.00144883 5.56166e-05 1 -2.95059e-05 0.000274041 -0.999778 -0.0210915 5.05916e-07 1 4.46356e-06 0.00319389 0.999668 0.0255524 9.06982e-05 1 5.19696e-05 -4.07212e-06 1 -2.83964e-06 0.000433981 1 0.000248565 -0.0199052 0.999736 -0.0115143 -0.00684414 0.999955 -0.00664537 -0.00813948 0.99993 -0.00862493 0.000461473 1 0.000458567 0.00822618 0.999962 -0.00287074 -0.0534023 0.994688 0.0879954 -1.74725e-05 0.999999 0.00173684 9.20255e-08 -1 -9.14773e-06 0.000220895 1 0.000330742 6.40221e-06 1 -0.000323791 0.0133057 0.999655 -0.0226382 -3.94478e-07 -1 3.38792e-07 2.09258e-06 1 -9.72472e-05 -2.14722e-05 0.999997 0.00241858 4.25699e-05 1 2.45606e-05 -0.0754026 0.996204 -0.0435034 0.000232224 1 0.00015522 4.18955e-05 1 4.46489e-05 -0.000165526 -0.999999 0.00125237 0.131223 -0.401496 -0.906411 0.149328 0.886885 -0.437192 -0.317895 -0.268691 0.909257 0.31855 -0.0473221 -0.946724 -0.00808498 0.999967 0.000710111 -0.122503 -0.826568 0.549344 1.04841e-07 1 -6.72408e-06 -0.000339906 0.999983 -0.00573904 -3.95212e-07 -1 5.88262e-06 -2.15174e-07 1 3.2028e-06 -2.58432e-06 1 9.63404e-06 6.18108e-07 1 4.30997e-07 -1.00365e-06 1 1.46924e-06 -1.70971e-07 1 -1.19222e-07 -0.00748209 0.99995 -0.00663635 3.33236e-05 1 2.16334e-05 -0.00396875 -0.999021 -0.0440676 -0.000340696 1 -0.000954784 0.0885957 0.984536 -0.151127 0.00122154 0.999979 -0.00639977 -1.66365e-06 1 -3.20144e-05 0.055399 -0.515276 -0.855232 -0.00375372 0.999852 -0.0168199 -0.00360115 0.998592 0.0529219 -0.235239 0.6958 0.67862 0.109384 0.462556 0.879817 -0.0728961 0.326118 0.942514 0.335669 0.566049 0.752938 -0.00141212 0.33406 0.942551 -0.238593 0.589886 0.771433 -0.000134038 -1 -3.18569e-06 -5.1876e-05 -1 -8.1901e-06 -1 -5.29679e-05 0 -1 0 -7.27935e-06 0.999997 0.00250343 -0.000661788 0.999997 -0.00233772 1.7724e-05 0.00232268 -0.999997 1.09472e-05 0.000411718 -1 0.000130368 -0.999999 0.00152608 -0.000224192 -1 0 -1.45512e-05 1 0 0 0.999969 0.00777628 -0.00107086 1 0.000847322 0.000244628 1 0.000467667 0.000393917 1 0.000393025 0.000417444 0.999998 0.00217126 8.50216e-06 -0.999996 0.00274475 -0.000130105 -1 0.000392888 0.000417298 -1 0.000467236 0.000393553 -1 0.000828932 0.000249282 0.529608 -0.79162 0.304718 -0.84624 -0.405853 0.345198 -0.515238 -0.414916 -0.749917 -0.245714 -0.814309 -0.525857 0.634545 0.212026 -0.743234 0 -0.999999 0.00119871 -0.0330139 -0.999131 0.025441 -0.738823 -0.673862 0.00716537 0.66397 -0.747635 -0.0136095 -0.823663 -0.566015 0.0347439 -0.542605 -0.838027 0.0573581 0.54397 -0.838472 0.0325763 0.824565 -0.564691 0.0348662 -1 -0.000448414 -0.000369599 -1 -2.50398e-06 -2.86456e-06 0.999964 -0.00561131 -0.00641934 0.999986 -0.00311132 -0.00436386 0.785525 0.61828 -0.026072 -0.00926323 0.999953 -0.00283041 -0.761778 0.647783 0.00844227 -0.70637 0.707676 -0.0153452 0.999861 0.0133421 0.0100173 0.442909 0.895702 0.0393603 0.288604 0.957353 0.0135061 -0.0412284 0.998988 -0.0179669 -0.999927 0.00907676 0.00800302 -0.33035 0 -0.943858 -0.182464 0.425748 -0.886254 0.261643 -0.610499 -0.747552 0.759257 0 -0.650791 0.0171564 -0.596703 0.802279 -0.0203162 -0.708359 0.70556 0.779249 0.616869 -0.110646 -0.779249 -0.616869 0.110646 0.530018 0.782646 -0.326414 -0.517468 0.717208 0.466733 0.799472 0.599976 0.0295549 -0.799472 -0.599976 -0.0295549 0.726756 0.684019 -0.0627982 -0.726756 -0.684019 0.0627982 -0.00054133 0.000983216 0.999999 0.963435 -0.080008 -0.25572 -0.963435 0.080008 0.25572 0.927609 0.153328 0.340635 -0.763887 0.631353 0.133679 -0.277647 0.900582 -0.334461 -0.853046 0.432993 0.291256 0.0818204 0.985201 -0.150615 -0.57411 -0.328373 0.750046 -0.887011 0.461678 -0.00803597 0.00190542 0.999957 -0.00904439 -0.0020009 0.999855 0.0168905 -3.02158e-10 -1.58571e-07 -1 3.58491e-08 -1.42305e-07 -1 2.13507e-07 -2.13398e-07 -1 2.23792e-07 -2.11254e-07 -1 0.00551649 -0.999485 0.031622 -0.00275297 -0.999807 -0.019453 9.94294e-05 -1 0.000277775 4.50837e-05 -0.999999 0.00112306 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -5.50603e-05 6.10413e-05 -1 -3.15837e-07 1.30284e-08 -1 1.41932e-05 -5.85477e-07 -1 -2.64268e-07 1.28928e-07 -1 0 0 -1 0.000130794 0.999999 -0.0011707 -0.000161369 0.999994 0.00337244 0 0 -1 -1.74218e-07 -1.7212e-08 -1 0 0 -1 -5.48363e-07 1.56439e-07 -1 9.57438e-08 -5.79986e-07 -1 7.46901e-07 -2.58712e-07 -1 5.44094e-07 5.12099e-07 1 -5.44094e-07 -5.12099e-07 -1 -5.54235e-07 1.07583e-06 -1 1.82274e-07 1.04919e-06 -1 4.87645e-05 -0.999999 -0.00166416 -0.000386753 -0.999992 0.0040855 0.000411027 0.999992 0.0040845 -0.000268961 0.999991 -0.00420603 -1.22218e-07 2.89091e-11 -1 -3.41964e-11 1.27142e-07 -1 1 -9.24194e-06 0.000371894 1 -1.07959e-10 -0.000214582 0 0 1 1.76966e-07 -5.057e-06 1 0.539217 0.441705 0.717037 -2.42484e-05 1.28308e-05 -1 -0.00355699 0.00525132 -0.99998 0.00355699 -0.00525132 0.99998 -1.23817e-05 -1.01426e-05 1 -0.00186601 -0.00126962 0.999997 2.04886e-06 -1.08413e-06 1 0.00070166 0.000978536 0.999999 -4.13507e-06 2.69751e-06 1 -0.000444249 0.000154552 1 1.17358e-05 4.193e-06 1 -1.39523e-06 -2.58577e-06 1 -2.72976e-05 -3.65246e-05 1 0.00837683 -0.00216907 0.999963 0.000697264 -0.00112625 0.999999 -3.28618e-05 -2.29926e-05 1 -3.27293e-07 -2.28999e-07 1 -2.07415e-05 -0.000252944 1 0 0 1 0 0 1 6.50704e-06 1.07557e-06 1 -0.927609 -0.153328 -0.340635 0 0 1 0 0 1 -1.15793e-05 0.000102451 1 0 0 1 -2.8038e-06 -5.01652e-06 1 -5.39729e-06 9.73412e-05 1 0.763887 -0.631353 -0.133679 -0.879099 0.35931 -0.31318 1.81341e-06 -1.70103e-06 1 1.85176e-06 5.75161e-06 1 0.879099 -0.35931 0.31318 -2.51445e-06 7.5362e-06 1 2.3511e-05 1.85064e-05 1 0 0 1 -1.56028e-05 -1.19307e-05 -1 6.5165e-06 2.62394e-06 1 -2.67279e-05 -2.04375e-05 -1 0 0 1 7.96421e-07 -9.0339e-06 1 -1.72749e-05 8.76846e-06 -1 0.853046 -0.432993 -0.291256 0 0 1 -6.62609e-06 -1.16665e-05 1 0 0 1 0 0 1 -1.07187e-05 0.000306418 1 0.00028076 0.000346285 1 -5.6234e-07 4.09367e-06 1 -0.0139871 0.000369653 0.999902 0.0139871 -0.000369653 -0.999902 -0.930486 -0.0994537 -0.35257 0 0 1 0 0 -1 0 0 1 2.33001e-05 -1.14245e-05 1 -2.68062e-06 4.03137e-06 1 0 0 1 0.000220005 -9.00814e-06 1 0.000284349 3.81057e-06 -1 -4.38639e-06 -0.000261682 -1 3.27671e-05 1.65415e-05 1 -4.10828e-07 0.000105477 -1 0.0024231 0.000209453 -0.999997 0.000100362 -7.52882e-06 -1 0.000268413 -0.000307726 -1 -2.5331e-06 -8.2813e-05 -1 -6.55752e-06 6.74392e-05 -1 4.13659e-06 -3.82138e-05 -1 -0.57787 0.580092 -0.574073 -2.41391e-05 -1.38882e-05 -1 -3.22893e-05 1.28e-06 -1 0.00347595 -0.999984 -0.00456543 -5.8479e-07 -4.78101e-08 1 5.05386e-05 0.00158482 -0.999999 2.81752e-05 0.000154348 -1 6.8418e-05 6.24601e-05 -1 0.000928854 -0.0011509 -0.999999 -0.000848766 -0.000240975 -1 0.630972 0.720582 0.287466 6.79097e-07 -0.000184998 -1 0.000111272 -5.73642e-06 -1 2.1166e-05 -1.74536e-06 -1 6.63947e-06 -0.000139261 -1 0 -6.04179e-05 -1 1.71673e-05 0.000334336 -1 -0.000313123 1.01375e-05 -1 2.65748e-05 -1.69626e-06 1 0 0 1 3.83576e-05 0.000132272 -1 -2.2334e-08 -7.70161e-08 -1 0.000229341 0.00162458 -0.999999 0.00108011 0.0013159 -0.999999 -0.000709115 -0.000551401 -1 -0.000263 -0.00141026 -0.999999 3.57336e-05 -0.000680764 -1 0.000989173 3.63449e-05 -1 2.8322e-07 7.88352e-08 1 2.18795e-07 2.80951e-06 -1 -7.31575e-05 -0.000957468 -1 -5.81997e-07 1.49396e-07 1 -1.00121e-05 -2.57778e-06 -1 6.81359e-05 -8.94756e-05 -1 6.78001e-06 1.22148e-05 1 -7.68647e-05 -0.000314906 1 0 0 1 2.19256e-07 1.65828e-08 -1 1.24392e-05 -1.27917e-07 -1 -1.33658e-05 -9.024e-07 1 8.20508e-06 -9.35227e-07 -1 -9.78598e-06 1.51159e-06 1 -1.12887e-06 -3.47978e-05 -1 -6.73718e-06 6.58742e-05 -1 -3.58245e-05 -1.75843e-05 -1 2.02242e-05 -1.06737e-05 -1 0.778504 0.275658 -0.563865 -0.930489 0.33244 -0.15386 0.00184115 -0.235663 -0.971833 6.73842e-06 3.92699e-05 -1 1.6865e-07 -6.6006e-06 -1 -2.28479e-06 8.94221e-05 -1 -6.38297e-06 1.34305e-05 -1 1.35067e-06 -5.6716e-05 -1 2.26315e-05 3.15921e-05 -1 -1.57874e-05 -4.81004e-05 -1 -1.59158e-05 -6.22506e-05 -1 6.23719e-06 -1.99573e-05 -1 6.03275e-06 -7.49846e-08 -1 8.0635e-05 6.34956e-05 -1 1.7415e-05 -3.08442e-07 1 -2.51915e-06 1.23497e-06 -1 -1.83945e-07 -2.04599e-07 1 0 0 -1 9.70823e-07 -4.16624e-06 1 5.74383e-06 -1.98797e-06 -1 -1.58016e-06 1.21551e-07 -1 1.46313e-05 -1.12549e-06 -1 -0.999998 0.00173753 -0.000664513 0 -0.181118 0.983461 -1 0 0 -1 0 0 -0.999995 0 -0.00304718 -1 0 0 0 -0.181118 0.983461 -1 0 0 -0.999998 -0.00170012 -0.000650206 -0.999998 -0.000181234 0.00196432 -0.999996 -0.000329531 0.00294828 -1 -0.000454094 -0.000545245 -1 0 0 -1 -0.000117752 -4.32474e-05 -0.999995 0.000334697 0.00307162 -0.999997 0.000528677 -0.00236886 -1 0 0 -1 0 0 -1 3.43879e-07 -8.75279e-06 -1 0 0 -0.009595 0.812957 0.582245 4.42643e-05 0.81918 0.573537 0.431507 0.699631 0.56949 0.441844 0.673056 0.593101 0.287793 0.790652 0.540411 0.11991 0.784914 0.607891 0.526541 0.627507 0.573576 0.526835 0.628133 0.57262 0.0140827 -0.844659 0.53512 -6.88494e-06 -0.819381 0.57325 -1.81291e-05 -0.819524 0.573046 6.37589e-05 -0.819152 0.573577 0.119166 -0.813315 0.56949 0.0941526 -0.799595 0.593113 0.28774 -0.790675 0.540406 0.401438 -0.689947 0.602346 0.451197 -0.685945 0.570877 0.526643 -0.627629 0.573348 0.534784 -0.645859 0.544861 0.415931 -0.768698 0.485907 0.0266688 -0.990377 0.135805 0.207346 -0.962252 0.176292 0.887011 -0.461678 0.00803597 0.544193 -0.683344 0.486718 0.277647 -0.900582 0.334461 0.930486 0.0994537 0.35257 -2.48615e-05 -0.939693 0.342018 0 1 0 0 1 0 0 -6.56914e-06 1 -3.26237e-05 0.000243088 1 1.63645e-06 0.000270211 1 3.67924e-06 0.000133961 1 5.49955e-05 0 1 -1.87369e-05 -8.15485e-05 1 -1.77133e-05 -0.000383069 1 0 2.34225e-05 1 -7.04649e-06 0.000343404 1 -2.26347e-06 -7.30586e-05 1 -6.89161e-05 0.000304696 1 0.000151871 0 1 -3.35191e-05 -0.000103376 1 -3.26582e-05 -0.000447409 1 0 -1 0 0 -1 0 0 0.181118 0.983461 0 0.939693 0.34202 0 0.939693 0.34202 -2.57883e-06 0.939693 0.34202 -2.41765e-06 -0.939693 0.34202 0 -0.939693 0.34202 0 1 0 0 1 0 0 0 1 0 -3.30921e-05 1 1.0567e-06 4.05396e-05 1 3.39472e-06 -2.39991e-06 1 -9.9004e-07 0 1 5.88178e-07 -4.50612e-06 1 4.00978e-06 2.56964e-05 1 -1.40099e-05 0.000142179 1 6.2448e-05 0 1 -1.60076e-05 -0.000146335 1 0 -1 0 0 -1 0 0 0.181118 0.983461 5.03674e-09 0.939693 0.34202 0 0.939693 0.34202 1 -2.01877e-06 4.31429e-05 1 -1.24498e-06 1.74661e-05 2.35507e-05 -5.03114e-07 -1 1.02204e-05 7.95694e-08 -1 0.0511511 -0.756397 -0.652109 1.49241e-05 -1.36323e-06 -1 4.42169e-06 7.22588e-07 -1 -3.57097e-06 -2.78013e-08 -1 1.17587e-07 1.37643e-07 -1 0.707104 1.07545e-05 0.707109 0.707108 -1.21635e-06 0.707106 0.707107 0 0.707107 0.707107 0 0.707107 0.707108 1.21635e-06 0.707106 0.707104 1.07545e-05 0.707109 0.707108 -1.21635e-06 0.707106 0.707107 -3.80692e-07 0.707107 0.707108 0 0.707106 0.707108 -6.0774e-07 0.707106 0.00440807 -0.233827 0.972268 -0.0121973 -0.997733 -0.0661753 0.00627988 -0.213967 -0.976821 -0.0464989 0.823475 -0.565444 0.0194055 0.629434 0.776811 0.150662 0.188545 0.970439 0.0347843 0.989605 -0.139543 0.00823349 -0.867453 0.497451 0 0.181118 0.983461 0 0.181118 0.983461 0.00823012 -0.867212 0.497871 1 5.6917e-07 0.000509991 0.999999 2.8444e-05 0.00109349 0.000693388 0.999943 0.0106812 -0.000517707 0.999992 -0.00408598 -0.999998 -0.000132419 0.00194518 -0.999993 0.000353113 -0.00374462 0.000156 -0.999975 -0.00713619 -0.00548312 -0.998085 0.0616203 -0.181969 -0.979255 -0.0891432 -0.171059 -0.984639 -0.0349936 -0.641844 -0.766825 0.00382621 -0.641141 -0.767298 0.0138861 -2.44484e-07 -2.5432e-07 -1 0 0 -1 0 1 0 0 1 0 -0.998202 -0.0150018 0.0580358 -0.999984 0.00140564 -0.00543785 6.83294e-06 -1 -0.000235053 -1.76678e-05 -1 0.000607772 0.999805 0.00140844 0.0197077 2.98735e-07 -4.40634e-06 -1 0 0 -1 0 0 -1 0.000972676 -0.000315205 -0.999999 -0.000416864 0 -1 -0.999993 -0.00043137 0.00374495 -0.999992 0.000236536 -0.00408375 0.00024472 -0.999857 0.0168913 1 2.91763e-05 0.000610443 1 -2.91768e-05 -0.000610454 0.002544 0.999854 -0.0168906 -0.00254405 0.999854 0.0168909 -0.641598 0.767008 -0.00715761 -0.641038 0.767357 -0.0152919 -0.182337 0.977896 0.102335 -7.17376e-06 -2.70164e-06 -1 1.1035e-06 4.2695e-07 -1 1.12312e-06 4.22967e-07 -1 -8.75152e-06 -1.98428e-06 -1 -0.999996 -0.000441307 0.00295096 -0.999994 0.000127347 -0.0034015 0.999993 0.00050902 0.00373934 1 9.00164e-05 -0.000981341 0.999957 0.000620283 0.00927558 0.999993 -0.000486239 -0.00369874 -0.999997 8.25493e-06 0.00225333 -1 0.000264718 -0.000702456 1 -2.09492e-05 0 0.999999 -9.02652e-05 -0.00134109 -1 2.70166e-05 -0.000610492 -0.999999 4.98886e-05 -0.00108948 1 4.45166e-05 0 0.999999 0.000105663 0.00118303 -1 4.98885e-05 -0.000835349 -1 3.91334e-05 -0.000610287 0.750154 -0.661264 0 0.353333 -0.757725 -0.548642 -0.836197 -0.393296 0.382222 0.785668 0.618648 0 -0.225891 0.907853 0.353236 0.75675 0.315312 -0.572632 0.476769 0.879029 0 0.418492 -0.881801 0.217467 0.921896 -0.184344 -0.340773 -0.399149 -0.840733 -0.365854 -0.428748 0.903424 0 -0.475925 0.877541 -0.058452 0.396218 0.827132 -0.398577 -0.543128 -0.801974 -0.248696 0.551847 -0.764857 0.332354 -0.845678 -0.52911 -0.0697999 0.845678 0.52911 0.0697999 0.961044 0.262194 0.08746 0.26113 0.794705 0.547955 -0.0181549 0.997444 0.0691066 -0.949809 0.302317 0.0804162 -0.86016 -0.494886 -0.123337 0.114321 -0.144911 0.982818 0.141465 -0.168592 -0.975482 0.00106172 -0.623027 0.782199 0.00371871 -0.252226 -0.967661 0.22953 -0.00747089 0.973273 0.707112 9.22068e-05 0.707102 0.705996 0.0001022 0.708215 0.653099 0.383323 0.653089 0.610034 0.365882 0.702843 -0.0296988 0.46155 0.886617 0.0131165 0.896774 0.442295 0.141538 0.168678 -0.975456 0.0276886 -0.950483 0.309542 0.0723419 0.951169 0.300074 0.00590967 0.0121358 0.999909 -0.713851 0.00651179 0.700268 -0.707112 0 0.707102 -0.707112 0 0.707102 -0.380996 -0.254862 0.888756 0.198462 -0.470765 0.859647 -0.258572 -0.774102 0.577847 0.277293 -0.934401 0.223612 -0.11976 -0.992162 0.0356789 -0.444306 0.872729 -0.202329 0.0308876 -0.747819 -0.663183 -0.100158 -0.742965 -0.661795 -0.0496912 -0.774302 -0.630863 0.226547 -0.191394 -0.95501 -0.0435276 -0.089475 -0.995037 0.201216 0.558202 -0.804936 -0.328632 0.926181 -0.184905 0.147979 0.755965 0.637667 -0.106233 0.835658 0.538879 -0.449111 0.563719 0.693195 0.185923 0.288203 0.939346 -0.631644 -0.0783943 -0.771285 -0.63167 -0.0783862 -0.771264 -0.852759 -0.294346 -0.431466 -0.963148 -0.208733 -0.169637 -0.783402 -0.620175 -0.0407999 -0.925264 -0.377574 0.0364012 -0.739929 -0.560082 0.372576 -0.933532 -0.256851 0.250092 -0.736718 -0.195741 0.64725 -0.988747 0.0160424 0.148734 -0.993098 0.0746518 0.0904641 -0.987058 0.154789 -0.0419253 -0.789506 0.443311 -0.424447 -0.635131 0.491564 -0.595797 -0.926826 0.192545 -0.322366 -0.173248 -0.947043 -0.27036 -0.308402 -0.185828 0.932929 -0.0389049 0.977349 0.208026 -0.395208 -0.00875098 -0.91855 -0.596916 -0.119452 0.793361 -0.590319 0.454694 -0.666915 0.00111588 0.281227 -0.959641 -0.296605 0.396267 0.868906 -0.591965 0.451565 -0.667583 -0.302946 0.657715 -0.689662 -0.825759 0.537233 0.171766 -0.7853 0.536393 0.309172 -0.65163 0.756777 -0.0516416 -0.47849 0.6879 0.545749 -0.18725 0.78876 -0.585487 -0.344674 0.935242 -0.0807626 -0.402806 -0.910636 -0.0921396 -0.456035 -0.850114 0.263321 -0.522198 -0.776087 0.353551 -0.421896 -0.584601 0.692997 -0.887178 -0.416024 0.199596 -0.917436 -0.331859 0.219502 -0.488693 -0.348542 0.799811 -0.395195 -0.0662633 -0.916204 -0.271976 -0.51961 -0.80996 -0.449286 -0.331339 -0.829673 -0.797536 -0.408111 -0.444277 -0.787269 -0.538531 -0.30032 -0.732582 -0.111035 0.671561 -0.988732 0.070054 -0.132291 0.909977 0.359693 -0.206308 0.981043 0.0783309 0.177252 0.99635 -0.000763056 0.0853637 0.996343 -0.00012309 0.085438 0.996231 0.00197691 0.0867228 0.995755 0.00530501 0.0918895 0.563577 0.817793 0.116601 0.000920436 -0.99547 0.0950771 0.142033 -0.0317888 0.989351 0.799443 -0.200048 -0.566455 0.787117 0.563672 -0.25044 -0.0786374 -0.881523 -0.465546 0.808272 -0.50865 -0.296598 0.836576 -0.529535 -0.140479 0.982544 -0.172507 0.0696251 0.829657 0.554587 -0.0640556 -0.989147 -0.138024 0.0503842 -0.751875 -0.64264 -0.1473 -0.034744 0.997398 -0.0631599 0.0723695 -0.0614721 0.995482 0.20916 0.853324 -0.477589 0.0202207 0.930252 -0.366363 -0.769311 0.438469 -0.464656 -0.628384 0.0549227 -0.775962 -0.23116 0.0592156 0.971112 -0.0878159 -0.0787429 -0.99302 -0.178045 0.0147316 -0.983912 -0.894138 0.433819 -0.110988 -0.350778 -0.92845 -0.122214 -0.579846 0.810596 0.0819279 0.0419617 0.354384 -0.934158 -0.905612 -0.214966 -0.365591 -0.935366 -0.246139 -0.25398 0.384594 -0.296925 -0.874027 -0.257724 -0.856032 -0.448093 0.930378 -0.281847 -0.234434 0.614743 -0.695086 -0.372755 0.655551 -0.540087 -0.527786 0.112412 -0.947965 -0.297869 0.735159 -0.244642 0.632211 0.938301 -0.320253 -0.130498 0.987191 -0.130317 0.0920431 0.394416 -0.563802 0.725646 0.365502 -0.605326 0.707099 0.367712 -0.507738 0.779095 0.205444 -0.79436 0.571651 0.875156 -0.318282 0.364416 0.864384 -0.425072 0.268614 0.996491 -0.0797682 0.0253558 0.98046 -0.107647 0.164653 0.995459 -0.0839154 0.04494 -0.382685 -0.549452 0.742734 -0.484102 -0.871162 0.0819828 -0.761666 -0.300456 0.5741 -0.935331 -0.334897 0.114018 -0.987613 -0.126623 -0.0926621 -0.916473 -0.358662 -0.177313 -0.775795 -0.171434 -0.60725 -0.649071 -0.690282 -0.319716 -0.408411 -0.379415 -0.830208 -0.0817419 -0.974945 -0.206882 -0.987134 -0.0999437 -0.124807 -0.986293 -0.0236538 -0.163296 -0.982374 -0.00462104 -0.18687 -0.999934 0.0104917 0.00460302 -0.994889 -0.0945773 -0.0353828 -0.926361 -0.376629 0.00242824 0.00623141 -0.604959 0.796233 -0.0121308 -0.604179 0.796756 -0.00749328 -0.580261 0.814396 -0.0320015 -0.590177 0.80664 -0.0512015 -0.565283 0.823307 0.138015 0.608061 -0.781801 0.145066 0.602635 -0.784721 0.117335 0.581593 -0.804973 0.118072 0.579973 -0.806034 0.103768 0.559763 -0.82213 -0.342796 -0.510845 0.78837 -0.0680259 0.547682 0.833917 -0.0643952 0.75665 0.650641 -0.0599875 0.768352 0.63721 -0.0591939 -0.796301 0.601997 -0.0629655 -0.812112 0.580095 0.998837 0.0425819 0.0226256 0.993619 0.108555 0.030616 0.995952 0.0187728 -0.0879029 0.99774 -0.0414795 0.0528535 0.097718 0.819871 0.564147 -0.0230746 0.53885 0.842086 -0.0605782 -0.688899 0.722322 -0.0619001 -0.685584 0.725357 0.0511732 0.76628 -0.640465 0.0412814 -0.75214 -0.657709 0.958185 -0.014607 0.285775 0.995446 0.0860416 0.0410469 0.985264 -0.0664101 0.157622 0.981897 -0.112983 0.15203 0.0708489 -0.671433 -0.737671 0.0646262 0.685305 -0.725383 -0.0464245 -0.790351 0.610893 -0.044633 -0.772151 0.633869 -0.0853735 -0.7968 0.598182 0.062626 -0.791707 -0.607682 0.0697722 0.75895 -0.6474 0.0710626 0.754601 -0.652324 -0.0335158 0.806582 -0.590171 -0.980951 0.019094 -0.193313 -0.338075 0.713045 -0.614225 -0.267893 0.609229 -0.746373 -0.137063 0.79613 -0.589398 -0.643964 0.647581 -0.40737 -0.687025 0.3396 -0.642393 -0.905092 0.385153 -0.180184 -0.933738 0.222816 -0.280156 -0.068184 0.99747 -0.0201388 -0.922462 0.383919 0.0408602 -0.722531 0.437514 0.535285 -0.625807 0.708436 0.326319 -0.440983 0.66055 0.607624 -0.356696 0.797664 0.486313 -0.957176 0.257332 0.132642 -0.983285 0.0758397 -0.165526 -0.989143 0.118843 -0.086439 -0.999576 0.025418 -0.0142178 -0.99666 0.0746112 -0.0331894 -0.0408081 0.775746 0.629725 0.0117457 0.735123 0.677832 -0.0420169 0.771964 0.634276 0.96182 0.00220176 0.273674 0.978735 0.0563296 0.197245 0.876815 0.306765 0.370259 0.840587 0.504525 0.19715 0.486667 0.728872 0.481561 0.511398 0.486358 0.708468 0.0970431 0.938849 0.330371 0.850067 0.307708 -0.427435 0.989791 0.120514 0.0760945 -0.143393 0.911283 -0.386007 0.639783 0.743706 -0.193853 0.612096 0.760661 -0.216179 0.568981 0.513821 -0.642066 0.859455 0.110923 -0.499032 0.941926 0.289419 -0.170327 0.997078 0.00878257 -0.0758779 0.993747 0.108104 0.0279319 0.989528 0.0748912 0.123389 0.0548954 0.994909 0.0845197 -0.0450663 -0.997802 -0.0485851 0.149157 -0.097025 0.984042 0.38506 0.0218489 -0.922633 0.0236431 -0.834389 0.550669 0.0331069 -0.720526 -0.692637 -0.881321 0.235928 -0.409403 -0.926937 -0.0016864 -0.375213 -0.946236 -0.189682 0.262026 -0.97429 0.00469213 0.22525 0.197059 -0.819331 -0.53839 -0.958837 0.28356 0.0150102 -0.939237 0.229249 0.255496 0.0515545 0.841853 -0.537239 0.221197 0.29666 0.929013 -0.341772 0.853018 0.394401 0.182302 0.607888 0.772812 -0.00732 0.65223 0.757986 0.00607026 0.674666 0.738098 -0.0315045 0.670694 0.741064 -0.0312943 0.70065 0.712818 -0.0618284 0.688899 0.722215 0.11408 -0.585252 -0.802786 0.126847 -0.559314 -0.819193 0.0341917 -0.678749 -0.733574 0.143407 -0.602013 -0.785503 0.0738938 -0.55535 -0.828327 0.0685554 -0.568785 -0.819624 -0.02612 -0.696337 0.717239 -0.0262743 -0.667925 0.743765 0.00561098 -0.648614 0.761097 -0.217555 -0.472128 0.854263 0.0704853 0.596958 -0.799171 0.253418 0.525816 -0.811971 0.0720798 0.566885 -0.820638 0.0726279 0.568922 -0.819178 0.118899 -0.642055 -0.757383 0.121505 -0.641303 -0.757606 0.151101 -0.683593 -0.714051 0.093218 -0.675234 -0.73169 0.0921413 -0.688035 -0.719804 0.0645219 -0.685975 -0.724759 0.0273795 0.51108 0.859097 -0.00458244 0.571748 0.820417 -0.0429948 0.583362 0.811073 -0.0179382 0.61306 0.789833 -0.0149082 0.613067 0.78989 -0.0724298 0.564412 0.82231 -0.0684794 -0.574552 0.815598 -0.0736871 -0.554289 0.829056 0.0663781 0.6926 -0.718262 0.11057 0.690202 -0.715119 0.105268 0.671291 -0.73368 0.143859 0.662923 -0.734737 0.105098 0.62909 -0.770195 0.995627 -0.0367684 0.0858721 0.995662 -0.0355823 0.0859664 -0.99586 -0.0213273 -0.0883681 -0.995996 -0.0165007 -0.0878598 0.0602468 0.643898 -0.762736 -0.0177828 -0.999837 -0.00302414 0.0201565 -0.999791 0.00347282 -0.0243224 0.999698 -0.00360692 0.99568 0.0286976 0.0883063 0.99623 0.00536219 0.0865886 -0.996193 -0.0101181 -0.0865884 -0.996227 -0.00811976 -0.0864011 0.224239 0.974055 0.0305629 0.242544 0.969563 0.0334587 -2.5888e-08 -1 -7.20336e-08 -0.0558749 -0.998436 -0.00166978 -0.320933 0.947037 -0.0110877 0.674226 0.735368 0.0682149 0.834649 0.545918 0.0730371 0.835572 -0.544496 0.0731032 0.839256 -0.538721 0.0736832 -0.709874 -0.700558 -0.0727894 -0.806661 -0.383744 -0.449487 -0.707781 0.704073 -0.0576891 -0.979588 0.188399 -0.0700926 0.0936742 -0.682895 -0.724485 -0.238295 0.12038 0.963703 -0.00434924 -0.674021 0.738699 0.109544 0.540584 -0.834128 -0.0722773 0.69343 0.71689 -0.0766781 0.698059 0.711923 -0.0720702 0.69287 0.717452 0.0663024 0.846668 -0.527974 0.249403 -0.115459 -0.961492 0.0144584 0.348128 0.937335 -0.105473 -0.994357 -0.0113914 -0.0302942 -0.742261 -0.669425 0.0905199 -0.677917 -0.729544 0.0539776 -0.652898 -0.75552 0.970969 0.0457612 -0.234787 -0.112451 -0.619995 -0.776506 -0.248663 -0.323646 -0.912918 0.921178 -0.287513 -0.262236 0.184436 -0.85184 -0.490257 -0.681988 0.0905259 0.725739 0.76038 -0.277898 0.587022 0.624181 -0.736173 0.261624 0.825033 -0.536749 0.176694 0.313249 -0.945835 -0.085267 -0.0723662 -0.219616 0.972899 -0.405952 -0.618578 0.672728 -0.351589 -0.55212 0.756008 -0.43102 -0.462214 0.77497 0.272453 -0.740525 0.614322 0.0884719 -0.178634 0.97993 0.441348 -0.0576618 0.895481 0.555378 -0.147473 0.818417 0.584946 -0.102807 0.80453 0.695682 -0.0341934 0.717536 -0.822545 -0.557326 0.113172 -0.566759 -0.820354 0.0761816 -0.94377 -0.121709 -0.307385 -0.630823 -0.348018 -0.693502 -0.0599366 -0.995641 -0.0714638 -0.396477 -0.337685 -0.853683 0.14861 -0.39854 -0.905031 0.355118 -0.701638 -0.617734 -0.345314 -0.233343 -0.909016 -0.489708 -0.0520741 -0.87033 -0.628738 -0.00363311 -0.777609 -0.588585 -0.0872863 -0.803709 -0.547416 -0.113425 -0.829138 -0.495468 -0.0256152 -0.868249 -0.488238 -0.0531108 -0.871093 -0.616596 -0.605011 0.503757 -0.618319 -0.605143 0.501482 -0.641096 -0.587749 0.493505 -0.653595 -0.555082 0.514488 -0.655774 -0.563566 0.502348 0.934879 0.304065 -0.183153 0.694601 0.610425 -0.380671 0.70976 0.578381 -0.40214 0.695606 0.586061 -0.415529 0.706985 0.559641 -0.432405 -0.669846 0.561638 0.485663 0.704753 -0.53366 -0.467472 -0.578901 0.734827 0.353418 -0.532013 -0.767802 0.356991 -0.539401 -0.758618 0.365438 0.475766 0.411619 0.777314 0.555681 0.0499758 0.829892 0.62027 -0.128901 0.773725 0.631381 -0.0483938 0.773961 -0.168038 0.846214 0.505653 -0.616668 0.660864 0.427761 -0.592606 -0.696043 0.405391 -0.602569 -0.685791 0.408168 0.533657 0.764383 -0.361841 0.533276 0.764842 -0.361432 0.528186 -0.771638 -0.354392 0.515954 -0.785486 -0.341764 0.459069 -0.0226156 0.888113 0.800237 0.0290844 0.598979 0.112451 0.619995 0.776506 0.250548 0.0260819 0.967753 0.507367 -0.106446 0.85513 0.550436 0.77723 -0.304851 0.19036 0.924796 -0.329416 0.603067 -0.686565 -0.406126 0.62891 -0.659184 -0.412248 0.602063 0.688575 -0.404209 0.604012 0.685174 -0.407071 -0.491588 -0.803004 0.336935 -0.521828 -0.770801 0.36546 -0.518377 -0.80448 0.289996 0.519457 -0.785392 -0.336637 0.530247 0.774046 -0.345964 0.620685 0.720754 -0.308648 -0.54213 0.00543024 -0.840277 0.25083 0.757656 -0.60253 0.349083 0.691265 -0.632688 -0.00550406 0.559903 -0.82854 -0.476785 0.417823 -0.773369 -0.652147 0.325659 -0.68458 -0.873297 0.184409 -0.450939 -0.634409 0.660057 -0.402306 -0.891554 0.448771 -0.0611159 -0.476267 0.059072 -0.877314 -0.564892 0.118528 -0.816608 -0.608293 0.0172082 -0.793526 -0.570515 0.113345 -0.813428 -0.466932 0.819246 0.332884 -0.509438 0.832266 0.218648 -0.518985 0.778144 0.35376 0.450686 0.0106741 0.892619 0.518493 0.0626932 0.85278 0.355115 0.386862 0.851018 -0.0833893 0.150124 0.985144 0.13757 0.644386 0.752224 -0.418861 0.573651 0.703904 -0.461974 0.214616 0.860535 -0.438799 0.567944 0.696344 -0.218838 0.717821 0.660941 0.509457 0.0432557 0.859408 0.578654 0.126893 0.805641 0.505575 0.843719 0.180366 0.274738 0.806948 0.522833 0.810221 0.577089 0.102518 0.791219 0.35257 0.499667 0.682117 0.430586 0.591027 0.559134 0.134375 0.818115 0.0756622 0.979597 0.186184 0.059035 0.997719 -0.0327368 -0.798749 0.0110408 0.601563 0.798865 0.318771 -0.510097 0.808478 -0.2452 -0.535014 -0.392342 -0.816961 0.42266 -0.324429 -8.12553e-05 -0.94591 -0.275931 -0.203009 -0.939494 0.479557 -0.760168 -0.438373 -0.415741 0.0451081 -0.908364 0.106181 -0.155626 -0.982093 -0.738323 -0.170286 -0.652596 -0.498929 -0.244517 -0.831433 0.524436 -0.844772 -0.106426 -0.874105 -0.0708323 -0.480544 -0.622689 0.0494887 -0.780903 -0.584742 0.288207 0.758297 -0.51902 0.854507 -0.0208929 0.248663 0.323646 0.912918 0.112451 0.619995 0.776506 -0.619787 0.634169 0.462271 -0.571088 0.665629 0.480413 -0.591392 0.67299 0.444229 -0.575043 0.694689 0.432126 -0.607368 0.677521 0.414811 0.700486 -0.550376 -0.454318 0.718975 -0.565296 -0.404371 0.694036 -0.579857 -0.426709 0.680175 -0.618199 -0.393944 0.675915 -0.617568 -0.40218 0.693092 -0.551992 -0.463604 0.682371 -0.566282 -0.462272 -0.577915 -0.682115 0.448032 -0.588786 -0.671708 0.449599 -0.572968 -0.657793 0.488893 -0.32927 -0.772777 0.542584 0.575596 0.708803 -0.407784 0.703676 0.53952 -0.46234 0.683241 0.56677 -0.460384 0.629754 -0.761824 -0.151769 0.655982 -0.689096 -0.307952 0.62456 -0.671283 -0.399129 0.622146 -0.685103 -0.378904 -0.639009 0.588962 0.494765 -0.641844 0.580319 0.501265 -0.660556 0.572595 0.485594 -0.661103 0.574822 0.482206 -0.61606 0.605978 0.50325 -0.505089 0.243496 0.828007 -0.684258 0.566459 0.459255 -0.685185 0.563988 0.460911 -0.686457 -0.560572 0.46318 -0.682616 -0.566251 0.461948 0.619134 0.684795 -0.384355 0.621407 0.670519 -0.405287 0.646545 0.674302 -0.356785 0.655067 0.655029 -0.376595 0.672984 0.650414 -0.352213 0.559116 -0.0270826 0.828647 0.558039 -0.0401945 0.828841 -0.56043 -0.0272661 -0.827753 -0.826618 0.286424 0.484421 -0.0122609 -0.999682 -0.0220232 0.00870536 -0.999844 0.0153993 -0.0059482 0.999897 -0.0130444 0.558944 0.0269743 0.828766 0.55945 0.0380624 0.82799 -0.557527 0.0275534 -0.829701 -0.0149145 0.999719 -0.0184055 0.0125644 0.999795 0.0158493 -0.030881 -0.998723 -0.0399939 -0.550769 0.0822705 -0.830593 -0.232981 0.917951 -0.321071 0.315983 0.810372 0.493409 0.466226 0.550169 0.692783 0.334277 -0.816594 0.470567 0.468063 -0.548548 0.692829 -0.563629 -0.0757786 -0.822545 -0.212788 -0.917463 -0.336128 0.621855 -0.683438 -0.382374 -0.563022 -0.057392 0.824447 0.973031 -0.0295138 -0.228781 0.760502 0.47438 -0.443396 -0.286651 0.955223 0.0733507 -0.33741 0.937906 -0.0805381 -0.678877 0.511875 0.526412 0.224657 0.0767505 -0.971411 0.712986 -0.336998 -0.614885 -0.611187 -0.686055 0.394689 -0.605519 -0.675942 0.420057 -0.0382529 -0.888892 -0.456518 -0.197039 -0.896112 -0.397693 0.0953348 -0.995361 -0.0129839 -0.43551 -0.77506 -0.457835 0.647096 -0.639817 -0.414609 0.604493 -0.673931 -0.424742 -0.593493 0.0721792 0.801596 -0.783819 -0.598679 0.16496 -0.463119 -0.749681 0.472758 -0.123887 -0.984387 -0.125036 0.289709 -0.819177 -0.494992 0.500923 -0.735591 -0.45605 0.498897 -0.724103 -0.47621 0.860393 -0.0812575 -0.503112 0.97801 0.0245978 -0.207101 0.377699 0.601427 -0.704009 0.592883 0.802208 0.0703785 -0.256898 0.903453 -0.343184 -0.354777 0.910269 0.213409 -0.427655 0.891117 0.151727 -0.742951 0.666817 0.0581252 -0.206219 -0.0498293 -0.977236 -0.276709 -0.0535657 -0.95946 -0.560523 -0.0820527 -0.824064 -0.848835 -0.515886 -0.115504 -0.648318 -0.0254684 -0.760944 -0.841373 0.0469679 -0.53841 -0.73134 0.0641977 -0.678985 -0.56123 0.0799585 -0.823788 -0.46744 0.0858356 -0.879848 -0.514893 0.0258069 -0.856866 0.100122 0.962638 -0.251601 0.882091 0.463152 -0.0860623 -0.175358 0.330919 -0.927223 0.548266 0.265064 -0.793187 -0.950318 0.228606 -0.211269 -0.689799 0.538552 -0.48388 -0.864699 0.438476 0.245019 -0.861556 0.425294 0.277213 0.132369 0.581475 -0.802724 -0.660279 0.527136 -0.534939 -0.623183 0.773233 -0.117279 0.130212 0.86188 -0.490109 0.0836953 0.793374 -0.602954 -0.519611 0.8514 -0.0715692 -0.413356 -0.444533 -0.794687 -0.26691 -0.945098 0.188544 -0.301936 -0.939642 -0.160959 0.11188 -0.77601 -0.620718 -0.582196 -0.670166 -0.460353 -0.45269 -0.434483 -0.77865 -0.922033 -0.383056 -0.0558914 -0.90944 -0.39679 0.124405 -0.909301 -0.286912 0.30142 0.571163 -0.376662 -0.729314 0.453537 -0.420749 -0.785668 0.115165 -0.734807 -0.668427 0.142599 -0.128288 -0.981432 -0.954629 -0.14765 -0.258616 -0.5804 -0.231858 -0.780626 0.0735714 -0.997152 0.0165824 -0.538788 0.0514556 0.840868 0.560223 -0.00324637 0.828336 0.560335 0.000459836 0.828266 0.560268 0.000596677 0.828311 0.559012 0.00184986 0.829158 0.556816 0.00268867 0.830631 0.161394 -0.00727376 0.986863 0.864614 0.349151 -0.361297 0.777077 -0.558888 -0.289475 -0.180096 -0.953848 -0.240291 -0.628175 -0.771065 0.104191 -0.185276 -0.971542 -0.147574 0.683467 -0.72272 0.102705 0.811 -0.584886 -0.0136723 -0.73887 0.6549 0.158677 -0.75642 0.639064 0.139379 -0.991045 -0.104629 -0.0829653 0.225441 0.969481 -0.0963471 0.16554 0.922923 -0.347576 -0.688892 0.675618 -0.262617 -0.782645 0.159968 -0.601562 0.481905 0.57309 -0.662824 0.131255 -0.83265 -0.53802 -0.909813 -0.117402 -0.398068 -0.131163 0.00571709 0.991344 -0.107929 0.0512736 -0.992836 0.907881 0.405035 -0.108159 0.749496 0.659182 0.061109 -0.288372 0.0351889 -0.956872 -0.119977 0.269402 -0.955525 -0.109664 0.888799 -0.444984 0.0512255 0.835657 -0.546858 -0.109719 0.844988 0.523409 0.0709857 0.788011 0.611555 -0.177173 -0.246033 0.952931 -0.22627 -0.272845 0.935071 -0.396125 -0.914192 -0.0856658 0.159166 -0.957369 0.241063 0.202448 -0.639551 -0.741613 0.390968 0.915548 -0.0944269 0.786112 -0.611821 0.0877646 0.233321 -0.891412 -0.388517 0.178867 -0.970778 0.159991 -0.311848 -0.941837 -0.125275 -0.578696 -0.7108 0.399844 -0.210239 -0.428727 0.878631 -0.980209 -0.111289 0.163725 -0.517333 0.370007 0.771662 -0.717169 0.637153 0.28232 -0.088695 0.840276 0.534854 0.463329 0.886135 -0.00953973 0.738851 0.434954 -0.514698 0.792577 0.457106 -0.403579 0.465977 -0.358894 -0.80874 0.866063 -0.137224 -0.480734 0.0968365 0.330907 0.938682 0.716418 -0.406024 -0.567354 0.109473 -0.351772 -0.929662 0.000994356 -0.75456 -0.656231 -0.280181 -0.959185 0.0382425 -0.231284 -0.971497 0.0519793 0.594627 -0.387033 0.704716 0.440606 -0.506823 0.740943 -0.366772 -0.201802 0.90816 0.280344 0.350406 0.893657 -0.0970725 0.742934 0.662288 0.356008 0.838521 0.412481 -0.376388 0.926412 -0.00966092 -0.0215753 0.828712 -0.55926 0.315446 0.885377 -0.341468 0.0756495 0.364455 -0.928143 0.253326 0.390708 -0.884971 -0.00185737 0.00121934 0.999998 0.416003 0.775729 -0.474537 0.419869 0.766881 -0.48539 -0.890274 0.170381 -0.422355 -0.522633 0.813548 0.254941 -0.183307 0.980479 -0.0711348 -0.220184 0.975241 -0.0205836 0.0400152 0.998791 0.0285431 0.391372 0.919518 0.036254 0.541441 0.817754 -0.195241 0.940605 0.249509 0.230234 0.943237 -0.20636 -0.260232 0.87344 -0.48057 0.0784559 0.390872 -0.919819 0.0339351 0.309038 -0.948646 -0.0675777 0.213837 -0.947055 -0.2395 0.0771503 -0.991673 -0.103114 0.10741 -0.986871 -0.120621 -0.365077 -0.929575 0.051073 -0.479192 -0.87598 -0.055082 -0.835252 -0.547413 0.0518995 -0.899648 -0.433607 -0.0511657 -0.997397 -0.0580048 0.0428385 -0.996052 0.066512 -0.0588006 -0.813779 0.577798 0.0625514 -0.734444 0.67488 -0.0716204 -0.291086 0.955873 0.0397042 0.219255 0.969783 0.106994 0.999632 -0.0180302 -0.020269 0.999632 0.0180302 0.020269 0.376422 -0.92119 -0.0985705 -0.568541 -0.750384 0.337172 -0.092335 -0.933258 -0.347136 -0.928581 0.292628 0.228268 -0.416467 0.825708 -0.380476 0.407056 0.899395 0.159359 0.946677 0.220275 -0.23512 0.787691 -0.50964 0.346135 -0.0705007 -0.944502 -0.320851 -0.837748 -0.488568 0.243884 -0.988571 0.0977865 -0.114736 -0.668102 0.739114 0.085727 -0.218904 0.968241 -0.120795 0.643269 0.556469 0.525877 0.625694 -0.222134 0.747773 0.691063 -0.720896 0.0523491 0.295729 0.935677 -0.192491 -0.991732 0.0415629 -0.121411 0.996118 0.0807816 0.0349657 -0.948822 -0.0148748 -0.31546 -0.91028 -0.41251 0.0350027 -0.992726 0.0353123 -0.115104 -0.985321 -0.0174035 -0.169825 0.739458 -0.435721 -0.513175 0.572692 -0.00653148 0.819745 0.558261 0.00181039 0.829663 0.559261 -7.53415e-05 0.828992 0.557303 0.00191712 0.830307 0.559158 -0.000625551 0.829061 0.559179 -2.93988e-05 0.829047 0.559046 -0.000251024 0.829136 0.541243 -0.155044 0.826449 0.540486 -0.0822368 0.837324 0.559089 -0.000714432 0.829108 0.559789 -0.000379318 0.828635 -0.000223514 -0.000271536 1 0.000109753 -0.00271113 0.999996 0.00365776 -0.0010024 0.999993 0.0113662 -0.037089 0.999247 -2.60453e-05 -0.0253321 0.999679 -0.0169313 -0.0200997 0.999655 0.00168634 -0.00285436 0.999995 -3.22511e-06 -0.00033162 1 0.00136957 -0.999997 0.00178128 0.00117066 -0.999998 0.00168887 0.0188176 -0.999238 0.0341949 0.0328921 -0.999 0.0302792 0.0207483 -0.998903 0.0419911 0.0120222 -0.999383 0.0330041 0.0184542 -0.999312 0.032164 0.0154694 -0.999067 0.0403301 0.0153391 -0.999741 0.0167928 0.0346573 -0.998937 0.0304091 0.0464727 -0.996262 0.0728146 0.0281427 -0.998748 0.0413667 0.996199 -0.000153327 0.0871069 0.996202 -0.00017617 0.0870727 0.271254 -0.960519 0.0618392 0.0399543 -0.999184 0.00584951 0.467607 -0.822083 -0.324843 0.46468 -0.823394 -0.325721 0.749573 0.447854 -0.487408 0.751676 0.445671 -0.486169 0.348169 0.893185 -0.284605 -0.453441 0.840199 0.297416 -0.417486 0.856827 0.302577 0.997108 -0.0720454 0.0241993 0.999209 0.0397563 0.000632131 0.999999 6.34089e-06 -0.00132988 0.993076 -0.110696 0.0393341 0.998936 0.0153138 -0.0435019 0.129697 -0.191354 0.972914 0.999114 0.00106884 -0.0420715 0.999615 0.00955588 -0.0260382 0.999848 0.0173363 -0.00165286 1 -0.000357105 0.00018784 0.999671 0.0255406 -0.00216963 0.999847 0.0155217 -0.00811461 0.999172 0.0406829 0.00105226 0.999999 0.00124306 -3.03321e-05 0.999999 0.00152126 -0.000133802 0.999999 3.95128e-05 -0.00102218 0.246288 0.966393 -0.0736593 0.999939 -0.00330915 -0.0105446 -0.855617 -0.000367907 -0.517609 -0.855529 -0.00118826 -0.517754 -0.85545 -0.000304844 -0.517886 -0.702274 -0.569018 -0.427819 -0.708692 -0.560693 -0.428228 -0.801271 -0.47569 -0.362882 -0.152935 0.0965328 0.98351 0.945754 -0.057496 0.319757 0.722814 -0.010639 0.690961 0.58795 -0.0167305 0.808724 0.926957 0.314012 0.205298 -0.0624195 0.0726542 0.995402 0.00803138 -0.0385544 0.999224 0.0755571 0.420294 0.904237 1 -0.000719064 0.000425878 0.999952 -0.0097536 1.02397e-07 -0.0204654 -0.851617 0.523765 -0.0625799 -0.888751 0.454099 -0.134708 -0.536827 0.832869 0.0979982 -0.434623 -0.895265 0.0410138 0.824292 -0.564677 0.0560862 0.816664 -0.574381 0.103286 0.410041 -0.9062 0.0432159 -0.820169 -0.570487 0.0535333 -0.814856 -0.577186 0.0884616 -0.63697 -0.765796 -0.165926 0.959433 0.227942 -0.0196032 0.8462 0.532504 -0.0906057 0.768216 0.633747 0.0419324 -0.973731 -0.223808 -0.0649528 -0.986676 -0.149168 0.223015 0.974745 0.0117238 0.000139348 -0.000304885 1 -9.09958e-05 -7.7037e-05 1 -6.71807e-05 -0.000193145 1 1.13277e-05 0.000198583 1 -0.000270425 -0.000475041 1 -0.000123382 0.00029535 1 -1.21169e-05 -8.41143e-05 1 -0.000478542 0.0033105 0.999994 2.4386e-05 4.47077e-05 1 0.000148422 -0.00119641 0.999999 0.0001088 -3.82029e-05 1 7.66558e-05 0.00164269 0.999999 6.08352e-06 -5.95414e-05 1 -6.918e-05 -0.000135136 1 -6.26749e-05 -3.00284e-05 1 1.67454e-05 -8.02296e-06 1 -0.000168817 -8.08823e-05 1 8.31491e-05 0.000128441 1 -9.95142e-05 4.76786e-05 1 -8.16937e-05 0 1 0.000471304 1.3323e-05 1 0.0236755 0.881901 -0.47084 0.064423 -0.866599 -0.494829 -0.000872221 -0.779473 -0.626436 -0.381297 0.391315 -0.837547 -0.000734687 -7.29011e-05 -1 0.916354 -0.126897 -0.379726 0.000412942 -4.06218e-06 -1 -0.0228656 0.00138932 -0.999738 -0.000807335 7.23526e-05 -1 -0.992136 0.00822742 -0.124892 0.341243 0.0610685 -0.937989 0.54026 0.0477426 0.840143 0.996404 0.00197662 -0.0847046 0.55728 -0.00207694 0.830322 0.559292 0.000980247 0.82897 0.534872 -0.00362801 0.844925 0.544882 0.169835 0.821133 0.559158 0.000655967 0.829061 0.561831 0.000179411 0.827252 0.557142 -0.00211173 0.830414 0.559165 4.0749e-05 0.829057 0.559379 0.00102363 0.828912 0.559216 9.00005e-05 0.829022 0.559201 4.62056e-05 0.829032 -0.746104 0.437873 0.501594 0.0609891 0.992667 -0.104367 0.374375 0.899719 -0.224387 0.514721 0.777555 -0.361206 0.490662 0.820439 -0.293481 -0.745961 0.416998 0.519283 -0.472369 -0.823891 0.313163 -0.468934 -0.837607 0.280206 0.579311 -0.692381 -0.430125 0.624641 -0.656487 -0.422905 0.628036 -0.680894 -0.376768 -0.74563 -0.438896 0.501405 0.743394 0.448425 -0.496266 -0.4749 0.822677 0.312527 -0.472239 0.833777 0.286017 -0.558006 -0.668551 0.491599 0.477766 -0.81088 -0.337955 0.496873 -0.800189 -0.33588 0.609448 0.671902 -0.420858 0.622229 0.6459 -0.442316 0.627532 0.678508 -0.381877 -0.107066 0.527815 0.842584 0.185268 0.773352 0.606302 -0.0732243 0.689676 0.720406 -0.127243 0.447756 0.885056 0.560811 0.000189748 0.827944 0.55819 -1.30792e-06 0.829713 -0.0432581 -0.437585 0.898136 0.988312 -0.000318394 0.152443 0.990103 2.21904e-05 0.14034 0.805839 -0.000444956 0.592134 0.739366 0.00139591 0.673302 1 -0.000266508 0.000226864 0.999976 -0.00116052 -0.0067666 0.999958 -5.15977e-05 -0.00918111 1 -0.000426205 -4.31344e-05 1 2.2183e-07 0.000377936 1 -0.000460294 -1.71871e-05 1 -0.000430647 4.92757e-07 0.999517 -0.0171252 0.0259458 1 -0.000653789 0.000623673 0.996189 0.000268227 0.0872252 0.996197 0.000513936 0.0871283 0.0370928 0.946893 -0.319401 -0.144445 0.309881 0.939739 0.128432 -0.76221 0.634462 -0.0740531 -0.692054 0.718037 -0.101952 -0.540021 0.835454 -0.064747 -0.666363 0.742811 0.997069 0.000720349 0.0765045 0.998491 -0.0523004 -0.0167226 -0.0458174 0.906736 0.419203 -0.000359197 0.990486 0.137612 -0.00828795 0.949358 -0.314088 0.0583916 0.790345 -0.609873 0.0587248 0.790057 -0.610214 -0.0603366 0.400529 0.914295 -0.0417758 -0.814772 0.578274 -0.0668603 -0.829313 0.55477 0.120216 -0.616318 -0.778268 0.0600622 -0.66004 -0.748826 0.0647315 -0.668322 -0.74105 0.087585 -0.680349 -0.727636 -0.0815414 -0.90445 0.418715 -0.0569206 -0.442068 0.895174 -0.0644957 0.843836 0.532712 -0.0472986 0.834481 0.549002 0.0731114 -0.856144 -0.511539 0.0352656 -0.819528 -0.571954 0.104249 0.658222 -0.745571 0.0721399 0.64174 -0.763522 0.0634096 0.650396 -0.756944 0.208829 -0.780452 -0.589309 -0.648484 0.634892 0.419977 -0.488899 0.811682 0.31961 -0.597734 0.653615 0.464222 -0.662884 0.618649 0.421734 0.752636 -0.437508 -0.492063 -0.373143 -0.897448 0.235271 -0.417042 -0.854021 0.311004 -0.570427 -0.749517 0.335912 0.485842 0.816126 -0.312884 0.483398 0.817279 -0.313658 1 1.286e-05 2.7792e-05 1 3.15983e-05 2.69584e-05 1 0 0.000832371 1 0 0.000378311 1 -9.498e-05 0.000413049 0.999704 0.00649552 0.0234498 0.999802 0.0197834 -0.00225971 1 4.7384e-05 -1.42449e-09 0.99993 -0.011415 0.00310315 0.999926 0.000313546 -0.0121743 1 8.74731e-05 -7.46285e-05 1 -4.57728e-05 1.75333e-05 0.99984 0.0171401 -0.00518194 0.999885 -0.0145321 0.00435426 0.999825 -0.0181445 0.00447093 0.999999 0.000404708 0.000978965 1 0 0 1 0 0 1 4.75189e-06 -3.60795e-06 1 -0.000205977 -0.000107263 1 2.1821e-06 2.59963e-07 1 2.16005e-06 1.54765e-07 1 -2.31573e-05 2.65013e-06 1 8.41209e-05 -9.62681e-06 1 -2.43039e-07 -4.71889e-05 1 -6.94746e-06 1.04237e-05 1 -2.76935e-06 3.58888e-06 1 2.17234e-05 -4.51002e-05 0.397666 0.0862792 0.913465 -0.105924 0.0030276 0.99437 0.397138 -0.0114485 0.917687 -0.654716 -0.622242 0.42914 -0.608396 -0.676618 0.41478 -0.611756 -0.673342 0.415169 -0.605264 -0.677906 0.417251 -0.602721 -0.682527 0.413381 0.999315 0.00844572 -0.0360194 0.99994 0.0109463 -0.000397372 0.999711 -0.00390053 -0.0237179 0.999985 -0.00543436 -0.000471423 0.999995 -0.00246796 -0.00171861 0.275816 -0.176853 -0.944801 1 0 0.000486768 1 1.49872e-06 0.000568459 0.999987 -2.405e-05 -0.00505684 4.31239e-06 -4.5814e-07 -1 0 -1.84995e-07 -1 0.000213636 -2.5795e-05 -1 0.00126178 -2.17865e-05 0.999999 0.620651 -0.262655 -0.738786 -0.0350706 0.818648 0.573223 0.0671451 -0.871336 -0.486071 -0.000422104 0.819517 0.573054 -0.000108385 -0.819151 0.573578 -8.86062e-05 -0.81894 0.573879 -0.000592008 -0.815136 0.57927 -0.067503 -0.983017 -0.170651 0.00684512 -0.971142 -0.238402 0.132525 -0.794904 0.592085 0.237499 -0.692574 0.681128 -0.145046 -0.258966 0.954934 0.0240802 0.0835563 0.996212 -0.00122139 -0.999999 1.17568e-06 0.00170352 -0.999999 -0.000121264 -0.000114431 -1 0.0002327 1 0.000380785 0.000308638 0.999998 -0.00121537 0.00160872 0.999998 -0.00147894 -0.00125137 1 7.59602e-06 0.000826319 0.0260225 -0.693138 0.720335 -0.000999432 -0.712103 0.702075 0 -1 0 4.36707e-05 -1 -1.28101e-05 8.41445e-05 -1 6.79202e-05 3.17869e-06 -1 -1.16552e-05 0.00102571 -0.999999 -0.000211425 0.000472005 0.415108 0.909772 -0.00974232 0.408741 0.912598 -1.73037e-06 0.00515027 0.999987 0.00105523 0.00418188 0.999991 -0.000117734 0.000172387 1 0.000640812 0.00110394 0.999999 0.999993 -0.000540135 0.00361057 0.999999 0.00065852 -0.00116177 1 2.58323e-05 6.82054e-05 0.999988 0.00235734 0.00433347 0.00151669 0.999999 -7.28988e-05 -0.000926201 1 2.32112e-05 3.10094e-06 1 0.000218598 -0.0515006 0.936065 0.348038 -0.00153438 0.999988 0.0047051 -0.0191028 0.972214 -0.233314 -0.0459874 0.958511 0.281321 -0.0710669 0.493556 0.866805 -0.0676541 0.98104 -0.181612 0.0168072 -0.397058 0.91764 0.000214496 -0.405622 0.914041 0.00147333 0.999999 -0.000498938 0.000170358 1 8.10524e-05 0.00248005 0.999997 -0.000691079 0 0.999997 -0.00239634 0.000512219 0.999998 -0.00187814 0 1 0 0 1 0 -0.00152623 0.999987 0.00484591 0.00391472 0.999915 0.0124653 0.0412657 0.685935 0.726492 0.00314226 0.711841 0.702333 0.27381 0.703095 0.656267 0.999982 0.00597537 -0.000718021 1 -0.00065554 6.06699e-05 0.77302 -0.634381 0.000863588 0.129169 -0.991623 -0.00012305 0.999854 -0.0169511 0.00202929 0.999995 0.00330134 -0.000373851 0.538954 0.84233 0.0029853 -0.705775 -0.56512 -0.427226 -0.754539 0.0445243 -0.654743 -0.590497 -0.0358822 -0.806242 -0.383433 0.0516468 -0.922124 -0.222388 -0.0231167 -0.974684 -0.000960464 0.00187111 -0.999998 -5.06204e-05 0 -1 -3.52091e-05 -0.760752 -0.649043 -3.47634e-05 -0.760752 -0.649043 -0.433394 -0.675114 -0.596985 -0.29607 -0.725757 -0.620982 -0.152781 -0.740601 -0.654346 -0.237527 0.725298 -0.646161 -0.28732 0.723851 -0.627286 -0.614099 0.604484 -0.507427 -0.706028 0.564908 -0.427087 -0.706042 0.564832 -0.427164 -0.7906 0.594052 -0.148506 -0.811146 0.576984 -0.0955597 -8.87763e-05 0.760715 -0.649086 -2.71006e-05 0.760752 -0.649043 -0.00096042 -0.00169424 -0.999998 -0.000160173 0 -1 -0.773631 0 -0.633636 -0.758059 -0.0153503 -0.652005 -0.382011 -0.0195164 -0.923952 -0.340778 0.0160346 -0.940007 -0.855645 8.18111e-06 -0.517564 -0.855644 0 -0.517566 -0.933212 -0.000130218 0.359326 -0.933325 0.000623573 0.359033 -0.743138 0.604924 0.286029 -0.743253 0.604668 0.286272 -0.721608 0.604466 0.337494 -0.00210197 0.828865 0.559445 -0.408446 -0.081614 0.909126 -0.0709777 0.0164572 0.997342 -0.569587 0.00535314 -0.821914 -0.569743 0.0053159 -0.821806 -0.558127 0.000230274 -0.829755 -0.559775 0.000192988 -0.828644 -0.557397 0.00181304 -0.830244 -0.559721 -0.00105988 -0.82868 -0.558344 -0.00117397 -0.829609 -0.557671 -0.00276245 -0.830058 -0.557296 -0.00239031 -0.830311 -0.55903 0.00246989 -0.829144 -0.557943 0.00115893 -0.829879 -0.572093 0.0117317 -0.820105 -0.560387 0.00071518 -0.82823 -0.558885 0.00547095 -0.829227 -0.559301 0.000264918 -0.828964 -0.559367 -2.62974e-05 -0.82892 -0.558958 -4.91927e-05 -0.829196 -0.559504 0.000527492 -0.828828 -0.55814 -1.14996e-06 -0.829747 -0.996072 -0.000936837 -0.0885465 -0.99616 -0.00050544 -0.0875506 -0.996226 -0.000919597 -0.0867903 -0.996186 -0.00127696 -0.0872423 -0.996005 -0.00137707 -0.0892863 -0.9963 0.00202669 -0.0859152 -0.99613 -0.000411724 -0.0878921 -0.996189 0.00071088 -0.0872232 -0.996237 -0.000432747 -0.0866698 -0.995803 -0.00249619 -0.0914923 -0.996385 -0.000729977 -0.084954 -0.995749 0.00309494 -0.0920579 -0.996158 0.00256427 -0.0875351 -0.996173 0.00357229 -0.0873255 -0.996242 -0.00102395 -0.0866079 -0.996204 -0.000197226 -0.0870471 -0.995874 -0.00107037 -0.0907395 -0.933355 -0.351642 -0.0720855 -0.845407 -0.000220488 -0.534123 -0.846784 -0.00653004 -0.531897 -0.525471 -0.360447 -0.770686 -0.515807 0.359804 -0.777486 -0.52755 0.373821 -0.762856 -0.930172 0.358182 -0.0805306 -0.156673 -0.0037438 -0.987643 -0.930947 0.00506222 0.365119 -0.933978 -0.00136702 0.357327 -0.83501 0.164326 -0.525124 -0.832588 0.174919 -0.525548 -0.783354 0.382095 -0.490266 -0.8216 -0.200924 -0.533482 -0.79015 -0.403334 -0.461503 -0.831219 -0.430321 -0.351993 -0.884617 -0.389011 -0.257144 -0.544213 -0.384779 -0.745505 -0.237893 -0.365111 -0.900056 -0.915233 0.386384 -0.114265 -0.747011 0.370378 -0.552082 -0.752624 0.364798 -0.54816 -0.150048 0.202058 -0.967811 -0.154731 0.220634 -0.963005 -0.16454 -0.0131121 -0.986283 -0.637746 -0.299552 -0.709611 -0.489282 -0.839623 0.235875 -0.473653 -0.184973 0.861068 -0.967405 -0.253227 -0.00213892 -0.974594 -0.223959 0.00300097 -0.965732 -0.25952 0.00347679 0.967032 0.254652 -0.00118692 -0.965912 -0.258849 0.00345593 -0.978174 -0.20674 0.0208346 -0.955819 -0.292629 0.0279061 -0.967304 -0.251093 -0.035705 8.29293e-05 -0.997561 0.0697953 6.59777e-05 -0.997564 0.0697639 8.16251e-05 -0.997565 0.0697463 0.000166125 -0.997566 0.069735 -6.12259e-05 -0.58236 0.812931 -0.000110945 -0.582518 0.812818 -7.14482e-05 -0.582405 0.812899 -0.447936 -0.674398 0.586976 -0.423357 -0.644224 0.63698 -0.827949 -0.560801 0.00168538 -0.841099 -0.540859 0.00494989 -0.628504 -0.708919 -0.320027 -0.680335 -0.59282 -0.430939 1.73377e-05 -0.993526 0.113607 1.81065e-05 -0.99354 0.113484 2.03215e-07 -0.991822 0.12763 0.00112193 -0.993218 0.116259 0.000275404 -0.993519 0.113669 4.62203e-05 -0.993563 0.113277 0.00025937 -0.993566 0.113254 8.10758e-05 -0.993521 0.11365 0.000172647 -0.993517 0.113679 0.000240964 -0.99355 0.113398 -7.35263e-06 -0.993542 0.113463 -0.429073 0.668392 0.607576 -0.515413 0.640024 0.569841 -0.742048 0.616371 0.263535 -0.755756 0.601665 0.258518 -0.699661 0.556554 -0.448021 -0.701447 0.551924 -0.450947 0.00714835 0.987402 0.158073 2.07243e-05 0.993541 0.113475 9.85344e-06 0.99354 0.113484 1.66993e-05 0.99354 0.113483 -6.79751e-06 0.993511 0.11374 -5.65003e-05 0.993528 0.113587 -8.9232e-05 0.993544 0.113444 1.00152e-05 0.99354 0.113483 -0.000136153 0.993536 0.113516 0.000173077 0.993535 0.113524 6.41444e-05 0.993571 0.113214 3.86342e-06 5.17586e-05 1 8.68696e-06 4.03557e-05 1 0.000117472 -3.53319e-05 1 1.85129e-05 -4.53053e-05 1 -0.00010325 -2.13791e-05 1 -0.00012445 3.76506e-05 1 -1.57393e-05 7.3736e-05 1 1.42332e-05 -1.83502e-05 1 2.96283e-05 -0.000157161 1 5.1428e-05 -0.000101964 1 0.000377599 4.21894e-05 1 2.27235e-05 9.52048e-06 1 0 0 1 4.68259e-05 1.47619e-05 1 0.000168494 -5.09999e-05 1 4.5197e-06 -1.36803e-06 1 -1.12943e-06 -1.49067e-06 1 6.75534e-08 -3.58331e-07 1 2.65811e-07 4.79439e-09 1 -9.14082e-09 3.9742e-07 1 9.83835e-08 4.57046e-07 1 -1.08148e-05 6.98839e-06 1 2.50072e-05 6.49268e-06 1 1.10585e-06 -6.0133e-09 1 3.95195e-08 -1.71821e-06 1 6.31116e-05 5.68428e-05 1 8.70553e-07 1.64447e-06 1 0.0133454 0.611478 -0.791149 -0.00404388 0.694972 -0.719026 -0.00261037 0.691301 -0.722562 -8.02322e-05 0.587198 0.809443 -7.2225e-05 0.587174 0.809461 -7.86296e-05 0.587191 0.809449 1.17767e-05 0.997563 0.0697732 3.64052e-05 0.997569 0.0696922 2.07955e-05 0.997563 0.0697693 3.25079e-05 0.997565 0.0697474 -0.00471642 -0.699179 -0.714932 7.94577e-05 -0.6899 -0.723904 4.11535e-05 -0.689868 -0.723936 -0.00120069 -0.689142 -0.724625 0.364273 -0.0387323 0.930486 0.468266 -0.757508 -0.454872 0.707787 2.74059e-05 0.706426 0.469227 0.771748 -0.429222 0.359654 0.0391088 0.932266 2.4442e-05 1 2.74895e-05 9.5296e-05 1 0.000174579 0.00113455 0.99979 0.0204407 -1.79855e-06 1 -3.48911e-05 2.20284e-05 1 -0.000234253 0.000613425 1 0.000344195 -0.000849413 0.999999 -0.000659122 -3.51136e-05 1 -0.000180126 0.000242448 1 0.000206264 0.000765543 1 -3.61107e-05 -0.000867067 0.999999 -0.000553681 0.000730039 0.999999 0.000927613 0.00149532 0.999998 0.00102727 0.000654127 1 -0.000697883 -0.939905 -0.339794 0.0334518 -0.526187 -0.726077 0.442651 -0.487603 -0.72306 0.489314 -0.69169 -0.590475 0.415818 -0.629571 -0.167589 0.758653 -0.654943 -0.165911 0.737241 -0.000644763 -1 0.000759834 9.25953e-05 -1 3.00627e-05 0.000103339 -1 -8.93652e-05 0.000691703 -0.999999 -0.00150586 0.00145949 -0.999997 -0.00171578 0.0026041 -0.999989 0.00378426 0.000203861 -1 -3.19937e-05 -0.000764644 -1 0.000223859 -0.00240515 -0.999996 -0.00127805 0.000544055 -1 0.000266526 0.00151683 -0.999999 0.000282728 1.00518e-06 -0.999923 0.0124077 0.000652534 -0.999999 0.000934488 -1.84444e-05 -1 1.56359e-05 -0.000884825 -0.999999 0.0014193 -0.00276994 -0.999996 0.000469024 -0.00654479 -0.999974 0.00307897 -1.7425e-05 -1 1.564e-05 -0.00210503 -0.999998 -0.000679508 -0.781867 -0.401206 -0.477198 -0.779421 -0.399002 -0.483012 -0.786354 -0.393523 -0.476222 -0.786669 -0.392838 -0.476268 -0.773645 -0.424103 -0.470754 -0.780815 -0.395423 -0.483703 -0.773293 -0.383743 -0.504737 -0.784796 -0.372892 -0.495022 -0.778446 -0.388394 -0.493125 -0.783296 -0.385659 -0.487561 -0.782838 -0.397047 -0.47908 -0.783291 -0.397557 -0.477915 -0.782863 -0.395246 -0.480527 -0.784 -0.39746 -0.476832 -0.783916 -0.397966 -0.476549 -0.849074 -0.416822 0.324552 -0.868454 -0.395439 0.299025 -0.854077 -0.402636 0.329297 -0.856656 -0.398655 0.327437 -0.854088 -0.401331 0.330857 -0.847977 -0.418892 0.324752 -0.867839 -0.383096 0.316376 -0.854176 -0.401291 0.33068 -0.855023 -0.407121 0.32123 -0.861226 -0.40153 0.311549 0.784178 -0.398166 0.475951 -0.783282 0.399975 -0.47591 -0.794017 0.391819 -0.464774 -0.792722 0.387808 -0.470316 -0.786418 0.407937 -0.463825 -0.777977 0.401631 -0.483161 -0.782466 0.396445 -0.480185 0.786502 -0.394453 0.475207 -0.771493 0.414774 -0.482454 -0.758775 0.457089 -0.464038 -0.786074 0.394213 -0.476113 -0.785199 0.395852 -0.476198 -0.781932 0.385427 -0.489926 -0.783012 0.393908 -0.481383 -0.791485 0.380635 -0.478192 -0.143767 -0.482016 -0.864287 -0.139311 -0.395078 -0.908023 -0.13895 -0.394771 -0.908212 -0.140394 -0.394181 -0.908246 -0.14345 -0.391313 -0.909008 -0.144126 -0.391437 -0.908848 -0.216219 -0.373807 -0.901952 -0.165725 -0.408565 -0.897558 -0.143787 0.392186 -0.908579 -0.14121 0.395054 -0.90774 -0.140069 0.395581 -0.907687 -0.1394 0.395011 -0.908039 -0.142936 0.471753 -0.870068 -0.161721 0.407973 -0.898557 -0.182195 0.394417 -0.900689 -0.156489 0.376117 -0.913262 -0.157882 0.397486 -0.903924 -0.857368 0.397874 0.32652 -0.868096 0.404829 0.287267 -0.854097 0.401324 0.330842 -0.854149 0.401302 0.330737 -0.820389 0.483507 0.305259 -0.854079 0.402595 0.329343 -0.861193 0.400332 0.31318 -0.867287 0.383198 0.317762 -0.856267 0.418475 0.302796 0.938943 0.297237 0.173309 0.932836 0.359773 0.0195285 0.87683 0.479619 0.0336826 0.430244 0.9008 0.0587284 0.523084 0.849973 0.0626745 0.401642 -0.913754 0.0611387 0.480415 -0.874704 0.0639933 0.967908 -0.250802 0.0158833 0.753707 -0.655884 0.0417398 0.902447 -0.429653 0.0314346 0.949077 -0.276738 0.150564 0.317925 -0.587361 -0.744265 -0.999999 -0.001459 0.000932426 -0.9991 0.00283195 -0.042321 -1 4.88107e-05 -8.3028e-05 -0.99991 0.00136355 -0.0133628 0.671309 0.594729 -0.442315 0.999999 3.26119e-05 0.00165958 0.000691393 3.10802e-05 -1 0.119992 0.204231 -0.971541 -7.25076e-05 -0.000203133 -1 5.56484e-05 -0.000109905 -1 0.000123061 -8.79346e-05 -1 0.00169783 7.58863e-05 -0.999999 0.000581967 0.000174413 -1 0.00107733 4.95288e-05 -0.999999 0.000508756 8.60281e-05 -1 1 -0.000605999 0.00023244 0.999946 0.000134393 -0.010383 0.0118807 0.376312 -0.926417 0.0216309 0.321481 -0.946669 -0.633291 0.207451 0.745592 0.999757 -0.0007983 -0.0220431 0.93967 0.00803598 -0.341988 0.0330917 0.995438 0.0894925 0.276575 -0.0550276 0.959415 0.272721 0.0550799 0.960515 0.0354666 0.989056 0.143214 -0.0254797 -0.999088 0.0342575 -0.0118974 -0.891886 0.452105 0.995538 -0.00263662 -0.0943293 0.00914833 0.999957 0.00138919 0.0225018 -0.999502 0.0221444 0.151977 -0.970844 0.185378 0 0.510427 -0.859921 0.00254013 -0.0856294 -0.996324 0.0174504 -0.618755 -0.78539 -0.0077501 -0.783006 -0.621966 0.00887624 -0.975497 0.219831 0.839604 -0.472851 -0.267352 0.700638 -0.00242424 -0.713513 -0.0284817 0.862871 -0.504622 0.808223 0.460523 -0.367006 0.46349 0.886102 0 0.0019327 0.713315 -0.700841 0.0752219 -0.962864 -0.259297 -0.0147358 -0.999807 0.0129729 0.0260198 -0.999661 0.000403339 0.0899619 0.995945 -0.000618639 0.0149226 0.999866 0.00673939 0.484605 -0.00289036 -0.874728 0.193965 0.0280606 -0.980607 0.357307 -0.253283 -0.898988 -0.000572977 1 2.27633e-05 0 1 0 0 0.600001 -0.799999 1 0 0 0.999137 -0.0414692 0.00251604 0.448993 0.691975 0.56531 -0.496244 -0.613045 0.61475 0.00042625 -1 0 0.000907753 -1 1.85757e-05 0.999604 0.0281338 3.47426e-05 0.999995 0.00266793 0.00149645 -0.512083 -0.515363 -0.687148 -1 0 0 -1 0 0 -0.329741 -0.575074 0.748706 0.338453 -0.542853 -0.768609 0.501054 0.500096 -0.706293 0.984251 -0.142256 0.104947 -0.999835 -0.0149362 0.0103182 -0.777029 -0.564713 -0.278074 1.19209e-06 0.600001 -0.8 0.649415 -0.65148 0.392217 0.999732 -0.00723202 0.0219948 0.159605 -0.981357 0.107069 0.571752 0.724621 0.384739 -2.77248e-06 7.87891e-07 -1 1.57522e-06 -7.68874e-11 -1 0.000654763 -0.000427102 -1 0.00159169 -0.000291087 -0.999999 -0.00296768 -0.00150727 -0.999995 -1.37829e-06 -1.39614e-07 -1 0.000482832 4.89084e-05 -1 0.000166241 9.69502e-05 -1 -0.00487411 0.00189498 -0.999986 -0.00254737 0.000247166 -0.999997 4.6893e-05 1.51001e-05 -1 0.0128325 0.00357406 -0.999911 -0.000269164 5.00361e-05 -1 4.57369e-06 -1.29976e-06 -1 -6.67141e-07 -2.95083e-06 -1 0.0032741 0.00204549 -0.999993 -0.000474466 -9.29742e-05 -1 -4.29463e-05 -8.63229e-05 -1 0.000156917 -9.86053e-06 -1 0.00711235 -0.00208537 -0.999973 -0.00478752 -0.00605878 -0.99997 -8.34238e-05 -5.33014e-05 -1 0.000366437 5.31823e-05 -1 0.000497144 9.80559e-05 1 0.909969 0.0338707 0.413291 -0.0143738 -0.829082 -0.558942 0.000771112 0.796243 0.604977 -0.00174479 0.783146 0.621836 0.00963469 0.999624 -0.0256571 0.012995 0.999849 -0.0115468 0.29074 0.894169 0.340486 -0.00790164 -0.999642 -0.0255777 0.144494 -0.971696 0.186889 0.000905159 -0.996238 -0.0866513 0.00123294 -0.710197 -0.704002 -0.0014341 -0.713649 -0.700502 0.00234715 0.709453 -0.704749 -0.00171185 0.714738 -0.699391 2.21112e-05 1 0.000130083 0.0907523 0.000623351 -0.995873 0.0357355 -0.99924 0.0155878 0.0400123 -0.999198 0.00152559 0.0424932 -0.999088 -0.00411986 0.0383071 -0.999225 0.00901599 0.0529221 -0.995458 0.0791375 0.0401849 -0.999116 0.0123711 0.0940287 -0.995523 0.00965618 0.0418927 -0.999118 0.00282707 0.0440186 -0.999015 -0.00566397 0.025654 -0.999671 -0.000862298 -0.051381 0.000141298 0.998679 -0.0495162 0.000685583 0.998773 0.921815 0.0137374 -0.387386 0.525907 -0.849773 0.0361615 0.477037 -0.725345 -0.496297 0.924626 0.380463 0.0177251 0.110248 0.953492 -0.280534 0.811584 0.5786 0.0809574 0.456012 0.88925 0.0358845 0.893146 -0.169409 0.416642 0.775495 0.00274727 0.631348 0.799318 0.00707627 0.600866 0.783694 -0.000108262 0.621147 0.847452 -0.0107958 -0.530763 0.889926 -0.0302633 -0.455099 0.0215535 0.999715 -0.0102817 0.0239501 0.999643 0.0118353 0.0307205 0.999526 0.00198636 0.0322045 0.999477 0.00281885 0.035206 0.999375 0.00308145 0.0365792 0.999324 0.00357506 0.908812 0.350771 0.225877 0.822142 0.56383 0.078599 0.887967 0.27507 0.36858 0.122895 0.475077 0.87132 0.893147 -0.118406 0.433899 0.855438 -0.511483 0.0813159 0.124879 -0.471877 0.872776 0.0607925 0.0157891 -0.998026 0.364963 0.0719185 -0.92824 0.122228 -0.000305316 -0.992502 0.956375 -0.290247 -0.0332218 0.842792 -0.533039 0.0746367 0.0977761 -0.353852 -0.930176 0.904025 -0.0652748 -0.422466 -0.0611291 -9.05673e-06 0.99813 -0.0719418 0.00127918 0.997408 0.0861012 0.00105766 -0.996286 0.592709 -0.778724 -0.205633 -0.404026 0.823565 0.398125 -0.803215 0.00176416 0.595687 -0.806845 0.000589945 0.590763 0.847803 -0.000121675 -0.530312 0.850718 0.0285571 0.524846 0.387028 -0.20906 0.898055 0.476511 -0.529376 0.701925 0.303083 -0.849444 0.431954 -0.740011 -0.478844 0.472326 0.158603 0.959822 0.231487 -0.297193 0.938743 -0.174467 0.308358 0.0720866 0.948535 0.322302 0.120316 0.93896 0.312073 -0.173201 0.934137 0.00889578 -1.87805e-05 0.99996 -0.762006 -0.0107979 0.64748 0.0119746 -0.000569721 0.999928 0.876541 0.00944988 -0.481235 0.969041 -0.00400264 -0.246866 0.0325762 0.998896 0.0338464 0.0670707 0.995913 0.0604885 0.0177917 0.999526 0.025123 0.0180774 0.999477 0.0268009 0.0195155 0.999391 0.028933 0.0191778 0.999137 0.0368339 0.0297533 0.996628 0.0764707 0.477317 0.529712 0.701123 0.213263 0.967216 0.137881 0.674307 -0.703357 -0.224942 0.745803 0.580846 -0.326182 0.515834 0.449159 0.729501 0.788328 0.168413 0.591757 0.479813 0.514064 0.710998 0.838667 0.204937 -0.504618 0.91155 0.00182905 0.411185 0.85614 -0.0154289 0.516513 0.395387 -0.830944 -0.39141 0.477486 -0.523244 0.705849 0.507385 -0.463125 0.726688 0.843112 0.00186253 -0.537735 0.882938 0.212418 -0.418688 -0.149013 -0.93103 0.333134 0.825387 0.114616 -0.55281 0.990187 0.00745934 0.139548 -0.757883 -0.495413 -0.424475 0.538745 -0.180317 -0.822946 0.103116 -0.965129 0.240611 -0.0312306 -0.995733 -0.086836 0.0846732 -0.44659 -0.890723 0.0786126 -0.435095 -0.896946 0.0776312 -0.4364 -0.896397 0.996324 -0.000906501 0.0856611 0.0785885 0.436457 -0.896286 0.0811975 0.433029 -0.897716 0.0820526 0.434514 -0.89692 0.996262 0.000971383 0.0863765 0.226738 -0.0932516 -0.969481 -0.078341 -0.434761 0.897132 -0.0650947 -0.450008 0.890649 -0.0767356 -0.43228 0.898469 0.995545 -0.0034062 0.0942283 -0.0781364 0.425776 0.901449 -0.0785845 0.432285 0.898306 -0.0703066 0.438241 0.896104 0.993499 0.0121753 0.113193 -0.12128 0.553796 0.823772 0.00702535 0.0191598 -0.999792 0.00293405 1.56869e-05 -0.999996 -0.0151138 -0.00269519 -0.999882 -0.0120654 -0.00411056 -0.999919 0.0251998 0.999076 0.034806 0.00229271 0.999997 -0.00100744 -0.00440501 0.99999 0.0012861 -0.00846022 -0.999964 0.00101309 -0.000154962 -1 1.04995e-05 0.183452 -0.465428 -0.865865 0.0805807 -0.70005 -0.709533 -0.13998 0.210563 0.967507 0.129221 -0.20199 0.970825 0.747142 -0.443165 -0.495362 0.747399 -0.432905 -0.503972 0.746976 -0.433433 -0.504146 0.559479 0.00519988 0.828828 0.748344 0.430377 -0.504734 0.750473 0.436223 -0.496488 -0.604671 -0.68264 0.410337 0.56215 0.00236341 0.827032 0.442189 -0.895962 -0.041498 -0.743493 -0.441852 0.50198 0.555261 -0.00261888 0.831672 -0.745992 0.436184 0.503229 0.74988 -0.441825 -0.492413 0.553936 0.00326732 0.832553 -0.373837 -0.00481514 0.927482 2.19291e-05 -0.000586944 -1 -0.000104373 -0.000571931 -1 0.000422162 -3.90447e-06 -1 0.000443635 9.69897e-06 -1 -0.000479525 -0.999999 0.00114419 0.00111614 -0.999998 -0.00140854 -6.04459e-05 -0.000423158 1 0.000469992 -5.52647e-05 1 0.999999 -0.000598494 0.00127633 1 0.000360394 -0.000959778 0.829283 -2.44902e-05 -0.558829 0.828915 -0.00117788 -0.559373 0.829313 9.92746e-06 -0.558784 0.829141 -0.000360275 -0.559039 -0.828729 -8.35103e-05 0.55965 -0.828764 -4.8874e-06 0.559598 -0.829057 -0.000831716 0.559163 -0.829043 -0.000858381 0.559184 -0.00116993 -0.999999 0.000506562 0.00122438 -0.999999 0.000188447 0.557955 -0.000514103 0.829871 0.559686 0.000381482 0.828705 0.609939 0.639111 -0.468521 -0.974843 -0.122808 0.186007 -0.0880711 -0.996107 0.00376379 -0.861561 0.40735 -0.302949 -0.943953 -0.123769 0.305996 -0.852723 -0.0610745 -0.518781 -0.863607 -0.354114 0.358868 0.82134 -0.279432 0.497312 0.603677 0.148589 0.78326 -0.195829 0.0123477 0.98056 -0.968593 -0.0359539 -0.246039 0.113812 -0.0464422 0.992416 0.339717 0.0111143 0.940462 0.884262 -0.0123475 0.466828 0.906167 -3.59813e-08 0.422921 -0.608919 0.295968 0.735948 -0.995677 -0.0674619 -0.0638416 0.711452 -0.0370264 -0.701759 0.302335 0.101456 -0.947787 -0.39505 -0.0695545 0.916023 -0.933326 0.0724618 -0.351642 -0.56104 -0.0397076 -0.826836 -0.90962 0.00516229 0.415409 -0.0152598 -0.0189842 0.999703 -0.355933 0.0106068 -0.934451 -0.232859 0.10942 -0.966335 -0.930708 -0.365725 -0.00529781 -0.864304 -0.480103 0.149929 -0.754045 -0.0253406 0.656334 -0.689862 0.000372566 0.723941 -0.678237 0.0280748 -0.734307 -0.858037 -0.0281836 -0.512813 -0.781375 -0.465631 -0.4155 -0.831752 -0.385215 -0.399747 -0.671365 0.740002 -0.0408235 -0.161861 -0.958883 0.233117 -0.00329775 -0.845193 0.534451 -0.00272422 0.000646435 0.999996 -0.000567812 -0.000792488 1 -4.13519e-05 0.888401 -0.459068 4.7767e-06 0.888574 -0.458733 -2.21887e-05 0.888528 -0.458823 -8.00049e-05 0.888686 -0.458516 -1.10416e-05 -0.888492 0.458892 0.00368733 0.886597 -0.462528 0 0.888498 -0.45888 9.42545e-06 0.88858 -0.458723 -4.87307e-08 0.88852 -0.458838 0 0.88852 -0.458838 -0.0132297 0.888144 -0.459374 -3.24615e-07 0.888533 -0.458813 3.07117e-07 0.888518 -0.458842 -0.793715 -0.451941 -0.407143 2.05949e-05 0.886457 -0.462811 -7.06102e-06 0.888716 -0.458458 0.00368792 0.891363 -0.453276 -9.00316e-07 0.888518 -0.458842 0.0784892 -0.995719 0.048817 8.9521e-08 -1 0 0 -1 4.96706e-06 0.0823435 -0.995395 0.0490716 -0.000734402 -0.961732 0.273991 0.00881104 -0.952747 0.303638 1.902e-06 -0.988406 0.151837 -0.00237959 -0.974844 0.222877 -0.0281098 -0.949662 0.312012 0.0466868 -0.969014 0.242554 0.00605395 -0.925063 0.379766 -0.00215547 -0.891767 0.452489 0.74413 -0.0920903 -0.661657 0.478729 0.295913 -0.826592 -0.496962 -0.75637 -0.425363 -0.712893 0.0802725 -0.696663 -0.759442 -0.0339288 -0.649689 0.000137295 -0.783652 0.6212 -1.57883e-05 -0.783563 0.621313 7.58479e-06 -0.783548 0.621332 1.08205e-05 -0.783537 0.621346 -3.42538e-07 -0.783496 0.621396 0.0175464 -0.776445 0.629941 -2.55744e-07 -0.783497 0.621396 5.08284e-07 -0.783499 0.621393 2.34237e-06 -0.783479 0.621418 7.12481e-06 -0.783497 0.621396 0.211355 -0.967842 -0.13642 -1.13782e-05 -0.999414 0.034231 0.00155459 -0.997978 0.0635364 0.0054391 -0.998533 0.0538673 0.000340807 -0.999386 0.0350441 4.3059e-06 -0.999409 0.0343686 0.0493277 -0.995636 0.0792257 -5.51563e-06 -0.999415 0.0341875 -1.74341e-06 -0.999417 0.0341396 0.94813 -0.180916 0.261379 0.931819 3.23621e-08 -0.362924 0.69327 -0.0743305 -0.716834 0.816508 -0.0737186 -0.572609 0.569347 0.0137605 -0.821982 -0.187895 -0.0153011 -0.98207 -0.275363 0.0142435 -0.961235 -0.883176 -0.0121453 -0.468884 -0.749776 -0.0704423 -0.657931 2.7572e-07 -0.999416 0.0341739 6.79227e-07 -0.999416 0.0341837 0.184385 -0.967026 0.175676 8.23846e-07 -0.999417 0.0341544 2.08302e-06 -0.999415 0.0342049 5.48612e-08 -0.999416 0.0341861 -0.000399208 -0.999437 0.0335528 2.2477e-06 -0.999416 0.0341791 -1.98749e-06 -0.999415 0.0341868 -7.97475e-06 -0.999416 0.0341843 2.40101e-07 -0.999413 0.0342606 1.52512e-08 -0.999416 0.0341853 0.00668863 -0.999512 0.0305062 -1.31919e-06 -0.999416 0.0341623 0.000368833 -0.999385 0.0350534 3.38002e-05 -0.999406 0.0344585 0 -0.999416 0.0341793 -3.90598e-06 -0.999415 0.0342105 0.0249606 -0.797087 0.603348 0.00015212 -1 0.000235951 1.12053e-05 -1 -7.41395e-05 -2.0294e-05 -1 -5.13814e-06 0.00754054 -0.999968 -0.00249686 0.00645406 -0.999978 0.00119129 9.86864e-05 -1 1.51125e-05 6.42054e-06 -1 -7.73064e-05 1.34605e-05 -1 -0.000115432 3.2082e-06 -1 3.25979e-06 -9.54961e-05 -1 -4.87526e-06 7.82597e-06 -1 1.71385e-05 0.696711 -0.0266154 0.716858 0.0109261 -0.149733 0.988666 -1 -1.33328e-05 -8.20016e-05 -1 0.000123813 -0.00030083 0.999989 -3.51367e-05 0.00475188 -0.98125 0.0365918 0.189235 -0.307978 -0.181904 -0.933842 -0.721198 -0.239393 -0.650049 0.98746 0.11677 0.106242 1 -2.98966e-05 -8.65512e-05 0.955907 0.171501 0.238389 1 5.93516e-05 4.31358e-05 0.997928 -0.0140397 -0.0627924 -0.995785 0.00133784 0.0917077 0.00112693 -0.0129564 -0.999915 0.044228 -0.00492886 -0.999009 0.993311 -0.0979746 -0.0611078 -0.239926 -0.126554 0.962507 -0.999994 -0.0032818 0.000599462 -0.988382 -0.09735 -0.116726 0.00112696 0.000182702 -0.999999 0.00112696 -0.000577084 -0.999999 -0.0118131 -0.00313674 -0.999925 -7.26643e-05 -9.79217e-05 1 0.311347 -0.102177 0.944787 0.00261491 -0.00551308 0.999981 -0.81862 -0.157406 0.552345 0.212435 -0.0876501 0.973236 -0.998109 0.0605829 -0.0103546 0.788739 0.000942127 0.614727 0.749536 -0.222848 -0.623326 -0.749352 0.0413025 -0.660883 -0.436298 -0.682833 0.585989 -0.977023 -0.0918673 -0.192319 -0.951409 -0.0282256 -0.306635 -1 -0.000412273 0.000354694 -0.605463 -0.309962 -0.733034 0.333891 0.828485 -0.449589 0 0.707094 -0.707119 0 -0.999996 -0.00294152 0.0515541 -0.99859 0.0126668 0.000273076 -1 -4.89164e-05 0 -1 0 1.39793e-07 -2.66083e-05 1 0 -1.66302e-05 1 0.287223 -0.612451 0.736483 -0.760241 0.621564 -0.188925 -0.757673 0.625074 -0.187657 -0.75694 0.626493 -0.185874 -4.53591e-05 -0.74091 -0.671605 0.00140691 -0.742923 -0.669376 -0.374008 -0.820098 -0.433079 -0.317238 -0.834683 -0.450182 -0.767355 -0.638637 -0.0575257 -0.805834 -0.543079 0.235999 0.717702 0.0752191 -0.692276 0.922542 -0.222676 0.31517 0.780107 -0.619368 0.088414 0.185291 0.411037 0.89259 -0.23496 -0.764314 0.600515 -0.8073 0.321686 0.494758 0.3957 0.724333 0.564591 -0.000585843 0.999999 -0.0010265 -0.00670428 0.999886 0.0135225 -0.000104464 1 0.000780484 0.00124899 0.999999 -0.000339588 -0.000106265 -0.000825629 -1 0.288549 -0.215499 -0.932899 -0.782989 0.423773 -0.455352 -0.375959 0.0416532 -0.9257 -0.841789 0.387979 -0.375319 -0.836935 0.394721 -0.379125 -0.517909 0.788582 0.331524 -0.563903 0.793909 0.227424 -0.000369513 0.742084 0.670307 8.68378e-05 0.741322 0.671149 0.72265 0.669244 -0.172883 0.675087 0.718622 0.166851 0.839223 0.376807 -0.392074 0.470134 0.170244 -0.86602 0.756638 0.397953 -0.518779 0 0.892321 -0.451402 0 0.997526 -0.0702932 -5.04105e-10 8.76896e-08 -1 4.35544e-10 8.84003e-08 -1 0 9.92887e-08 -1 0 9.29157e-08 -1 0 9.29157e-08 -1 0.755447 -0.624841 0.197161 0.758973 -0.623855 0.186456 0.758533 -0.624166 0.187201 0.569262 -0.75899 0.316031 0.0940146 0.721681 -0.685812 0.681124 -0.700637 0.212549 0.678131 -0.703828 0.211578 0.698268 -0.6841 0.210782 0.681055 -0.700659 0.212701 -0.00190345 -0.996736 0.0807065 -0.971117 -2.7064e-06 0.238602 -0.971117 1.13037e-07 0.238602 -0.971117 1.29417e-06 0.238602 -0.971117 1.05807e-06 0.238602 -0.971117 2.15839e-07 0.238602 -0.208761 0.965664 -0.154634 -0.304001 0.929504 -0.208821 -0.581271 0.755937 -0.301138 0.207634 -0.778182 0.592724 0.213776 -0.780137 0.58795 0.255913 -0.78262 0.567464 0.672895 -0.653295 0.347013 0.673318 -0.651003 0.350481 0.000493505 -0.996647 0.081814 0 -0.888458 0.458957 -1.63732e-07 -0.888534 0.458811 -5.96776e-05 -0.888604 0.458676 -2.35656e-06 -0.888523 0.458832 -2.87215e-06 -0.888519 0.458839 1.53845e-06 -0.888495 0.458887 1.07361e-06 -0.888499 0.45888 4.43857e-06 -0.888518 0.458842 3.59499e-06 -0.888517 0.458845 -8.90811e-05 -0.888658 0.45857 1.72379e-05 -0.888589 0.458705 0.00305323 -0.939318 0.343034 -0.00187628 -0.982744 0.184962 -0.75467 -0.634589 0.166641 -0.758525 -0.624315 0.186735 -0.758651 -0.624262 0.186401 -0.758648 -0.624271 0.186386 -0.758269 -0.624756 0.186302 -0.758605 -0.624322 0.186388 -0.758638 -0.62428 0.186396 -0.758652 -0.624261 0.186399 0.207914 -0.977668 -0.030617 -0.351486 -0.911193 0.214906 0.0821048 -0.973681 0.212613 -0.115713 -0.870879 0.477682 0.0800648 -0.878467 0.471048 -0.807114 -0.543418 -0.230792 -0.941142 -0.273457 0.198676 0.167334 -0.0314086 0.9854 -0.00672634 -0.0891003 0.996 0.971117 0 -0.238602 0.971117 1.03761e-07 -0.238602 0.971117 5.74365e-07 -0.238603 0.971117 2.78468e-06 -0.238602 0.970971 -0.00682613 -0.239099 -0.4875 -0.349778 0.8 -0.00035351 0.258732 0.965949 0.00107443 0.241947 0.970289 -0.375603 0.86925 -0.321444 -0.634847 0.732294 -0.246404 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -6.25357e-05 0.00205226 -0.999998 0 0 -1 0 -1 0 -0.804943 -0.592066 -0.0390525 -4.65979e-08 -1 9.59207e-07 0 -1 0 0 1 0 0 -1 0 0 -1 0 -1.93611e-08 -1 2.4916e-06 0 -1 0 -8.74025e-08 -1 1.42407e-06 0.222608 -0.974828 -0.0124888 0 -1 0 -1.27228e-07 0.998029 -0.0627585 -9.43955e-07 0.998029 -0.0627558 0.00140341 0.665421 0.746467 -8.45774e-07 0.998027 -0.0627854 -9.41991e-08 0.998029 -0.062753 -1.2824e-05 0.998041 -0.0625561 5.1212e-06 0.998053 -0.062369 -0.000129155 0.998036 -0.0626473 0.0386694 0.998458 -0.0398295 -0.310293 0.896565 -0.316053 -1.02481e-06 0.998029 -0.062753 -0.271084 0.885074 -0.378362 -0.0282226 0.976543 -0.213463 -0.0650734 0.926842 -0.369769 0.138091 -0.979143 0.149028 0.11922 -0.987351 0.104517 0.361016 -0.903032 0.232811 0.549338 -0.783062 0.291619 1.95581e-06 -0.998029 0.0627534 1.5676e-06 -0.998029 0.0627556 -8.90165e-06 -0.998034 0.0626714 -0.00237244 -0.998525 0.0542436 0.00466182 -0.997915 0.0643728 -6.0553e-05 -0.998032 0.0627043 1.18122e-06 -0.998029 0.0627572 -0.83437 -0.408857 0.369679 1.18887e-06 -0.998029 0.0627566 1.32578e-06 -0.998029 0.0627586 -1.42878e-06 0.998029 -0.0627602 1.88654e-06 -0.998028 0.0627632 0.298281 -0.77846 -0.552294 0.560527 -0.816169 -0.140279 0.898398 -0.312112 0.308979 -0.00184374 0.861742 -0.507344 0.0345447 0.830067 -0.556593 0.000831813 0.89459 -0.446888 -0.00198617 0.979056 -0.20358 0.00318641 0.946522 -0.322623 -6.36072e-07 0.972 -0.234982 0.667422 0.621112 -0.410813 0.216376 0.0480356 0.975128 -0.302481 0.310314 -0.901227 0.345575 0.0543996 0.936813 -0.518788 0.568165 -0.638785 -0.0159093 0.976868 -0.21325 -0.0183894 0.837501 -0.546127 0.586752 0.681407 -0.437501 -0.00434179 0.650904 -0.759148 0.972309 -0.0105803 0.233461 0.966763 -0.0190744 0.254962 0.967548 -0.0214884 0.251771 0.972403 -0.0114726 0.233026 0.00140825 -0.738717 0.674014 0.000130947 -0.732069 0.68123 0.000930362 -0.732434 0.680837 3.21202e-10 -5.87296e-08 1 0 -6.65352e-08 1 -3.21202e-10 -5.87296e-08 1 0.915156 -0.29853 0.270868 0 -5.07586e-05 1 2.79754e-09 -1.12467e-07 1 0.580174 -0.713797 0.392291 9.55731e-06 0.000100029 1 -0.696201 -0.71783 0.00493141 5.75121e-10 -6.81166e-08 1 0 -5.6392e-05 1 0 -5.6392e-05 1 -0.0867151 -0.996179 0.0103914 0 -1 0 0 -1 0 -0.0497213 -0.99819 0.0338438 0.311167 -0.820198 0.480052 0 -0.837023 0.547168 0.189517 -0.825946 0.530939 -0.210199 -0.940072 0.268477 0.485146 -0.843614 0.230107 -0.19637 -0.655595 0.729132 -0.681001 0.701245 -0.210932 -0.681598 0.70049 -0.211513 -0.683338 0.699632 -0.208723 0.957996 0.286615 -0.00975104 0.971834 0.235608 -0.00524535 0.96553 0.260288 0.00156453 0.965794 0.25929 -0.00324543 -0.00620504 0.484555 -0.874739 0.00514157 0.47299 -0.881053 -0.000206896 0.441293 -0.897363 -0.959816 0.280565 -0.00606801 -0.964753 0.263136 -0.00337214 -0.965524 0.260316 0.000111113 -0.965141 0.261726 0.00138604 -0.960766 0.277201 -0.0094143 -0.00119013 0.982334 -0.18713 0.00177319 0.971885 -0.235451 0.758652 0.624262 -0.186399 0.758667 0.624242 -0.186404 0.758657 0.624256 -0.186396 0.758663 0.624247 -0.186401 -0.0253574 0.724497 0.688811 -0.559605 0.511285 0.65225 -0.559583 0.511335 0.65223 -0.559581 0.511345 0.652223 -0.559585 0.511337 0.652227 0 0.850746 0.525577 0 0.850746 0.525577 0.00132863 0.783448 -0.621456 -3.56233e-08 0.783494 -0.621399 -0.00122878 0.78303 -0.621983 -0.0171211 0.785696 -0.618376 0.00612327 0.78108 -0.6244 0.000641338 0.78343 -0.62148 0.0271766 0.758075 -0.651601 -9.79158e-07 0.783498 -0.621394 8.08395e-05 0.789679 -0.61352 -0.0116799 0.787997 -0.615569 0.00964582 0.775688 -0.631043 -0.00998247 0.789073 -0.614219 0.00678838 0.831728 -0.555143 -0.00886881 0.698854 -0.715209 -0.16619 0.78735 -0.593684 -0.244357 0.793151 -0.557854 -0.675478 0.62714 -0.387846 -0.67369 0.651801 -0.348277 0.00175662 0.88982 -0.456309 -7.30545e-05 0.999423 -0.0339673 -9.32998e-05 0.999424 -0.0339481 -9.41516e-05 0.999399 -0.0346586 0.000473348 0.999409 -0.0343634 7.79968e-07 0.999415 -0.0341919 0.0885609 -0.990477 0.105413 -1.78075e-09 0.999416 -0.0341856 0 0.999416 -0.0341857 5.11422e-06 0.999415 -0.0341939 -3.74453e-05 0.999417 -0.0341409 3.19035e-05 0.999418 -0.0341257 -0.000104424 0.999401 -0.0346074 -2.56589e-05 0.999417 -0.0341332 -7.30825e-08 0.999416 -0.0341859 -1.1094e-08 0.999416 -0.0341862 -0.0717156 0.994144 -0.0808427 0.000290275 0.999412 -0.0342853 0.000324929 0.999393 -0.0348406 -3.44504e-06 0.999409 -0.0343845 -0.961458 0.115244 -0.249634 -0.971117 -6.89483e-06 -0.238602 -0.971143 0.000241377 -0.2385 -0.971115 0.000250301 -0.238611 -0.97109 -0.000615397 -0.238713 -0.969307 -0.00776046 -0.245733 -0.658491 0.6831 -0.315854 -0.216089 0.814654 -0.538186 -0.146705 0.803089 -0.577517 0.559581 0.511345 0.652223 0.55959 0.511272 0.652273 0.559582 0.511345 0.652223 0.0475542 -0.177588 0.982955 0.000857107 -0.999999 0.000999003 -6.41344e-05 -1 -0.000282347 0 -1 0 0 -1 0 0 -1 0 0.000536667 -0.999991 -0.00412341 -0.00296336 -0.734416 0.678694 -0.00138677 -0.741179 0.671306 0.997294 0.0705826 0.0205544 4.11371e-06 -1 0.000762306 -3.72074e-06 -1 1.56775e-06 0.669592 -0.645269 -0.367797 0.0905024 -0.102997 0.990556 -3.1042e-06 -1 0.00073249 -8.9779e-05 -1 0.000259282 4.93465e-06 -1 3.38526e-05 0.782338 -0.528474 -0.329641 -0.0388114 -0.0219597 0.999005 -0.0156945 -0.999793 0.0129417 -0.0208667 -0.999758 0.00695236 -3.30479e-05 -1 8.56175e-05 4.12451e-06 -1 0.000752723 -3.09808e-06 -1 0.000739747 -4.7449e-06 -0.999999 -0.0012126 0.355891 -0.0948956 0.929697 0.55882 -0.417986 -0.716246 -0.0279377 -0.999576 -0.00817584 0.383619 -0.569352 0.7271 -0.0201607 -0.99968 -0.0153101 -0.0568255 -0.153087 0.986578 -0.0383455 -0.15845 0.986622 0.0561129 -0.082104 0.995043 0.0902778 -0.122221 0.988389 0.0941989 -0.317374 0.94361 -0.154312 -0.161653 0.974708 0.973725 -0.0287753 -0.2259 -0.963242 0.0109293 0.268414 -0.948021 0.0306223 0.316732 0.808918 -0.105141 0.578444 -0.403348 0.495716 -0.76914 -0.564375 0.371103 -0.737403 0.00229051 -0.0138587 -0.999901 0.00560978 -0.0558805 -0.998422 0.985043 0.0376326 -0.168151 0.99012 -0.00762949 -0.140018 0.99241 0.0232048 -0.120768 0.975149 0.049772 -0.215888 0.0114595 -0.189249 0.981862 0.00180659 -0.0136748 0.999905 -0.381907 0.862786 0.331281 -0.996589 -0.0822554 -0.00664704 -0.999995 -0.00281632 -0.00128999 -0.988605 -0.0378533 -0.145695 -0.963409 -0.267998 0.00445707 -0.999997 0.0023866 0.000237348 -1 0.000893789 -0.000245859 -1 0.000561586 -0.000702313 -0.000504949 0.999274 -0.0380992 -0.000858729 0.999395 -0.0347653 0.00870665 0.999414 -0.0330901 0.00315793 0.999368 -0.0354043 -0.000333453 0.999394 -0.0347957 -0.00157421 0.99941 -0.034318 -0.00113942 -0.999545 0.0301405 0.000824221 0.999507 -0.031386 0.000372041 0.999354 -0.0359279 -0.000660206 0.999481 -0.0322027 0.572488 -0.188667 0.797911 -0.0496373 -0.147488 0.987818 0.00573755 0.905673 -0.423939 -0.0109144 0.889678 -0.456459 -0.00430385 0.888692 -0.458485 0.00581259 0.888638 -0.458573 3.5382e-05 0.890519 -0.454947 -0.758713 -0.0819517 -0.646249 0.000258298 0.000465666 -1 0.000299888 0.000534589 -1 0.999997 0.00252321 0.000138557 1 0.000900473 -0.000418514 0.999931 -0.00614866 -0.0100148 -0.00048267 0.00436222 0.99999 -2.2248e-05 1 0.00049813 -5.89925e-06 1 0.000626205 -0.000441489 1 4.07945e-05 -0.000473461 1 4.4875e-05 4.91487e-07 1 -0.000395122 3.89071e-05 1 -9.63208e-05 0.000173699 1 3.88113e-05 0.000644441 1 -2.12337e-05 -0.99997 -0.00772669 0.000599173 -0.999887 0.0149372 -0.001604 -0.00136675 -0.0163213 -0.999866 0.00153855 0.0135886 -0.999906 0.999957 -0.00925915 -2.30707e-05 0.999927 0.0118973 0.00203266 0.000837613 -0.0117884 0.99993 -0.00167744 0.0140889 0.999899 -0.999993 0.00172312 0.00328433 -0.999831 -0.0141724 0.011696 -1 -0.000736154 -0.00057089 0.769113 -0.208856 -0.604023 0.00147926 -0.0127326 -0.999918 -0.000938862 -0.00295772 -0.999995 0.630768 0.259746 -0.731207 1 1.10257e-05 -1.27114e-06 0.999997 0.00139675 -0.00217797 0.999987 -0.00502386 -0.000991156 1 -0.000181271 -0.000204809 0.679577 0.0055966 0.733583 0.736064 -0.0168953 0.676701 0.0015137 -0.00137644 0.999998 0.00126171 -0.00119075 0.999999 -0.723603 -0.0137099 0.690081 -0.663943 0.00743324 0.747746 0.0364359 -0.888704 0.457032 -0.0156787 -0.887915 0.459739 -1.2839e-05 -0.888499 0.458878 0.000385647 -0.889602 0.456736 -0.00152757 -0.888509 0.458857 0.00452351 -0.889098 0.457696 0.00155322 -0.88917 0.457574 0.162707 -0.978248 0.128672 0.122689 -0.985915 0.113665 0.000414884 0.999445 -0.0333046 -0.000107797 -0.999413 0.0342545 -2.19901e-05 -0.999421 0.0340265 0.195216 -0.980614 -0.0169669 -0.000670831 -0.999399 0.0346463 -0.00246201 -0.999479 0.0321934 -2.37236e-06 -0.999434 0.0336392 -0.000299918 -0.999409 0.0343675 0.0239201 -0.99884 0.0418025 -0.011079 -0.998494 0.0537248 -0.00162345 -0.998866 -0.0475786 0.0475225 -0.997992 0.0418792 -0.00888144 -0.999955 0.00344584 -0.0470061 -0.998716 0.0188974 -0.0490677 -0.998663 0.0162424 -0.0324464 -0.998674 -0.0399615 0.00284625 -0.998613 -0.052571 3.88393e-05 -0.998989 -0.0449658 0.020333 -0.999571 0.0210692 -0.0134462 -0.999516 -0.0280635 0.663921 -0.640449 0.386049 0.895529 0.423626 -0.136271 0.202946 0.0293024 0.978751 0.683833 -0.0620368 0.726996 0.417032 -0.159255 -0.894831 0.373794 -0.150352 0.915244 0.973716 -0.0833362 -0.211973 0.873175 -0.00139551 -0.487404 0.124279 -0.024388 -0.991948 0.249074 -0.00145165 -0.968484 0.0358181 -0.00143073 0.999357 0.936227 -0.351337 0.00642955 0.934484 -0.356004 0 0.816414 -0.00359183 0.577456 0.847174 -0.0208452 0.530907 0.861016 -0.00753271 -0.508522 0.831671 0.0132993 -0.55511 0.0242129 -0.999679 0.00745166 0.0138846 -0.999751 0.0174737 0.926677 0.158177 0.340954 0.94567 0.00423733 -0.3251 0.408563 -0.0227734 0.912446 0.0255764 -0.789849 0.612769 -7.41767e-07 -0.878183 -0.478325 0.0616379 -0.997984 -0.0151443 0.000784383 0.00325492 0.999994 5.58943e-10 0.000704129 -1 0.262248 0.116885 -0.957896 0.981215 -0.1082 -0.159718 0.860828 0.0440782 0.506983 0.0701031 -0.0804534 0.99429 -0.759445 -0.115781 0.640185 -0.925915 -0.0475623 0.374726 -0.305939 0.0300969 0.951575 0 -1 0 0 -1 0 0.00396362 -0.999944 0.00985775 -0.00135948 -0.999999 0 0.189579 -0.278161 -0.94164 7.54614e-05 -0.99994 0.0109608 0.0116479 -0.999927 0.00325639 -0.00589091 -0.999948 -0.00837555 0.00841258 -0.99981 0.0175582 -0.512833 -0.694898 0.504103 -0.568281 0.234136 -0.78882 -0.0100753 -0.999949 -0.000285774 0.677773 -0.681716 -0.275475 -0.000715676 -0.999438 0.0335082 -0.689492 -0.33442 -0.642467 0.575691 -0.317243 -0.753616 0.730899 -0.647354 -0.216147 -0.772677 -0.0665905 0.631297 -0.595892 -0.205811 0.776243 0.0227365 -0.999576 0.018208 8.49655e-05 -1 -0.00021099 -4.88144e-05 -1 0 0 -1 -0.00101515 4.88602e-10 -0.999999 -0.00139518 0.71081 -0.663063 -0.234727 -0.166538 -0.707539 0.686771 -4.52428e-08 -8.72624e-05 -1 -4.29372e-05 9.36312e-08 -1 -5.03734e-05 -9.33055e-08 1 0 -0.000102264 1 0.0183068 0.0103873 -0.999778 -7.6759e-05 -4.34423e-05 -1 0.0465569 -0.0102735 0.998863 -0.021939 0.0112645 0.999696 3.54708e-07 -0.0127952 -0.999918 -0.00670873 -0.0435847 -0.999027 0.00143737 -0.00482328 0.999987 0.000260286 -2.56373e-05 1 -0.0002626 6.63586e-07 1 4.58168e-08 0.00144872 0.999999 0 -0.000472685 -1 -6.98384e-05 -2.10672e-06 -1 0.8 -0.6 0 0.331769 -0.539124 -0.774128 -0.331769 -0.539125 0.774128 -0.371391 -0.928477 0 -0.999999 -0.00105906 1.58212e-05 -3.03323e-05 -0.383173 0.923677 1 0.000612963 0.00071429 0.999888 0.0149085 -0.000886665 3.4166e-05 -0.0636686 -0.997971 6.55305e-07 -0.998029 0.0627549 1.58489e-06 -0.998029 0.0627556 -0.0620843 0.984924 -0.161462 -0.0651086 0.997199 0.0368073 0.909863 -0.371634 0.184494 0.943953 0.123769 -0.305996 0.861561 -0.40735 0.302949 0.871149 -0.319331 0.372997 0.108151 0.00770068 0.994105 -0.238752 0.0228456 0.970812 -0.685338 0.643969 -0.340024 0.146604 -0.868052 0.474335 -0.110264 -0.684957 -0.720192 -0.623886 0.195766 -0.756599 0.779553 0.0895899 -0.619895 -0.10598 -0.169178 -0.979871 0.634139 0.0689806 -0.770136 0.738338 -0.101294 -0.66678 0.878818 -0.36414 -0.308353 -0.302913 -0.364976 -0.880362 -0.99594 -0.0896596 -0.00805073 -0.625169 0.0931287 -0.774913 -0.558772 0.0614593 -0.827041 0.507991 -0.0536657 0.859689 -0.9332 -0.0280571 -0.358261 -0.437018 -0.0216539 -0.899192 -0.913883 0.204826 -0.350521 -0.249262 -0.491906 -0.834205 -0.630451 0.386083 -0.673403 -0.979956 -0.198318 -0.0188612 -0.0868321 -0.127571 0.988021 -0.971269 -0.018655 0.237251 -0.549014 0.0148435 0.835681 -0.238926 -0.0361881 0.970363 -0.636688 0.632987 -0.440404 -0.116788 -0.0163937 0.993021 -0.516555 0.164383 0.840327 -0.225512 -0.020279 -0.974029 -0.000551375 -0.00146065 -0.999999 6.31287e-09 -0.00166929 -0.999999 -0.00129061 -0.00035838 -0.999999 -2.40096e-05 -0.999999 -0.00130131 0.0353709 -0.9993 0.01218 -0.000453412 -0.999998 -0.00203841 -0.0142122 -0.940109 0.340578 -0.108845 -0.96149 0.252366 0 1 -3.47694e-05 0.000386958 1 -0.000355952 0 1 8.26022e-07 9.05441e-06 1 2.22465e-06 5.31134e-06 1 4.88575e-06 -0.000267557 1 -0.000246118 0 1 0 0 1 0 0 1 0 -5.95828e-07 1 2.21968e-06 0.0189121 0.999148 0.0366817 -0.0461062 0.9988 -0.0165088 0.182976 0.0781486 -0.980006 0.47027 0.624212 -0.623863 0.00533276 0.999983 -0.00246697 -1.10317e-05 0.999999 0.00106526 -1.10321e-05 1 -0.000838971 2.38288e-06 1 -6.02429e-06 -0.67006 -0.738456 0.0755206 0.577164 -0.815769 -0.0374555 0.950559 -0.00374981 0.310522 0.332126 -7.38828e-07 0.943235 0.957204 0.0130665 0.289121 0.836902 0.205471 -0.507323 0.217945 -0.45642 -0.862659 0.243813 0.030538 0.969341 0.564327 -0.0213595 0.825275 0.960707 0.00755134 0.277461 0.428648 0.827832 0.361876 0.613301 0.19715 -0.764849 0.948836 -0.154802 0.275219 0.716807 0.131063 0.684843 0.00844622 -0.999858 -0.014602 0.00444127 -0.999989 0.00138144 -5.54411e-05 -1 -0.000533446 -0.00018638 0.999985 0.0055432 3.01823e-06 -1 -7.04796e-05 -6.8242e-06 -1 0.000463503 6.60179e-08 -1 3.05075e-05 3.10411e-05 -1 0.000750513 -0.000102648 -0.999976 -0.00699502 -0.000325754 -1 0.000172819 -0.000521224 -1 -0.000295994 4.08494e-05 -1 2.89562e-05 2.59109e-05 1 0.000253903 -4.52952e-06 1 -7.82442e-06 2.47655e-06 -1 -4.07362e-05 -0.000122579 -0.999999 0.00131397 1.32778e-05 -1 -0.000601149 -7.55823e-06 -1 -0.000374633 -0.000259558 -0.999997 0.00242258 0.00466421 -0.999985 0.00297008 -0.0178941 -0.985148 0.170774 4.53457e-05 -1 0.000138295 0.000948682 -0.999999 0.000668841 -0.0195095 -0.999718 -0.0135463 0.000310462 -0.999998 -0.00191563 -0.0677233 0.988507 -0.135155 0.000194772 -0.999992 -0.00400368 0.000328153 -0.999977 -0.00674543 -0.0012893 -0.999996 -0.00257072 0.000410059 -0.999994 -0.0034809 -0.000226572 0.999988 0.00487058 -0.000769273 -1 -0.000608395 0.00485502 -0.999981 0.00393507 -1.22798e-05 -1 -0.00021332 -5.26915e-06 -1 -9.59986e-05 1.76319e-05 1 -9.17521e-05 0.000156749 -0.999991 -0.00430567 0.000381375 -0.999967 -0.00810722 -0.000550455 -0.999997 0.00250989 3.61984e-05 -1 4.84927e-05 -0.0571933 -0.997803 -0.033442 0.0198908 -0.999769 -0.00815914 0.00745002 -0.999819 -0.017501 6.94631e-05 -1 -1.90325e-05 -0.000220192 1 0.000353945 0.00622761 -0.999914 -0.0115798 0.00457976 -0.999982 0.00382745 0.00606882 0.999771 0.0205323 0.156898 -0.859667 0.486163 -0.00618145 -0.999825 0.0176745 0.0311359 -0.997842 0.057801 -1.40215e-05 -1 -0.000234589 -0.0162021 -0.997361 0.0707702 -0.0288126 -0.996962 -0.0723703 0.00101086 -1 -2.36493e-05 0.0377564 0.118213 0.99227 0.00121465 -0.999999 0.000588732 -7.72696e-07 -1 -7.43891e-06 -2.27643e-05 -1 4.34267e-05 0 -1 0 -1.00429e-05 -0.999491 -0.0319051 -1.93588e-06 -1 2.56919e-05 3.80565e-07 -1 2.03291e-06 0 -1 0 -4.3599e-06 7.19936e-06 -1 8.76184e-11 -0.000147053 -1 -0.000378698 0.0359805 -0.999352 -6.3823e-07 1.80223e-05 -1 0 0 -1 0.000564392 1 0.00013867 -0.000694885 1 4.45019e-07 0.489032 0.0584144 0.870308 0 0.737318 0.675546 -0.714162 -0.0258512 0.699503 0 0.737318 0.675546 -1.05243e-08 0.737317 0.675547 -0.752509 0.634565 0.176234 -0.760848 0.621503 0.186664 -0.768414 0.619281 0.161341 -0.757877 0.625724 0.184639 -0.7564 0.62995 0.176131 -0.750553 0.650383 0.116931 -0.76342 0.618488 0.186179 -0.738957 0.648829 0.18156 -0.622078 0.772299 0.128737 -0.762464 0.619317 0.187336 0.00125389 0.999997 0.00215878 0.00244306 0.999996 0.00113645 -2.05532e-06 1 -6.89291e-06 3.87463e-05 1 -2.64867e-06 3.01179e-06 1 4.18721e-05 0.000108013 1 7.73624e-05 0 1 0 2.57277e-05 1 6.66097e-05 0.000260954 1 9.61108e-05 -0.826829 0.558024 -0.0704488 0 1 0 0 1 0 -6.67156e-07 -1 -3.174e-05 0 1 0 5.75398e-06 -1 0.000954317 -1.54741e-06 -1 -0.000283928 -3.07319e-07 1 -5.83741e-05 -1.14987e-05 1 -0.00054705 -0.000118061 1 -7.80277e-05 0 1 0 4.5153e-05 1 2.01321e-05 7.23012e-07 1 4.34156e-06 0 1 0 0 1 0 2.86152e-05 1 0.000171829 -1.25073e-07 1 -5.28823e-07 -1.98399e-06 1 -1.38351e-06 -1.05159e-05 -0.999997 -0.00224272 0 1 0 0.00055494 -1 0.000366765 -0.000112068 1 -9.97107e-05 -1.2549e-06 1 -6.70453e-06 2.16265e-05 1 3.82243e-06 -0.173641 0.548157 -0.818152 0.000165717 0.998944 0.0459519 0.000147353 1 -0.000894727 4.34457e-06 1 1.83693e-05 2.79717e-06 -1 -0.000511241 -0.00431726 0.0802902 0.996762 0.0177186 0.490288 -0.871381 -0.157575 0.516165 -0.841869 -5.13222e-06 1 -0.000146312 -5.10483e-05 1 -0.000354842 1.42013e-06 0.999999 -0.00106108 3.70327e-05 0.999997 -0.00247566 -1.44197e-05 1 -0.000973218 -7.96813e-06 1 -0.000509584 0 1 0 4.15414e-05 -0.999999 0.00132796 0.0019568 -0.0203433 0.999791 0.00112875 -0.0039835 -0.999991 0.493279 -0.357394 0.79306 0.0002518 -0.749489 0.662017 -9.47823e-05 -0.509804 0.86029 -0.000535921 -0.695716 0.718317 0.00121797 -0.557931 0.829887 0.000259166 -0.410883 0.911688 -0.000399352 -0.319182 0.947693 0.00186031 -0.122996 0.992405 -0.00220359 -0.257731 0.966214 0 -0.0943664 0.995538 -0.000152229 -0.0812964 0.99669 0.00235413 -0.266777 0.963755 -0.000219046 -0.525428 0.850838 0.000578587 -0.321516 0.946904 -0.00273871 -0.122677 0.992443 -0.00121944 -0.555153 0.831747 0.00122821 -0.749488 0.662016 0 -0.712502 0.70167 -0.000908906 -0.80403 0.594589 -0.00223135 -0.80161 0.597843 0.00170503 -0.797621 0.603157 -1.79403e-05 -0.800674 0.599101 6.54513e-07 -0.800782 0.598956 1.2886e-07 -0.80078 0.598958 -1.08043e-06 -0.800784 0.598953 5.5039e-08 -0.800781 0.598958 0 -0.800777 0.598962 -0.000192232 -0.800984 0.598685 -6.05648e-06 -0.80077 0.598972 -0.0123432 0.237073 -0.971413 -6.75852e-07 0.178713 -0.983901 0.0103181 0.11298 -0.993544 0.190617 0.841193 -0.506023 0.672233 -0.0354843 0.739489 -0.918495 -0.153164 -0.364566 -0.645123 -0.285322 -0.708808 -0.00269471 0.999982 0.00540403 -0.161201 -0.978457 0.128979 -0.0985469 -0.989541 0.105341 -0.337499 -0.869351 0.361002 -0.339313 -0.8699 0.357968 0.552333 -0.438776 0.708805 0.0318109 -0.413703 0.909856 -0.388058 0.819515 0.42167 -0.289721 -0.328313 -0.89904 0.1074 -0.106926 0.988449 0.316554 -0.215821 0.923696 -0.829201 0.0143434 0.558766 -0.914079 0.0456702 -0.402957 0.696831 0.0329307 0.71648 0.914658 -0.237006 -0.327458 -0.101965 -0.990979 0.0869659 -0.0105044 -0.999726 0.0209224 5.3265e-07 -1 8.05322e-05 1.72938e-08 -1 1.4519e-05 -0.0665343 -0.989158 -0.130918 0 -1 0 0 -1 0 -0.522267 0.0217484 0.852505 -0.907491 -0.237309 0.346619 -0.607078 0.0264338 -0.794202 -0.878818 0.36414 0.308353 -0.26615 0.963795 -0.0162044 -0.274679 0.961536 0 0 1 0 0 1 0 0.283308 0.958521 0.0312044 0.268091 0.963394 0 -0.118263 0.0848298 0.989352 -0.186548 -0.0700136 0.979948 0.977779 0.0539823 0.202567 -0.918574 -0.0831714 0.3864 -0.668803 0.0922963 0.737688 0.668803 -0.0922963 -0.737688 0.00313758 0.999992 -0.00246451 -0.971042 0.00486844 -0.238861 -0.869089 -0.439991 -0.226034 0.000506432 0.0822037 -0.996615 -0.000940216 0.446205 -0.894931 0.00110631 0.446204 -0.89493 -0.153947 -0.186614 0.970297 0.246442 -0.644368 0.723917 -0.203044 0.978034 -0.0471539 -0.193705 0.979761 -0.0504681 -0.0676404 0.660862 0.747454 0.26192 0.871471 -0.414652 0.0457122 0.855053 -0.516522 2.06419e-07 0.798641 -0.601807 -2.13342e-05 0.798099 -0.602527 0.218542 0.425265 -0.878288 0.211868 0.436075 -0.874614 0.0109608 0.798593 -0.601771 -0.925553 -0.366321 -0.0957088 -0.283099 -0.935159 -0.212916 0 1 2.23444e-06 6.67703e-06 1 1.64053e-06 -0.802919 -0.428016 -0.414879 0.232028 0.857617 -0.458972 -0.124661 -0.887987 0.442649 -0.150448 -0.876755 0.4568 -0.102351 -0.994421 -0.0255039 -0.100869 -0.994562 -0.0259332 0.0272797 -0.215255 -0.976177 0.065515 -0.663768 -0.745064 -0.00503255 -0.767796 -0.640675 -0.0181137 -0.725877 -0.687586 0.00237023 -0.751108 -0.660175 -2.49067e-07 -0.737328 -0.675535 2.40099e-07 -0.73731 -0.675555 9.65456e-09 -0.737333 -0.675529 -2.64202e-07 -0.737328 -0.675535 0.00030926 0.73794 0.674866 0.0977046 -0.97839 0.182225 0.340966 -0.870288 0.355446 0.33986 -0.869955 0.357314 0.973589 0.013654 -0.227901 0.220684 -0.261536 -0.939626 0.186258 0.0346873 0.981888 0.132349 -0.0368626 0.990518 0.0940505 -0.995183 -0.0276646 0.100505 -0.994601 -0.0258441 0.12026 -0.898832 0.421471 0.151937 -0.885084 0.439934 0.000404374 1 -9.93541e-05 0 1 -0.000140243 -0.199379 0.151179 -0.968191 0.000257009 0.00160374 -0.999999 0.142108 0.193958 -0.970662 -0.0268766 0.0801679 -0.996419 -0.0645392 -0.0408187 -0.99708 0.217669 0.187964 -0.957752 0.0109402 0.00331145 -0.999935 -0.00172435 0.0175308 -0.999845 0 0 -1 0 0 -1 0.00231346 0.0235201 -0.999721 0.923652 -0.319721 -0.211296 0.316633 -0.942577 0.106263 0.232707 -0.970651 -0.0607043 0.971117 -6.78374e-06 0.238602 0.971118 0 0.238602 -0.971117 0 0.238602 -0.971118 -6.24584e-06 0.238602 0 0.344498 0.938787 -0.0302442 0 0.999543 0.348737 -0.834244 0.427106 0.39488 -0.766843 0.505986 0.460396 -0.713014 0.528817 0.499757 -0.692072 0.520845 0.50742 -0.666752 0.545863 -0.352135 -0.827828 0.436693 -0.396464 -0.760712 0.513939 -0.458839 -0.711342 0.532409 -0.519936 -0.677847 0.519799 -0.500119 -0.684029 0.531023 0 0 1 0.0242833 0.293413 0.955677 -0.329917 0.421222 -0.844824 -0.258879 0.503735 -0.824156 2.27764e-05 0.802743 -0.596325 -0.000117328 0.798446 -0.602066 0.00294716 -0.0126556 0.999916 0.00205437 -0.00504114 0.999985 0.6071 -0.672497 0.423293 0.610112 -0.667994 0.426084 0.00160074 0.00274534 -0.999995 -0.800479 -0.202276 -0.564196 -0.812509 -0.137058 -0.566608 -0.762569 0.504798 0.404559 -0.0301625 0.129201 -0.99116 -0.140543 0.362238 0.921429 0.293856 -0.578647 0.7608 0.607551 -0.671743 0.423845 0.0830111 0.229689 -0.969718 0.532163 -0.769065 0.354035 -0.0843284 -0.384697 -0.919183 -0.813048 -0.13001 -0.567495 -0.812703 -0.13545 -0.566717 -0.310171 -0.0516951 0.949274 -0.00788721 0.0659644 0.997791 0.0219125 -0.069212 0.997361 0.605877 -0.674358 0.422083 0.607155 -0.672462 0.42327 0.0105832 0.00551303 -0.999929 0.00990239 0.00274023 -0.999947 -0.784556 -0.266335 -0.559944 -0.813812 -0.128157 -0.566821 -0.842036 -0.539192 -0.0157301 -0.00537463 -0.445678 0.895177 0.606878 -0.672767 0.423183 0.606751 -0.672921 0.42312 -0.613645 0.669796 -0.418107 0.192734 -0.201855 -0.960265 0.144762 0.0367938 -0.988782 -0.813001 -0.13566 -0.566238 -0.813595 -0.126886 -0.567418 0.0162391 0.0284992 -0.999462 0.00829087 -0.00390424 -0.999958 -0.812866 -0.135287 -0.566522 -0.813105 -0.13177 -0.567007 -0.24285 -0.625136 0.741774 -0.0166624 0.0904106 0.995765 0.193381 -0.363782 0.911189 0.606663 -0.673225 0.422763 0.607266 -0.672327 0.423326 0.997613 -0.02325 0.0650167 0.94248 0.121981 -0.311211 0.603074 -0.0442742 -0.796456 -0.80061 0 -0.599186 -0.00800507 -0.047338 -0.998847 -0.112008 -0.0169439 0.993563 -0.341264 0.159249 0.92638 0.761057 0.199255 0.617324 0.949102 -0.00471825 0.314935 -0.0568586 -0.142898 0.988103 0.622095 -0.00721285 -0.782908 0.445211 0.0613901 -0.893319 0.183727 0.172078 -0.967798 -0.0264787 0.0891538 -0.995666 -0.886121 0.0705839 0.458047 -0.943709 0.149525 0.295052 0.355466 0.014917 -0.93457 0.262495 -0.0362829 -0.964251 0.996412 0.0039969 -0.0845391 0.974381 0.0163267 -0.224309 0.930338 -0.00647921 -0.366645 0.755546 0.0376084 -0.654015 -0.761416 -0.334264 -0.555439 -0.812431 -0.137799 -0.566539 -0.090342 0.372965 0.923437 0.0124503 -0.143679 0.989546 0.583734 -0.707815 0.39781 0.612147 -0.665633 0.426859 -0.810848 -0.151068 -0.565424 -0.610524 0.73046 -0.306086 -0.262486 -0.525012 0.809607 0.105055 -0.111559 0.988189 0.242157 0.312393 0.91857 0.614203 -0.664183 0.426164 0.60672 -0.672935 0.423142 -0.963372 0.00244198 -0.268157 -0.960329 0.00521144 -0.278822 -0.290589 -0.00270323 -0.956844 -0.70584 0.0022231 -0.708368 -0.719666 0.00695196 -0.694285 0.812297 0.430091 -0.393949 0.423858 -0.0274838 0.905312 0.881317 -0.000712465 0.472524 0.718416 -0.0700877 0.692074 -0.00210135 0.140286 0.990109 0 0.0829482 0.996554 0 0.0829482 0.996554 -0.00520191 -0.0601844 0.998174 -0.695096 0.667278 0.26755 0.156373 0.0240434 0.987405 -0.486665 0.242655 0.839211 -0.707706 -0.0855174 0.701312 -0.741515 0.562162 0.366236 0.070702 0.724885 0.685232 0.184825 0.982093 -0.0365194 0.196392 0.979472 -0.0454306 0.0120339 -0.200123 -0.979697 -0.735289 -0.570742 -0.36552 -0.550021 -0.720945 -0.421563 -0.760533 -0.620688 -0.190621 -0.759499 -0.622908 -0.187477 -0.760065 -0.622277 -0.187277 -0.759699 -0.62291 -0.186656 -0.758542 -0.624473 -0.186138 -0.581142 -0.57823 -0.572647 -0.745437 -0.619853 -0.245164 -0.6261 -0.76574 -0.147107 -0.670122 -0.718245 -0.187242 -0.594953 -0.723909 -0.349265 -0.718441 -0.636332 -0.280934 -0.192805 0.695543 -0.692132 -0.184799 0.704527 -0.685195 -0.549338 -0.0336279 0.834923 -0.0911405 0.0966655 0.991135 0.0037422 0.0634449 0.997978 -0.993344 -0.0468274 0.105236 0.57688 0.504871 0.642118 0 0.80077 -0.598971 2.427e-05 0.800802 -0.598929 -1.16672e-05 0.800774 -0.598967 -0.0868541 0.829686 -0.551432 -3.6231e-06 0.800792 -0.598942 6.23385e-08 0.800779 -0.598961 2.00606e-07 0.723334 -0.690499 0 0.723325 -0.690507 -0.0327123 0.732218 -0.680284 0 0.86507 -0.501651 -0.000121353 0.868693 -0.495351 -0.00124453 0.868825 -0.495118 -0.00213539 0.868967 -0.494865 0.0145789 0.870727 -0.491551 -0.157625 0.972362 0.172239 0.40611 -0.769458 -0.492959 0.743663 -0.573124 -0.344228 0.75669 -0.627673 -0.182885 0.75835 -0.624795 -0.185842 0.572048 -0.57601 -0.583929 0.759053 -0.623695 -0.186663 0.758177 -0.624876 -0.186274 0.540513 -0.681869 -0.492849 0.670556 -0.712758 -0.205741 0.626487 -0.76421 -0.153286 0.745422 -0.638254 -0.192297 0.725386 -0.638891 -0.256189 0.744079 -0.606883 -0.279354 0.722119 -0.62166 -0.303452 0.189215 0.699539 -0.689088 0.183978 0.705314 -0.684606 -0.567445 0.810897 0.143012 0.00161355 0.868786 -0.495186 0.00171494 0.868468 -0.495743 0.00375962 0.868795 -0.495157 -0.00148791 0.869171 -0.494509 0 0.869233 -0.494403 0 0.723334 -0.690499 0.000419897 0.740242 -0.67234 -0.00478682 0.901694 -0.432349 0 0.800779 -0.59896 0.000133665 0.80061 -0.599185 0.00713078 0.793517 -0.608506 8.21404e-08 0.800779 -0.59896 0 0.800779 -0.59896 -0.0289266 0.812232 -0.582616 0.0198054 0.999792 -0.00486615 -0.0174561 0.999848 -3.00782e-06 0.744194 0.663086 0.0805744 0.766638 0.611992 0.194247 0.766871 0.620422 0.16427 0.751935 0.635601 0.174945 0.761823 0.620154 0.187178 0.771676 0.607663 0.187783 0.631903 0.763839 0.131336 0.746054 0.640159 0.183304 0.755898 0.629407 0.18018 0.758266 0.62577 0.18288 0.129503 0.118077 -0.984524 0.846993 0.415121 -0.332081 0.999665 0.000516017 -0.0258894 0.499201 -0.0503237 0.865024 -0.99959 -0.0284207 0.00359425 0.628918 0.218178 0.746231 1 7.62522e-05 -1.09397e-05 1 0.000330995 -4.74872e-05 -0.200809 0.97963 2.1968e-06 -0.0094808 0.999884 0.0119523 -1 0.000390354 -4.88545e-05 -1 1.98691e-06 6.83552e-06 -0.65881 0.209986 0.722409 1 7.54396e-05 -1.04843e-05 1 0 0 7.40391e-06 1 -5.92575e-06 9.68722e-05 1 -4.56364e-07 -1 0.000107071 -0.00010221 -1 7.82977e-05 -0.000119547 -0.999997 -0.00232507 -0.00116873 1 6.48083e-05 -5.49222e-05 1 5.95352e-05 -5.68327e-05 1 0.000757753 9.69115e-05 0.777088 0.628205 0.0386377 0.710161 0.704015 0.00585504 -0.701969 0.711741 0.0257643 -0.490323 0.844309 0.216162 -0.921101 0.370548 -0.119447 0.987664 0.156202 0.0110272 -0.510955 -0.859378 -0.0198708 -0.972234 -0.0174015 0.233361 -1 0.000265924 -0.000198902 -1 0.000239109 -0.000211203 -0.99984 0.0170865 0.00537223 1 -6.23188e-05 2.22923e-05 1 -3.68215e-05 3.25241e-05 0.999999 0.00107699 0.000353128 0.000768247 -7.84276e-07 1 -0.00210611 0.00288705 0.999994 -0.869761 0.174839 0.461462 0.650706 0.711028 0.266498 0.51141 0.397543 -0.761853 0.0692993 0.880905 -0.468192 -0.754335 0.545751 -0.364876 -0.55085 0.153186 0.820426 -0.567144 -0.051339 -0.822017 -0.842864 0.480874 -0.241537 0.178087 0.889807 0.420152 -0.833365 0.552719 -0.0020839 -0.623583 0.531287 -0.57348 -0.420216 0.660235 -0.622502 0.116432 0.350235 -0.929397 -0.752022 0.548909 -0.364913 -0.307521 0.554716 0.773124 0.626299 -0.0727515 -0.776181 0.143488 0.28925 -0.946438 -0.0533737 -0.983433 0.173235 -0.000397072 -0.951312 0.30823 -0.00272477 0.924133 -0.382061 0.761494 -0.648012 0.014414 0.993515 -0.113633 -0.00405418 -0.814705 0.579824 -0.00770259 0.869961 0.406159 0.279649 0.253553 0.439659 -0.861632 0.957636 -0.0521791 -0.283216 -0.957636 0.0521791 0.283216 0.93495 -0.172924 -0.309784 -0.94774 -0.250219 0.19794 0.000303011 -0.999285 0.0377956 0.000234008 -0.999289 0.0377112 0.00472104 -0.572231 -0.820079 1.18744e-05 -0.281529 0.959553 -0.0165385 -0.343886 0.938866 0.0192752 -0.998915 0.0424 0.107545 -0.992099 0.0646108 0.000474642 -0.999351 0.0360265 -2.12547e-05 -0.999385 0.0350681 0 -0.99936 0.035762 0.00523691 -0.509973 0.860174 0.0592466 -0.983844 0.16894 -0.999979 -0.00632767 -0.00141251 -1 0.00100805 0.000171539 -0.999987 0.00350381 0.00361217 -0.440154 0.0151781 0.897794 -2.80301e-05 -2.06454e-05 1 0 2.29542e-05 1 0.403475 0.00850263 0.914951 0.950741 -0.0302024 0.308512 0.999984 0.0031346 0.00474524 1 0.000424558 0.000657664 0.000811405 0.000695242 -0.999999 -0.915868 -0.184351 -0.356653 0.00103945 -0.000339339 -0.999999 4.94824e-05 0.88838 -0.459108 0.000166475 0.888325 -0.459216 -0.107564 0.854351 -0.508443 -0.00311787 0.999235 -0.0389852 -0.0110873 0.940618 -0.339286 0.00473882 0.999674 -0.0250826 -0.879398 -0.449416 0.157113 -0.999843 -0.0157995 -0.00805974 -0.997115 0.0758864 -0.00176237 0.986418 0.0101303 -0.163942 0.930104 -0.332095 0.156904 0.999514 0.0311743 0.000124067 0.998251 0.0585877 -0.00784596 0.999861 0.0109633 -0.0125343 0.000870494 0.0175984 0.999845 0.03774 -0.891453 0.451538 0.109376 -0.891297 0.44003 0.00977551 -0.999847 0.0145189 0.00456002 -0.99997 -0.00630415 -0.180653 -0.69143 0.699492 -0.0831865 -0.974846 -0.206775 0.0371928 -0.915429 0.400758 0.00166768 -0.902264 0.431182 0.0701878 -0.309511 -0.948302 -0.374467 0.585661 -0.718871 -0.951967 0.143886 -0.270288 0.171829 -0.953767 -0.246585 -0.983519 0.00915279 -0.180573 -0.980796 -0.0417093 -0.190523 0.00106477 -0.957939 0.28697 0.00151495 0.0282326 0.9996 0.375864 0.75463 -0.537829 0.99987 -0.0159582 -0.00223258 8.48045e-05 -0.998686 0.0512568 -0.256791 -0.927738 -0.270851 0.00433484 -0.890502 0.454958 0.000827618 -0.888515 0.458848 -7.22577e-05 -0.888853 0.458192 0.000126224 0.000243656 1 -0.000289806 -0.000724833 1 -0.999992 -0.00230352 0.0034181 -0.997234 -0.0723157 0.0171802 -1 0.000175167 -6.67126e-05 -1 0.00026956 -0.000163506 -0.999987 -0.00244407 -0.00441458 -0.00223007 0.00034037 -0.999997 -0.00181817 -0.00120413 -0.999998 -8.91005e-06 0.000274618 -1 0.000809809 -0.000399671 -1 0.997988 -0.0597782 0.0211171 0.999996 -0.00176877 0.00205212 1 0.00030181 -0.000119844 1 8.3219e-05 -0.00045829 0.99997 -0.00320007 -0.00703635 -2.81836e-08 -0.999995 -0.00316313 -1.60562e-05 -0.999996 -0.00297035 -7.56352e-05 -1 1.48938e-05 -0.00287662 -0.999996 -0.000222374 -1.9509e-05 -1 0.000416854 7.53639e-06 -1 9.72016e-05 0.00297121 -0.999996 -5.0148e-06 0.000597455 -1 -0.000205317 -0.958376 -0.285507 0.000583978 -0.957427 -0.288676 0.000920298 -1.44494e-05 -0.323666 0.946171 0.00171856 -0.341826 0.939762 0.944973 -0.327145 -0.00171249 0.950664 -0.310222 -0.000281947 -0.000724454 -0.30137 -0.953507 -0.00178959 -0.312866 -0.949796 -0.603942 0.180939 0.776219 0.407304 0.00772006 0.91326 -0.634564 -0.0266251 0.772412 -0.00834081 -0.994327 -0.106035 -0.0216083 -0.998456 -0.0511649 -0.0102662 -0.999182 -0.0391166 0.0318156 0.0150519 -0.99938 0.000460408 -0.0865291 0.996249 -0.104328 -0.152501 -0.982781 0.160023 -0.410127 -0.89788 0.103567 -0.982634 0.153962 -0.976321 -0.216107 0.009768 -0.00120644 -0.999365 0.0356206 -0.00191745 -0.573258 -0.819373 0.00258171 -0.553844 -0.832616 -0.00316585 -0.359103 0.933293 -0.000124841 -0.345735 0.938332 -0.849001 -0.525085 -0.05902 0.946171 -0.322254 0.0302002 0.948047 -0.31685 0.0285104 -0.102448 -0.896372 -0.431302 0.00850022 -0.790427 0.612497 -0.776094 0.383251 0.500796 0.205784 -0.136956 0.968967 0.201423 -0.0174386 -0.979349 -0.209755 -0.136738 -0.968145 -0.993746 0.079482 -0.0784351 -0.939913 -0.0177386 -0.340953 -0.994496 0.0200191 -0.102846 -0.0316282 -0.0305045 0.999034 -0.126808 -0.837199 -0.531993 -0.476701 -0.743713 -0.468666 -0.463158 -0.745888 -0.478682 -0.140049 -0.792279 -0.593869 -0.138838 -0.792388 -0.594008 -0.488986 0 0.872292 0.0208196 0.0944608 0.995311 -0.0330207 0.115157 0.992798 -0.477245 -0.00290078 0.878765 -0.860718 -0.0100831 0.508983 -0.779995 0 -0.625785 -0.919001 0.00506886 0.394223 -0.990788 0.0740243 0.113404 -0.998471 0.0483664 0.0267806 -0.835434 -0.0428001 -0.547921 -0.522957 0.0284851 -0.851883 -0.618004 0.49557 0.610313 -0.572725 -0.0634639 0.817287 0.354905 0.168449 0.919602 -0.910375 0.228381 -0.345048 -0.99987 -0.0159438 -0.00257781 -0.412013 0.122123 -0.902957 -0.490145 0.0203478 -0.871404 0 -0.88852 -0.458838 0 -0.888521 -0.458837 -3.08506e-07 -0.888488 -0.4589 5.16338e-06 -0.888417 -0.459038 0 -0.88852 -0.458837 2.48649e-06 -0.888528 -0.458823 -5.46029e-08 -0.888519 -0.458839 7.92962e-08 -0.88852 -0.458837 2.16815e-08 -0.88852 -0.458837 -4.82681e-06 -0.88853 -0.458818 8.44489e-08 -0.88852 -0.458838 2.6472e-07 -0.888519 -0.458839 5.66358e-07 -0.888521 -0.458836 0 -0.888519 -0.45884 0.00476971 0.88851 0.458833 -0.059702 0.89985 0.432095 4.7247e-05 0.888663 0.458561 -0.0517052 0.868315 0.49331 2.27225e-05 0.88852 0.458838 -2.29285e-05 0.888586 0.458711 1.81857e-05 0.888583 0.458716 -1.44007e-07 0.88852 0.458837 -0.000226474 0.965604 0.260019 -1.78827e-07 0.88852 0.458838 -1.78916e-07 0.888509 0.458859 0.00501791 0.888964 0.457949 0.00409019 0.888808 0.458261 0.000199744 0.889139 0.457637 0 0.888687 0.458514 9.40362e-07 0.998029 0.062756 1.06087e-06 0.998029 0.0627568 0.928566 0.3594 0.0927185 0.932618 0.360865 5.36931e-07 0.13411 0.983838 0.118648 0.166422 0.975235 0.145675 0.601925 0.731655 0.31995 -0.00406647 0.998286 0.0583819 -0.758598 0.624331 0.186386 -0.754946 0.632237 0.174163 -0.758361 0.624637 0.186325 -0.758556 0.624303 0.186654 -0.755962 0.625371 0.193474 -0.75864 0.624277 0.186397 -0.758651 0.624262 0.186399 -0.758649 0.624266 0.186397 -0.971118 -2.35528e-06 0.238601 -0.406929 -0.414525 -0.813989 -0.971449 -0.0151552 0.236765 -0.973089 0.0890906 0.212511 -0.971117 -4.23529e-05 0.238602 -0.971118 0 0.238598 -0.971118 1.23562e-05 0.2386 -0.971117 1.62406e-06 0.238602 -0.999999 -0.000289979 0.00162303 -0.999972 0.00743476 1.36911e-06 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -0.862504 0.498669 -0.0861221 -1.12852e-06 0.999416 0.0341855 0 0.999415 0.0341893 0 0.999416 0.0341858 3.26362e-06 0.999416 0.0341845 0 -9.29157e-08 -1 0 -9.29157e-08 -1 -0.0483568 0.997134 0.0581791 1.22731e-06 0.999378 0.0352749 -5.87096e-05 0.000212003 1 0 -0.000931361 1 3.39393e-05 4.84784e-07 1 0 2.03501e-05 1 -8.22943e-06 0 1 0.00259344 -0.593614 -0.804746 1.5716e-06 -0.000385759 -1 1.54189e-07 -1.34077e-07 -1 -5.09154e-05 4.42743e-05 -1 0 0.999416 0.0341855 0 0.999416 0.0341855 0 -9.29157e-08 -1 0 -9.29157e-08 -1 0 0 1 0 0.78351 0.62138 0.636323 0.515039 0.574306 -8.57768e-06 0.783489 0.621406 0 0.999416 0.0341853 2.02998e-07 0.999416 0.0341858 0 -9.29157e-08 -1 0 -9.29157e-08 -1 0.000197473 0.999209 0.0397591 -0.00470639 0.997695 0.067698 0 0 1 0 0 1 0 4.68782e-06 -1 -8.9305e-07 -1.57155e-12 -1 0.834306 0.0604859 -0.547973 0.920373 0.181431 -0.346405 0.997849 0.0644856 -0.0118073 0.951378 -0.000892771 0.308025 0.0125866 0.565326 0.824771 0.08627 0.0690027 0.993879 0.364097 -0.0111769 0.931294 -0.438232 0.162285 -0.884091 0.347442 0.160756 0.923819 0.467363 0.172671 -0.867039 0.768927 0.00964287 -0.639264 0.930349 0.209467 -0.300957 0.993249 0.110777 -0.0344112 0.905743 -0.00818729 0.423748 0.412713 -0.00638183 0.910839 0.448559 0.00265119 0.893749 0.0486255 0.994193 0.0959972 0.0188562 0.99742 0.0692688 0.206829 0.779087 0.591815 0.000219309 0.982713 0.185134 0.674738 0.650778 0.348162 0.675072 0.649708 0.349511 0 0.999416 0.0341858 1.48542e-08 0.999416 0.0341859 0 0.999416 0.0341858 -1.62601e-06 0.999416 0.034186 0.000297126 0.902671 0.430332 0.00124599 0.908691 0.417467 0.000764778 0.910428 0.413668 4.43206e-05 0.981548 0.191218 0.000295239 -9.29157e-08 -1 3.11813e-07 0.000349848 -1 0.000322781 0.783488 0.621407 -0.0026013 0.999331 0.0364769 -0.00622869 0.999196 0.0395948 0 -9.29157e-08 -1 0 -9.29157e-08 -1 3.03935e-06 0.999416 0.034186 0 0.999416 0.0341857 0.0057388 0.999498 0.0311561 0.00214958 0.889756 0.456432 0 0.889257 0.457408 -0.0467904 0 0.998905 0.000403562 0.889606 0.456728 0 0.88852 0.458839 0 6.54988e-06 1 1.00008e-07 0 1 -3.25798e-05 0.998044 0.0625189 8.28911e-07 0.998029 0.0627492 0.0793287 0.989523 0.120629 0.0223645 0.999735 -0.00549493 0 0.999999 0.00155477 -0.00031478 1 -1.28818e-05 0 0 -1 0.409543 -0.0487053 -0.91099 -0.760434 -0.621996 -0.186711 -0.759265 -0.623719 -0.185718 -0.758263 -0.624816 -0.186126 0.000554769 0.783837 0.620966 0 -0.999775 -0.0212265 0 -0.999871 -0.0160526 -6.20209e-07 -0.998029 -0.0627519 -0.0240911 -0.99689 -0.0750343 -0.295045 -0.905874 -0.303877 -4.28247e-07 -0.998029 -0.0627525 3.42562e-07 -0.998029 -0.0627555 -0.939027 0.306403 0.15603 -0.038989 0.991088 0.127372 0.194376 0.0302435 0.980461 -0.00805649 0.0892837 0.995974 -0.841035 0.502638 -0.200037 -0.631466 0.771781 0.0748618 0.971117 0 -0.238602 0.972087 0.00648347 -0.234533 0.967075 -0.0107119 -0.254265 0.971117 -2.80883e-06 -0.238606 0.971117 -1.37149e-05 -0.238602 0.971118 -4.4283e-05 -0.238601 0.111796 0.992951 0.0393795 0.202858 0.516578 0.831863 -0.0568235 0.232968 0.970823 -0.69801 0.713368 -0.062349 0 1 0 0 1 0 -0.505666 0.861547 -0.0451617 0.308616 0.920594 -0.239298 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.999968 0.0080247 0.000691284 1 -0.000683827 -0.731729 -0.678773 0.0619628 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.23561 -0.78646 -0.570937 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.172117 -0.890212 -0.421781 -0.621644 -0.712275 -0.32592 -0.505198 -0.811718 -0.293068 -0.162079 -0.978859 -0.124762 0.0609066 -0.981614 -0.180897 0.111575 -0.929147 -0.352473 0.0538029 -0.8544 -0.516823 -0.000969864 -0.860822 -0.508906 1.46269e-05 -0.877234 -0.480064 1.51742e-05 -0.940271 -0.340428 0.0213618 -0.816275 -0.577269 0.00324451 -0.984044 -0.177897 3.37437e-07 -0.964714 -0.263301 0.7585 0.623147 0.190698 0.759839 0.622033 0.188994 -0.000972658 0.998675 0.0514479 -2.17079e-07 0.999416 0.0341867 -1.40216e-06 0.999415 0.0341959 0.158513 0.750381 0.641718 0.652802 0.712892 0.256193 0.0157336 0.790801 0.611871 0.517171 0.842613 0.150127 0.855252 0.491967 0.162828 0.970915 0.00283771 0.239406 0.969439 -0.00899299 0.245169 0.966788 0.0227226 0.254566 0.00317613 0.999913 0.0128135 -0.00845215 0.981691 0.190295 -0.644375 0.653455 0.397212 0.341638 0.837759 0.425962 0 9.6827e-05 -1 4.81304e-05 -9.28713e-08 -1 0.00217712 0.990355 0.138537 -0.00384447 0.943137 0.332382 0.652804 0.645042 0.3972 0.341545 0.809508 0.477539 0.496134 0.832973 0.244964 0.00512678 0.997166 0.0750591 0.676776 0.705382 0.210737 0.679152 0.702213 0.213657 0.683622 0.697984 0.213259 -0.0997395 -0.0565927 0.993403 0.0940594 0.990314 0.102133 0.245818 0.960473 0.13063 0.557543 0.767444 0.316505 0.654386 0.6791 0.332568 0.00197226 0.727483 0.686123 0.00163723 0.72737 0.686244 7.31351e-10 4.50624e-08 1 0 6.20935e-08 1 0.000668686 0.000406757 1 0 9.86685e-08 1 0.982945 0.183326 0.0144918 0.0444183 0.80285 0.594525 0.978155 0.206945 -0.0196796 0 5.6392e-05 1 0 5.6392e-05 1 0 -0.850746 0.525577 0 -0.850746 0.525577 -0.559582 -0.511345 0.652223 -0.559579 -0.511378 0.652199 -0.559611 -0.511291 0.65224 -0.0277836 0.532596 0.845914 0.758688 -0.62421 -0.186427 0.758651 -0.624262 -0.1864 0.75865 -0.624264 -0.186399 0.758651 -0.624263 -0.186399 0.75861 -0.624324 -0.186361 0.000780614 -0.979887 -0.19955 -0.000190229 -0.966144 -0.258003 0.00100217 -0.90624 -0.422762 0 -0.926383 -0.376584 -0.670743 -0.653647 -0.350498 -0.671022 -0.653674 -0.349916 -0.670966 -0.653873 -0.349651 -0.670816 -0.654707 -0.348375 -0.00145963 -0.783796 -0.621016 -3.70771e-08 -0.783503 -0.621388 0.00277352 -0.784537 -0.620075 3.68723e-06 -0.783488 -0.621407 0.000642899 -0.795515 -0.605934 -0.616928 -0.740008 -0.267932 -0.681555 -0.700543 -0.211478 -0.68159 -0.700498 -0.211512 -0.68159 -0.700498 -0.211513 -0.107779 0.719601 0.685972 -0.0371819 0.999059 0.0223365 0.461491 0.863866 0.201893 -0.00235056 0.879257 0.476343 -0.0827329 0.880371 0.467014 -5.21551e-05 1 0 0 1 0 -0.000906301 0.999963 0.00851923 0.22201 0.960707 0.166595 0 1 0 0 1 0 0.232448 0.972609 0 0 1 3.86676e-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 0.99985 -0.0173428 0 1 0 -3.30137e-05 1 -0.000310329 -0.0351969 0.999101 0.0236153 -0.0537417 0.998555 -0.000505975 0 1 0 0 1 0 0 0.999999 -0.00124819 -3.91631e-05 1 1.71139e-05 0 1 0 0 1 0 0 1 0 -4.34073e-07 1 4.34072e-07 0 1 -1.49013e-05 0 1 -1.49013e-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.000606017 -0.999505 -0.0314691 -3.61288e-05 -0.999421 -0.0340304 2.14241e-05 -0.999412 -0.0342774 4.27437e-07 -0.999416 -0.0341817 -1.95978e-09 -0.999416 -0.0341857 -8.92282e-05 -0.99942 -0.0340424 -0.00020121 -0.999379 -0.0352424 3.16038e-05 -0.99939 -0.0349266 1.45209e-08 -0.999416 -0.0341856 0 -0.999416 -0.0341857 -1.50087e-05 -0.999415 -0.0341939 -4.85902e-07 -0.999416 -0.0341851 1.10762e-05 -0.999416 -0.034183 3.41581e-05 -0.999416 -0.0341766 1.12241e-07 -0.999416 -0.0341848 -7.74389e-06 -0.999412 -0.0342845 0.000464488 -0.999409 -0.0343851 0.00143837 -0.999428 -0.0337802 0.559605 -0.511286 0.652249 0.559582 -0.511338 0.652228 0.559581 -0.511346 0.652223 -0.00673439 0.0548754 0.998471 -0.937397 0.251251 -0.241163 -0.971097 0.000187612 -0.238686 -0.968139 0.0241865 -0.249241 -0.971162 -0.000552669 -0.238421 -0.97115 0.000288611 -0.238471 -0.971091 0.000239349 -0.238709 -0.00814177 0.994184 0.107386 0.000146349 1 -0.000644291 0 1 0 0 1 0 0 1 0 -0.000105212 1 -0.000808384 -0.622133 -0.716649 -0.315222 -0.626691 -0.715292 -0.309218 -0.165401 -0.801711 -0.57437 -0.180872 -0.804729 -0.565417 0.00141915 0.723919 0.689883 -0.000546311 0.73426 0.678869 0.00908658 0.729693 0.683715 0.168386 0.98553 -0.0194251 -0.000184192 0.994223 -0.107334 -3.05755e-06 0.999976 -0.00698064 0.17973 0.956885 -0.228183 0.126808 0.837199 0.531993 -0.397579 -0.12261 0.909339 0.915332 -0.201558 0.348628 -0.100752 -0.605956 0.789092 0.995726 0.0386987 -0.0838599 0.409167 -0.0318097 -0.911905 0.0886883 0.0100218 -0.996009 0.464451 -0.011746 0.885521 -1 -0.00026488 -1.27745e-06 -0.947704 0.308454 -0.0819388 1 0 0 0.999529 -0.0285738 -0.0112026 0.949109 0.0895676 -0.301942 -1 0 0 -1 0 0 -1 7.76447e-06 -1.4964e-05 -0.996529 0.024356 -0.0796 0.99784 0.0189021 -0.0629095 1 0 -2.2077e-06 0.999997 -0.00112755 -0.00193414 1 3.16409e-06 -1.10478e-06 1 9.91101e-07 3.39016e-08 -1 0 0 -1 0 0 1 -0.000173333 0.000167558 1 0 0 -1 -9.49902e-05 0 -1 -8.37271e-12 -9.01108e-05 0 0 1 2.71295e-07 1.33271e-06 1 0 0 -1 0 0 -1 1.56065e-09 -0.00189632 0.999998 -8.22988e-07 1 0.000141593 1.51673e-05 1 -3.72658e-06 -2.43129e-06 -0.000575553 -1 0.0304565 0.825078 0.564197 0.158324 0.887872 0.431991 0.261074 0.806795 0.530021 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 3.73484e-06 -5.71799e-06 1 0 2.2782e-06 1 -2.30656e-06 0 -1 5.35751e-06 -1.84629e-07 -1 0 0 -1 6.82156e-06 -1.58325e-06 0.999834 0.0142804 0.0113262 1 0.000718335 -0.000694403 1 0 0 -0.610567 0.79103 -0.0384592 -1 0 0 -1 0 0 1 8.33878e-09 -7.12853e-09 1 2.32289e-08 0 -1 -2.32289e-08 0 -1 -2.50163e-08 -8.55704e-10 1 1.87629e-08 6.37784e-06 1 -6.62811e-06 0 1 1.75976e-06 -8.78083e-06 -1 -8.3799e-09 -5.5065e-07 -1 -1.87629e-08 0 -1 -7.37742e-07 1.66871e-07 -0.0988923 -0.832753 -0.544741 0.0988923 0.832753 0.544741 0.776094 -0.383251 -0.500796 0.475968 0.87308 0.10576 0.654548 0.756004 -0.00499972 -0.0174523 0.175772 0.984276 0.078602 0.178317 -0.980829 0.0217401 0.0491505 -0.998555 -0.00508818 0 -0.999987 0 0.00491891 -0.999988 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.00119599 -0.0066389 0.999977 -0.00439153 0 0.99999 -0.00075047 -0.00335791 0.999994 0 0 1 0 0 1 0 0 1 0 0 1 2.91389e-05 0 -1 -5.21795e-05 0.000391346 -1 0 0 -1 2.90879e-05 0 -1 -0.000774781 -0.00371511 -0.999993 0 0 -1 0 0 -1 -9.87e-06 -0.000229573 -1 7.54939e-06 0.000304312 -1 -7.50861e-05 -0.000440041 1 0.764889 -0.356264 -0.536676 -0.86447 0.208562 -0.457376 -0.0124391 -0.0630449 -0.997933 -0.651812 -0.61382 -0.445384 0.762151 -0.496895 -0.414995 0.525459 -0.848267 0.0658438 0.902714 0.428746 0.0358472 0.823853 -0.500462 0.26609 0.899827 0.434597 0.037907 -0.267945 -0.96336 0.0119777 0.307588 -0.46943 0.827663 0.0671534 0.0582979 0.996038 0.364551 0.542321 0.756961 0.350722 0.739619 0.57442 -0.0952372 -0.995053 -0.0282652 -0.0057589 -0.295458 0.955338 -0.468892 -0.742658 0.478121 -0.169807 -0.102037 0.980181 -0.6907 -0.42052 0.588299 -0.508211 -0.461681 0.72703 -0.545998 -0.479651 0.686892 -0.467922 -0.864901 0.181648 0.264644 0.390671 0.881669 0.212563 0.938861 0.270846 -0.635075 -0.770275 0.0579243 0.822294 -0.565105 -0.0669974 -0.0627692 -0.40389 0.912652 0.0681101 0.139788 -0.987836 0.999653 0.00854527 0.0249106 -0.257911 -0.95399 0.152923 -0.562863 -0.811493 0.157047 -0.555326 -0.814279 0.169006 0.501802 -0.617076 0.606146 0.92379 0.252431 0.287908 -0.575384 0.800695 0.166797 0.0959695 -0.846278 -0.524027 -0.0879544 -0.519624 -0.849856 -0.123818 -0.991065 0.0495982 -0.143814 0.0906686 -0.985442 -0.263112 0.963802 0.04311 -0.155196 0.638467 -0.753839 -0.153276 0.634002 -0.757989 -0.0877819 0.995991 0.0171878 -0.0881476 -0.486597 -0.869168 0.431657 -0.653913 -0.621345 0.306103 0.0566583 0.950311 -0.386924 0.82648 -0.408926 -0.307523 0.0812948 -0.948062 -0.647754 0.7357 -0.19789 -0.730327 0.491312 -0.47459 -0.636983 0.28385 -0.716716 -0.37716 0.0967734 -0.921078 0.998412 -0.00667386 0.0559386 0.94781 0.00202038 0.318829 0.661613 0.000348465 0.749846 0.513612 0.00942768 0.857971 0.173525 0.00228167 0.984827 -0.129523 0.00710982 0.991551 -0.310223 -0.000587479 0.950664 -0.667714 -0.00142459 0.744417 -0.831625 0.00874152 0.555269 -0.946786 -0.00247164 0.321853 -0.385801 0.5107 -0.768338 -0.233785 -0.153663 -0.960069 -0.257715 -0.0967387 -0.961366 -0.173189 -0.366102 -0.914317 -0.029839 -0.650413 -0.758995 -0.334874 0.279618 -0.899819 0.377658 -0.78157 0.496511 0.378099 -0.776966 0.503354 0.319829 -0.936297 0.14511 0.288586 -0.957234 -0.0205308 -0.375401 0.789031 -0.486317 0.0801306 -0.824475 -0.560197 0.378766 0.756635 0.532953 -0.382127 -0.480065 -0.789631 -0.339432 -0.290837 -0.894539 -0.219086 0.232208 -0.947671 0.0631661 0.790191 -0.609597 -0.222792 0.223386 -0.948927 -0.0883579 0.520173 -0.849478 -0.0146631 0.689092 -0.724526 -0.24691 0.109692 -0.96281 -0.312825 -0.0712689 -0.947133 -0.365851 -0.59371 -0.716702 0.191035 0.937692 -0.29024 0.369779 0.699161 0.611913 0.323803 0.929996 0.173949 0.376661 0.771714 0.51243 0.891284 0.339121 0.301013 0.342705 0.730799 0.590327 -0.559054 0.807489 0.188202 -0.717069 0.691162 -0.0900448 0.000331907 0.999875 0.0157817 0.162889 0.212182 0.963559 -0.00331402 0.983711 0.179726 0.000304014 0.818093 0.575086 0.00120021 0.533197 0.845991 -0.00266176 -0.0140339 0.999898 0.00110548 -0.0899383 0.995947 0.00101424 -0.574362 0.818601 0.00370824 -0.642338 0.766413 -0.000301941 -0.840442 0.541902 0.155141 -0.216751 0.963821 0.00252935 -0.999975 -0.00665758 -0.000248627 -0.979064 0.203552 0.00276237 -0.920422 0.390917 0.000787191 0.999827 0.0186021 0.15678 0.233543 0.959624 -0.00163659 0.860229 0.509905 -0.00121937 0.493426 0.869787 0.00272061 -0.159409 0.987209 0.00238503 -0.82314 0.567833 0.00282485 -0.828102 0.56057 0.161598 -0.198107 0.966768 0.00258675 -0.999992 -0.00293656 -0.000782673 -0.985841 0.167682 0.000469784 -0.520667 -0.85376 0.00101248 -0.636776 -0.771048 0.00174421 -0.838497 -0.544904 0.00248936 -0.825848 -0.563887 -0.0011797 -0.97501 -0.222156 -0.000924928 -0.971986 -0.235036 0.00090398 0.0216865 -0.999764 -0.00058973 -0.0169762 -0.999856 -7.48476e-05 -0.508552 -0.861031 0.000869313 0.463869 -0.885903 -0.000797842 0.511 -0.85958 -0.00111409 0.823529 -0.567273 -0.000312385 0.838476 -0.544938 -0.00311228 0.993211 -0.116282 -0.000170475 -0.986025 -0.1666 0.00166904 -0.840313 -0.542099 0.000430863 -0.481628 -0.876376 0.000882789 -0.670378 -0.742019 0.00111119 -0.829911 -0.557895 -0.00154446 -0.99987 -0.0160234 -0.00315483 0.0687565 -0.997629 0.00126575 -0.497293 -0.867582 0.00436345 0.306102 -0.951989 -0.00193552 0.505278 -0.862954 -0.00113203 0.837574 -0.546323 -0.00077604 0.832036 -0.554722 -0.00309569 0.982876 -0.184243 0.0311697 -0.00264861 0.999511 -0.000914282 0.00147877 -0.999999 -0.113878 0.982283 -0.148834 0.0147023 -0.0516197 0.998559 -0.000847069 -0.00140522 -0.999999 0.000321987 -0.000101147 -1 -0.112119 0.921245 -0.372475 -0.0634091 -0.933038 -0.354146 -0.917441 -0.093159 -0.386811 -0.414121 -0.648571 -0.638639 -0.199533 -0.831634 -0.518238 0.946613 0.277322 0.164364 0.718809 -0.687957 0.100148 -0.350566 -0.890936 -0.288681 -0.373182 -0.838148 -0.397797 -0.329221 -0.918913 -0.217287 0.378274 0.537262 0.753829 -0.206207 -0.947882 0.242894 -0.210974 -0.949768 0.231151 -0.0909892 -0.843671 0.529094 -0.0491964 -0.783663 0.619235 0.0719384 -0.574544 0.815306 0.141497 -0.409065 0.901468 0.285416 -0.00369465 0.958396 0.320603 0.159281 0.933726 0.377312 0.520126 0.766227 -0.348449 0.89927 -0.264379 -0.373992 0.680625 -0.629983 -0.340043 0.910272 -0.23617 0.374251 -0.474354 0.796821 -0.222884 0.954047 0.200293 -0.207315 0.946006 0.249187 -0.064117 0.805044 0.58974 -0.022311 0.738102 0.67432 0.0972415 0.520683 0.848194 0.270813 0.0305848 0.962146 0.257796 0.0848584 0.962466 0.374702 -0.477732 0.794588 -0.156051 -0.186726 -0.969939 -0.33247 0.0281135 -0.942695 0.859345 0.010529 -0.511288 0.639429 -0.00158353 -0.768848 0.342942 0.0043923 -0.939346 0.238325 0.000408334 -0.971185 -0.350966 -0.0016093 -0.936387 -0.523732 -0.0106089 -0.851817 -0.741955 -0.000446969 -0.67045 -0.960868 -0.00180074 -0.277 -0.95473 -0.000732809 -0.297473 0.91519 0.0259167 -0.402189 0.898033 0.313737 -0.308393 -0.54636 0.620297 0.562782 -0.532214 0.493674 0.687776 0.204815 -0.938194 0.279002 -0.315223 0.34127 0.885533 -0.620208 0.769359 0.153064 -0.59364 -0.657728 -0.463666 0.0161237 0.946642 -0.321883 -0.806612 -0.397841 0.437149 -0.861519 -0.410515 -0.298767 -0.766039 -0.445878 -0.463009 0.998315 -0.0200407 -0.0544575 0.718358 0.569937 0.398915 0.573058 0.0588021 -0.817403 -0.523868 -0.807248 -0.271869 0.16334 0.912825 -0.374259 -0.0451683 0.555341 -0.830395 0.04297 0.823648 -0.56547 -0.0243911 0.99175 -0.125847 -0.101734 -0.648533 -0.754357 -0.17827 0.120543 -0.97657 -0.373571 0.75184 -0.543306 -0.00373397 -0.014648 -0.999886 0.0907615 -0.0645006 -0.993782 -0.84838 -0.505425 -0.157471 -0.565218 -0.807831 0.167145 -0.0741815 0.917064 -0.39178 -0.624444 0.399015 -0.671459 -0.90052 0.0745388 -0.428379 0.994379 0.0151852 -0.104782 0.10327 -0.259844 0.960113 0.0628636 0.0782026 -0.994954 0.00313585 0.0291227 -0.999571 -0.997583 0.033549 -0.0608504 -0.786731 0.511223 0.345985 0.0857558 0.992021 0.0924109 0.936929 0.177532 0.301075 -0.0681101 -0.139788 0.987836 -0.108444 -0.993062 -0.045479 -0.175313 0.967344 -0.183061 -0.666268 -0.0421283 0.744521 0.393739 0.063007 0.91706 0.735182 -0.0407409 0.676644 0.00870475 0.684181 0.72926 0.751667 -0.0583005 0.656962 0.734898 -0.0605003 0.675474 0.00922323 0.698257 0.715788 0.617975 0.0333097 0.785492 0.997635 0.0160225 -0.0668367 0.999996 -0.0022712 -0.00171538 -0.0927905 0.948661 -0.302379 0.999969 0.001285 -0.00770784 -0.234844 0.926542 -0.293884 0.999958 0.00500472 -0.00769119 0.421042 -0.322934 -0.847607 0.999219 -0.0127052 -0.0374091 0.290704 0.00826348 0.956777 0.291927 0.00174756 0.956439 -0.399639 -0.541469 -0.739662 -0.184203 -0.569646 -0.800982 -0.191321 0.978074 0.0822612 -0.822294 0.565105 0.0669974 0.635075 0.770275 -0.0579243 -0.099734 -0.86442 -0.492779 -0.0299233 -0.833867 -0.551154 0.330868 0.324879 -0.885991 -0.174171 0.876472 -0.448844 -0.00172038 -0.984494 -0.175411 0.993574 -0.00290779 -0.113151 0.869404 -0.493754 0.0185648 0.782378 0.607331 -0.137963 0.664702 0.166849 0.728239 0.886608 -0.456395 0.075031 0.264085 -0.404357 0.875645 -0.545186 -0.0887345 0.833605 0.673187 0.652787 0.347402 -0.82778 -0.317677 0.462451 0.104057 -0.945322 0.309094 -0.129987 -0.897802 0.420778 0.155854 -0.623078 0.766474 -0.0905854 -0.54361 0.834436 0.0242562 0.00718652 0.99968 -0.105142 -0.0337696 0.993884 0.162855 0.412489 0.896287 -0.26645 0.630509 0.729015 0.118212 0.786002 0.606817 0.0379164 0.966854 0.252497 -0.196486 0.970988 0.136294 0.994558 -0.100167 0.028642 0.923231 -0.335809 0.186751 0.0445777 0.970068 0.238706 -0.144152 0.907776 0.393908 0.0439784 0.832739 0.551917 0.00511482 -0.89983 -0.43621 -0.0251486 -0.905668 -0.423242 0.0650942 -0.633288 -0.771174 -0.157952 -0.514224 -0.842986 0.149373 -0.1928 -0.969802 -0.110356 0.0984216 -0.989007 0.0212279 0.199847 -0.979597 -0.025262 0.53575 -0.843999 -0.0167212 0.54027 -0.841326 0.0584892 0.807198 -0.587376 -0.109958 0.865563 -0.48858 0.0381188 0.994971 -0.0926288 -0.0193133 0.992454 -0.121084 -0.0168935 -0.916871 -0.398825 0.139866 -0.937025 -0.320034 0.076596 -0.601657 -0.795073 0.0271387 -0.652169 -0.757588 0.123908 -0.985009 0.120014 0.104678 -0.607675 0.787257 0.0315057 -0.54994 0.83461 0.123713 0.138162 0.982653 0.0832359 0.804409 0.588217 -0.0728657 0.884262 0.461271 -0.00740138 -0.967587 0.252428 0.072795 -0.885603 0.458703 -0.0145124 -0.846072 0.532871 0.0388172 -0.275291 0.960577 0.00501931 -0.250398 0.96813 -0.00343099 0.252206 0.967667 0.0491524 0.485737 0.872722 -0.0341457 0.550723 0.833989 0.072477 0.960386 0.269084 -0.666072 -0.212143 0.715083 0.845496 0.325924 0.422978 -0.46273 -0.686801 -0.560522 -0.241069 -0.943531 -0.227235 -0.237139 -0.910293 -0.339311 0.0278206 -0.998209 0.0529628 -0.0372118 -0.991789 0.122354 0.0206167 -0.95291 0.302553 0.30139 -0.845948 0.439927 -0.669385 -0.67353 0.313497 0.0231909 -0.927367 0.373434 0.0160558 -0.901279 0.432941 0.0517013 -0.727309 0.68436 -0.0823086 -0.606873 0.790525 0.0827776 -0.500569 0.86173 0.0179206 -0.399048 0.916755 0.0194043 -0.152826 0.988063 -0.00389127 -0.134057 0.990966 -0.0203331 0.143894 0.989384 0.171317 0.246063 0.953993 0.0201544 0.541215 0.840643 -0.599658 -0.113844 0.792117 0.0167331 0.544529 0.838575 0.0615684 0.768355 0.637056 0.00324851 0.699026 0.715089 -0.00498235 0.63446 0.77294 0.0152469 0.976521 0.214882 -0.0543253 0.994465 0.0899337 -0.0458843 0.979066 -0.198303 0.129882 0.881735 -0.453513 -0.00370091 0.859363 -0.511353 0.0409198 0.366199 -0.929637 0.0578981 -0.51896 -0.852836 0.12943 -0.945475 -0.298875 -0.0394039 -0.97892 -0.200409 -0.035998 -0.625021 -0.779778 0.0264099 -0.721487 -0.691924 -0.0216418 -0.83723 -0.546422 -0.000174846 -0.825322 -0.564662 0.00228799 0.142889 -0.989736 0.008471 -0.147195 -0.989071 0.00104392 -0.153701 -0.988117 -0.034081 0.820942 -0.569994 0.0330377 0.749153 -0.661573 0.0108778 0.632758 -0.774273 -0.0286017 0.601766 -0.79816 0.0653874 0.995202 -0.072785 -0.766994 -0.634333 -0.0966492 -0.0179206 0.399048 -0.916755 -0.492053 0.819917 0.29261 0.83506 0.543009 -0.088415 -0.284419 0.794563 -0.536447 0.155499 0.604578 -0.781221 0.0158012 0.493031 -0.869868 -0.0965404 -0.00193942 -0.995327 0.468559 -0.695681 -0.5445 -0.0260196 -0.88577 -0.463395 0.00828971 -0.868753 -0.495177 0.0212655 0.976781 -0.213184 0.0554724 0.886851 -0.458714 0.0618708 0.888858 -0.453987 0.0533149 0.26555 -0.962622 0.019399 0.244583 -0.969434 0.0147406 -0.257762 -0.966096 0.0257687 -0.263933 -0.964197 0.0347158 -0.520738 -0.85301 0.241896 -0.312465 -0.918614 0.0611388 -0.959401 -0.27534 0.00279501 -0.974653 -0.223703 0.99985 0.000204459 -0.0172947 0.288297 -0.171471 0.942063 0.669385 0.67353 -0.313497 0.999344 0.0191747 0.0307093 0.998422 0.0420814 -0.0371847 0.996981 0.0767349 0.0118685 0.969093 0.168314 0.180357 0.994259 -0.105173 0.0196897 0.4051 -0.0496513 -0.912923 0.999458 0.0323845 0.00586579 0.999757 -0.0190178 0.0111319 0.999843 0.00169244 -0.0176417 0.120108 -0.374283 0.919504 0.154736 0.375511 0.91381 -0.0467709 -0.986688 -0.155751 0.122796 -0.915134 -0.383992 -0.0651158 0.738782 -0.670791 0.00655355 0.981927 0.189148 -0.665278 0.485756 -0.566963 0.00774422 0.577195 -0.81657 0.300176 0.572922 0.762663 0.392059 0.700521 0.596288 0.610375 0.735734 0.293493 0.0313812 -0.460641 0.887031 0.224637 0.894988 0.385402 0.0256412 -0.828418 0.559524 0.148956 -0.879703 0.451591 0.0106025 -0.348852 -0.937118 -0.742156 -0.660856 0.111692 -0.890968 -0.388274 0.235414 -1 0.000483486 0.000257197 -0.898277 0.220283 -0.380228 -1 -5.49652e-06 1.11328e-06 -0.998758 -0.0415899 -0.0274537 -1 -5.64678e-06 1.07858e-06 -1 0.000182295 -3.48198e-05 -1 -1.45821e-05 9.79134e-07 -1 -6.68327e-06 1.04074e-05 -1 0 0 -1 6.22642e-07 6.58558e-06 -1 1.47071e-07 8.32613e-06 -1 -1.66989e-05 -4.21253e-06 -1 5.12207e-06 2.7309e-07 -0.690887 0.249891 -0.678402 -1 -3.65518e-05 7.97089e-05 -1 -2.71405e-05 3.59364e-05 -1 -4.94031e-05 -5.24634e-05 -1 -3.08472e-05 -0.000142225 -1 -2.97119e-05 -0.000149454 -1 0.000127975 -8.78275e-05 -1 5.43661e-06 6.62034e-06 -1 -1.06531e-05 -1.49411e-05 -1 4.72479e-05 2.05305e-05 -1 5.48192e-05 3.45763e-05 -0.999148 -0.0412513 0.00160351 -1 6.14061e-06 -1.28744e-05 -0.99989 -0.00541562 -0.0138047 -0.551332 -0.694712 -0.461962 -0.999989 -0.00328067 0.00330563 0.0196853 -0.996152 0.0854077 -0.0593523 -0.997455 0.039504 -0.960789 -0.266319 0.0771899 -0.674196 -0.608637 0.418355 -0.960575 0.150237 0.233932 -0.929568 0.36865 0.000510748 -0.620744 0.764013 -0.175957 -0.230322 0.730894 -0.642453 0.996968 0.0748541 -0.0212749 -0.907881 0.261466 -0.327701 0.873401 0.0381999 -0.485501 -0.980212 -0.0778913 -0.181983 -0.802059 -0.582144 -0.133454 0.999025 0.0415245 0.0149817 0.988015 0.086223 -0.128029 0.999211 -0.0117702 -0.0379316 0.996102 -0.0869937 -0.0145889 0.961679 0.272839 0.027072 0.919625 0.246591 0.305748 0.872358 0.31436 0.374392 0.915001 -0.0905158 0.393166 0.99472 -0.00497541 0.102507 0.944122 -0.209876 0.254136 0.997168 -0.0705924 0.0259481 0.995924 0.0506545 -0.0746359 -0.519445 0.22972 -0.823046 0.999707 0.0136499 -0.0199686 0.452682 -0.822036 -0.345449 0.758622 0.000326771 0.651531 0.976998 -0.160564 -0.140333 0.994399 -0.0553831 -0.0900239 0.993995 0.108499 0.0141975 0.998083 0.0406234 0.0467011 -0.126515 0.878404 -0.460869 0.124591 0.983806 -0.128854 0.0869741 0.9646 -0.248962 0.0736107 0.818698 -0.569487 0.0640294 0.475983 -0.877121 -0.0580442 0.531418 -0.845119 0.0933498 0.0590182 -0.993883 -0.0449212 0.136722 -0.98959 0.0102362 -0.422456 -0.906326 -0.09844 -0.38074 -0.919427 0.13957 -0.745569 -0.65165 -0.0711054 -0.994595 -0.0756609 -0.149926 -0.854743 -0.496927 0.999993 0.000491981 -0.00379006 0.999996 -3.62867e-05 -0.00290994 0.999999 0.000912219 -0.00111628 0.999472 0.0250689 -0.0206651 0.99959 0.0252139 -0.0135535 0.999926 -0.0108197 -0.00560212 0.999551 0.0277087 0.0114497 0.999256 0.038202 0.00520573 0.999893 0.00266726 -0.0143527 0.998688 0.00539886 0.0509163 0.994702 0.06723 0.0777694 0.998487 0.0419872 -0.0354954 0.999871 -0.0102753 0.0123335 0.999083 0.000320611 0.0428195 0.999398 0.00821361 0.0336972 0.999996 -0.0014733 0.00223942 0.999128 -0.031897 0.026932 0.99924 -0.035279 0.016566 0.999885 0.0138049 0.00633932 0.999869 -0.0156017 -0.00438591 0.994043 -0.103162 0.0351452 0.981329 -0.186764 -0.045961 0.994083 -0.0713507 -0.081898 0.998054 -0.0411027 -0.0468954 0.997695 -0.0517249 -0.0439212 0.999999 -0.000448245 -0.00108569 0.999991 -0.000314279 -0.00433423 -0.661428 0.323129 0.676831 -1 3.85826e-05 0.000941163 -1 0.000537427 -0.000459231 -1 3.11891e-05 -8.3871e-05 -1 1.84288e-05 -0.000264973 -1 3.9918e-06 -0.000212285 -1 -4.06352e-05 0.000446363 -1 1.57111e-06 0.000197269 -0.999908 -0.00305048 0.0132362 -0.715493 -0.282332 0.639029 -1 -9.67211e-05 9.4536e-05 -1 -3.073e-05 -0.000444751 0.0363042 0.5263 0.849523 -0.126686 0.376877 0.917559 0.080865 0.150934 0.985231 -0.0896402 -0.048349 0.9948 0.12386 -0.273527 0.953856 -0.16842 -0.551105 0.817262 0.05272 -0.678242 0.732945 -0.999962 0.00827645 -0.00290566 -0.999972 0.00699707 -0.00285495 -0.906398 -0.380903 0.182637 -0.999987 0.000264499 -0.00511395 -0.999816 -0.0162287 -0.0102603 -0.999495 -0.0150251 -0.0280041 -0.999893 0.000698084 -0.0146432 -0.999954 0.00222417 -0.00928524 -0.999837 0.0104688 -0.0147175 -0.999883 0.0100431 0.0115073 -0.999988 0.00250287 0.00410745 -0.999996 0.00249317 0.0014881 -0.999993 0.00316735 0.00213437 -0.999958 0.00905106 -0.00154097 -0.999954 -0.00771277 -0.00567827 -0.999981 -0.00516649 0.00347566 -0.999999 -0.000373602 0.00108146 -1 0.000614032 -0.000320425 -0.999951 -0.00968735 -0.00206362 -0.999547 -0.0161351 0.0254215 -0.999002 -0.00443131 0.044456 0.963874 0.0328008 -0.26433 0.479712 0.286149 -0.829455 0.126027 0.731074 -0.670558 0.382762 0.901521 -0.201873 0.872493 0.454637 0.179055 0.343769 0.832976 0.43356 0.326346 0.324029 0.887977 0.95309 -0.223168 0.204488 0.436391 -0.89917 0.0325123 0.214799 -0.893783 -0.393717 0.964712 -0.206308 -0.163609 -0.764755 0.0842411 -0.63879 0.30281 -0.114053 -0.946202 0.0374019 -0.536234 -0.84324 -0.474856 -0.530721 -0.702031 0.213222 -0.894045 -0.39398 0.0084332 0.645776 -0.763481 0.0119928 -0.792853 0.609295 -0.586959 -0.0138121 0.809498 0.0110069 0.637794 0.770129 0.539035 0.472968 0.696952 0.649601 0.680167 0.339693 0.31896 -0.695648 -0.643692 0.691417 -0.0101614 0.722385 0.644815 -0.668534 -0.370509 0.625319 0.72846 -0.279861 0.639116 0.744299 -0.193775 0.914614 0.352866 -0.197398 -0.888206 0.315572 0.333923 -0.705141 0.700214 0.1117 -0.782378 -0.607331 0.137963 0.999337 0.0334439 -0.0143669 0.938226 -0.344765 -0.029478 0.991036 -0.0204238 0.132025 0.386112 0.384285 -0.838596 0.855544 0.381513 0.34999 0.416357 0.5682 0.709785 0.993361 0.0683535 -0.0925298 0.997844 -0.0566656 -0.0331124 0.997199 -0.0145921 0.0733639 0.998999 0.0443908 0.00553267 0.99856 0.0491368 -0.0215302 0.99807 0.000156751 -0.0621042 0.999547 0.0150187 -0.0260993 0.949414 0.313684 0.0147065 0.999763 0.0216529 -0.00223375 0.990764 -0.128297 0.0438952 0.990465 0.0819327 -0.110756 0.999959 0.00159928 0.00891537 0.986164 0.126484 0.107159 0.997316 0.0711265 -0.0173669 0.999967 0.00477113 0.00663652 0.9978 -0.0318631 0.0581379 0.997996 0.00802269 0.0627722 0.999555 -0.00294737 -0.0296929 0.999915 0.0112086 -0.00662403 0.999869 -0.00540778 0.0152904 0.999929 0.0111082 -0.0043025 0.989784 0.130621 0.0571421 0.999851 -0.0165474 0.0049603 0.999182 0.0356216 -0.0191695 0.999989 -0.00237313 0.00399153 0.997729 -0.0517179 -0.0431479 0.999953 -0.00963434 -0.000593111 0.997593 0.0152905 -0.0676423 0.99991 -0.00583492 -0.0120958 0.99991 0.0134127 0.000970183 0.996841 0.0773312 -0.0181012 0.998423 0.0439299 0.0349454 0.999798 -0.00128653 -0.0200319 0.997579 -0.0176777 -0.0672555 0.999158 -0.00142202 0.0410151 0.99972 0.0119639 0.0204107 0.999494 -0.0304404 -0.00928434 0.995842 -0.0900376 -0.0138317 0.999833 -0.00667674 -0.0170329 -0.122125 0.746861 0.65367 0.215379 -0.223837 0.950531 -0.109231 -0.993837 0.0189117 -0.511408 0.205875 -0.834312 -4.48757e-05 0.98532 -0.170715 0.00635957 0.996824 0.0793778 -0.187204 0.87534 0.445797 0.0702514 -0.740565 0.668303 -0.0442191 -0.84065 0.53977 -0.0842909 -0.807566 -0.583723 -0.105665 0.213747 0.971158 0.215689 -0.234951 0.947774 0.0425439 0.0538241 -0.997644 0.00247374 -0.0532194 -0.99858 -0.144622 0.263571 -0.953737 0.0186115 0.74368 0.668277 -0.0626192 0.663122 0.745888 -0.942299 -0.0482339 0.331279 -0.942788 -0.0739913 0.325078 -0.0301513 -0.781158 -0.623605 0.268505 0.184188 -0.945505 -0.0878303 0.931744 -0.352335 -0.0268581 0.990795 0.132681 -0.72302 -0.640732 0.258272 -0.401209 -0.244773 0.882676 -0.015058 -0.991465 0.129503 -0.996981 -0.0767349 -0.0118685 -0.0781627 -0.683979 0.725303 -0.831462 0.377891 -0.40727 -0.316417 -0.281669 -0.905838 -0.206195 0.789341 -0.578295 0.0130772 0.297847 0.954524 -0.0593214 -0.0744202 0.995461 -0.00492073 -0.00352296 0.999982 -0.999843 -0.00169244 0.0176417 -0.0141626 -0.584919 0.810968 -0.026617 -0.993869 0.107316 -0.487992 0.857905 -0.160818 0.999843 0.00169244 -0.0176417 -0.999843 -0.00169244 0.0176417 -0.918319 0.328277 0.221191 0.0162262 -0.947616 0.319 0.398334 0.903881 0.15598 0.566155 0.579731 0.585987 0.779875 0.4128 0.470522 0.652526 0.110249 0.749703 0.68027 -0.457984 0.572262 0.480677 0.0732451 0.873833 -0.612341 -0.491638 -0.619137 0.612341 0.491638 0.619137 -0.104016 0.102888 0.98924 -0.506195 -0.851698 0.135566 0.506195 0.851698 -0.135566 -0.865974 0.0828216 0.493184 0.823292 0.130832 0.552335 0.21628 -0.82949 -0.514946 -0.21628 0.82949 0.514946 0.147149 0.756149 0.637641 -0.992303 0.105291 0.0651777 0.494909 0.655181 0.570792 0.99869 -0.0400939 0.0317965 0.952787 -0.0574371 -0.298156 0.99584 0.0704541 -0.0577791 -0.997901 -0.0642157 0.00830349 0.999502 -0.0140252 -0.0282572 -0.355485 -0.921781 0.154757 0.122598 0.0405355 0.991628 -0.212751 0.22881 0.949939 -0.0328669 -0.303403 0.952295 -0.409184 -0.157634 0.898733 -0.117758 -0.0931306 0.988666 0.0912851 0.841741 0.532108 0.0861374 0.955482 0.282196 -0.336814 0.664605 0.666976 -0.57483 0.550261 0.605627 0.113967 0.437036 0.892195 0.0715907 0.308309 0.948588 0.0488811 -0.281673 0.958265 0.0924407 -0.451615 0.887411 -0.45108 -0.541865 0.709161 0.0670135 -0.708271 0.702752 -0.185747 -0.852406 0.488775 0.0818835 -0.924804 0.371528 0.082214 -0.918494 0.386794 -0.446951 -0.701849 0.554655 -0.439473 0.837416 0.324958 -0.111836 0.814466 0.569332 -0.036917 0.164668 0.985658 0.0397226 0.117605 0.992266 -0.103151 -0.614752 0.781946 0.191208 -0.973582 0.124812 -0.727239 0.543687 0.41896 -0.796659 0.0724176 0.600075 -0.749104 -0.661523 0.0350622 -0.669155 -0.734708 0.111517 -0.549658 -0.462854 0.695444 -0.592096 -0.464326 0.658653 -0.769972 0.10496 0.629386 -0.52461 0.573419 0.629266 -0.223534 -0.957588 0.181816 -0.156111 -0.731303 0.663947 -0.200809 0.276307 0.939857 -0.0471815 0.38096 0.923387 -0.00457529 0.64185 0.766816 -0.125835 0.703301 0.699667 -0.135974 0.933531 0.331708 -0.0218792 0.967333 0.252563 -0.0156595 -0.996387 0.0834763 -0.0116373 -0.995615 0.0928137 0.0112038 -0.961783 0.273582 -0.00673329 -0.92873 0.370697 0.0109273 -0.875871 0.482421 -0.016371 -0.809034 0.587534 0.0112912 -0.650966 0.759023 0.00559648 -0.661438 0.749979 -0.00778614 -0.403093 0.915126 0.0112286 -0.34584 0.938227 -0.0161669 -0.166472 0.985914 0.0196907 0.0164524 0.999671 -0.0171392 0.156889 0.987467 0.00991264 0.380614 0.924681 -0.0142234 0.339338 0.940557 0.0162911 0.561138 0.827562 -0.0196186 0.641705 0.7667 0.00834333 0.801118 0.598448 0.0118546 0.807749 0.589407 -0.0137048 0.896688 0.442452 0.0102761 0.967487 0.252713 -0.01423 0.955048 0.29611 0.410567 -0.503876 0.759963 0.538521 -0.837134 0.0959231 0.765331 -0.519495 0.379991 0.715466 0.04943 0.696896 0.576803 0.54892 0.604967 0.804082 0.572428 0.160557 0.74346 0.615671 0.261185 0.162166 -0.911649 0.377622 -0.133485 -0.827863 0.544816 0.236585 -0.266708 0.934288 -0.234002 0.109682 0.966029 0.244024 0.551851 0.797442 0.22539 0.973004 0.0496207 -0.235416 0.895804 0.376981 -0.800303 -0.560034 0.214189 -0.816967 0.48087 0.318323 -0.209865 -0.248638 0.945588 -0.401135 0.849278 0.343244 -0.591754 0.342133 0.729912 0.64491 0.271507 -0.714405 -0.285804 0.957495 0.0389813 0.306154 0.919327 0.2472 -0.297819 0.832747 0.466729 0.337264 0.622393 0.706314 -0.445012 0.334429 0.830735 -0.425431 -0.283808 0.859338 0.263449 -0.520801 0.81201 -0.27631 -0.760795 0.587234 0.189213 -0.871321 0.452767 -0.179273 -0.977213 0.113647 0.0618139 -0.997064 0.045184 0.0436399 0.988871 0.142232 0.0320583 0.989775 0.138987 0.0424666 0.734488 0.677291 -0.171436 0.673382 0.719143 0.162455 0.293706 0.94199 0.0100056 0.240935 0.97049 -0.186831 -0.131907 0.973496 0.186483 -0.324139 0.927447 -0.069232 -0.52142 0.850487 0.0855597 -0.730968 0.677027 -0.0755485 -0.792122 0.605669 0.0221513 -0.956735 0.290117 0.0358528 -0.958038 0.28439 -0.374525 0.824458 0.424264 0.380837 0.76547 0.51867 -0.24757 0.368751 0.895953 -0.0441867 0.351945 0.934977 0.247959 -0.263932 0.932124 -0.0525125 -0.309575 0.949424 -0.397704 -0.714016 0.576205 0.438418 -0.781822 0.443333 -0.569977 -0.81616 0.0949164 -0.375258 0.823397 0.425675 0.372553 0.768259 0.52056 -0.245121 0.368641 0.896671 -0.0441868 0.351945 0.934977 0.247959 -0.263932 0.932124 -0.146055 -0.318033 0.936762 -0.289681 -0.758577 0.583649 0.438416 -0.781823 0.443334 -0.569977 -0.81616 0.0949164 -0.737671 -0.64349 -0.204357 0.894929 -0.394928 -0.20769 -0.737676 -0.643485 -0.204355 0.735494 -0.61541 -0.283406 0.788616 -0.488543 0.373376 0.851705 0.499473 0.15851 0.336288 -0.793482 0.507244 -0.897524 0.271933 0.347135 -0.453209 -0.854057 -0.255319 0.953792 -0.272243 -0.127141 -0.166684 0.227425 0.959424 0.908098 0.047104 0.4161 -0.903334 -0.146303 0.403216 0.12045 0.732436 -0.670096 -0.746077 0.522165 -0.413175 0.730074 0.678242 -0.083551 -0.251799 0.966744 -0.0447529 0.50281 0.279795 -0.817861 -0.443734 0.348471 -0.825632 0.856936 -0.48162 0.183582 0.432763 0.82626 0.360569 0.91117 0.0631572 0.407162 -0.943265 0.303326 0.135072 0.131489 0.988621 -0.0730669 -0.22882 -0.940861 0.249845 -0.970303 -0.0573243 -0.235002 -0.98774 -0.112058 -0.108688 0.87041 0.26093 -0.417495 -0.844879 -0.263931 -0.465317 -0.573499 -0.487747 -0.658181 0.939103 -0.305094 0.158123 -0.94181 -0.0801143 0.32646 0.835929 0.0162132 -0.548598 0.17192 -0.265312 -0.948711 -0.933878 -0.0157667 -0.357245 0.51828 0.26731 0.812361 -0.913047 0.0177052 0.407471 0.790357 -0.14283 0.595764 0.104491 0.734321 -0.670711 -0.650667 0.597077 -0.469182 0.64178 0.761134 -0.0937787 -0.169353 0.984646 -0.0423407 0.961059 0.0168599 -0.275829 -0.352275 0.364133 -0.862154 0.899296 -0.266349 -0.34688 -0.957619 -0.283258 0.0522589 0.793236 0.190326 0.578405 -0.832798 -0.0694522 0.549203 0.102434 -0.23191 0.967329 0.104489 0.734322 -0.670711 -0.650665 0.597079 -0.469183 0.641776 0.761137 -0.0937789 -0.169351 0.984646 -0.0423408 0.962424 0.0149296 -0.27114 -0.35227 0.364134 -0.862155 0.70026 -0.272122 -0.659989 -0.957618 -0.283261 0.0522591 0.540251 -0.807199 -0.237821 -0.221231 -0.882905 -0.414169 -0.0682548 -0.71088 -0.699994 0.387167 -0.57318 -0.722196 0.0351471 -0.228814 -0.972836 0.33841 -0.164871 -0.926443 -0.211136 0.333209 -0.918909 0.564969 0.435412 -0.700875 -0.329953 0.664264 -0.670735 0.443237 0.875284 -0.193439 -0.0409837 0.988053 -0.148567 0.540251 -0.807199 -0.237821 -0.221231 -0.882905 -0.414169 0.0603776 -0.505304 -0.860827 -0.72897 -0.425552 -0.536197 0.503441 -0.151375 -0.850666 -0.525726 0.128357 -0.840914 0.565958 0.435055 -0.700299 -0.37099 0.630301 -0.681973 0.443237 0.875284 -0.193439 -0.0409837 0.988053 -0.148567 -0.0412384 -0.990225 -0.133241 0.083976 -0.980756 -0.176253 -0.0839755 -0.731691 -0.676444 0.0196116 -0.708915 -0.705022 -0.0229417 -0.376462 -0.926148 0.102444 -0.314197 -0.943814 -0.170768 0.0429217 -0.984376 0.13388 0.173499 -0.975692 0.0477672 0.569024 -0.820932 -0.178797 0.624364 -0.760396 0.158265 0.893928 -0.41934 -0.0941179 0.942194 -0.321578 0.999999 -0.00119566 0.000822882 0.999998 -0.000944944 -0.00161335 0.97786 -0.19022 -0.0872152 0.998067 -0.00397254 -0.0620239 1 -0.000117381 0.000585564 1 0.000178071 -0.000307896 1 -0.000155201 -0.000296072 1 4.6688e-05 0.000423096 0.999993 0.000337325 -0.00367548 0.999976 0.00680184 0.00101931 0.999991 0.00410586 0.000619695 0.999975 0.00495882 -0.00497335 1 -5.49111e-07 -2.93825e-05 1 6.71591e-05 -3.29398e-05 1 0.000259831 -0.000169749 0.999999 -0.00118454 0.000231505 1 -0.000137714 -5.92304e-06 1 0.000291793 -5.66643e-05 1 -3.36797e-05 5.48076e-05 1 8.37706e-05 7.06436e-05 -0.999713 -0.0075978 -0.0227182 1 8.6174e-05 -4.60749e-05 0.999969 -0.00757346 0.00198773 0.999983 -0.00576627 -0.00100505 1 1.06591e-05 1.86478e-05 1 2.72514e-05 0.000146346 1 0.000331742 -0.00021781 1 0.0002918 -0.000147124 0.999998 0.00197529 -0.000281746 0.999995 -0.00329486 0.000463996 -1 1.38727e-05 0.000117918 1 7.0186e-06 -8.46125e-05 1 7.18056e-06 0.000114757 1 -1.05639e-09 -2.48281e-05 1 2.0529e-06 1.74496e-05 1 -2.20443e-05 2.39024e-05 1 -0.000181762 -7.52094e-05 1 0.000314215 -1.71667e-05 1 0.000128279 -3.26617e-05 -0.10854 -0.894943 -0.432776 0.191446 -0.852048 -0.4872 -0.28487 -0.204936 -0.936403 0.492463 0.0820156 -0.866461 -0.477614 0.346004 -0.807568 0.252824 0.85239 -0.457725 0.970811 -0.23581 0.043809 0.348102 0.922715 0.165595 -0.736452 0.605798 -0.301077 -0.286525 0.678718 -0.6762 0.0179878 -0.585316 -0.810606 -0.635787 -0.756639 0.152554 -0.912077 0.12518 -0.390443 0.999999 -0.00145637 0.00067792 0.999999 0.00157134 2.99882e-05 0.999901 0.00439767 -0.0133935 0.999999 0.000752309 -0.00077534 -0.999673 0.0254623 0.00236171 0.999997 0.0014338 0.00183218 0.999997 -0.000713985 0.00233923 0.999858 -0.00872614 0.0143906 0.999108 -0.0257548 -0.033467 1 -0.000289495 -0.00040304 -0.24875 0.791857 -0.55775 0.231459 0.556647 -0.797854 0.0866239 -0.261813 -0.961223 -0.198346 -0.0776281 -0.977053 0.100444 -0.834538 -0.541718 -0.205393 -0.902857 -0.377706 0.560306 0.821159 -0.108424 0.778148 0.505985 -0.37211 0.653602 0.510411 -0.558824 0.613323 0.216391 -0.759611 0.765833 -0.0544791 -0.640728 0.793661 -0.555163 -0.248789 0.522886 -0.322195 -0.789165 0.527349 -0.602107 -0.599474 0.975781 0.161554 0.147484 1 6.94796e-05 -0.000111365 0.999883 -0.0148193 -0.0037828 1 0 0 0.999964 -0.00250697 -0.0081062 0.999601 -0.008363 -0.0269882 0.999977 0.00532936 -0.00416632 0.999992 0.00397948 0.000459817 -0.885049 -0.457794 -0.0843379 0.998955 0.0423002 0.0172907 -0.999205 0.0152283 0.0368356 0.999983 0.00511745 -0.002903 0.995614 0.0747384 -0.0562746 0.999925 -0.0117171 -0.00343059 0.999951 0.00190602 0.00973851 0.99895 -0.0457096 -0.00298088 0.999339 0.0292637 -0.0215544 0.991078 0.112861 -0.0708999 0.99616 -0.0277551 -0.0830337 0.995655 0.0170721 0.0915453 0.994402 -0.0381403 0.098541 0.999987 0.00490872 0.000992196 0.999988 0.00427979 0.00244488 1 0.000307371 0.000517513 0.99824 -0.038919 0.0447448 0.999438 -0.00456368 -0.0332056 0.999961 0.0077937 -0.00416801 0.999147 0.0300335 -0.0283294 0.998443 -0.02203 0.0512496 0.913752 -0.343112 0.217559 -0.999997 0.00050921 -0.0023517 -0.999998 -5.73535e-05 -0.00181019 -0.999999 0.00126264 -0.000630556 -1 0.000659866 -0.000604509 -1 8.87614e-05 -0.000286376 -1 8.7724e-05 -0.000287211 -0.999999 -0.00146357 -0.000189467 -1 -0.000358508 -0.000503156 -0.999999 -0.000818663 -0.000707018 -0.999999 -0.000848526 -0.000793313 -0.999999 -0.0017056 0.000366465 -0.999984 -0.0036162 -0.00442036 -0.999634 -0.0269426 0.0026278 0.833384 -0.55269 -0.00226652 -0.999998 -0.00203191 -9.70559e-05 -0.999999 -0.00123279 0.000549579 -1 -0.000592553 0.000525311 -1 -0.00015238 0.00028078 -1 -0.000135457 0.000314867 -0.999957 -0.0018989 -0.00913078 -0.999977 -0.00376429 -0.00557498 -0.999426 -0.0336337 -0.00401669 -0.999157 -0.0332368 -0.024081 0.0222504 0.999752 0.000190334 -0.99992 0.0123692 -0.00263429 -0.999994 0.00016968 0.00335479 -0.999287 0.00675829 -0.0371523 -0.99979 0.020026 -0.00427298 -0.999955 0.0094106 -0.00117204 -0.999967 0.0076954 -0.0027982 -0.999998 -0.000578994 -0.00208624 -1 -0.000847215 5.0207e-05 -0.999995 0.00323905 -0.000238416 -0.999955 0.00823707 0.00479541 -0.998823 0.012246 0.0469315 -0.999996 -0.00278239 0.000307432 -0.999998 5.92714e-05 0.00181121 -0.999997 -0.000469535 0.00231663 -0.999999 0.00134109 8.33075e-05 -0.999306 0.0334716 0.0163161 -0.999488 0.0286432 -0.0142949 -0.0118061 0.997374 -0.0714486 0.00888851 0.961806 -0.273587 -0.0122673 0.905539 -0.424085 0.00671803 0.875903 -0.48244 -0.00828382 0.757036 -0.65332 0.0251279 0.661239 -0.749755 -0.0238651 0.55081 -0.834289 0.0187737 0.345794 -0.938123 -0.0199124 0.208789 -0.977758 0.0201242 -0.0400693 -0.998994 0.00725933 -0.0164553 -0.999838 -0.0104578 -0.342461 -0.939474 -0.0118444 -0.339347 -0.940587 0.012643 -0.561168 -0.827606 -0.0174243 -0.65142 -0.758517 0.0100349 -0.810505 -0.585647 0.00751234 -0.807783 -0.589432 -0.0102699 -0.955949 -0.293353 -0.011488 -0.955084 -0.296111 0.00850468 -0.995747 -0.0917354 -0.0268513 0.997573 -0.0642434 -0.200776 0.614761 -0.76273 -0.187005 -0.248925 -0.950298 -0.17706 -0.717738 -0.673425 -0.0245934 -0.810369 -0.585403 -0.0727681 -0.944198 -0.321239 -0.998151 0.0364269 0.0486488 -0.999996 0.000932478 -0.00278154 -0.999996 0.00213247 -0.00163605 -0.999999 0.00129001 -0.000897069 -0.999376 -0.0222603 0.0274286 -0.999994 -0.00107747 -0.00336018 -1 0.000561486 -0.000501975 -0.999999 -0.00112562 -4.97142e-05 -1 -0.000709429 -0.000328949 -0.999999 0.0013658 7.50916e-05 -1 -0.000135075 0.000395916 -1 0.000560989 0.000848496 -0.999999 -0.0014662 -0.000346805 -0.999999 -0.00130482 -0.000394529 -1 3.05846e-05 0.000903322 -1 -0.000175744 0.00033784 -1 0.000145057 -0.000113334 -1 0.00037616 -4.00567e-05 -0.557629 -0.677938 -0.479009 -0.766111 -0.027201 -0.642132 -0.627669 0.771276 -0.105664 -0.663531 0.743629 -0.082115 -0.595241 0.45862 -0.659815 -0.695279 0.456738 -0.554958 -0.640795 -0.165298 -0.749706 -0.761109 -0.438311 -0.478118 -0.242444 -0.895956 -0.372135 0.197472 -0.667391 -0.718049 -0.120119 -0.416426 -0.901199 0.0740786 -0.0433338 -0.99631 -0.136201 0.165165 -0.976816 0.123911 0.650543 -0.749293 -0.14379 0.772636 -0.618351 0.112565 0.987081 -0.114021 -0.563794 0.61563 -0.550578 -0.508838 0.184411 -0.840878 -0.877706 -0.28017 -0.388765 -0.403903 -0.837425 -0.368215 1 -0.000800311 -0.000216909 -0.996774 0.0801496 0.00417066 -0.997262 0.0738223 0.00443098 -0.994603 -0.0166807 -0.102406 -1 0.000429472 0.000243969 -0.992586 -0.0558252 -0.107961 -0.999996 -0.00142962 -0.00241861 -0.999645 0.0170761 0.0204663 -0.999169 0.00606305 0.0403133 -0.996445 -0.0670399 0.0510273 -0.998737 -0.0476307 0.0159984 -0.155612 -0.936514 -0.314207 -0.0371061 0.302518 -0.952421 -0.414691 0.158785 -0.896001 0.125369 -0.0389084 -0.991347 -0.113238 0.0920801 -0.989292 -0.247391 -0.247271 -0.936832 -0.172486 0.982988 -0.0631117 -0.097072 0.948257 -0.302301 0.10938 -0.993509 -0.0312508 -0.0521781 -0.936711 -0.346194 -0.155211 -0.903186 -0.400205 0.0255719 -0.697868 -0.71577 0.0207548 -0.389801 -0.920665 0.0179382 -0.335304 -0.941939 0.0410615 0.282675 -0.958336 0.0737981 0.455361 -0.887243 -0.501368 0.540838 -0.67537 0.0609506 0.709208 -0.702359 -0.0144791 0.916345 -0.400128 0.0508036 0.928101 -0.368847 0.0507519 0.928693 -0.367361 0.998751 0.040224 -0.0296393 0.999209 -0.0329889 0.0222027 0.999998 -0.00145546 -0.00134556 0.999996 0.000254138 -0.00290072 1 5.84001e-05 -0.000243699 0.999999 -0.00146928 0.000501476 0.999998 0.00168348 -0.000962502 0.999983 0.00570667 0.000700012 1 0.000494324 0.000731115 0.999999 0.000887014 0.00140831 0.999999 0.000425056 0.00144535 0.999996 9.87333e-05 0.00295128 1 -8.91171e-05 0.000582051 0.999994 0.000384592 0.00335561 1 -0.000356365 0.000416099 0.999084 -0.0339467 0.0260701 0.999998 0.0017826 -0.000529252 0.99994 -0.0107826 0.00174333 0.999725 -0.0232274 -0.00312539 0.999231 -0.00368572 0.0390361 0.999667 -0.0249835 -0.00646599 0.999997 0.00058419 -0.0022371 0.999999 -0.00124803 -0.000832625 1 -0.000148495 -0.000365317 0.999998 -0.00146577 -0.00152908 0.999978 0.00623947 0.00220214 0.998559 0.0231638 -0.0484076 0.967012 -0.18792 0.171969 0.977448 0.138371 0.159528 -0.941915 0.0169009 -0.335427 0.989885 -0.127867 0.0614676 0.989791 0.110964 0.0894479 0.999226 -0.00185382 -0.0392829 0.994163 0.033318 0.102618 0.999345 -0.0305752 -0.0193822 0.994282 -0.0180244 -0.105258 0.997906 -0.00272564 0.0646275 0.994851 0.0601458 -0.0815681 0.990449 0.0980421 -0.0969483 -0.933452 0.0726185 0.351274 -0.494909 -0.655181 -0.570792 -0.977745 0.203465 -0.0511489 -0.994509 -0.104633 -0.00191288 -0.147149 -0.756149 -0.637641 -0.975061 -0.19883 -0.0986068 -0.828723 0.559657 0.00157869 0.00708116 -0.999975 0.000292694 0.0142153 -0.999899 -0.000335023 0.000989246 4.25483e-05 1 -0.0028443 -0.000122336 0.999996 -0.00668488 0.999978 0.000254977 -0.00213756 0.999998 -4.18065e-05 -0.282908 0.908213 -0.308403 0.133781 0.960257 -0.244968 0.163844 -0.648953 -0.742978 0.313317 -0.605924 -0.731224 0.422893 -0.458459 -0.78165 -0.441047 -0.194599 -0.876133 0.0242586 -0.131541 -0.991014 0.410444 0.133687 -0.902033 -0.428896 0.366309 -0.825752 -0.096678 0.496847 -0.862436 -0.129439 0.636727 -0.760148 0.380222 0.667587 -0.640124 -0.408759 -0.785851 -0.464063 0.378994 -0.877873 -0.292751 -0.169811 -0.977379 -0.126075 -0.999998 -0.000342151 -0.00218776 -0.99988 -0.0144637 0.00563287 -1 -6.16473e-05 -5.94051e-05 -0.984487 -0.172386 0.0326998 -0.98647 0.109917 0.121637 -0.99645 0.0493229 -0.0682231 -1 7.88072e-05 -5.94195e-05 -0.999993 0.00295031 -0.00222449 -0.999999 -0.000657658 -0.00105803 -0.999999 -0.000360705 -0.0011055 -0.999999 0.00148454 -0.000600428 -1 0.000294907 -0.000208308 -0.999999 -0.000395142 -0.00102727 -0.999999 -0.000179436 -0.00113785 -0.999999 -0.000352506 -0.0009736 -0.999999 -0.000196812 -0.00127708 -0.999999 -0.000455126 -0.00167127 -1 -5.07529e-05 -1.59466e-05 -1 -0.000316865 -0.000179078 -1 -0.000694702 -0.000661336 -0.99995 -0.00408949 0.00910931 -1 -0.000163227 0.000344492 -0.99995 -0.00110613 0.00992398 -0.999999 -0.00129143 6.49068e-05 -1 -0.000739368 0.00032229 -0.999993 0.00360195 -0.000462022 -1 8.82384e-06 -6.8536e-06 -1 -2.70006e-05 -5.52671e-05 -1 -0.000105939 0.000120252 -1 -0.000286968 2.52616e-05 -1 3.42699e-05 8.73834e-09 -0.999996 -0.00292525 8.23188e-06 -1 3.241e-05 -3.6239e-05 -0.999998 0.00178644 0.000564043 -0.999995 0.00283527 0.00156099 -0.999987 -0.00386913 -0.00346587 -1 0.000107144 -0.000152711 -1 -2.35064e-05 0.00023057 1 0 0 -1 -1.39415e-05 0.000388921 -1 4.21248e-06 -1.70238e-05 -1 0.000119302 -0.000137597 1 0.000728346 -0.000286687 -0.999996 -0.00206458 0.00179763 -0.999999 0.00161938 -0.000340646 -1 0.000132963 -6.23529e-06 -0.000884852 -0.989591 0.143908 -0.474054 -0.844643 0.248697 0.414233 -0.362469 0.834882 0.414187 0.695807 0.586773 -0.356454 0.410128 0.839485 0.99966 0.0253267 -0.00626742 0.999999 0.00126382 0.000547044 0.999997 0.000348176 0.00252387 0.999837 -7.85904e-05 0.0180352 -0.975536 -0.10219 0.194643 0.0190118 0.999819 0.00104102 0.214257 0.976727 -0.00994216 0.527049 0.845453 -0.0861891 0.0211092 0.000751329 0.999777 -0.00179552 -0.000136853 0.999998 0.00653692 -0.999973 0.0035113 -0.917511 0.183569 -0.35281 -0.689204 0.688949 -0.224382 -0.522218 -0.852638 -0.0172553 -0.669738 -0.340254 -0.660059 0.810026 -0.0106434 -0.586298 0.0390084 0.323421 -0.945451 0.00842224 -0.948112 -0.317825 0.356881 -0.842126 -0.404302 0.36993 -0.117403 -0.921612 0.51436 0.131821 -0.847383 -0.0141112 0.000479573 -0.9999 -0.00248571 0 -0.999997 0.261313 0.963121 -0.0641315 -0.075691 0.997129 -0.00224083 -0.142387 0.527508 0.837533 0.97119 0.176086 0.160571 -0.915991 0.372141 0.149905 0.917366 0.397064 0.0279415 0.364123 -0.930314 0.04393 0.683181 -0.616931 0.390716 -0.487525 -0.700853 0.520696 0.967351 0.057891 0.24674 0.607172 -0.284057 0.74206 0.734622 0.126174 0.666641 -0.0908073 0.00108383 0.995868 -0.00173734 -0.999998 0.00103346 0.793595 -0.606892 -0.0434674 -0.788394 0.303789 0.534928 0.514667 -0.4 0.758365 -0.500336 -0.767121 0.401485 0.958231 0.229734 -0.170343 0.982304 -0.171986 -0.0741602 0.980086 -0.184871 -0.0724906 0.999283 0.00512536 -0.0375228 0.998982 -0.0281281 -0.0352803 0.104016 -0.102888 -0.98924 0.59376 0.676627 -0.435459 -0.0331787 -0.541876 -0.839803 -0.706841 -0.245479 -0.663412 1 -0.000230996 7.63633e-05 0.99999 -0.00397313 -0.00186379 0.999999 -0.0015505 -0.000367596 1 -0.00022366 3.36304e-05 1 0.000565721 -0.000612099 1 -7.21647e-05 -0.000296093 1 -1.21118e-05 -4.96951e-05 0.999928 0.0120074 -6.0213e-05 1 -0.000210658 -0.000247982 0.989639 -0.0167274 -0.142604 0.999938 -0.00348843 -0.0105685 1 -1.83033e-06 -4.40602e-05 0.998163 0.0461538 0.0392523 1 1.7014e-05 -0.000369424 1 0.000547972 -0.000661936 1 7.72997e-05 -9.3376e-05 0.999999 -0.00159914 2.37939e-05 0.999998 -0.0018439 0.000214439 1 -0.000621501 -0.00025291 1 0.000505313 0.000136146 1 0.000563691 0.000264426 1 4.65347e-05 -0.000117894 1 -0.000657527 9.88683e-05 0.999999 0.000816414 -0.000824367 0.997919 0.0495763 0.0412178 1 -9.14814e-05 -0.00037535 1 -3.6267e-05 -0.000148804 0.984068 -0.14101 0.10829 1 -0.000340735 4.14943e-05 1 1.31307e-05 0.000333652 1 0 0 1 5.56066e-07 -1.51563e-07 1 3.72355e-06 -0.000135718 0.999999 0.000523709 -0.00112009 1 1.22685e-05 -0.000167245 0.993653 -0.0234815 0.110014 1 1.49972e-05 -1.74412e-06 -0.989739 0.118267 0.0801865 -0.999999 -0.000641477 0.00110108 -1 -0.000527597 -9.81718e-06 -1 -3.16957e-05 -4.87044e-05 -1 8.71768e-05 -0.000130754 -0.999999 -0.00100368 -0.000257758 -0.998002 -0.0137588 0.0616644 -1 3.03162e-05 -3.93138e-05 -0.999605 -0.0243838 0.013989 -1 3.35294e-05 -4.8488e-05 -1 -7.20645e-05 -0.000120591 -1 3.13745e-05 -3.40418e-05 -1 -0.000555373 -0.000110933 -1 0 0 -0.999999 -0.000777191 0.0011552 0.454675 0.821036 0.345209 1 -0.000676645 -0.000297757 1 0.000505313 0.000136146 1 -0.000564173 -2.29685e-05 0.999998 0.00115832 0.00157108 0.999991 -0.0036655 -0.00200444 0.997912 0.049694 0.0412658 0.999987 0.00359803 -0.0037443 0.999999 0.00114653 0.000323848 1 -0.000377937 -0.000106751 0.984129 -0.140576 0.1083 0.999988 -0.00439181 -0.00200326 0.999937 -0.0042759 -0.010336 1 -0.000530906 0.000442087 0.999999 0.000542497 0.00164866 0.999998 -0.000461503 0.00192716 1 0.000598704 0.000132229 0.999995 0.000625465 -0.00311794 0.999986 0.00299821 -0.0044429 0.993653 -0.0234817 0.110015 1 1.49972e-05 -1.74412e-06 -0.989739 0.118269 0.0801873 -0.999999 -0.000641476 0.00110108 -1 -0.000527596 -9.81993e-06 -1 -3.16957e-05 -4.87043e-05 -1 8.71768e-05 -0.000130754 -0.999999 -0.00100176 -0.000257535 -0.998002 -0.0137589 0.0616651 -1 1.41979e-05 1.76117e-05 -0.999605 -0.0243838 0.013989 -1 8.21775e-05 8.07512e-05 -1 -7.20646e-05 -0.000120592 -1 2.46181e-05 0.000187393 -1 -0.000555373 -0.000110933 -1 0 0 -0.999999 -0.000777192 0.0011552 0.454673 0.821038 0.34521 0.768293 0.0472073 0.638355 -0.764268 0.58865 0.263411 -0.905215 0.348036 0.243838 -0.954016 -0.296485 0.0441675 0.928768 -0.155488 0.336471 -0.900907 -0.0901506 -0.424546 -0.95034 0.178269 -0.255098 0.284863 0.241833 -0.927561 -0.908248 -0.417663 -0.0253777 0.00699238 -0.984503 0.175228 0.593261 -0.766673 0.245468 0.19166 -0.221189 0.956212 0.758995 0.0503118 0.64915 -0.759968 0.594092 0.263635 -0.493733 0.830451 0.258031 -0.954016 -0.296483 0.0441673 0.928771 -0.155483 0.336467 -0.637161 -0.0887817 -0.7656 -0.0304703 -0.207577 -0.977744 -0.949587 0.177548 -0.258382 0.221334 0.246022 -0.943655 -0.911207 -0.41119 -0.0249819 -0.810118 -0.576267 0.107821 0.554152 -0.747237 0.366813 0.222207 -0.219097 0.950064 -0.832627 -0.508878 -0.218577 -0.98684 -0.148551 -0.0638742 0.782531 -0.611205 -0.118633 0.425747 -0.543728 -0.723256 0.672765 -0.110357 -0.731579 0.666043 0.469721 -0.579439 -0.789297 -0.15131 0.595076 0.938902 0.333082 -0.0867177 0.893267 -0.447155 0.0461195 0.984038 -0.0597178 -0.167637 0.901485 0.431669 0.0314011 0.476592 0.112978 0.871835 -0.0162262 0.947616 -0.319 -1 -4.72829e-05 0.000552281 -1 0.000627409 7.79196e-05 -1 0.000219004 -0.00014141 -1 -0.000159534 -8.25999e-05 -1 -5.31108e-06 -9.54464e-07 -0.993882 0.0811473 0.0749204 -0.999999 -0.000639813 0.00092306 -1 -0.000664129 0.00066945 -0.995072 0.063009 0.0765614 -0.998901 -0.0149763 -0.0444131 -1 -0.000146618 0.00022229 -0.989018 0.000493579 -0.147793 -0.9976 0.039519 0.0568539 -1 0.000147517 -0.000730797 -1 -0.000143839 0.000163383 -1 0.00011108 6.27229e-05 -1 0 0 -1 0.000103211 0.000417897 -1 -3.03316e-05 0.000377458 -0.999999 -0.000683114 0.000934747 -0.0162241 0.947616 0.319 -0.399781 -0.90326 0.15587 -0.566161 -0.579727 0.585985 -0.779873 -0.412801 0.470523 -0.652526 -0.110249 0.749703 -0.680271 0.457983 0.572261 -0.555118 -0.109368 0.82455 0.612341 0.491638 -0.619137 -0.612341 -0.491638 0.619137 0.323995 0.936144 -0.136605 -0.323995 -0.936144 0.136605 -0.307935 0.907625 -0.285296 0.307935 -0.907625 0.285296 -0.216279 0.829492 -0.514943 0.216279 -0.829492 0.514943 -0.14715 -0.756149 0.63764 0.302527 0.256762 0.917906 0.995053 0.0902836 0.0414458 0.98381 -0.0807151 0.160011 0.982142 -0.177028 0.0636994 -0.295087 -0.54635 0.783853 -0.856422 -0.0862419 -0.509022 0.992931 0.0472293 -0.108891 0.266363 0.940857 0.209377 -0.122596 -0.0405355 0.991628 0.212753 -0.228809 0.949938 0.0328699 0.303403 0.952295 0.409183 0.157633 0.898733 0.117759 0.0931307 0.988666 -0.0980564 -0.993871 0.0510433 -0.0912859 -0.841742 0.532107 -0.086402 -0.95296 0.290519 0.336813 -0.664605 0.666976 0.574832 -0.55026 0.605625 -0.113967 -0.437036 0.892194 -0.071591 -0.30831 0.948588 -0.0488823 0.281672 0.958265 -0.0924417 0.451615 0.887411 0.45108 0.541865 0.709161 -0.0670145 0.708272 0.702752 0.185747 0.852407 0.488775 -0.0818824 0.924804 0.371528 -0.0822129 0.918494 0.386793 0.653071 -0.105291 0.749941 0.933558 0.046951 0.355337 0.379813 -0.825451 0.41758 0.410899 -0.824977 0.388039 0.119658 -0.813496 0.569128 -0.00849933 -0.14947 0.98873 -0.0742984 -0.117318 0.990311 0.0719588 0.544268 0.835819 -0.0732708 0.652176 0.754519 0.140176 0.927399 0.346816 -0.0323337 0.981826 0.187011 0.739779 -0.53216 0.411743 0.828115 -0.0673003 0.556504 0.63341 0.623056 0.458904 0.757753 0.644985 0.0990151 0.581037 0.268454 0.768328 0.759373 0.412088 0.503523 0.471064 -0.515072 0.716101 0.554946 -0.829042 0.0687331 0.218164 0.956884 0.191777 0.139312 0.748541 0.648289 0.117112 0.19158 0.974465 -0.0146148 -0.141395 0.989845 0.145901 -0.283506 0.947807 0.0715703 -0.858407 0.507951 0.0645906 -0.983263 0.170356 0.0149448 0.99621 0.0856926 0.0118478 0.995612 0.0928267 -0.0111666 0.961784 0.273582 0.00656568 0.929438 0.368919 -0.0112642 0.875868 0.482419 0.0164082 0.810408 0.585637 -0.0086047 0.664718 0.747045 -0.0101817 0.661414 0.749952 0.0112109 0.481513 0.876367 -0.0245802 0.345745 0.938007 0.0277056 0.197724 0.979866 -0.0253077 -0.0164498 0.999544 0.0188766 -0.141282 0.989789 -0.0106171 -0.387332 0.921879 0.0109728 -0.339349 0.940597 -0.0120682 -0.561172 0.827611 0.0180868 -0.647898 0.761513 -0.0115545 -0.802317 0.596786 -0.0153691 -0.807711 0.589378 0.0124425 -0.888861 0.458008 -0.00707498 -0.967156 0.254086 0.027615 -0.954768 0.296066 -0.507837 0.849673 0.141979 0.0771448 0.589623 0.803986 -0.845432 0.438727 0.304571 -0.520708 0.443498 0.729501 -0.767415 -0.0955112 0.633997 -0.71504 -0.0547689 0.696935 -0.599697 -0.502032 0.62316 -0.810268 -0.568683 0.14165 -0.730165 -0.629035 0.266785 -0.164714 0.911259 0.37746 0.182752 0.8047 0.564853 -0.200122 0.268946 0.942135 0.253736 -0.0878436 0.963277 -0.2845 -0.581533 0.762154 0.296172 -0.88041 0.370352 0.955047 0.261878 0.138941 0.227448 -0.00583485 0.973773 0.677728 -0.719641 0.151004 0.857193 -0.510585 -0.0672527 0.535255 -0.775167 0.335586 -0.337256 -0.773247 0.53698 0.430636 -0.337052 0.837227 0.425412 0.283811 0.859346 -0.263442 0.520807 0.812009 0.27631 0.760795 0.587234 -0.189212 0.871321 0.452768 0.179273 0.977213 0.113647 -0.284005 0.958582 -0.0215038 -0.04364 -0.988871 0.142232 -0.0320578 -0.989775 0.138987 -0.0424447 -0.737319 0.67421 0.163315 -0.674323 0.72015 -0.159469 -0.292734 0.942802 -0.0100064 -0.240935 0.97049 0.186832 0.131907 0.973496 -0.186483 0.324139 0.927447 0.0692319 0.52142 0.850487 -0.0855596 0.730968 0.677026 0.0755484 0.792122 0.605669 -0.0221513 0.956735 0.290118 -0.0358526 0.958038 0.28439 0.0165014 -0.955099 0.295829 0.0478301 -0.956089 0.289148 -0.177614 -0.763175 0.621302 0.15969 -0.714046 0.681643 0.294147 -0.837161 0.461128 -0.653139 -0.266736 0.708704 0.419801 -0.0875475 0.903384 -0.33641 0.199538 0.920333 0.337574 0.351815 0.873081 0.0236666 0.732365 0.6805 0.317698 0.737449 0.596017 -0.388126 0.905534 0.171367 0.0620878 0.991389 0.115295 0.0615542 -0.964373 0.257284 -0.0615562 -0.955369 0.28893 0.0678001 -0.795661 0.601936 -0.0897919 -0.77237 0.628794 0.145866 -0.362242 0.9206 0.0441865 -0.351945 0.934977 -0.223389 0.206531 0.952598 0.447208 0.287577 0.846938 -0.102223 0.728731 0.677128 0.286227 0.7594 0.584282 -0.388126 0.905534 0.171367 0.0620878 0.991389 0.115295 0.85877 0.493223 -0.138726 -0.894928 0.394928 -0.20769 0.858772 0.49322 -0.138726 -0.89493 0.394926 -0.207689 -0.458145 -0.0602738 0.886831 0.377843 0.139539 0.915294 0.336956 -0.795174 -0.504141 -0.756205 0.447063 0.477796 -0.974545 -0.22364 -0.0157364 -0.9904 -0.117931 -0.0721104 0.453201 0.854061 -0.25532 -0.953792 0.272242 -0.12714 -0.966556 -0.153194 0.205674 0.758005 -0.150445 0.634661 -0.860848 0.0746005 0.503364 0.761257 0.221232 0.609545 -0.974574 -0.108396 -0.196102 0.809751 -0.460175 -0.364063 -0.812871 -0.562955 -0.14941 0.81517 -0.578605 -0.0267401 -0.806717 0.193212 -0.558459 0.981733 -0.0158191 -0.189607 -0.856936 0.48162 0.183582 0.859723 -0.457875 0.226334 -0.886051 -0.164186 0.43354 -0.876664 -0.479002 0.0449045 0.228836 0.940857 0.249843 0.970303 0.0573241 -0.235002 0.985412 0.167885 0.027905 0.981248 0.00384982 -0.192712 -0.984297 -0.0432197 0.171148 -0.465888 0.87656 0.120796 0.94181 0.0801141 0.326459 0.528121 0.337558 -0.779193 0.780627 -0.320334 -0.536663 -0.878139 0.213692 -0.428027 0.260295 0.947718 -0.184602 -0.518279 -0.26731 0.812362 0.77678 -0.0886365 0.623503 -0.662607 0.174611 0.728329 0.957874 0.185673 0.219093 -0.104488 -0.734322 -0.670711 0.650668 -0.597076 -0.469181 -0.641776 -0.761136 -0.0937785 0.169346 -0.984647 -0.0423413 -0.407127 -0.294591 -0.86456 0.352274 -0.364134 -0.862154 -0.700261 0.272122 -0.659988 0.631803 0.712069 0.306238 -0.518277 -0.267311 0.812363 0.776778 -0.0886369 0.623506 -0.662605 0.174612 0.728331 0.957873 0.185675 0.219097 -0.10449 -0.734322 -0.670711 0.650664 -0.597079 -0.469183 -0.641774 -0.761139 -0.0937789 0.169344 -0.984647 -0.0423414 -0.962424 -0.0149296 -0.27114 0.352268 -0.364135 -0.862156 -0.70026 0.272122 -0.659989 0.6318 0.712072 0.306239 0.359856 0.844687 -0.396241 -0.524572 0.69498 -0.49176 0.40903 0.498384 -0.7644 -0.483507 0.242238 -0.841155 -0.061088 0.170652 -0.983436 0.350772 -0.28694 -0.891417 -0.67561 -0.400301 -0.61912 0.246568 -0.681946 -0.688589 -0.0081403 -0.9842 -0.176872 -0.0933373 -0.982098 -0.163623 0.359856 0.844687 -0.396241 -0.524572 0.694979 -0.49176 0.409031 0.498384 -0.7644 -0.372852 0.296654 -0.879191 0.488823 -0.0281616 -0.871929 0.0401379 -0.172365 -0.984215 -0.469599 -0.53048 -0.705739 0.254852 -0.663422 -0.703507 -0.00991815 -0.984869 -0.173015 -0.0705548 -0.983945 -0.163931 0.0412389 0.990225 -0.133241 -0.0839758 0.980756 -0.176254 0.0839756 0.731691 -0.676444 -0.0196114 0.708915 -0.705021 0.0229418 0.376463 -0.926148 -0.0920445 0.31964 -0.943058 0.185346 -0.0428048 -0.981741 -0.132844 -0.179288 -0.974786 -0.0477677 -0.569024 -0.820932 0.178796 -0.624363 -0.760396 -0.158265 -0.893928 -0.41934 0.0941182 -0.942194 -0.321578 -0.999999 0.00119661 0.000825059 -0.999998 0.000944946 -0.00161335 -0.995911 0.0818631 -0.038216 -0.999617 0.00185437 -0.0276228 -1 0.00011738 0.000585565 -1 -0.00017807 -0.000307895 -1 0.000155201 -0.000296072 -1 -4.66882e-05 0.000423095 -0.999993 -0.00033726 -0.00367458 -0.999985 -0.00534998 0.000804109 -0.999991 -0.00410476 0.000619533 -0.999975 -0.00495751 -0.0049721 -1 5.4911e-07 -2.93825e-05 -1 -0.000257684 -0.000168126 -0.999999 0.0011721 0.000229078 -1 -0.00023012 0.000144077 -0.999999 -0.00128164 -5.96608e-06 -1 -0.000294786 -5.72485e-05 -1 -0.000100074 -0.000439217 -0.999999 0.00108265 -0.000529742 0.999934 0.00522432 -0.0102508 -1 -0.000110462 0.000216741 -0.999976 0.00673326 0.00186629 -0.999983 0.00576624 -0.00100505 -1 -1.06591e-05 1.86478e-05 -1 -8.21347e-06 0.000158534 -1 -0.000345519 -0.000238461 -1 -0.000294793 -0.000148691 -0.999998 -0.00195584 -0.000278993 -0.999995 0.00329485 0.000463995 1 -1.38728e-05 0.000117918 -1 -1.02445e-05 -0.000108156 -1 -1.16475e-05 0.000164123 -1 1.51247e-08 -0.000148521 -1 -1.08796e-05 9.24762e-05 -1 -7.99443e-06 9.33073e-05 -0.999997 -0.00194025 0.001224 -0.999996 0.00282587 0.000233522 -1 0.000555343 2.29821e-07 0.465518 0.796621 -0.385602 0.102481 0.211938 -0.971895 -0.178166 -0.376426 -0.909153 0.112593 -0.333137 -0.936132 -0.156894 -0.775623 -0.611386 0.474157 -0.790124 -0.388432 -0.43192 -0.889978 -0.146232 0.667429 -0.189398 -0.720185 0.33786 0.674532 -0.656397 0.940571 0.313563 0.1304 0.960356 -0.242281 -0.137897 -0.999991 0.00379566 0.00164687 -0.99997 -0.00768628 0.00085224 -0.999939 -0.00649923 -0.00898169 -0.999985 -0.00541198 -0.000607764 -0.999957 -0.00566441 0.00738236 -0.999977 0.00192297 0.00657454 -0.999937 0.00688546 0.00885276 -0.999879 0.0011366 -0.0155329 -0.999843 0.0141422 -0.0106799 -0.237751 -0.9654 -0.107132 0.238949 -0.79379 -0.559287 -0.161601 -0.565048 -0.809077 0.0893359 0.0486877 -0.994811 0.166972 0.0924029 -0.981622 -0.197277 0.787939 -0.583295 0.1548 0.895772 -0.41669 -0.593713 -0.800896 -0.0779124 -0.757192 -0.526637 -0.386412 -0.652859 -0.540307 -0.53089 -0.601749 -0.174144 -0.779469 -0.793974 0.0454021 -0.606254 -0.496818 0.511316 -0.701233 -0.749386 0.605732 -0.267412 -1 0 0 -0.999968 0.00235855 -0.00762628 -0.999955 0.000861953 0.00949974 -0.999961 0.00758253 -0.00444388 -0.999992 -0.00048082 -0.00391104 -0.999891 0.00240046 -0.0146031 -0.999983 -0.00460688 0.00348692 -0.999943 -0.00562889 -0.00902222 -0.999055 -0.0103683 -0.0422123 -0.999956 0.00762027 0.00551969 -1 0.000370086 -2.54387e-05 -0.999999 0.00168895 0.000105972 -0.999758 -0.0214326 0.00503701 -0.999987 0.00344391 -0.00369489 -0.992967 0.037925 0.112151 -0.999929 -0.0116189 -0.00278585 -0.804047 -0.524295 0.280398 -0.996815 -9.50667e-05 0.0797447 -0.999306 0.0298953 -0.0222093 0.999031 -0.0433727 0.0074943 -0.996771 0.0768811 -0.0231667 -0.999998 0.00182057 0.000934383 -0.999131 0.0396268 -0.0129528 -0.999882 -0.00675213 -0.0138034 -0.999854 -0.0134807 0.0105416 -0.999849 -0.0168222 -0.004387 -0.997292 0.00883123 -0.0730158 -0.99902 -0.0402685 0.0183529 -0.913749 0.343119 0.217562 0.999997 -0.000509208 -0.0023517 0.999998 5.7354e-05 -0.00181019 0.999999 -0.00126209 -0.000631812 1 -0.000663674 -0.000605953 1 -8.78612e-05 -0.000285197 1 -8.53136e-05 -0.000287248 0.999999 0.00146437 -0.000187739 1 0.000356443 -0.000502242 0.999999 0.000817684 -0.000706583 0.999999 0.000846872 -0.00079093 0.999999 0.00170105 0.000364931 0.999984 0.00361095 -0.00442013 0.999634 0.0269367 0.0026278 -0.833382 0.552692 -0.00226652 0.999998 0.00203191 -9.70554e-05 0.999999 0.00123231 0.000548276 1 0.000588757 0.000523881 1 0.000153359 0.000282003 1 0.000137234 0.000314481 0.999957 0.0018989 -0.00913077 0.999977 0.00376366 -0.00557618 0.999426 0.0336337 -0.00401792 0.999157 0.0332368 -0.024081 -0.038612 -0.999254 0.000233399 0.999919 -0.0124915 -0.00263427 0.999994 -0.000670625 0.00351009 0.999307 -0.00564813 -0.0367903 0.999888 -0.0146503 -0.00311563 0.99989 -0.0147038 -0.00172467 0.999915 -0.0122863 -0.00434363 0.999998 0.000578993 -0.00208624 1 0.000849298 5.0354e-05 0.999995 -0.00323905 -0.000238416 0.999948 -0.00883498 0.00510897 0.998823 -0.0122485 0.0469409 0.999996 0.00278252 0.000308764 0.999998 -5.73761e-05 0.0018116 0.999997 0.000469231 0.00231491 0.999999 -0.00134109 8.33071e-05 0.997265 0.0593992 0.0439785 0.999307 -0.03347 0.0163152 0.997517 -0.0201826 -0.0674737 0.00103081 -0.997761 -0.0668699 0.00307726 -0.963583 -0.267393 0.00121145 -0.961845 -0.273592 0.00273379 -0.908699 -0.417443 -0.00970962 -0.875882 -0.482428 0.0155089 -0.804713 -0.593461 -0.00886524 -0.666425 -0.74552 -0.0110124 -0.661408 -0.749945 0.0139057 -0.523764 -0.85175 -0.00807268 -0.35764 -0.933825 -0.0119361 -0.345836 -0.938219 0.0135354 -0.180364 -0.983507 -0.00971231 0.0207458 -0.999738 -0.00738338 0.0164556 -0.999837 0.0106655 0.34571 -0.938281 0.0143553 0.339338 -0.940555 -0.0162682 0.561138 -0.827562 0.028386 0.660574 -0.750224 -0.0251391 0.807552 -0.589261 0.0189919 0.874916 -0.483902 -0.0099624 0.969112 -0.246418 0.0116192 0.955083 -0.296112 -0.00864762 0.995747 -0.0917266 -0.00481932 -0.997504 -0.0704484 0.143975 -0.957322 -0.250611 0.119835 -0.956613 -0.265578 0.116409 -0.745924 -0.655779 0.0942743 -0.4577 -0.884095 0.0679065 -0.126076 -0.989694 0.00213884 0.0207905 -0.999782 0.150343 0.17945 -0.972211 -0.0972411 0.343154 -0.934232 0.0928599 0.65762 -0.747605 0.229527 0.683431 -0.692993 -0.0495831 0.873716 -0.483902 0.0524761 0.955707 -0.289603 0.999998 0.000317249 0.00189553 0.999997 -0.00213805 -0.000846364 0.999994 -0.00230343 -0.00256792 0.999996 0.00235718 0.00154113 0.998978 0.023382 -0.0386927 0.999997 -0.00151415 0.0021644 0.999996 -0.00186182 0.00203667 1 0.00019289 -0.000565316 0.999998 -0.000595743 -0.00200309 0.999998 0.000178757 -0.00209245 0.999998 -0.00145423 -0.00125268 0.999994 0.00297193 0.00182131 0.999996 -0.00127602 0.00266013 0.999998 -0.00046779 -0.00170062 0.999994 0.00301273 0.00177702 0.999994 0.00290533 0.00181302 0.999999 0.00119025 0.000133092 0.999999 0.00121923 8.08626e-05 0.773853 0.564032 -0.288131 0.512999 0.587591 -0.625755 0.808112 0.0584652 -0.58612 0.633634 -0.587076 -0.503835 0.752154 -0.652179 -0.0944758 0.748138 -0.430709 -0.504756 0.628325 -0.092071 -0.772483 0.614128 0.786692 -0.0629456 0.0971401 0.923978 -0.369903 -0.094357 0.875665 -0.473611 0.133878 0.426807 -0.894378 -0.216492 0.11506 -0.969481 0.221884 -0.337036 -0.914972 -0.165331 -0.662374 -0.730702 0.11773 -0.89333 -0.433707 -0.0837458 -0.989828 -0.115013 0.930453 -0.221546 -0.291848 0.928383 0.281699 -0.242386 0.998066 -0.058829 0.0200866 0.999328 -0.0321957 -0.017533 0.997454 -0.0448886 -0.0554145 0.995868 0.0727221 -0.0543991 0.999686 -0.0014631 -0.0250351 0.999702 -0.0160056 0.0184423 0.998547 0.0132788 0.0522318 0.999349 0.0357163 0.00501664 0.999342 0.0359309 0.00493212 -0.916888 0.399015 -0.0101134 0.999351 0.0166726 0.0319342 0.420766 0.883888 -0.204201 0.0371058 -0.302517 -0.952422 0.414689 -0.158785 -0.896002 -0.12537 0.0389082 -0.991347 0.113238 -0.0920805 -0.989292 0.247388 0.247272 -0.936833 0.146416 -0.97773 -0.150353 0.0970719 -0.948258 -0.302299 -0.0783585 0.99656 -0.0269884 0.042827 0.937529 -0.345262 0.154507 0.902653 -0.401679 -0.0255716 0.697868 -0.71577 -0.0207552 0.389802 -0.920665 -0.0179386 0.335304 -0.941939 -0.0410604 -0.282675 -0.958337 -0.0737974 -0.455362 -0.887243 0.501368 -0.540838 -0.67537 -0.0609501 -0.709208 -0.702359 0.0144783 -0.916345 -0.400128 -0.0508037 -0.9281 -0.368848 -0.050752 -0.928693 -0.367359 -0.998751 -0.040224 -0.0296393 -0.999209 0.0329889 0.0222027 -0.999998 0.00145662 -0.00134664 -0.999996 -0.000253579 -0.00290184 -1 -6.00904e-05 -0.000244936 -0.999999 0.00147108 0.000502091 -0.999998 -0.00168348 -0.000962505 -0.999983 -0.00570668 0.000700011 -1 -0.000494326 0.000731116 -0.999999 -0.000887016 0.00140831 -0.999999 -0.000425056 0.00144535 -0.999996 -9.87339e-05 0.00295128 -1 8.91171e-05 0.00058205 -0.999994 -0.000384593 0.00335561 -1 0.000356365 0.0004161 -0.999084 0.0339467 0.0260701 -0.999998 -0.00178067 -0.000528667 -0.99994 0.0107847 0.00174253 -0.999725 0.0232274 -0.00312539 -0.999231 0.00368741 0.0390354 -0.999667 0.0249829 -0.00646485 -0.999997 -0.000584191 -0.0022371 -0.999999 0.00124892 -0.000833001 -1 0.000148495 -0.000365316 -0.999998 0.0014651 -0.00153118 -0.999978 -0.00623986 0.00220324 -0.998559 -0.0231629 -0.0484087 -0.99197 0.123362 0.0278733 -0.688322 -0.0318248 -0.724707 -0.993299 -0.0687288 0.0929186 -0.995684 0.0927671 0.00277692 0.995684 -0.0927671 -0.00277692 0.979743 -0.0536904 0.192926 -0.999072 -0.04058 0.0144248 -0.997833 -0.0650362 0.0100333 -0.980963 0.166276 -0.100316 -0.992791 -0.119296 0.0116034 0.408349 -0.875478 -0.258437 -0.534907 0.62995 0.563061 -0.999984 0.00548963 0.00150187 0.996063 -0.0828527 -0.031539 -0.99466 0.030804 -0.0985013 -0.997866 0.0113876 0.0642877 -0.99651 0.00894039 -0.0829895 -0.978674 -0.0711203 -0.192715 -0.996759 -0.00036621 0.080446 0.295087 0.54635 -0.783853 0.965288 -0.163923 -0.203341 0.14715 0.756149 -0.63764 -0.331038 0.943585 -0.00780261 -0.00708064 0.999975 0.000292653 0.00702379 0.999974 0.00153354 -0.00236765 -0.000101835 0.999997 0.00284431 0.000122336 0.999996 0.00714566 -0.999974 0.000255062 -0.00272315 -0.999996 -0.000413834 0.282909 -0.908212 -0.308404 -0.0312044 -0.963701 -0.265155 -0.163843 0.648952 -0.742978 -0.313316 0.605924 -0.731224 -0.422891 0.45846 -0.781651 0.441046 0.194599 -0.876134 -0.0242573 0.131541 -0.991014 -0.410443 -0.133686 -0.902034 0.428896 -0.366309 -0.825752 0.0966781 -0.496847 -0.862436 0.129439 -0.636727 -0.760148 -0.380222 -0.667587 -0.640124 0.40876 0.785851 -0.464062 -0.378992 0.877874 -0.292751 0.169812 0.977379 -0.126075 0.999998 -0.00194987 0.00078555 0.999996 0.00037098 -0.0029111 0.99995 0.00948819 0.0030485 0.998489 0.0459627 -0.0301081 0.998468 -0.0357379 -0.0422408 0.999359 -0.0174694 0.03125 1 0.000115693 -0.000434624 1 0.000316006 -0.000691997 0.999999 0.000964584 -0.0014366 0.999999 0.000925145 -0.000994944 0.999999 0.000605354 -0.00138434 0.999996 -0.00279199 -0.00101659 1 -0.00102542 -5.21986e-05 0.999999 -0.00153018 -0.000220621 0.999999 0.000394552 -0.00102652 1 0.000259212 -0.00095816 0.999998 -0.000761663 -0.00198656 0.99999 0.00254319 -0.00373095 0.999992 0.000656822 -0.00384233 1 4.78363e-05 -1.55703e-05 0.999999 0.00120981 -0.000706388 0.999965 0.00318805 0.00773237 1 0.000143849 0.000303594 0.999991 0.000421466 0.00430833 0.999999 0.00119298 5.90569e-05 1 0.000715151 0.00023891 1 -0.000879591 -0.000130492 1 1.67269e-07 -3.24945e-06 1 4.09596e-06 -8.38398e-06 1 7.03069e-05 0.000117251 1 1.89888e-05 1.81894e-06 1 -1.27442e-05 -2.29053e-07 0.999995 -0.00303294 0.000801108 0.999999 -0.00118721 -0.000109871 -0.999991 0.00308482 0.00296865 1 -3.46261e-05 4.08441e-05 1 2.07157e-05 0.000203197 -1 0 0 1 1.39272e-05 0.00027234 1 1.27987e-06 5.17232e-06 -1 -0.000730801 -0.000289463 0.999997 0.00197846 0.00170026 0.999999 -0.00153581 -1.08851e-05 0.00973345 0.989545 0.143894 0.473536 0.844727 0.249398 -0.414232 0.362471 0.834881 -0.486517 -0.784765 0.383986 0.487762 -0.383203 0.784375 -0.999867 -0.0147817 -0.00691596 -0.783826 0.445467 0.432639 -0.497219 0.654189 -0.569921 -0.705297 -0.42078 -0.570527 -0.999997 -0.000365593 0.00257407 -0.999837 9.54635e-05 0.0180702 0.975537 0.102189 0.194641 0.0149675 -0.999887 0.00104124 -0.233682 -0.972205 -0.0145331 -0.527046 -0.845455 -0.0861883 -0.0052817 -0.000137579 0.999986 0.00179671 0.000136899 0.999998 -0.00653728 0.999973 0.00351102 0.91751 -0.18357 -0.352812 0.689201 -0.688952 -0.224382 0.52222 0.852636 -0.0172557 0.822605 0.268501 -0.501227 -0.182525 0.323012 -0.928627 -0.749213 -0.0322751 -0.661543 -0.0390051 -0.323422 -0.945451 -0.252566 0.118589 -0.960285 -0.283671 -0.0746558 -0.956011 0.0136721 -0.000589223 -0.999906 0 0 -1 -0.807124 -0.582173 0.0981079 -0.349966 -0.933436 -0.0788746 0.0863724 -0.996261 0.00216334 -0.84034 -0.250601 0.480654 -0.364129 0.930312 0.0439287 -0.683179 0.616933 0.390717 0.487526 0.700853 0.520695 -0.967351 -0.0578904 0.246741 -0.759002 0.188919 0.623078 -0.256079 -0.290997 0.921816 0.0188408 0.0548918 0.998315 -0.309786 0.938612 -0.151787 -0.0299239 0.999552 -0.000723745 -0.793593 0.606895 -0.043467 -0.280873 -0.724434 0.629528 0.42584 -0.446798 0.786786 -0.514665 0.400001 0.758366 0.500336 0.76712 0.401486 -0.958229 -0.229737 -0.170345 -0.99898 0.0440103 -0.0100778 -0.993234 -0.101468 -0.0564945 -0.999283 -0.00512549 -0.0375228 -0.98635 -0.157729 -0.0472812 -0.701725 0.387857 -0.59762 -0.714591 0.384083 -0.584671 -1 0.000466123 -0.000223383 -0.99999 0.00397315 -0.0018638 -0.999999 0.00155051 -0.000367598 -1 1.87779e-05 6.13349e-05 -1 0.000181613 -0.000185918 -1 -3.18748e-05 3.26304e-05 -0.999928 -0.0120074 -6.02076e-05 -1 0.000158656 -0.00024334 -1 0.000140336 0.000104849 -0.999859 0.00354392 -0.016412 -1 2.6217e-05 4.78852e-05 -1 -1.91676e-06 -3.50094e-06 -0.999197 0.0220823 0.0334176 -0.995153 -0.0471486 -0.0863011 -1 -0.000229806 0.000546685 -0.999999 0.00159914 2.37932e-05 -0.999998 0.0018439 0.00021444 -0.999999 0.00100825 -0.000602296 -1 0.000564881 -0.000150704 -1 -0.000507197 0.000136675 -1 -0.00056578 0.000265406 -1 -0.000351399 0.00010692 -1 0.000745663 0.000134004 -0.999999 -0.00081515 -0.000823091 -0.998206 -0.0450895 0.0393895 -1 9.13394e-05 -0.000374769 -1 3.62668e-05 -0.000148804 -0.984068 0.14101 0.10829 -1 -5.71086e-05 8.75907e-05 -1 -6.30951e-05 0.000187953 -1 -1.31308e-05 0.000333651 -1 0 0 -1 -5.56067e-07 -1.51564e-07 -1 -5.82375e-06 -0.000212267 -0.999999 -0.000720425 -0.000918794 -0.99336 0.0709881 0.0905347 -0.994973 -0.0843356 0.0540034 -0.993653 0.0234815 0.110014 -1 -1.49972e-05 -1.74413e-06 1 -0.000404409 -7.65321e-05 0.987575 -0.121829 0.0992649 0.999999 0.000820681 0.00109182 0.999999 0.000813413 0.000666557 1 -8.05871e-05 -7.60422e-06 1 -0.000784943 0.000104847 0.990903 -0.0833408 0.105669 0.999537 0.0223034 0.0206855 0.999518 0.0234429 0.0203612 1 -3.35294e-05 -4.8488e-05 1 0.000424097 -0.000128259 0.998122 -0.0502734 0.0350028 0.995014 0.0842324 0.0534012 1 -1.77445e-05 2.60842e-05 1 -2.15674e-05 3.17037e-05 1 0.000628088 0.000104643 1 -7.43044e-05 -0.000137996 0.999999 0.000508061 0.000943554 -0.454674 -0.821037 0.345209 -1 0.000534006 -0.000180056 -1 -0.000507197 0.000136675 -0.999998 -0.00116044 0.0015721 -0.999991 0.00366477 -0.00200444 -0.997912 -0.0496939 0.0412657 -0.999999 -0.000632034 -0.00103543 -1 0 0 -1 0.00071707 -6.50114e-05 -0.984129 0.140576 0.108301 -0.999988 0.00439268 -0.00200325 -0.999937 0.00427675 -0.010338 -1 0.000530906 0.000442086 -0.999999 -0.000542497 0.00164866 -0.999998 0.000461503 0.00192716 -1 -0.000598704 0.00013223 -0.999999 -0.000513604 -0.00102445 -0.999986 -0.00299883 -0.00444377 -0.993653 0.0234816 0.110015 -1 -1.49972e-05 -1.74413e-06 1 -0.000404409 -7.65321e-05 0.987575 -0.12183 0.0992658 0.999999 0.00062892 0.00100087 1 0.000496847 -8.2586e-05 1 -8.15782e-05 -7.446e-06 1 -0.000784943 0.000104847 0.990903 -0.0833405 0.10567 0.999537 0.0223041 0.0206853 0.999518 0.0234429 0.0203612 1 -3.35294e-05 -4.84879e-05 1 0.000425741 -0.000128756 1 8.22703e-05 -5.62898e-06 1 -1.8167e-05 2.67052e-05 1 -2.15674e-05 3.17038e-05 1 0.000630523 0.000105049 1 -7.45925e-05 -0.000138531 0.999999 0.000508062 0.000943555 -0.454668 -0.82104 0.34521 -0.768293 -0.0472068 0.638355 0.764268 -0.588651 0.263411 0.49373 -0.830452 0.258033 -0.310986 0.939938 0.14073 0.934049 0.0286773 -0.355992 0.950339 -0.17827 -0.255098 -0.338327 -0.231482 -0.912114 0.671374 0.685613 -0.281411 0.82609 0.554869 0.09847 -0.702037 0.224351 0.675878 -0.440589 -0.130663 0.888149 0.46107 -0.849797 0.255461 0.493731 -0.830451 0.258032 -0.310988 0.939937 0.14073 0.934049 0.0286779 -0.355991 0.938155 -0.167487 -0.303009 0.582241 0.606275 -0.541689 0.831706 0.545749 0.10209 -0.711752 0.221031 0.666749 0.975669 0.18004 -0.125123 0.975669 0.180041 -0.125122 -0.782534 0.611201 -0.118632 -0.425748 0.543728 -0.723256 -0.672765 0.110357 -0.731579 -0.666039 -0.469723 -0.579441 -0.99821 -0.0541998 -0.0252889 -0.937549 0.321861 -0.131938 0.051135 0.341189 0.938603 0.0162241 -0.947616 -0.319 1 4.91213e-05 0.000552828 1 -0.000627064 7.74165e-05 1 -0.000219004 -0.00014141 1 0.000160438 -8.24594e-05 1 7.08143e-06 -1.27262e-06 0.999045 0.0436981 0.000461844 0.999999 0.000639813 0.00092306 0.994982 0.0102669 -0.0995261 1 0.000675962 -0.000481996 1 0.000133669 0.000678186 0.995799 -0.0166345 -0.0900451 0.989018 -0.000494173 -0.147795 0.9976 -0.0395189 0.0568539 0.997056 -0.00307424 -0.0766183 1 0.000142818 0.00016298 1 -0.00011108 6.27229e-05 1 0 0 1 -0.00010321 0.000417897 1 2.97153e-05 0.000377645 0.999999 0.000683115 0.000934747 -0.999699 0.0134882 -0.020499 0.0352484 -0.99091 0.129828 0.0129279 -0.57124 0.820682 0.158949 -0.803398 0.573835 -0.17458 -0.626667 0.759481 0.149751 -0.979862 -0.132084 -0.0737888 0.0517652 0.99593 0.0342061 0.279908 0.959417 -0.216057 -0.399652 0.890841 0.03248 0.813092 0.581229 0.0257296 0.897241 0.440792 0.447365 -0.747153 -0.491556 -0.460255 -0.495677 -0.736525 0.528377 -0.120756 -0.840378 -0.376208 0.102606 -0.920836 0.0668189 0.361004 -0.930167 0.171413 0.888596 -0.425459 -0.0907066 -0.929362 -0.357853 0.0488348 -0.905667 -0.421168 -0.0255037 -0.620448 -0.783833 0.0311701 -0.637401 -0.769902 -0.130817 -0.268484 -0.95436 0.226413 -0.00850578 -0.973994 -0.0526755 0.126341 -0.990587 -0.0365617 0.584726 -0.810407 0.0406078 0.611798 -0.789971 -0.0321373 0.826291 -0.562326 -0.114059 0.987675 -0.107183 -0.965833 -0.166658 -0.198473 -0.975643 0.191952 0.106186 -0.976757 0.117879 0.179027 -0.950588 -0.276627 0.140927 -0.99372 -0.11139 -0.0106032 0.802534 -0.596285 0.0195928 -0.988178 -0.113738 -0.102797 0.133789 0.984116 -0.116686 -0.0980242 0.965902 -0.239635 -0.0283457 0.78768 -0.615432 0.148103 0.706848 -0.691687 -0.086799 0.510442 -0.85552 0.0967229 0.176365 -0.979561 0.0776276 0.167055 -0.982887 -0.125556 -0.198311 -0.972064 0.13497 -0.472749 -0.8708 0.0167206 -0.54027 -0.841326 -0.0582341 -0.80645 -0.588428 0.084308 -0.867738 -0.489819 -0.0713792 -0.967156 -0.243954 0.116259 -0.991505 -0.0583298 0.0970443 -0.994418 -0.0414155 0.0168909 -0.916869 0.398831 -0.19042 -0.468305 0.862804 -0.0271489 -0.652159 0.757596 -0.123697 -0.985038 -0.119992 -0.164371 -0.60317 -0.780492 -0.0383119 -0.505871 -0.861758 -0.12396 0.137937 -0.982653 -0.113078 0.78453 -0.609694 -0.0495717 0.825008 -0.562943 0.00696466 -0.967714 -0.251956 -0.0896535 -0.884277 -0.458276 -0.122349 -0.896589 -0.425628 -0.0385546 -0.275219 -0.960608 -0.00502546 -0.250988 -0.967977 -0.0399529 0.214119 -0.97599 -0.026135 0.510426 -0.859524 -0.00736158 0.523456 -0.852021 -0.0272517 0.962381 -0.270334 -0.00722257 0.96589 -0.258853 0.635221 -0.507085 -0.582545 0.442366 -0.212242 -0.871359 0.703259 0.520949 -0.483775 0.999942 -0.00845456 -0.00671005 -0.00568689 -0.82032 -0.571877 -0.0843006 -0.548211 -0.83208 -0.0273684 -0.427098 -0.903791 0.161958 -0.747306 0.644441 -0.297305 0.825474 -0.479794 -0.0167171 0.993064 -0.116379 0.0152858 0.996096 -0.0869476 -0.0469738 0.593757 -0.803272 0.00592659 0.626215 -0.779628 0.00380332 0.82619 -0.563379 0.0215828 0.833892 -0.551506 -0.0132258 -0.183146 -0.982997 0.0216079 -0.141691 -0.989675 -0.0276872 0.00171691 -0.999615 0.01737 0.158975 -0.98713 0.0658317 0.0926998 -0.993515 0.0017098 -0.816308 -0.577614 0.019203 -0.610855 -0.79151 -0.0178945 -0.986157 -0.164843 0.0226494 -0.991936 -0.124701 -0.0316261 0.991916 0.122895 0.0331158 0.979055 0.200884 -0.0150515 0.827297 0.561563 0.00860233 0.67286 0.73972 -0.0168729 0.833495 0.552269 -0.0050812 0.651582 0.758561 -0.0683899 0.570731 0.818284 -0.0113973 0.607828 0.793987 -0.0202133 0.082132 0.996417 0.0315862 0.133647 0.990526 0.000485832 -0.1316 0.991303 -0.0184504 -0.149638 0.988569 0.0478406 -0.635557 0.77057 -0.0162643 -0.584058 0.811549 -0.0618507 -0.766039 0.639811 0.0446515 -0.832331 0.552478 0.00840102 -0.839917 0.542651 -0.0146505 -0.911987 0.409957 0.0332371 -0.982917 0.181022 -0.0187333 -0.991882 0.125772 0.143137 0.637792 0.756791 -0.869592 0.221594 0.441255 -0.442366 0.212242 0.871359 -0.635221 0.507085 0.582545 -0.834384 0.543924 0.0891603 0.284425 0.794566 0.536439 -0.106084 0.608272 0.786608 0.0114516 0.513828 0.857817 -0.447245 -0.709813 0.544185 0.026016 -0.88577 0.463395 -0.00966201 -0.868029 0.496419 0.0721082 0.945393 0.317856 -0.117885 0.881747 0.456756 -0.0575186 0.310497 0.948833 0.0644062 0.211679 0.975215 -0.0865379 -0.257616 0.962364 -0.161571 -0.293738 0.942132 -0.141872 -0.315143 0.93838 -0.0606047 -0.959435 0.275339 -0.00283332 -0.974424 0.2247 -0.999911 0.0030271 -0.0130099 -0.999923 0.00279997 0.0121009 -0.996878 0.074875 -0.025074 -0.998283 -0.0370402 0.0453701 -0.999554 0.0231472 -0.0188823 -0.997154 0.0751107 -0.00654364 -0.999942 0.00845456 0.00671005 -0.998647 0.0214939 -0.0473455 -0.136729 -0.3505 -0.926528 -0.0285634 -0.9944 0.101751 0.569976 -0.475746 -0.66992 -0.0256995 -0.828448 -0.559477 -0.306874 0.903822 -0.298219 -0.0538214 -0.842264 -0.536372 -0.00506465 -0.426487 -0.90448 -0.177693 0.394564 0.901524 -0.372445 0.598817 -0.709015 -0.194381 0.41317 -0.889667 -0.16314 0.977993 -0.130057 -0.225933 -0.409236 0.884014 0.304329 0.917734 0.25524 -0.122788 -0.914944 0.384448 0.0865861 0.866378 0.491826 -0.0672937 0.738403 0.670994 0.880522 -0.429978 0.1995 0.847821 -0.422671 0.320231 0.999963 -0.00821647 0.00243933 1 0.000437327 -0.000234837 1 -1.92e-05 2.03836e-06 1 -2.99107e-05 0.000456935 1 -5.43385e-07 1.69022e-06 1 -1.85388e-06 -7.48587e-07 0.999995 0.00328617 0.00022355 1 -2.44953e-05 -8.30733e-05 1 -4.88614e-05 -2.22902e-05 0.796959 -0.195231 -0.571613 1 6.2402e-07 4.87725e-05 1 -2.87053e-05 -0.00010234 1 0 0 1 -2.01902e-06 1.43745e-06 1 -2.06031e-05 -3.45086e-05 1 6.30019e-06 -3.11157e-05 1 0 0 1 0.000236863 -0.000827356 0.999991 0.00407769 0.00136707 0.999999 0.00051466 0.00148633 0.999988 0.00475169 -0.00109653 0.999999 0.000774566 -0.00145554 1 -2.06888e-05 -0.000101411 1 0.000202951 -8.7908e-05 1 5.61296e-05 8.92527e-05 1 2.42018e-05 7.13693e-05 1 0.000247037 5.95376e-05 1 0.000159194 -0.000357176 1 -4.41125e-05 -3.21867e-05 0.99999 -0.00136656 -0.00429458 1 5.9846e-05 0.000196377 -0.131329 0.921138 0.366411 0.955033 0.187005 -0.230089 0.903466 0.421342 0.0788691 -0.416724 0.668032 0.616502 0.969624 0.0853371 0.229233 0.932953 -0.348069 -0.0919086 0.935738 -0.183923 0.300942 -0.959459 0.195847 -0.202689 -0.983421 0.115931 -0.139439 -0.942257 0.0429329 -0.332127 -0.986825 -0.0378859 -0.157296 -0.987619 -0.0353939 -0.152824 -0.995097 0.0932636 0.0329083 -0.996761 0.0270224 0.075746 -0.996876 -0.0419199 0.0669333 -0.996163 0.0602006 -0.0635233 -0.999314 -0.0369162 0.00289974 -0.987051 -0.0621499 0.147876 -0.974992 -0.00982239 0.222021 0.128639 0.991021 0.0364698 -0.0706671 0.888024 0.454334 -0.0601603 0.890491 0.451007 0.048489 0.56869 0.821121 -0.0947558 0.506842 0.856815 0.116647 0.170992 0.978343 -0.125547 0.0127907 0.992005 0.081704 -0.311874 0.946604 -0.135418 -0.435297 0.890044 0.205012 -0.688985 0.695176 -0.214996 -0.856309 0.469587 0.171072 -0.975108 0.141063 0.0139163 -0.997644 0.0671714 -0.999002 -0.000333166 -0.0446586 -0.999634 0.0141619 -0.023049 -0.999959 -0.00739531 0.00518376 -0.999205 -0.0249125 -0.0311287 -0.999148 -0.037362 -0.0175573 -0.999878 0.0142242 -0.00643816 -0.999888 -0.0141373 0.00482335 -0.999811 -0.019272 0.00264182 -0.999969 -0.00281763 -0.00738089 -0.999941 -0.00390801 0.0101113 -0.999739 -0.0160848 0.0162119 -0.999381 -0.0109285 0.0334358 -0.995574 -0.0200261 0.0918261 -0.998101 0.0105617 0.0606912 -0.999595 -0.017177 0.0226812 -0.999996 0.00167395 0.00240227 -0.999403 0.0263156 0.0224019 -0.999479 0.0287448 0.0146585 -0.999951 -0.00593854 0.00796857 -0.999998 0.00200546 0.000222656 -0.998715 0.0502642 -0.00650482 -0.999183 0.0403 0.00315542 -0.999998 0.00172971 -0.00134358 -0.999144 0.0234807 -0.0340592 -0.999 0.0275073 -0.0352601 -0.999815 0.0173014 0.00844412 -0.999878 -0.012597 -0.00929362 0.999999 0.000168744 0.00123421 0.999994 0.00121961 0.00322498 1 -3.36115e-06 -0.000108387 1 0.000371198 0.000678935 1 -0.000772361 0.000638711 0.999798 -0.0174078 0.0100696 1 1.20015e-05 -3.92657e-05 1 -3.80541e-06 -0.000106663 1 -1.32304e-05 0.000265269 0.99992 -0.00169399 0.0125732 1 -2.65364e-05 2.87012e-05 0.999972 0.000325915 0.00750071 -0.0378794 -0.661875 0.748657 0.12482 -0.579085 0.805655 -0.0990565 -0.236287 0.966621 0.12399 -0.058787 0.990541 -0.0736044 0.148121 0.986226 0.0750334 0.433596 0.897978 -0.010702 0.500278 0.865799 0.998631 -0.0425002 -0.0304787 0.893974 -0.396226 0.209322 0.999992 0.00229611 -0.00320934 0.998057 0.0620419 -0.00583263 0.999915 -0.00891066 -0.00952925 0.999367 -0.0229687 -0.0271804 0.999044 -0.0237083 -0.0367228 0.999183 0.00959648 -0.0392587 0.999858 0.00102347 -0.0168059 0.999744 0.0142287 -0.0175758 0.999839 0.0126477 -0.0127 0.952929 -0.222081 -0.206412 0.992664 -0.110998 0.0479301 0.999999 0.00151928 4.12475e-05 0.999999 0.00101399 -0.000942243 0.999834 -0.0160971 0.00848535 0.999672 -0.00457691 0.0252105 0.999693 -0.00420046 0.024432 0.999938 0.0111308 0.000569486 0.999947 0.0102018 0.00121001 0.9998 0.0173978 0.00990112 0.998103 0.0294151 0.0540831 -0.908245 0.33848 0.246013 -0.642059 -0.765598 0.0402609 -0.907529 -0.358837 0.218236 -0.43543 0.886453 -0.15685 -0.353908 0.792555 -0.496595 -0.851424 0.387865 -0.353041 0.430704 0.90077 0.0557355 -0.481277 0.640691 0.598237 0.257388 0.153455 0.954045 -0.414127 -0.0317954 0.909663 0.243417 -0.337974 0.909132 -0.734782 -0.587885 0.33836 0.014394 0.656249 -0.754407 0.0908746 0.631387 -0.770125 0.000582011 -0.792579 0.609769 0.00365408 -0.79328 0.608846 -0.00762039 0.605174 0.796057 0.281924 0.664086 0.692466 -0.538689 0.473411 -0.696918 -0.297675 -0.716253 0.631166 -0.612508 0.725899 -0.312897 -0.640198 0.742757 0.196111 -0.542098 0.840288 0.0067705 -0.83729 0.524354 0.154913 -0.662538 -0.649277 0.373473 -0.587576 -0.790821 -0.171337 0.841544 -0.371472 0.392188 0.886063 0.311377 0.343419 0.889419 0.314169 0.332013 -0.948495 0.315137 -0.0323348 0.0871665 -0.993419 -0.0743018 -0.937872 -0.0858539 0.336191 -0.966888 0.174597 0.18613 -0.996197 -0.0466687 -0.0735734 -0.998509 -0.0144396 -0.0526372 -0.996989 0.0644865 -0.0430668 -0.998258 -0.00172756 0.0589714 -0.999999 -0.000695268 0.000790502 -0.999726 -0.0222717 -0.00727374 -0.999818 -0.0140365 0.0128905 -0.997553 0.0698743 -0.00234264 -0.253784 -0.559801 -0.788807 -0.762196 0.633562 -0.132879 -0.996473 0.00908571 -0.0834253 -0.999958 0.00336625 0.00847501 -0.99785 0.0537498 0.0375131 -0.999554 0.0249197 0.0164316 -0.999184 -0.0206927 0.0346744 -0.995954 0.0622535 0.064803 -0.999362 0.0356994 -0.00064551 -0.982369 0.184721 -0.0288 -0.999899 0.0140145 0.00250454 0.999403 0.0344764 0.00244573 -0.999878 0.00622534 0.0143363 -0.997993 0.0429109 0.0465644 -0.999993 0.00361398 0.000494345 -0.998556 -0.0355716 0.040246 -0.999313 -0.036912 -0.00323955 -0.99331 -0.0260996 0.112489 -0.997064 -0.0183505 0.0743433 -0.986598 -0.156177 0.0472578 -0.998484 -0.0085162 -0.0543712 -0.999856 0.0169613 0.000729349 -0.999981 -0.00339551 0.00510879 -0.999949 0.00309295 -0.00956868 -0.999949 0.00785596 0.00638834 -0.998776 -0.0464392 -0.0170303 -0.998804 -0.0473956 -0.0120399 -0.999191 0.00287037 -0.0401072 -0.999702 0.0226006 -0.00926082 -0.996697 -0.0596456 -0.0551053 -0.999956 0.0093446 0.000266758 -0.999981 -0.00311585 -0.00540623 -0.999904 -0.0058938 0.0125634 -0.999308 -0.0139252 -0.0344919 -0.999205 -0.038969 -0.00839424 0.997154 -0.0751107 0.00654364 0.0269584 -0.988989 -0.145514 0.0698546 -0.996287 -0.0503219 0.998647 -0.0214939 0.0473455 0.0302884 -0.817909 0.57455 -0.145498 -0.644719 0.750445 0.267852 0.848895 0.455668 0.00455286 0.993573 -0.113103 0.0019949 0.977248 -0.212089 -0.133242 0.981432 0.13798 0.464521 0.564232 -0.682541 0.456557 -0.0555728 -0.887957 0.0678345 -0.432042 -0.899299 0.0470721 0.755795 0.653114 -0.193911 0.909658 0.367314 0.0644137 -0.0635993 -0.995895 0.00488515 0.0135006 -0.999897 0.941678 -0.00733834 0.336437 0.14442 0.937718 0.315955 -0.263919 0.891473 -0.368269 0.314231 -0.220437 -0.923399 -0.0129216 -0.777275 -0.629028 0.903405 -0.120377 -0.411544 -0.046621 -0.231373 -0.971747 -0.224966 0.112421 -0.967859 0.628915 0.769068 0.11402 0.148285 -0.0744814 -0.986136 -0.170828 -0.548931 -0.818225 0.998283 0.0370402 -0.0453701 -0.0632235 0.369034 0.927263 -0.136992 0.26692 0.953932 -0.0435329 0.627607 -0.777313 0.999911 -0.0030271 0.0130099 -0.0179051 0.652937 -0.7572 0.0671664 -0.982492 0.173778 0.358059 0.92886 0.0949356 0.251242 -0.455693 -0.853945 0.0680146 -0.211919 -0.974918 -0.220836 0.378892 -0.898706 -0.0153227 0.840394 -0.541759 -0.16651 -0.901465 -0.399545 0.922451 -0.385829 0.0148573 -0.118058 0.020189 -0.992802 0.118058 -0.020189 0.992802 0.932383 -0.316883 0.173916 0.110742 -0.761349 0.638814 0.413048 -0.177612 0.893222 -0.450164 0.238704 0.860449 0.0788548 0.838249 0.539556 -0.00696456 0.97411 0.225966 0.820935 -0.0430969 0.569392 0.119891 -0.933154 0.338895 -0.0978645 -0.901137 0.422343 0.0206045 -0.545739 0.837702 0.0634162 -0.532152 0.84427 -0.0572262 0.00717569 0.998335 -0.116104 -0.0144392 0.993132 0.176788 0.401279 0.898733 -0.172761 0.599336 0.781633 0.200846 0.825443 0.527547 -0.0657014 0.899323 0.43232 0.978684 -0.192477 0.071626 0.986531 -0.150075 0.0650779 0.984814 -0.103143 0.139653 0.940929 0.290225 0.174417 -0.708325 -0.012171 0.705781 0.0445775 0.970068 0.238706 -0.114632 0.921607 0.370811 0.111472 0.828219 0.549206 0.00920256 -0.886249 -0.463118 -0.100034 -0.90141 -0.421251 0.144035 -0.628016 -0.764755 -0.183529 -0.406774 -0.894903 0.100738 -0.193995 -0.975816 -0.0672692 0.132194 -0.988939 0.0212275 0.199848 -0.979597 -0.0252607 0.535751 -0.843998 -0.0167206 0.54027 -0.841326 0.0584872 0.807198 -0.587376 -0.109956 0.865565 -0.488577 0.0381185 0.994971 -0.0926289 -0.0193137 0.992454 -0.121085 -0.596624 -0.670042 -0.441683 0.228243 -0.882906 -0.410344 0.119765 -0.599093 -0.791672 0.21365 -0.510589 -0.832858 0.828673 -0.551875 0.0934581 -0.286826 -0.792081 0.538831 0.132791 -0.605386 0.784777 0.0160379 -0.510086 0.859974 0.130563 0.133659 0.982389 0.113529 0.784236 0.609988 -0.0728474 0.884274 0.461251 -0.0125312 -0.967739 0.251643 0.0533082 -0.886801 0.459066 -0.0155682 -0.856965 0.51514 0.0691166 -0.278415 0.957971 -0.00137488 -0.21726 0.976113 -0.00707193 0.255156 0.966874 0.0150953 0.510349 0.859835 0.00733861 0.516384 0.856326 0.0674074 0.958739 0.276179 -0.169775 -0.983892 -0.0559717 0.590491 -0.275592 0.758531 -0.63453 -0.770523 -0.0605396 -0.00159931 -0.992755 0.120148 0.0431202 -0.985846 0.162015 -0.0252105 -0.878164 0.477695 0.0671839 -0.833224 0.548839 -0.0374176 -0.622533 0.781699 -0.0317518 -0.625678 0.779435 0.0344207 -0.244807 0.968961 0.0248026 -0.361587 0.932008 0.208515 -0.299454 0.931047 0.00346033 -0.0278734 0.999605 -0.0536579 -0.107654 0.992739 0.0504267 0.162896 0.985354 0.0961751 0.480835 0.87152 -0.599616 -0.113749 0.792163 0.0188745 0.535229 0.844496 -0.648696 0.755373 0.0927607 0.00459809 0.709127 0.705065 -0.00498268 0.63446 0.772939 0.0170888 0.991483 0.129113 -0.0240965 0.995647 0.0900329 -0.0460345 0.97906 -0.198298 -0.144761 0.879799 -0.452767 0.0458372 0.913651 -0.403906 0.028916 0.405524 -0.913627 0.0531405 -0.510723 -0.858101 0.134336 -0.496906 -0.857344 0.0696969 -0.903152 -0.423626 0.0422459 -0.916979 -0.396691 -0.0199285 -0.99421 -0.105587 -0.00486918 -0.992731 -0.120259 -0.0295443 -0.625783 -0.779438 0.0152323 -0.753137 -0.657687 -0.0243755 -0.824261 -0.565685 0.0101312 0.180229 -0.983573 -0.0219972 0.14283 -0.989503 0.0276905 -0.00170593 -0.999615 -0.0158413 -0.153683 -0.987993 0.0280281 -0.211623 -0.976949 -0.0344307 0.820741 -0.570262 0.0295587 0.753899 -0.656325 -0.0172232 0.610973 -0.791464 -0.0285347 0.602482 -0.797623 0.0258613 0.99299 -0.115333 -0.836472 0.463391 -0.292547 -0.590491 0.275592 -0.758531 0.124674 0.985158 -0.117985 0.179017 0.601678 -0.778419 0.0343772 0.494177 -0.868681 0.13446 -0.782821 -0.607546 -0.0103792 -0.871678 -0.489969 0.0310994 0.976303 -0.214163 0.0703367 0.885554 -0.45918 0.0453856 0.877431 -0.47755 0.0366101 0.264293 -0.963747 0.0141252 0.252284 -0.96755 -0.00763729 -0.242247 -0.970185 0.0416671 -0.271918 -0.961418 0.016068 -0.520656 -0.853616 0.146568 -0.412024 -0.899308 0.0714727 -0.960497 -0.268954 -0.00695083 -0.977964 -0.208656 0.991587 -0.00522962 -0.129335 0.999883 0.0150553 -0.00256117 0.981244 0.151353 0.119387 0.922241 -0.378049 0.0809315 -0.922241 0.378049 -0.0809315 0.977982 0.0446618 0.203855 0.999839 -0.0179439 0.000860217 0.991925 -0.110311 0.062587 -0.841977 -0.538213 -0.0374343 -0.440808 0.0964509 -0.892404 0.975493 0.199982 -0.0917625 0.0742935 0.784489 0.615676 0.993664 0.105723 0.0381377 0.999846 -0.00273109 -0.0173136 0.993084 0.0787067 0.0871157 0.164889 -0.417996 0.89336 -0.0460302 -0.983432 -0.175338 -0.266176 -0.0404822 0.963074 0.0766843 0.165339 -0.983251 0.29029 -0.924032 -0.248789 0.419133 0.89598 -0.146787 0.0538226 0.842262 -0.536375 -0.00272334 0.989275 0.146037 -0.639563 0.533791 -0.553197 0.117796 0.367658 -0.922471 0.307684 0.670843 0.67476 0.318551 0.678122 0.662326 0.050667 0.958373 -0.280988 0.00520827 -0.238539 0.971119 0.233444 -0.424596 0.87477 0.122774 0.914491 0.38553 -0.073523 -0.79076 0.607694 0.000875452 -0.740126 0.672467 0.311613 -0.908872 -0.277217 -0.89041 -0.385752 0.241589 -1 0.000481643 0.00025703 -0.999986 0.00268028 -0.00461163 -1 -8.2236e-06 4.8347e-07 -0.999722 0.0214333 0.00987117 -1 -5.64677e-06 1.07858e-06 -1 0.000182295 -3.48198e-05 -1 -1.50664e-05 3.46522e-06 -1 -8.46813e-06 1.13411e-05 -1 5.24511e-07 2.41833e-06 -1 3.46225e-06 5.10015e-06 -1 3.18663e-06 6.11432e-06 -1 -1.66989e-05 -4.21253e-06 -1 3.21736e-06 5.44409e-06 -0.725857 0.237752 -0.64545 -1 -0.000159706 -0.000448411 -1 -3.67555e-05 7.8399e-05 -1 2.09416e-06 -0.000102294 -0.999869 0.00564255 0.0151922 -1 3.73232e-06 1.72084e-05 -1 3.20573e-06 2.02764e-05 -1 -3.53224e-05 5.18485e-06 -1 -1.01379e-05 -1.35839e-05 -0.999823 -0.0138393 -0.0127096 -1 4.97308e-05 2.51366e-05 -1 5.48192e-05 3.45763e-05 -0.999948 -0.0102186 0.000424797 -0.999914 -0.00658577 -0.0113617 -0.999967 -0.0040841 -0.00705484 -0.999727 -0.0232043 0.00282862 -0.165018 -0.986192 -0.0139473 -0.0590831 -0.997558 0.0372537 -0.799589 -0.563952 0.206436 -0.0309775 -0.77245 0.634319 -0.951678 -0.18053 0.248433 -0.360244 -0.131616 0.923527 0.433615 0.244529 0.867285 -0.892553 0.305742 0.331468 -0.860669 0.504837 -0.0662413 -0.407209 0.876103 -0.258117 0.313347 0.593929 -0.740988 -0.784707 0.532694 -0.316973 -0.820886 0.0529621 -0.56863 0.599163 0.200333 -0.775158 -0.620951 -0.232098 -0.748699 -0.969675 -0.12431 -0.210421 0.996954 0.0762571 -0.0163553 -0.985018 0.0769986 -0.154308 0.998702 -0.00804315 -0.0502932 0.857379 -0.319117 -0.403814 0.988908 -0.137912 -0.0551407 0.997518 0.0427181 0.0559774 0.995883 0.00310679 0.0905972 0.990455 -0.0775536 0.113953 0.964584 0.196243 -0.176257 0.996482 0.0306164 -0.0780177 0.992248 0.0336717 -0.119624 0.939093 -0.34041 -0.0471701 0.26894 0.732441 -0.625461 0.527787 -0.526148 -0.66679 0.353127 0.186626 -0.916773 0.991676 0.128355 -0.0102323 0.984416 0.057847 0.16607 0.990435 0.0149633 0.137167 -0.0527705 0.864485 -0.49988 -0.0821738 0.995417 -0.0489189 0.126206 0.982461 -0.137267 -0.122742 0.521332 -0.844481 0.126249 0.108213 -0.986079 -0.0940564 -0.354577 -0.930284 0.10119 -0.735023 -0.670449 -0.0978575 -0.987271 -0.125383 0.016093 -0.98515 -0.170938 0.992517 -0.0698782 -0.100138 0.943736 0.0725282 -0.322648 0.9774 0.138565 -0.159655 0.979697 0.129822 -0.152773 0.989284 0.140112 -0.041061 0.999912 -0.00622656 -0.0117526 0.999999 0.00115888 -7.12685e-05 0.999656 0.0260229 0.00324831 0.999733 0.0230586 -0.00138221 0.999997 0.00219907 0.00080135 0.998944 0.0257301 0.03806 0.998762 0.0302476 0.0394984 0.999757 0.0176457 -0.0132124 0.999553 -0.020526 0.0217176 0.996497 0.000613331 0.0836311 0.997743 0.0177832 0.0647587 0.999996 -0.00147151 0.00223797 0.999384 -0.0267331 0.022741 0.999463 -0.0296465 0.0139262 0.999923 0.0112191 0.00539629 0.999538 -0.0289513 -0.0092553 0.999384 -0.0347072 -0.00522895 0.999914 -0.000745931 0.0130865 0.999807 0.00385788 -0.0192511 0.929197 -0.32252 -0.180482 0.895463 -0.255056 -0.364818 0.970634 0.0094349 -0.240378 0.998359 0.00186896 -0.0572331 -0.999999 0.000122273 0.00114627 -1 0.000193344 -0.000649348 -1 0.000230689 0.000321126 -1 4.03665e-05 -0.000111317 -1 -3.73392e-06 1.02969e-05 -1 1.82191e-06 0.000197077 -0.820549 -0.136563 0.555023 -0.845316 -0.197852 0.496282 -1 -9.65199e-05 9.28921e-05 -1 -9.10653e-06 -0.000621458 0.0360435 0.545333 0.837444 -0.140083 0.376158 0.915905 0.0800376 0.149979 0.985444 -0.0896389 -0.0483503 0.9948 0.12386 -0.273527 0.953856 -0.168417 -0.551102 0.817265 0.0527132 -0.678243 0.732945 -0.999653 0.0112046 -0.0238556 -0.999849 0.016673 0.00482202 -0.999568 0.0191971 -0.0222485 -0.999955 -0.00951594 -8.1745e-05 -0.999717 -0.0063328 -0.0229175 -0.99969 -0.0125202 -0.0215213 -0.999971 -0.000842649 -0.00757869 -0.999947 0.000473661 -0.0103215 -0.999931 0.00694233 -0.0094365 -0.999894 -0.00179718 0.0144825 -0.999583 0.011969 0.0262864 -0.999936 0.00965255 0.00598285 -0.999911 0.0117041 0.00640712 -0.999946 0.00993548 0.00312801 -0.999996 0.0028446 0.000868121 -0.999995 0.00293648 0.000773431 -0.999989 -0.00400751 -0.00243391 -0.999904 -0.0120719 0.00687378 -0.999691 -0.0133196 0.0209725 -0.999885 -0.00206738 0.0150383 0.500404 0.298613 -0.812666 0.807591 0.369657 -0.459512 0.866151 0.348298 0.358428 0.853459 -0.514009 -0.0860352 -0.846385 0.0483288 -0.530375 0.24923 -0.386686 -0.887896 -0.305385 -0.651801 -0.694187 0.429339 -0.845142 -0.318439 -0.01885 0.641967 -0.7665 0.0119763 -0.792853 0.609295 -0.58695 -0.0138431 0.809505 0.0110082 0.637794 0.770129 0.64697 0.675992 0.352795 0.642958 -0.387552 0.660613 0.607046 -0.716628 -0.343424 0.530433 -0.499247 -0.685123 0.663279 0.399244 -0.632981 0.652013 0.703594 -0.28255 -0.942494 -0.312787 -0.117765 0.867278 -0.099079 -0.487865 0.93943 -0.0545728 -0.33837 0.86853 0.494595 -0.0321275 -0.882955 0.294573 0.365536 -0.0797279 -0.960887 -0.265216 0.926981 -0.374733 -0.0167771 0.907151 0.402857 0.121588 0.807162 -0.404734 0.429743 0.955543 0.0872853 0.281636 0.915595 0.362851 0.173279 0.998715 0.0185092 0.0471682 -0.44227 -0.381772 -0.811571 0.951732 0.130491 -0.277811 0.999526 -0.00161016 0.0307463 0.998318 0.0579686 -4.37389e-05 0.998015 0.0492043 -0.0393197 0.999503 -0.0086003 -0.0303287 0.999978 0.0054509 -0.00366697 0.997479 0.00711356 0.0705988 0.999957 0.00908789 0.00196907 0.998865 -0.0347064 0.0326233 0.999466 -0.0227159 0.0234916 1 -1.91281e-05 0.000360992 0.999998 0.00136477 0.00136585 0.999886 -0.0088448 0.0122357 0.999862 -0.00744577 0.0148661 0.999605 0.0148733 0.0238316 0.997525 0.0143758 -0.0688207 0.999989 0.00454339 0.000715227 0.999943 -0.010607 0.000922939 0.999969 0.00459795 0.00640768 0.97444 0.0759066 0.211437 0.99995 -0.00737297 0.00668728 0.999997 -0.00132193 -0.00214907 0.999959 -0.00857144 0.00275416 0.992813 0.108859 0.0497159 0.999991 -0.00421535 -0.000918856 0.974718 0.200086 -0.0994476 0.999621 -0.0210439 -0.0177232 0.999941 -0.0102073 -0.0037253 0.999549 0.01004 -0.0282891 0.999274 -0.0378098 -0.00459175 0.998731 0.0461334 0.0202224 0.997754 0.0615387 -0.0264713 0.999983 0.00132104 -0.00566607 0.983784 0.0530884 0.171318 0.995782 0.0312901 0.0862485 0.999997 -0.000892176 -0.00211458 0.998896 0.00732929 -0.0463987 0.99734 -0.0587865 -0.0430873 -0.660671 0.700046 -0.271017 -0.025875 0.797421 0.602869 0.203944 -0.831753 0.516328 0.222065 -0.854505 0.469582 -0.062095 0.993738 0.0928912 -0.0508479 0.995498 0.0799945 -0.0552366 -0.739354 0.671047 -0.0932476 0.425617 0.900086 -0.273326 0.159667 0.948578 0.0444861 -0.98073 -0.190237 0.0513889 0.0491814 -0.997467 0.00323065 -0.053219 -0.998578 -0.285922 0.714481 0.638566 -0.0161859 0.951818 0.306237 -0.977876 0.0951439 0.186296 -0.137012 -0.711626 -0.689069 0.234984 0.185856 -0.954065 -0.128059 0.976589 0.172841 -0.0308042 0.998688 0.0409105 -0.665784 -0.745474 -0.0316373 -0.0711168 -0.995575 0.061422 -0.865694 0.122927 -0.485245 -0.289272 -0.548061 0.784825 -0.197535 -0.659661 0.725139 -0.211358 0.897256 0.387633 -0.37864 0.319706 -0.868573 0.0969537 0.489168 -0.866784 -0.417563 0.270736 0.867377 0.132941 0.931049 -0.339816 0.0311721 -0.0745597 0.996729 -0.0214171 -0.144817 0.989227 -0.993084 -0.0787067 -0.0871157 -0.204583 0.455975 0.86616 -0.0442352 -0.991433 0.122897 -0.529549 0.837718 -0.133441 -0.522444 -0.517766 -0.677474 -0.999846 0.00273109 0.0173136 0.0162241 -0.947616 0.319 0.399781 0.90326 0.15587 0.566161 0.579727 0.585985 0.779873 0.412801 0.470523 0.652526 0.110249 0.749703 0.680271 -0.457983 0.572261 0.555118 0.109368 0.82455 -0.612341 -0.491638 -0.619137 0.612341 0.491638 0.619137 -0.323995 -0.936144 -0.136605 0.323995 0.936144 0.136605 0.307935 -0.907625 -0.285296 -0.307935 0.907625 0.285296 0.216279 -0.829492 -0.514943 -0.216279 0.829492 0.514943 0.14715 0.756149 0.63764 -0.302527 -0.256762 0.917906 -0.995053 -0.0902836 0.0414458 -0.98381 0.0807151 0.160011 -0.982142 0.177028 0.0636994 0.295087 0.54635 0.783853 0.856422 0.0862419 -0.509022 -0.992931 -0.0472293 -0.108891 -0.258664 -0.941987 0.213902 0.122596 0.0405355 0.991628 -0.212753 0.228809 0.949938 -0.0328699 -0.303403 0.952295 -0.409183 -0.157633 0.898733 -0.117759 -0.0931307 0.988666 0.0914646 0.994615 0.0487326 0.0912859 0.841742 0.532107 0.086402 0.95296 0.290519 -0.336813 0.664605 0.666976 -0.574832 0.55026 0.605625 0.113967 0.437036 0.892194 0.071591 0.30831 0.948588 0.0488823 -0.281672 0.958265 0.0924417 -0.451615 0.887411 -0.45108 -0.541865 0.709161 0.0670145 -0.708272 0.702752 -0.185747 -0.852407 0.488775 0.0818824 -0.924804 0.371528 0.0822129 -0.918494 0.386793 -0.653071 0.105291 0.749941 -0.933558 -0.046951 0.355337 -0.379813 0.825451 0.41758 -0.410899 0.824977 0.388039 -0.119658 0.813496 0.569128 0.00849933 0.14947 0.98873 0.0742984 0.117318 0.990311 -0.0719588 -0.544268 0.835819 0.0732708 -0.652176 0.754519 -0.140176 -0.927399 0.346816 0.0323337 -0.981826 0.187011 -0.739779 0.53216 0.411743 -0.828115 0.0673003 0.556504 -0.63341 -0.623056 0.458904 -0.757753 -0.644985 0.0990151 -0.581037 -0.268454 0.768328 -0.759373 -0.412088 0.503523 -0.471064 0.515072 0.716101 -0.554946 0.829042 0.0687331 -0.218164 -0.956884 0.191777 -0.139312 -0.748541 0.648289 -0.117112 -0.19158 0.974465 0.0146148 0.141395 0.989845 -0.145901 0.283506 0.947807 -0.0715703 0.858407 0.507951 -0.0645906 0.983263 0.170356 -0.0149448 -0.99621 0.0856926 -0.0118478 -0.995612 0.0928267 0.0111666 -0.961784 0.273582 -0.00656568 -0.929438 0.368919 0.0112642 -0.875868 0.482419 -0.0164082 -0.810408 0.585637 0.0086047 -0.664718 0.747045 0.0101817 -0.661414 0.749952 -0.0112109 -0.481513 0.876367 0.0245802 -0.345745 0.938007 -0.0277056 -0.197724 0.979866 0.0253077 0.0164498 0.999544 -0.0188766 0.141282 0.989789 0.0106171 0.387332 0.921879 -0.0109728 0.339349 0.940597 0.0120682 0.561172 0.827611 -0.0180868 0.647898 0.761513 0.0115545 0.802317 0.596786 0.0153691 0.807711 0.589378 -0.0124425 0.888861 0.458008 0.00707498 0.967156 0.254086 -0.027615 0.954768 0.296066 0.507837 -0.849673 0.141979 -0.0771448 -0.589623 0.803986 0.845432 -0.438727 0.304571 0.520708 -0.443498 0.729501 0.767415 0.0955112 0.633997 0.71504 0.0547689 0.696935 0.599697 0.502032 0.62316 0.810268 0.568683 0.14165 0.730165 0.629035 0.266785 0.164714 -0.911259 0.37746 -0.182752 -0.8047 0.564853 0.200122 -0.268946 0.942135 -0.253736 0.0878436 0.963277 0.2845 0.581533 0.762154 -0.296172 0.88041 0.370352 -0.955047 -0.261878 0.138941 -0.227448 0.00583485 0.973773 -0.677728 0.719641 0.151004 -0.857193 0.510585 -0.0672527 -0.535255 0.775167 0.335586 0.337256 0.773247 0.53698 -0.430636 0.337052 0.837227 -0.425412 -0.283811 0.859346 0.263442 -0.520807 0.812009 -0.27631 -0.760795 0.587234 0.189212 -0.871321 0.452768 -0.179273 -0.977213 0.113647 0.284005 -0.958582 -0.0215038 0.04364 0.988871 0.142232 0.0320578 0.989775 0.138987 0.0424447 0.737319 0.67421 -0.163315 0.674323 0.72015 0.159469 0.292734 0.942802 0.0100064 0.240935 0.97049 -0.186832 -0.131907 0.973496 0.186483 -0.324139 0.927447 -0.0692319 -0.52142 0.850487 0.0855596 -0.730968 0.677026 -0.0755484 -0.792122 0.605669 0.0221513 -0.956735 0.290118 0.0358526 -0.958038 0.28439 -0.0165014 0.955099 0.295829 -0.0478301 0.956089 0.289148 0.177614 0.763175 0.621302 -0.15969 0.714046 0.681643 -0.294147 0.837161 0.461128 0.653139 0.266736 0.708704 -0.419801 0.0875475 0.903384 0.33641 -0.199538 0.920333 -0.337574 -0.351815 0.873081 -0.0236666 -0.732365 0.6805 -0.317698 -0.737449 0.596017 0.388126 -0.905534 0.171367 -0.0620878 -0.991389 0.115295 -0.0615542 0.964373 0.257284 0.0615562 0.955369 0.28893 -0.0678001 0.795661 0.601936 0.0897919 0.77237 0.628794 -0.145866 0.362242 0.9206 -0.0441865 0.351945 0.934977 0.223389 -0.206531 0.952598 -0.447208 -0.287577 0.846938 0.102223 -0.728731 0.677128 -0.286227 -0.7594 0.584282 0.388126 -0.905534 0.171367 -0.0620878 -0.991389 0.115295 -0.85877 -0.493223 -0.138726 0.894928 -0.394928 -0.20769 -0.858772 -0.49322 -0.138726 0.89493 -0.394926 -0.207689 0.458145 0.0602738 0.886831 -0.377843 -0.139539 0.915294 -0.336956 0.795174 -0.504141 0.756205 -0.447063 0.477796 0.974545 0.22364 -0.0157364 0.9904 0.117931 -0.0721104 -0.453201 -0.854061 -0.25532 0.953792 -0.272242 -0.12714 0.966556 0.153194 0.205674 -0.758005 0.150445 0.634661 0.860848 -0.0746005 0.503364 -0.761257 -0.221232 0.609545 0.974574 0.108396 -0.196102 -0.809751 0.460175 -0.364063 0.812871 0.562955 -0.14941 -0.81517 0.578605 -0.0267401 0.806717 -0.193212 -0.558459 -0.981733 0.0158191 -0.189607 0.856936 -0.48162 0.183582 -0.859723 0.457875 0.226334 0.886051 0.164186 0.43354 0.876664 0.479002 0.0449045 -0.228836 -0.940857 0.249843 -0.970303 -0.0573241 -0.235002 -0.985412 -0.167885 0.027905 -0.981248 -0.00384982 -0.192712 0.984297 0.0432197 0.171148 0.465888 -0.87656 0.120796 -0.94181 -0.0801141 0.326459 -0.528121 -0.337558 -0.779193 -0.780627 0.320334 -0.536663 0.878139 -0.213692 -0.428027 -0.260295 -0.947718 -0.184602 0.518279 0.26731 0.812362 -0.77678 0.0886365 0.623503 0.662607 -0.174611 0.728329 -0.957874 -0.185673 0.219093 0.104488 0.734322 -0.670711 -0.650668 0.597076 -0.469181 0.641776 0.761136 -0.0937785 -0.169346 0.984647 -0.0423413 0.407127 0.294591 -0.86456 -0.352274 0.364134 -0.862154 0.700261 -0.272122 -0.659988 -0.631803 -0.712069 0.306238 0.518277 0.267311 0.812363 -0.776778 0.0886369 0.623506 0.662605 -0.174612 0.728331 -0.957873 -0.185675 0.219097 0.10449 0.734322 -0.670711 -0.650664 0.597079 -0.469183 0.641774 0.761139 -0.0937789 -0.169344 0.984647 -0.0423414 0.407121 0.294593 -0.864562 -0.352268 0.364135 -0.862156 -0.6318 -0.712072 0.306239 -0.359856 -0.844687 -0.396241 0.594748 -0.64587 -0.478671 -0.474776 -0.480681 -0.737247 0.305017 -0.234601 -0.922999 0.0939301 -0.167812 -0.981334 -0.00860366 0.285172 -0.958438 -0.0544986 0.293214 -0.954492 -0.276272 0.676284 -0.682872 0.433764 0.715301 -0.547898 -0.265754 0.948841 -0.170518 0.0715804 0.992067 -0.103345 -0.359856 -0.844687 -0.396241 0.524572 -0.694979 -0.49176 -0.409031 -0.498384 -0.7644 0.372852 -0.296654 -0.879191 -0.488823 0.0281616 -0.871929 -0.0401379 0.172365 -0.984215 0.469599 0.53048 -0.705739 -0.254852 0.663422 -0.703507 0.00991815 0.984869 -0.173015 0.0705548 0.983945 -0.163931 -0.0412389 -0.990225 -0.133241 0.0839758 -0.980756 -0.176254 -0.0839756 -0.731691 -0.676444 0.0196114 -0.708915 -0.705021 -0.0229418 -0.376463 -0.926148 0.0920445 -0.31964 -0.943058 -0.185346 0.0428048 -0.981741 0.132844 0.179288 -0.974786 0.0477677 0.569024 -0.820932 -0.178796 0.624363 -0.760396 0.158265 0.893928 -0.41934 -0.0941182 0.942194 -0.321578 0.999999 -0.00119661 0.000825059 0.999998 -0.000944946 -0.00161335 0.995911 -0.0818631 -0.038216 0.999617 -0.00185437 -0.0276228 1 -0.00011738 0.000585565 1 0.00017807 -0.000307895 1 -0.000155201 -0.000296072 1 4.66882e-05 0.000423095 0.999993 0.00033726 -0.00367458 0.999985 0.00534998 0.000804109 0.999991 0.00410476 0.000619533 0.999975 0.00495751 -0.0049721 1 -5.4911e-07 -2.93825e-05 1 0.000257684 -0.000168126 0.999999 -0.0011721 0.000229078 1 0.00023012 0.000144077 0.999999 0.00128164 -5.96608e-06 1 0.000294786 -5.72485e-05 1 0.000100074 -0.000439217 0.999999 -0.00108265 -0.000529742 -0.999934 -0.00522432 -0.0102508 1 0.000110462 0.000216741 0.999976 -0.00673326 0.00186629 0.999983 -0.00576624 -0.00100505 1 1.06591e-05 1.86478e-05 1 8.21347e-06 0.000158534 1 0.000345519 -0.000238461 1 0.000294793 -0.000148691 0.999998 0.00195584 -0.000278993 0.999995 -0.00329485 0.000463995 -1 1.38728e-05 0.000117918 1 1.02445e-05 -0.000108156 1 1.16475e-05 0.000164123 1 -1.51247e-08 -0.000148521 1 1.08796e-05 9.24762e-05 1 7.99443e-06 9.33073e-05 0.999997 0.00194025 0.001224 0.999996 -0.00282587 0.000233522 1 -0.000555343 2.29821e-07 -0.465518 -0.796621 -0.385602 -0.143363 -0.197623 -0.969738 -0.0127259 0.351497 -0.936102 -0.112593 0.333137 -0.936132 0.156894 0.775623 -0.611386 -0.474157 0.790124 -0.388432 0.43192 0.889978 -0.146232 -0.667429 0.189398 -0.720185 -0.33786 -0.674532 -0.656397 -0.940571 -0.313563 0.1304 -0.960356 0.242281 -0.137897 0.999991 -0.00379566 0.00164687 0.99997 0.00768628 0.00085224 0.999939 0.00649923 -0.00898169 0.999985 0.00541198 -0.000607764 0.999957 0.00566441 0.00738236 0.999977 -0.00192297 0.00657454 0.999937 -0.00688546 0.00885276 0.999879 -0.0011366 -0.0155329 0.999843 -0.0141422 -0.0106799 0.237751 0.9654 -0.107132 -0.238949 0.79379 -0.559287 0.161601 0.565048 -0.809077 -0.0893359 -0.0486877 -0.994811 -0.166972 -0.0924029 -0.981622 0.197277 -0.787939 -0.583295 -0.1548 -0.895772 -0.41669 0.593713 0.800896 -0.0779124 0.757192 0.526637 -0.386412 0.652859 0.540307 -0.53089 0.601749 0.174144 -0.779469 0.793974 -0.0454021 -0.606254 0.496818 -0.511316 -0.701233 0.749386 -0.605732 -0.267412 1 0 0 0.999968 -0.00235855 -0.00762628 0.999955 -0.000861953 0.00949974 0.999961 -0.00758253 -0.00444388 0.999992 0.00048082 -0.00391104 0.999891 -0.00240046 -0.0146031 0.999983 0.00460688 0.00348692 0.999943 0.00562889 -0.00902222 0.999055 0.0103683 -0.0422123 0.999956 -0.00762027 0.00551969 1 -0.000370086 -2.54387e-05 0.999999 -0.00168895 0.000105972 0.999758 0.0214326 0.00503701 0.999987 -0.00344391 -0.00369489 0.992967 -0.037925 0.112151 0.999929 0.0116189 -0.00278585 0.804047 0.524295 0.280398 0.996815 9.50667e-05 0.0797447 0.999306 -0.0298953 -0.0222093 -0.999031 0.0433727 0.0074943 0.996771 -0.0768811 -0.0231667 0.999998 -0.00182057 0.000934383 0.999131 -0.0396268 -0.0129528 0.999882 0.00675213 -0.0138034 0.999854 0.0134807 0.0105416 0.999849 0.0168222 -0.004387 0.997292 -0.00883123 -0.0730158 0.99902 0.0402685 0.0183529 0.913749 -0.343119 0.217562 -0.999997 0.000509208 -0.0023517 -0.999998 -5.7354e-05 -0.00181019 -0.999999 0.00126209 -0.000631812 -1 0.000663674 -0.000605953 -1 8.78612e-05 -0.000285197 -1 8.53136e-05 -0.000287248 -0.999999 -0.00146437 -0.000187739 -1 -0.000356443 -0.000502242 -0.999999 -0.000817684 -0.000706583 -0.999999 -0.000846872 -0.00079093 -0.999999 -0.00170105 0.000364931 -0.999984 -0.00361095 -0.00442013 -0.999634 -0.0269367 0.0026278 0.833382 -0.552692 -0.00226652 -0.999998 -0.00203191 -9.70554e-05 -0.999999 -0.00123231 0.000548276 -1 -0.000588757 0.000523881 -1 -0.000153359 0.000282003 -1 -0.000137234 0.000314481 -0.999957 -0.0018989 -0.00913077 -0.999977 -0.00376366 -0.00557618 -0.999426 -0.0336337 -0.00401792 -0.999157 -0.0332368 -0.024081 0.038612 0.999254 0.000233399 -0.999919 0.0124915 -0.00263427 -0.999994 0.000670625 0.00351009 -0.999307 0.00564813 -0.0367903 -0.999936 0.0110829 -0.00232021 -0.99989 0.0147038 -0.00172467 -0.999915 0.0122863 -0.00434363 -0.999998 -0.000578993 -0.00208624 -1 -0.000849298 5.0354e-05 -0.999995 0.00323905 -0.000238416 -0.999971 0.00656393 0.00392269 -0.998823 0.0122485 0.0469409 -0.999996 -0.00278252 0.000308764 -0.999998 5.73761e-05 0.0018116 -0.999997 -0.000469231 0.00231491 -0.999999 0.00134109 8.33071e-05 -0.999861 -0.0098438 0.0134213 -0.999307 0.03347 0.0163152 -0.999092 0.0254957 -0.0341379 -0.00103081 0.997761 -0.0668699 -0.00307726 0.963583 -0.267393 -0.00121145 0.961845 -0.273592 -0.00273379 0.908699 -0.417443 0.00970962 0.875882 -0.482428 -0.0155089 0.804713 -0.593461 0.00886524 0.666425 -0.74552 0.0110124 0.661408 -0.749945 -0.0139057 0.523764 -0.85175 0.00807268 0.35764 -0.933825 0.0119361 0.345836 -0.938219 -0.0135354 0.180364 -0.983507 0.00971231 -0.0207458 -0.999738 0.00738338 -0.0164556 -0.999837 -0.0106655 -0.34571 -0.938281 -0.0143553 -0.339338 -0.940555 0.0162682 -0.561138 -0.827562 -0.028386 -0.660574 -0.750224 0.0251391 -0.807552 -0.589261 -0.0189919 -0.874916 -0.483902 0.0099624 -0.969112 -0.246418 -0.0116192 -0.955083 -0.296112 0.00864762 -0.995747 -0.0917266 0.00481932 0.997504 -0.0704484 -0.143975 0.957322 -0.250611 -0.119835 0.956613 -0.265578 -0.116409 0.745924 -0.655779 -0.0942743 0.4577 -0.884095 -0.0679065 0.126076 -0.989694 -0.00213884 -0.0207905 -0.999782 -0.150343 -0.17945 -0.972211 0.0972411 -0.343154 -0.934232 -0.0928599 -0.65762 -0.747605 -0.229527 -0.683431 -0.692993 0.0495831 -0.873716 -0.483902 -0.0524761 -0.955707 -0.289603 -0.999998 -0.000317249 0.00189553 -0.999997 0.00213805 -0.000846364 -0.999994 0.00230343 -0.00256792 -0.999996 -0.00235718 0.00154113 -0.998978 -0.023382 -0.0386927 -0.999997 0.00151415 0.0021644 -0.999996 0.00186182 0.00203667 -1 -0.00019289 -0.000565316 -0.999998 0.000595743 -0.00200309 -0.999998 -0.000178757 -0.00209245 -0.999998 0.00145423 -0.00125268 -0.999994 -0.00297193 0.00182131 -0.999996 0.00127602 0.00266013 -0.999998 0.00046779 -0.00170062 -0.999994 -0.00301273 0.00177702 -0.999994 -0.00290533 0.00181302 -0.999999 -0.00119025 0.000133092 -0.999999 -0.00121923 8.08626e-05 -0.773853 -0.564032 -0.288131 -0.512999 -0.587591 -0.625755 -0.808112 -0.0584652 -0.58612 -0.633634 0.587076 -0.503835 -0.752154 0.652179 -0.0944758 -0.748138 0.430709 -0.504756 -0.628325 0.092071 -0.772483 -0.614128 -0.786692 -0.0629456 -0.0971401 -0.923978 -0.369903 0.094357 -0.875665 -0.473611 -0.133878 -0.426807 -0.894378 0.216492 -0.11506 -0.969481 -0.221884 0.337036 -0.914972 0.165331 0.662374 -0.730702 -0.11773 0.89333 -0.433707 0.0837458 0.989828 -0.115013 -0.930453 0.221546 -0.291848 -0.928383 -0.281699 -0.242386 -0.998066 0.058829 0.0200866 -0.999328 0.0321957 -0.017533 -0.997454 0.0448886 -0.0554145 -0.995868 -0.0727221 -0.0543991 -0.999686 0.0014631 -0.0250351 -0.999702 0.0160056 0.0184423 -0.998547 -0.0132788 0.0522318 -0.999349 -0.0357163 0.00501664 -0.999342 -0.0359309 0.00493212 0.916888 -0.399015 -0.0101134 -0.999351 -0.0166726 0.0319342 -0.394112 -0.89325 -0.216285 -0.0371058 0.302517 -0.952422 -0.414689 0.158785 -0.896002 0.12537 -0.0389082 -0.991347 -0.113238 0.0920805 -0.989292 -0.247388 -0.247272 -0.936833 -0.151095 0.979246 -0.135084 -0.0970719 0.948258 -0.302299 0.115451 -0.992795 -0.0320828 -0.042827 -0.937529 -0.345262 -0.154507 -0.902653 -0.401679 0.0255716 -0.697868 -0.71577 0.0207552 -0.389802 -0.920665 0.0179386 -0.335304 -0.941939 0.0410604 0.282675 -0.958337 0.0737974 0.455362 -0.887243 -0.501368 0.540838 -0.67537 0.0609501 0.709208 -0.702359 -0.0144783 0.916345 -0.400128 0.0508037 0.9281 -0.368848 0.050752 0.928693 -0.367359 0.998751 0.040224 -0.0296393 0.999209 -0.0329889 0.0222027 0.999998 -0.00145662 -0.00134664 0.999996 0.000253579 -0.00290184 1 6.00904e-05 -0.000244936 0.999999 -0.00147108 0.000502091 0.999998 0.00168348 -0.000962505 0.999983 0.00570668 0.000700011 1 0.000494326 0.000731116 0.999999 0.000887016 0.00140831 0.999999 0.000425056 0.00144535 0.999996 9.87339e-05 0.00295128 1 -8.91171e-05 0.00058205 0.999994 0.000384593 0.00335561 1 -0.000356365 0.0004161 0.999084 -0.0339467 0.0260701 0.999998 0.00178067 -0.000528667 0.99994 -0.0107847 0.00174253 0.999725 -0.0232274 -0.00312539 0.999231 -0.00368741 0.0390354 0.999667 -0.0249829 -0.00646485 0.999997 0.000584191 -0.0022371 0.999999 -0.00124892 -0.000833001 1 -0.000148495 -0.000365316 0.999998 -0.0014651 -0.00153118 0.999978 0.00623986 0.00220324 0.998559 0.0231629 -0.0484087 0.99197 -0.123362 0.0278733 0.688322 0.0318248 -0.724707 0.993299 0.0687288 0.0929186 0.995684 -0.0927671 0.00277692 -0.995684 0.0927671 -0.00277692 -0.979743 0.0536904 0.192926 0.999072 0.04058 0.0144248 0.997833 0.0650362 0.0100333 0.980963 -0.166276 -0.100316 0.992791 0.119296 0.0116034 -0.408349 0.875478 -0.258437 0.534907 -0.62995 0.563061 0.999984 -0.00548963 0.00150187 -0.996063 0.0828527 -0.031539 0.99466 -0.030804 -0.0985013 0.997866 -0.0113876 0.0642877 0.99651 -0.00894039 -0.0829895 0.978674 0.0711203 -0.192715 0.996759 0.00036621 0.080446 -0.295087 -0.54635 -0.783853 -0.965288 0.163923 -0.203341 -0.14715 -0.756149 -0.63764 0.331038 -0.943585 -0.00780261 0.00708064 -0.999975 0.000292653 -0.00702379 -0.999974 0.00153354 0.00236765 0.000101835 0.999997 -0.00284431 -0.000122336 0.999996 -0.00714566 0.999974 0.000255062 0.00272315 0.999996 -0.000413834 -0.282909 0.908212 -0.308404 0.0312044 0.963701 -0.265155 0.163843 -0.648952 -0.742978 0.313316 -0.605924 -0.731224 0.422891 -0.45846 -0.781651 -0.441046 -0.194599 -0.876134 0.0242573 -0.131541 -0.991014 0.410443 0.133686 -0.902034 -0.428896 0.366309 -0.825752 -0.0966781 0.496847 -0.862436 -0.129439 0.636727 -0.760148 0.380222 0.667587 -0.640124 -0.40876 -0.785851 -0.464062 0.378992 -0.877874 -0.292751 -0.169812 -0.977379 -0.126075 -0.999998 0.00194987 0.00078555 -0.999996 -0.00037098 -0.0029111 -0.99995 -0.00948819 0.0030485 -0.998489 -0.0459627 -0.0301081 -0.998468 0.0357379 -0.0422408 -0.999359 0.0174694 0.03125 -1 -0.000115693 -0.000434624 -1 -0.000316006 -0.000691997 -0.999999 -0.000964584 -0.0014366 -0.999999 -0.000925145 -0.000994944 -0.999999 -0.000605354 -0.00138434 -0.999996 0.00279199 -0.00101659 -1 0.00102542 -5.21986e-05 -0.999999 0.00153018 -0.000220621 -0.999999 -0.000394552 -0.00102652 -1 -0.000259212 -0.00095816 -0.999998 0.000761663 -0.00198656 -0.99999 -0.00254319 -0.00373095 -0.999992 -0.000656822 -0.00384233 -1 -4.78363e-05 -1.55703e-05 -0.999999 -0.00120981 -0.000706388 -0.999965 -0.00318805 0.00773237 -1 -0.000143849 0.000303594 -0.999991 -0.000421466 0.00430833 -0.999999 -0.00119298 5.90569e-05 -1 -0.000715151 0.00023891 -1 0.000879591 -0.000130492 -1 -1.67269e-07 -3.24945e-06 -1 -4.09596e-06 -8.38398e-06 -1 -7.03069e-05 0.000117251 -1 -1.89888e-05 1.81894e-06 -1 1.27442e-05 -2.29053e-07 -0.999995 0.00303294 0.000801108 -0.999999 0.00118721 -0.000109871 0.999991 -0.00308482 0.00296865 -1 3.46261e-05 4.08441e-05 -1 -2.07157e-05 0.000203197 1 0 0 -1 -1.39272e-05 0.00027234 -1 -1.27987e-06 5.17232e-06 1 0.000730801 -0.000289463 -0.999997 -0.00197846 0.00170026 -0.999999 0.00153581 -1.08851e-05 -0.00973345 -0.989545 0.143894 -0.473536 -0.844727 0.249398 0.414232 -0.362471 0.834881 0.486517 0.784765 0.383986 -0.487762 0.383203 0.784375 0.999867 0.0147817 -0.00691596 0.783826 -0.445467 0.432639 0.497219 -0.654189 -0.569921 0.705297 0.42078 -0.570527 0.999997 0.000365593 0.00257407 0.999837 -9.54635e-05 0.0180702 -0.975537 -0.102189 0.194641 -0.0149675 0.999887 0.00104124 0.233682 0.972205 -0.0145331 0.527046 0.845455 -0.0861883 0.0052817 0.000137579 0.999986 -0.00179671 -0.000136899 0.999998 0.00653728 -0.999973 0.00351102 -0.91751 0.18357 -0.352812 -0.689201 0.688952 -0.224382 -0.52222 -0.852636 -0.0172557 -0.822605 -0.268501 -0.501227 0.182525 -0.323012 -0.928627 0.749213 0.0322751 -0.661543 0.0390051 0.323422 -0.945451 0.252566 -0.118589 -0.960285 0.283671 0.0746558 -0.956011 -0.0136721 0.000589223 -0.999906 0 0 -1 0.807124 0.582173 0.0981079 0.349966 0.933436 -0.0788746 -0.0863724 0.996261 0.00216334 0.84034 0.250601 0.480654 0.364129 -0.930312 0.0439287 0.683179 -0.616933 0.390717 -0.487526 -0.700853 0.520695 0.967351 0.0578904 0.246741 0.759002 -0.188919 0.623078 0.256079 0.290997 0.921816 -0.0188408 -0.0548918 0.998315 0.309786 -0.938612 -0.151787 0.0299239 -0.999552 -0.000723745 0.793593 -0.606895 -0.043467 0.280873 0.724434 0.629528 -0.42584 0.446798 0.786786 0.514665 -0.400001 0.758366 -0.500336 -0.76712 0.401486 0.958229 0.229737 -0.170345 0.99898 -0.0440103 -0.0100778 0.993234 0.101468 -0.0564945 0.999283 0.00512549 -0.0375228 0.98635 0.157729 -0.0472812 0.701725 -0.387857 -0.59762 0.714591 -0.384083 -0.584671 1 -0.000466123 -0.000223383 0.99999 -0.00397315 -0.0018638 0.999999 -0.00155051 -0.000367598 1 -1.87779e-05 6.13349e-05 1 -0.000181613 -0.000185918 1 3.18748e-05 3.26304e-05 0.999928 0.0120074 -6.02076e-05 1 -0.000158656 -0.00024334 1 -0.000140336 0.000104849 0.999859 -0.00354392 -0.016412 1 -2.6217e-05 4.78852e-05 1 1.91676e-06 -3.50094e-06 0.999197 -0.0220823 0.0334176 0.995153 0.0471486 -0.0863011 1 0.000229806 0.000546685 0.999999 -0.00159914 2.37932e-05 0.999998 -0.0018439 0.00021444 0.999999 -0.00100825 -0.000602296 1 -0.000564881 -0.000150704 1 0.000507197 0.000136675 1 0.00056578 0.000265406 1 0.000351399 0.00010692 1 -0.000745663 0.000134004 0.999999 0.00081515 -0.000823091 0.998206 0.0450895 0.0393895 1 -9.13394e-05 -0.000374769 1 -3.62668e-05 -0.000148804 0.984068 -0.14101 0.10829 1 5.71086e-05 8.75907e-05 1 6.30951e-05 0.000187953 1 1.31308e-05 0.000333651 1 0 0 1 5.56067e-07 -1.51564e-07 1 5.82375e-06 -0.000212267 0.999999 0.000720425 -0.000918794 0.99336 -0.0709881 0.0905347 0.994973 0.0843356 0.0540034 0.993653 -0.0234815 0.110014 1 1.49972e-05 -1.74413e-06 -1 0.000404409 -7.65321e-05 -0.987575 0.121829 0.0992649 -0.999999 -0.000820681 0.00109182 -0.999999 -0.000813413 0.000666557 -1 8.05871e-05 -7.60422e-06 -1 0.000784943 0.000104847 -0.990903 0.0833408 0.105669 -0.999537 -0.0223034 0.0206855 -0.999518 -0.0234429 0.0203612 -1 3.35294e-05 -4.8488e-05 -1 -0.000424097 -0.000128259 -0.998122 0.0502734 0.0350028 -0.995014 -0.0842324 0.0534012 -1 1.77445e-05 2.60842e-05 -1 2.15674e-05 3.17037e-05 -1 -0.000628088 0.000104643 -1 7.43044e-05 -0.000137996 -0.999999 -0.000508061 0.000943554 0.454674 0.821037 0.345209 1 -0.000534006 -0.000180056 1 0.000507197 0.000136675 0.999998 0.00116044 0.0015721 0.999991 -0.00366477 -0.00200444 0.997912 0.0496939 0.0412657 0.999999 0.000632034 -0.00103543 1 0 0 1 -0.00071707 -6.50114e-05 0.984129 -0.140576 0.108301 0.999988 -0.00439268 -0.00200325 0.992532 -0.00269464 -0.121952 1 -0.000530906 0.000442086 0.999999 0.000542497 0.00164866 0.999998 -0.000461503 0.00192716 1 0.000598704 0.00013223 0.999999 0.000764323 -0.0010477 0.995281 -0.0571897 0.0783929 0.992855 0.026354 -0.116378 0.993653 -0.0234816 0.110015 1 1.49972e-05 -1.74413e-06 -1 0.000404409 -7.65321e-05 -0.987575 0.12183 0.0992658 -0.999998 -0.00117968 0.00153332 -1 -1.25307e-06 -2.06701e-05 -1 0.000784943 0.000104847 -0.990903 0.0833405 0.10567 -0.999537 -0.0223041 0.0206853 -0.999518 -0.0234429 0.0203612 -0.999998 -0.00150351 0.00115164 -1 3.35294e-05 -4.84879e-05 -1 -0.000425741 -0.000128756 -0.99826 0.0386718 -0.0445135 -0.992035 -0.0799917 0.0973041 -1 1.8167e-05 2.67052e-05 -1 2.15674e-05 3.17038e-05 -1 -0.000592582 6.17303e-05 -1 -3.53712e-05 -0.000133804 -1 0.000119061 0.000450391 0.454668 0.82104 0.34521 0.768293 0.0472068 0.638355 -0.764268 0.588651 0.263411 -0.49373 0.830452 0.258033 0.310986 -0.939938 0.14073 -0.910096 -0.0746992 -0.407608 -0.641141 -0.648291 -0.41068 -0.82609 -0.554869 0.09847 0.702037 -0.224351 0.675878 0.440589 0.130663 0.888149 -0.46107 0.849797 0.255461 -0.493731 0.830451 0.258032 0.310988 -0.939937 0.14073 -0.934049 -0.0286779 -0.355991 -0.938155 0.167487 -0.303009 -0.582241 -0.606275 -0.541689 -0.831706 -0.545749 0.10209 0.711752 -0.221031 0.666749 -0.975669 -0.18004 -0.125123 -0.972748 -0.147207 -0.17914 0.782534 -0.611201 -0.118632 0.425748 -0.543728 -0.723256 0.672765 -0.110357 -0.731579 0.666039 0.469723 -0.579441 0.99821 0.0541998 -0.0252889 0.937549 -0.321861 -0.131938 -0.051135 -0.341189 0.938603 -0.0162241 0.947616 -0.319 -1 -4.91213e-05 0.000552828 -1 0.000627064 7.74165e-05 -1 0.000219004 -0.00014141 -1 -0.000160438 -8.24594e-05 -1 -7.08143e-06 -1.27262e-06 -0.999045 -0.0436981 0.000461844 -0.999999 -0.000639813 0.00092306 -0.994982 -0.0102669 -0.0995261 -1 -0.000675962 -0.000481996 -1 -0.000133669 0.000678186 -0.995799 0.0166345 -0.0900451 -0.989018 0.000494173 -0.147795 -0.9976 0.0395189 0.0568539 -0.997056 0.00307424 -0.0766183 -1 -0.000142818 0.00016298 -1 0.00011108 6.27229e-05 -1 0 0 -1 0.00010321 0.000417897 -1 -2.97153e-05 0.000377645 -0.999999 -0.000683115 0.000934747 + + + + + + + + + + + + + + +

367 0 111 0 105 0 159 1 168 1 357 1 10 2 358 2 168 2 168 3 358 3 166 3 166 4 9 4 167 4 11 5 12 5 14 5 311 6 233 6 36 6 70 7 224 7 223 7 70 8 223 8 224 8 73 9 220 9 209 9 263 10 273 10 225 10 263 11 225 11 273 11 181 12 207 12 18 12 30 13 99 13 5 13 11 14 205 14 170 14 170 15 205 15 11 15 352 16 203 16 165 16 22 17 23 17 24 17 20 18 27 18 144 18 191 19 99 19 27 19 189 20 248 20 96 20 189 21 96 21 102 21 187 22 92 22 359 22 185 23 94 23 186 23 110 24 355 24 15 24 167 25 9 25 113 25 113 26 9 26 112 26 167 27 354 27 11 27 205 28 354 28 113 28 113 29 354 29 167 29 111 30 10 30 168 30 111 31 168 31 159 31 10 32 111 32 358 32 358 33 111 33 112 33 166 34 358 34 112 34 166 35 112 35 9 35 11 36 354 36 205 36 205 37 12 37 11 37 12 38 205 38 13 38 12 39 13 39 14 39 15 40 14 40 13 40 14 41 15 41 174 41 174 42 15 42 355 42 17 43 155 43 151 43 153 44 16 44 148 44 21 45 16 45 153 45 21 46 153 46 155 46 21 47 155 47 19 47 19 48 155 48 17 48 17 49 151 49 144 49 21 50 139 50 16 50 19 51 18 51 21 51 144 52 20 52 17 52 17 53 20 53 138 53 18 54 19 54 138 54 138 55 19 55 17 55 21 56 18 56 207 56 21 57 207 57 139 57 137 58 125 58 126 58 126 59 127 59 8 59 129 60 130 60 22 60 22 61 130 61 25 61 22 62 25 62 26 62 22 63 26 63 23 63 23 64 131 64 24 64 24 65 131 65 107 65 137 66 118 66 125 66 125 67 118 67 119 67 125 68 119 68 6 68 125 69 6 69 126 69 126 70 6 70 106 70 126 71 106 71 127 71 127 72 106 72 8 72 8 73 106 73 104 73 8 74 104 74 128 74 128 75 104 75 115 75 128 76 115 76 129 76 129 77 115 77 114 77 129 78 114 78 130 78 130 79 114 79 25 79 25 80 114 80 7 80 25 81 7 81 103 81 25 82 103 82 26 82 26 83 103 83 23 83 23 84 103 84 109 84 23 85 109 85 131 85 131 86 109 86 107 86 107 87 109 87 108 87 192 88 30 88 5 88 192 89 92 89 29 89 192 90 29 90 30 90 30 91 31 91 99 91 99 92 31 92 27 92 27 93 31 93 28 93 90 94 28 94 31 94 29 95 89 95 83 95 29 96 83 96 30 96 30 97 83 97 32 97 30 98 32 98 31 98 84 99 31 99 32 99 86 100 90 100 84 100 84 101 90 101 31 101 81 102 80 102 79 102 35 103 82 103 79 103 79 104 80 104 35 104 35 105 33 105 82 105 78 106 156 106 154 106 80 107 34 107 35 107 270 108 77 108 307 108 270 109 307 109 231 109 231 110 307 110 313 110 231 111 313 111 36 111 36 112 313 112 311 112 233 113 311 113 308 113 233 114 308 114 219 114 219 115 308 115 37 115 219 116 37 116 3 116 3 117 37 117 321 117 3 118 321 118 227 118 384 119 178 119 38 119 384 120 38 120 377 120 377 121 38 121 381 121 38 122 169 122 381 122 381 123 169 123 382 123 382 124 169 124 39 124 39 125 170 125 382 125 382 126 170 126 380 126 380 127 170 127 171 127 380 128 171 128 371 128 371 129 171 129 173 129 371 130 173 130 172 130 371 131 172 131 370 131 304 132 278 132 276 132 304 133 276 133 340 133 340 134 276 134 281 134 340 135 281 135 40 135 40 136 281 136 296 136 296 137 281 137 380 137 296 138 380 138 284 138 296 139 284 139 341 139 341 140 284 140 64 140 335 141 286 141 291 141 335 142 291 142 327 142 327 143 291 143 41 143 327 144 41 144 333 144 333 145 41 145 326 145 326 146 41 146 347 146 326 147 347 147 294 147 326 148 294 148 322 148 322 149 294 149 42 149 43 150 325 150 324 150 43 151 324 151 318 151 44 152 299 152 298 152 44 153 298 153 342 153 360 154 362 154 361 154 361 155 362 155 36 155 361 156 36 156 56 156 363 157 234 157 366 157 365 158 366 158 220 158 282 159 369 159 372 159 282 160 372 160 277 160 45 161 46 161 47 161 45 162 47 162 48 162 48 163 47 163 385 163 49 164 378 164 279 164 279 165 378 165 383 165 279 166 383 166 275 166 275 167 383 167 376 167 53 168 379 168 49 168 49 169 379 169 378 169 50 170 54 170 282 170 275 171 376 171 51 171 276 172 51 172 381 172 276 173 381 173 45 173 45 174 381 174 46 174 282 175 54 175 369 175 277 176 372 176 52 176 277 177 52 177 55 177 283 178 55 178 68 178 283 179 68 179 53 179 53 180 68 180 379 180 48 181 385 181 380 181 380 182 54 182 50 182 365 183 220 183 234 183 365 184 234 184 363 184 361 185 56 185 362 185 292 186 300 186 290 186 290 187 300 187 346 187 290 188 346 188 345 188 57 189 306 189 287 189 287 190 306 190 305 190 287 191 305 191 0 191 0 192 305 192 1 192 293 193 344 193 57 193 57 194 344 194 306 194 289 195 303 195 348 195 295 196 58 196 341 196 314 197 334 197 312 197 312 198 334 198 59 198 312 199 59 199 60 199 317 200 337 200 61 200 61 201 337 201 336 201 61 202 336 202 2 202 2 203 336 203 329 203 316 204 332 204 317 204 317 205 332 205 337 205 318 206 330 206 349 206 320 207 319 207 322 207 322 208 42 208 323 208 323 209 42 209 62 209 323 210 62 210 289 210 323 211 289 211 339 211 339 212 289 212 63 212 339 213 63 213 331 213 331 214 63 214 285 214 331 215 285 215 328 215 328 216 285 216 288 216 328 217 288 217 335 217 335 218 288 218 286 218 341 219 64 219 297 219 297 220 64 220 280 220 297 221 280 221 283 221 297 222 283 222 343 222 343 223 283 223 302 223 302 224 283 224 65 224 302 225 65 225 66 225 66 226 65 226 67 226 66 227 67 227 304 227 304 228 67 228 278 228 370 229 172 229 164 229 370 230 164 230 373 230 373 231 164 231 176 231 373 232 176 232 52 232 52 233 176 233 175 233 52 234 175 234 68 234 68 235 175 235 165 235 68 236 165 236 374 236 374 237 165 237 375 237 375 238 165 238 69 238 375 239 69 239 384 239 384 240 69 240 178 240 211 241 74 241 73 241 216 242 263 242 255 242 255 243 263 243 244 243 244 244 263 244 241 244 241 245 263 245 213 245 241 246 213 246 70 246 70 247 214 247 241 247 214 248 261 248 241 248 241 249 261 249 240 249 274 250 71 250 215 250 215 251 71 251 240 251 215 252 240 252 261 252 75 253 76 253 250 253 264 254 218 254 72 254 218 255 264 255 251 255 4 256 71 256 262 256 71 257 4 257 249 257 73 258 218 258 251 258 210 259 267 259 4 259 4 260 212 260 210 260 71 261 274 261 262 261 72 262 216 262 255 262 216 263 72 263 218 263 268 264 211 264 73 264 268 265 73 265 250 265 250 266 73 266 251 266 251 267 264 267 72 267 251 268 72 268 255 268 76 269 75 269 211 269 268 270 250 270 76 270 268 271 76 271 211 271 211 272 267 272 210 272 75 273 267 273 211 273 75 274 249 274 267 274 267 275 249 275 4 275 212 276 4 276 262 276 212 277 262 277 274 277 227 278 321 278 309 278 227 279 309 279 273 279 310 280 316 280 272 280 272 281 316 281 271 281 271 282 316 282 315 282 315 283 77 283 270 283 33 284 35 284 156 284 78 285 154 285 34 285 80 286 78 286 34 286 82 287 33 287 156 287 81 288 156 288 78 288 81 289 78 289 80 289 82 290 156 290 81 290 83 291 89 291 79 291 84 292 79 292 86 292 87 293 82 293 81 293 86 294 79 294 87 294 79 295 82 295 87 295 32 296 79 296 84 296 32 297 83 297 79 297 81 298 79 298 89 298 81 299 89 299 87 299 89 300 85 300 87 300 86 301 91 301 90 301 87 302 91 302 86 302 85 303 88 303 87 303 87 304 88 304 91 304 88 305 85 305 89 305 88 306 89 306 29 306 185 307 28 307 90 307 185 308 90 308 91 308 185 309 91 309 206 309 206 310 91 310 101 310 91 311 88 311 101 311 29 312 92 312 88 312 95 313 101 313 88 313 95 314 88 314 92 314 95 315 92 315 188 315 93 316 182 316 95 316 95 317 182 317 101 317 182 318 93 318 364 318 182 319 364 319 184 319 185 320 206 320 94 320 94 321 206 321 184 321 94 322 184 322 364 322 364 323 363 323 94 323 28 324 185 324 98 324 98 325 185 325 186 325 359 326 93 326 95 326 359 327 95 327 188 327 359 328 92 328 248 328 248 329 92 329 96 329 92 330 192 330 96 330 192 331 5 331 102 331 99 332 245 332 190 332 99 333 190 333 5 333 245 334 247 334 190 334 247 335 246 335 97 335 98 336 100 336 28 336 99 337 100 337 245 337 359 338 248 338 360 338 97 339 246 339 102 339 94 340 98 340 186 340 206 341 101 341 184 341 102 342 5 342 97 342 102 343 246 343 189 343 189 344 246 344 248 344 121 345 205 345 113 345 121 346 113 346 197 346 121 347 196 347 205 347 205 348 196 348 120 348 205 349 120 349 13 349 13 350 120 350 195 350 112 351 198 351 197 351 198 352 112 352 199 352 199 353 112 353 111 353 199 354 111 354 200 354 200 355 111 355 105 355 200 356 105 356 201 356 201 357 105 357 119 357 201 358 119 358 118 358 163 359 6 359 119 359 115 360 104 360 203 360 203 361 104 361 106 361 203 362 106 362 163 362 163 363 106 363 6 363 7 364 114 364 162 364 7 365 162 365 103 365 103 366 162 366 160 366 103 367 160 367 109 367 194 368 107 368 108 368 194 369 108 369 368 369 368 370 108 370 109 370 368 371 109 371 160 371 194 372 368 372 110 372 159 373 119 373 105 373 105 374 111 374 159 374 113 375 112 375 197 375 194 376 15 376 13 376 194 377 13 377 195 377 110 378 15 378 194 378 116 379 202 379 162 379 116 380 162 380 114 380 114 381 115 381 116 381 116 382 115 382 203 382 117 383 163 383 119 383 117 384 119 384 158 384 158 385 119 385 159 385 132 386 107 386 194 386 132 387 194 387 195 387 132 388 195 388 134 388 134 389 195 389 120 389 134 390 120 390 133 390 133 391 120 391 196 391 133 392 196 392 135 392 135 393 196 393 121 393 135 394 121 394 183 394 183 395 121 395 122 395 122 396 121 396 197 396 122 397 197 397 123 397 123 398 197 398 198 398 123 399 198 399 199 399 123 400 199 400 136 400 136 401 199 401 124 401 124 402 199 402 200 402 124 403 200 403 137 403 137 404 200 404 201 404 137 405 201 405 118 405 24 406 107 406 132 406 134 407 133 407 135 407 183 408 122 408 123 408 123 409 136 409 193 409 193 410 136 410 124 410 193 411 124 411 137 411 135 412 183 412 18 412 138 413 134 413 18 413 134 414 138 414 24 414 24 415 138 415 20 415 207 416 183 416 123 416 207 417 123 417 193 417 18 418 134 418 135 418 140 419 129 419 22 419 140 420 22 420 20 420 20 421 22 421 24 421 193 422 139 422 207 422 142 423 126 423 8 423 129 424 140 424 143 424 129 425 143 425 128 425 142 426 8 426 143 426 143 427 8 427 128 427 126 428 142 428 139 428 139 429 193 429 126 429 144 430 140 430 20 430 141 431 143 431 145 431 16 432 139 432 147 432 147 433 139 433 142 433 143 434 141 434 142 434 142 435 141 435 147 435 145 436 143 436 140 436 145 437 140 437 144 437 144 438 151 438 150 438 144 439 150 439 145 439 145 440 150 440 152 440 145 441 152 441 141 441 141 442 152 442 146 442 141 443 146 443 147 443 147 444 146 444 148 444 147 445 148 445 16 445 180 446 148 446 146 446 180 447 146 447 152 447 152 448 150 448 149 448 149 449 150 449 151 449 154 450 180 450 34 450 180 451 154 451 153 451 180 452 153 452 148 452 149 453 35 453 152 453 34 454 180 454 35 454 152 455 35 455 180 455 149 456 156 456 35 456 153 457 154 457 156 457 153 458 156 458 155 458 156 459 149 459 151 459 151 460 155 460 156 460 368 461 161 461 110 461 177 462 356 462 352 462 356 463 116 463 203 463 177 464 157 464 116 464 177 465 116 465 356 465 116 466 157 466 202 466 357 467 158 467 159 467 117 468 158 468 357 468 161 469 355 469 110 469 350 470 161 470 368 470 350 471 368 471 160 471 350 472 160 472 162 472 162 473 202 473 351 473 351 474 202 474 157 474 352 475 356 475 203 475 203 476 353 476 352 476 353 477 203 477 163 477 353 478 163 478 179 478 179 479 163 479 117 479 179 480 117 480 204 480 204 481 117 481 357 481 179 482 69 482 352 482 14 483 171 483 11 483 164 484 350 484 176 484 175 485 177 485 165 485 165 486 352 486 69 486 69 487 204 487 178 487 168 488 38 488 357 488 357 489 38 489 178 489 38 490 168 490 169 490 169 491 168 491 166 491 169 492 166 492 39 492 39 493 166 493 167 493 170 494 39 494 11 494 167 495 11 495 39 495 171 496 170 496 11 496 171 497 14 497 173 497 173 498 174 498 172 498 350 499 164 499 355 499 355 500 164 500 172 500 174 501 173 501 14 501 172 502 174 502 355 502 351 503 177 503 175 503 350 504 351 504 176 504 176 505 351 505 175 505 165 506 177 506 352 506 204 507 357 507 178 507 179 508 204 508 69 508 181 509 101 509 182 509 181 510 184 510 101 510 183 511 182 511 184 511 181 512 182 512 183 512 181 513 183 513 184 513 187 514 359 514 188 514 92 515 187 515 188 515 102 516 96 516 192 516 190 517 97 517 5 517 190 518 247 518 97 518 27 519 28 519 191 519 191 520 28 520 100 520 191 521 100 521 99 521 27 522 20 522 144 522 24 523 132 523 134 523 193 524 137 524 126 524 165 525 203 525 352 525 207 526 181 526 183 526 181 527 18 527 183 527 208 528 218 528 73 528 208 529 73 529 209 529 210 530 221 530 211 530 235 531 211 531 221 531 236 532 212 532 228 532 228 533 212 533 274 533 215 534 229 534 228 534 215 535 228 535 274 535 216 536 226 536 225 536 216 537 225 537 263 537 263 538 225 538 213 538 213 539 225 539 223 539 213 540 223 540 70 540 70 541 223 541 214 541 214 542 223 542 222 542 214 543 222 543 261 543 261 544 222 544 229 544 261 545 229 545 215 545 216 546 217 546 226 546 217 547 216 547 218 547 217 548 218 548 208 548 36 549 362 549 231 549 233 550 366 550 234 550 366 551 219 551 3 551 234 552 220 552 269 552 233 553 232 553 56 553 232 554 362 554 56 554 272 555 225 555 273 555 226 556 273 556 225 556 229 557 222 557 270 557 270 558 222 558 271 558 224 559 223 559 225 559 271 560 222 560 223 560 271 561 223 561 224 561 271 562 224 562 272 562 224 563 225 563 272 563 208 564 265 564 217 564 273 565 226 565 217 565 273 566 217 566 227 566 219 567 366 567 233 567 233 568 234 568 266 568 36 569 233 569 56 569 227 570 217 570 265 570 227 571 265 571 3 571 230 572 229 572 270 572 230 573 228 573 229 573 362 574 221 574 236 574 209 575 235 575 269 575 362 576 236 576 230 576 230 577 236 577 228 577 270 578 231 578 230 578 362 579 232 579 221 579 230 580 231 580 362 580 221 581 232 581 233 581 221 582 233 582 266 582 234 583 221 583 266 583 221 584 269 584 235 584 221 585 234 585 269 585 220 586 209 586 269 586 3 587 265 587 208 587 3 588 208 588 366 588 366 589 208 589 220 589 220 590 208 590 209 590 209 591 73 591 74 591 209 592 74 592 235 592 235 593 74 593 211 593 212 594 236 594 210 594 210 595 236 595 221 595 242 596 237 596 239 596 242 597 239 597 238 597 238 598 239 598 243 598 243 599 239 599 260 599 243 600 260 600 259 600 249 601 239 601 71 601 71 602 239 602 237 602 71 603 237 603 253 603 239 604 75 604 260 604 260 605 75 605 250 605 251 606 257 606 259 606 241 607 240 607 252 607 253 608 240 608 71 608 255 609 257 609 251 609 241 610 254 610 244 610 254 611 241 611 258 611 258 612 241 612 252 612 238 613 362 613 360 613 238 614 360 614 242 614 93 615 362 615 238 615 365 616 364 616 243 616 243 617 364 617 238 617 238 618 364 618 93 618 98 619 365 619 243 619 98 620 243 620 256 620 254 621 245 621 244 621 245 622 100 622 244 622 244 623 100 623 256 623 256 624 100 624 98 624 237 625 248 625 253 625 248 626 246 626 253 626 253 627 246 627 252 627 252 628 246 628 258 628 247 629 258 629 246 629 245 630 254 630 247 630 247 631 254 631 258 631 242 632 360 632 248 632 237 633 242 633 248 633 239 634 249 634 75 634 260 635 250 635 259 635 259 636 250 636 251 636 252 637 240 637 253 637 255 638 244 638 256 638 255 639 256 639 257 639 257 640 243 640 259 640 257 641 256 641 243 641 73 642 209 642 220 642 271 643 315 643 270 643 310 644 272 644 309 644 309 645 272 645 273 645 275 646 276 646 278 646 64 647 282 647 280 647 280 648 282 648 277 648 67 649 275 649 278 649 65 650 49 650 67 650 49 651 279 651 67 651 67 652 279 652 275 652 284 653 380 653 50 653 280 654 277 654 283 654 277 655 55 655 283 655 48 656 380 656 281 656 45 657 48 657 281 657 275 658 51 658 276 658 281 659 276 659 45 659 49 660 65 660 53 660 53 661 65 661 283 661 284 662 50 662 282 662 284 663 282 663 64 663 0 664 291 664 286 664 295 665 44 665 42 665 42 666 44 666 62 666 62 667 44 667 342 667 288 668 0 668 286 668 285 669 57 669 288 669 0 670 301 670 291 670 57 671 287 671 288 671 288 672 287 672 0 672 294 673 347 673 58 673 62 674 342 674 289 674 345 675 347 675 41 675 292 676 290 676 41 676 41 677 290 677 345 677 41 678 291 678 292 678 57 679 285 679 293 679 293 680 285 680 63 680 348 681 63 681 289 681 58 682 295 682 294 682 294 683 295 683 42 683 301 684 304 684 340 684 66 685 306 685 302 685 306 686 344 686 302 686 297 687 343 687 298 687 297 688 298 688 341 688 341 689 298 689 299 689 301 690 1 690 304 690 346 691 40 691 296 691 58 692 296 692 341 692 340 693 40 693 300 693 303 694 343 694 302 694 40 695 346 695 300 695 1 696 305 696 304 696 304 697 305 697 66 697 66 698 305 698 306 698 0 699 1 699 301 699 2 700 313 700 307 700 320 701 43 701 321 701 2 702 307 702 77 702 321 703 43 703 309 703 309 704 43 704 318 704 2 705 338 705 313 705 317 706 61 706 315 706 315 707 61 707 77 707 77 708 61 708 2 708 37 709 308 709 319 709 309 710 318 710 310 710 318 711 349 711 310 711 60 712 308 712 311 712 314 713 312 713 311 713 311 714 312 714 60 714 311 715 313 715 314 715 317 716 315 716 316 716 349 717 316 717 310 717 319 718 320 718 37 718 37 719 320 719 321 719 338 720 335 720 327 720 328 721 337 721 331 721 337 722 332 722 331 722 323 723 339 723 324 723 323 724 324 724 322 724 322 725 324 725 325 725 338 726 329 726 335 726 59 727 333 727 326 727 319 728 326 728 322 728 327 729 333 729 334 729 330 730 339 730 331 730 333 731 59 731 334 731 329 732 336 732 335 732 335 733 336 733 328 733 328 734 336 734 337 734 2 735 329 735 338 735 313 736 338 736 327 736 313 737 327 737 314 737 314 738 327 738 334 738 320 739 322 739 43 739 43 740 322 740 325 740 318 741 324 741 339 741 349 742 330 742 316 742 316 743 330 743 331 743 316 744 331 744 332 744 60 745 59 745 308 745 308 746 59 746 326 746 308 747 326 747 319 747 291 748 301 748 340 748 291 749 340 749 292 749 292 750 340 750 300 750 295 751 341 751 44 751 44 752 341 752 299 752 342 753 298 753 289 753 289 754 298 754 343 754 348 755 303 755 63 755 63 756 303 756 302 756 63 757 302 757 293 757 293 758 302 758 344 758 345 759 346 759 347 759 347 760 346 760 296 760 347 761 296 761 58 761 303 762 289 762 343 762 330 763 318 763 339 763 161 764 350 764 355 764 351 765 350 765 162 765 351 766 157 766 177 766 352 767 353 767 179 767 361 768 93 768 359 768 361 769 359 769 360 769 362 770 93 770 361 770 366 771 94 771 363 771 363 772 364 772 365 772 366 773 365 773 98 773 366 774 98 774 94 774 367 775 105 775 111 775 369 776 371 776 370 776 371 777 369 777 54 777 373 778 52 778 372 778 373 779 372 779 369 779 373 780 369 780 370 780 381 781 51 781 377 781 378 782 374 782 375 782 378 783 379 783 374 783 51 784 376 784 377 784 55 785 52 785 68 785 379 786 68 786 374 786 385 787 382 787 380 787 380 788 371 788 54 788 381 789 382 789 46 789 377 790 376 790 384 790 376 791 383 791 384 791 384 792 383 792 375 792 382 793 47 793 46 793 385 794 47 794 382 794 375 795 383 795 378 795 454 796 574 796 388 796 572 797 538 797 549 797 572 798 549 798 453 798 453 799 549 799 428 799 486 800 425 800 575 800 535 801 543 801 534 801 555 802 159 802 386 802 472 803 562 803 389 803 472 804 389 804 562 804 401 805 495 805 491 805 396 806 500 806 392 806 465 807 499 807 495 807 465 808 495 808 401 808 461 809 395 809 460 809 396 810 392 810 495 810 521 811 400 811 466 811 521 812 466 812 393 812 393 813 466 813 469 813 393 814 469 814 480 814 480 815 469 815 479 815 479 816 469 816 464 816 479 817 464 817 397 817 479 818 397 818 398 818 398 819 397 819 399 819 398 820 399 820 470 820 470 821 399 821 471 821 400 822 526 822 466 822 472 823 399 823 463 823 526 824 459 824 465 824 451 825 490 825 442 825 442 826 490 826 402 826 442 827 402 827 447 827 455 828 492 828 391 828 455 829 391 829 452 829 452 830 391 830 403 830 403 831 391 831 496 831 403 832 496 832 448 832 448 833 496 833 494 833 448 834 494 834 449 834 449 835 494 835 390 835 449 836 390 836 404 836 404 837 390 837 564 837 564 838 390 838 493 838 564 839 493 839 490 839 564 840 490 840 451 840 405 841 552 841 508 841 506 842 431 842 435 842 394 843 555 843 553 843 394 844 553 844 436 844 556 845 436 845 482 845 554 846 507 846 481 846 554 847 481 847 406 847 513 848 515 848 407 848 544 849 434 849 478 849 544 850 478 850 536 850 556 851 482 851 537 851 537 852 482 852 507 852 537 853 507 853 435 853 406 854 481 854 515 854 406 855 515 855 551 855 513 856 407 856 549 856 549 857 407 857 434 857 549 858 434 858 548 858 536 859 478 859 510 859 457 860 562 860 389 860 562 861 416 861 389 861 416 862 562 862 579 862 416 863 579 863 530 863 456 864 110 864 426 864 456 865 426 865 458 865 563 866 458 866 426 866 563 867 426 867 579 867 579 868 426 868 408 868 579 869 408 869 530 869 419 870 530 870 408 870 419 871 408 871 535 871 535 872 420 872 419 872 420 873 535 873 534 873 420 874 534 874 425 874 409 875 575 875 425 875 409 876 484 876 575 876 484 877 409 877 418 877 418 878 409 878 417 878 417 879 432 879 561 879 410 880 487 880 531 880 432 881 531 881 561 881 411 882 532 882 432 882 532 883 410 883 432 883 432 884 410 884 531 884 444 885 386 885 159 885 444 886 159 886 441 886 567 887 450 887 441 887 567 888 430 888 566 888 566 889 430 889 565 889 578 890 412 890 387 890 428 891 429 891 453 891 427 892 110 892 576 892 576 893 110 893 456 893 453 894 429 894 414 894 414 895 429 895 413 895 414 896 413 896 427 896 414 897 427 897 577 897 387 898 550 898 446 898 446 899 550 899 573 899 446 900 573 900 445 900 565 901 430 901 415 901 415 902 430 902 431 902 415 903 431 903 412 903 415 904 412 904 578 904 567 905 441 905 159 905 425 906 543 906 534 906 425 907 534 907 420 907 420 908 534 908 543 908 511 909 510 909 421 909 511 910 421 910 540 910 542 911 439 911 477 911 542 912 477 912 543 912 546 913 483 913 438 913 405 914 437 914 423 914 405 915 423 915 552 915 552 916 423 916 533 916 540 917 421 917 539 917 539 918 421 918 439 918 539 919 439 919 440 919 543 920 477 920 483 920 543 921 483 921 546 921 438 922 483 922 559 922 559 923 483 923 422 923 559 924 422 924 437 924 559 925 437 925 508 925 533 926 423 926 436 926 533 927 436 927 553 927 424 928 417 928 409 928 409 929 425 929 534 929 579 930 408 930 426 930 579 931 426 931 539 931 427 932 574 932 110 932 573 933 538 933 428 933 429 934 428 934 413 934 412 935 406 935 571 935 571 936 387 936 412 936 567 937 568 937 430 937 430 938 568 938 537 938 533 939 386 939 411 939 555 940 394 940 556 940 431 941 506 941 554 941 435 942 507 942 506 942 545 943 433 943 438 943 433 944 545 944 546 944 440 945 439 945 509 945 509 946 542 946 440 946 541 947 511 947 540 947 511 948 541 948 510 948 510 949 541 949 536 949 434 950 512 950 547 950 434 951 547 951 548 951 550 952 514 952 513 952 551 953 515 953 514 953 514 954 550 954 551 954 416 955 530 955 527 955 444 956 441 956 443 956 387 957 446 957 570 957 450 958 443 958 441 958 442 959 447 959 532 959 443 960 450 960 451 960 443 961 451 961 442 961 570 962 449 962 569 962 569 963 449 963 404 963 570 964 448 964 449 964 565 965 569 965 404 965 565 966 404 966 564 966 450 967 564 967 451 967 569 968 565 968 415 968 569 969 415 969 578 969 570 970 446 970 445 970 570 971 445 971 572 971 577 972 453 972 414 972 570 973 572 973 448 973 448 974 572 974 403 974 403 975 572 975 453 975 403 976 453 976 452 976 577 977 454 977 453 977 453 978 454 978 452 978 452 979 454 979 455 979 455 980 454 980 388 980 457 981 455 981 456 981 456 982 455 982 388 982 456 983 388 983 576 983 457 984 456 984 458 984 457 985 389 985 455 985 455 986 389 986 492 986 459 987 396 987 465 987 465 988 396 988 499 988 401 989 395 989 461 989 461 990 460 990 503 990 524 991 503 991 497 991 524 992 497 992 525 992 463 993 461 993 503 993 501 994 462 994 525 994 462 995 459 995 526 995 503 996 472 996 463 996 472 997 503 997 468 997 468 998 503 998 524 998 468 999 524 999 467 999 467 1000 524 1000 525 1000 467 1001 525 1001 462 1001 462 1002 526 1002 400 1002 463 1003 399 1003 461 1003 461 1004 399 1004 464 1004 461 1005 464 1005 401 1005 401 1006 464 1006 465 1006 465 1007 464 1007 469 1007 465 1008 469 1008 466 1008 465 1009 466 1009 526 1009 468 1010 473 1010 472 1010 462 1011 400 1011 476 1011 462 1012 476 1012 475 1012 462 1013 475 1013 474 1013 462 1014 474 1014 467 1014 472 1015 471 1015 399 1015 399 1016 397 1016 464 1016 472 1017 517 1017 516 1017 516 1018 470 1018 471 1018 516 1019 471 1019 472 1019 517 1020 472 1020 473 1020 468 1021 517 1021 473 1021 468 1022 518 1022 517 1022 467 1023 519 1023 468 1023 468 1024 519 1024 518 1024 474 1025 520 1025 467 1025 467 1026 520 1026 519 1026 475 1027 520 1027 474 1027 400 1028 521 1028 476 1028 475 1029 476 1029 520 1029 519 1030 483 1030 518 1030 518 1031 483 1031 477 1031 518 1032 477 1032 517 1032 517 1033 477 1033 439 1033 517 1034 439 1034 516 1034 516 1035 439 1035 421 1035 516 1036 421 1036 470 1036 470 1037 421 1037 510 1037 470 1038 510 1038 478 1038 470 1039 478 1039 398 1039 398 1040 478 1040 434 1040 398 1041 434 1041 479 1041 479 1042 434 1042 407 1042 479 1043 407 1043 515 1043 479 1044 515 1044 480 1044 480 1045 515 1045 481 1045 480 1046 481 1046 393 1046 393 1047 481 1047 507 1047 393 1048 507 1048 521 1048 521 1049 507 1049 482 1049 521 1050 482 1050 436 1050 521 1051 436 1051 476 1051 476 1052 436 1052 423 1052 476 1053 423 1053 520 1053 520 1054 423 1054 437 1054 520 1055 437 1055 422 1055 520 1056 422 1056 519 1056 519 1057 422 1057 483 1057 558 1058 484 1058 418 1058 484 1059 558 1059 575 1059 489 1060 557 1060 486 1060 489 1061 486 1061 488 1061 560 1062 488 1062 558 1062 558 1063 488 1063 486 1063 558 1064 486 1064 575 1064 485 1065 560 1065 531 1065 531 1066 560 1066 561 1066 420 1067 557 1067 419 1067 505 1068 419 1068 489 1068 489 1069 419 1069 557 1069 485 1070 487 1070 560 1070 560 1071 487 1071 529 1071 560 1072 529 1072 488 1072 488 1073 529 1073 528 1073 488 1074 528 1074 489 1074 489 1075 528 1075 527 1075 489 1076 527 1076 505 1076 527 1077 523 1077 498 1077 498 1078 389 1078 527 1078 527 1079 389 1079 416 1079 402 1080 500 1080 487 1080 500 1081 522 1081 487 1081 487 1082 522 1082 529 1082 529 1083 522 1083 528 1083 528 1084 522 1084 523 1084 528 1085 523 1085 527 1085 495 1086 496 1086 491 1086 491 1087 496 1087 391 1087 491 1088 391 1088 492 1088 491 1089 492 1089 498 1089 498 1090 492 1090 389 1090 500 1091 402 1091 490 1091 500 1092 490 1092 392 1092 392 1093 490 1093 493 1093 392 1094 493 1094 390 1094 392 1095 390 1095 495 1095 495 1096 390 1096 494 1096 495 1097 494 1097 496 1097 523 1098 522 1098 502 1098 523 1099 502 1099 497 1099 523 1100 497 1100 504 1100 498 1101 504 1101 460 1101 498 1102 460 1102 491 1102 491 1103 460 1103 395 1103 491 1104 395 1104 401 1104 495 1105 499 1105 396 1105 500 1106 396 1106 459 1106 500 1107 459 1107 501 1107 500 1108 501 1108 522 1108 503 1109 460 1109 504 1109 503 1110 504 1110 497 1110 497 1111 502 1111 525 1111 525 1112 502 1112 522 1112 525 1113 522 1113 501 1113 462 1114 501 1114 459 1114 402 1115 532 1115 447 1115 487 1116 485 1116 531 1116 530 1117 419 1117 527 1117 527 1118 419 1118 505 1118 394 1119 436 1119 556 1119 506 1120 507 1120 554 1120 405 1121 508 1121 437 1121 438 1122 433 1122 546 1122 542 1123 509 1123 439 1123 434 1124 544 1124 512 1124 514 1125 515 1125 513 1125 523 1126 504 1126 498 1126 402 1127 487 1127 410 1127 402 1128 410 1128 532 1128 568 1129 567 1129 555 1129 555 1130 567 1130 159 1130 406 1131 412 1131 431 1131 571 1132 550 1132 387 1132 547 1133 427 1133 413 1133 547 1134 413 1134 428 1134 534 1135 543 1135 409 1135 545 1136 409 1136 546 1136 554 1137 406 1137 431 1137 408 1138 440 1138 542 1138 408 1139 542 1139 535 1139 535 1140 542 1140 543 1140 551 1141 571 1141 406 1141 110 1142 541 1142 426 1142 571 1143 551 1143 550 1143 568 1144 555 1144 556 1144 543 1145 546 1145 409 1145 386 1146 533 1146 553 1146 110 1147 536 1147 541 1147 574 1148 536 1148 110 1148 555 1149 386 1149 553 1149 568 1150 556 1150 537 1150 547 1151 428 1151 549 1151 549 1152 548 1152 547 1152 559 1153 508 1153 417 1153 537 1154 435 1154 430 1154 427 1155 512 1155 574 1155 574 1156 512 1156 544 1156 440 1157 579 1157 539 1157 426 1158 541 1158 539 1158 539 1159 541 1159 540 1159 508 1160 432 1160 417 1160 431 1161 430 1161 435 1161 408 1162 579 1162 440 1162 552 1163 533 1163 411 1163 549 1164 538 1164 513 1164 536 1165 574 1165 544 1165 547 1166 512 1166 427 1166 409 1167 545 1167 424 1167 424 1168 545 1168 438 1168 573 1169 550 1169 513 1169 573 1170 513 1170 538 1170 438 1171 559 1171 424 1171 432 1172 508 1172 552 1172 432 1173 552 1173 411 1173 557 1174 420 1174 543 1174 557 1175 543 1175 486 1175 486 1176 543 1176 425 1176 424 1177 418 1177 417 1177 558 1178 418 1178 424 1178 558 1179 424 1179 560 1179 560 1180 424 1180 559 1180 560 1181 559 1181 561 1181 561 1182 559 1182 417 1182 579 1183 562 1183 539 1183 539 1184 457 1184 563 1184 563 1185 457 1185 458 1185 539 1186 562 1186 457 1186 450 1187 567 1187 568 1187 450 1188 568 1188 564 1188 564 1189 568 1189 537 1189 564 1190 537 1190 565 1190 565 1191 537 1191 566 1191 567 1192 566 1192 568 1192 568 1193 566 1193 537 1193 569 1194 578 1194 406 1194 569 1195 406 1195 570 1195 570 1196 406 1196 571 1196 570 1197 571 1197 387 1197 406 1198 578 1198 571 1198 571 1199 578 1199 387 1199 572 1200 573 1200 538 1200 538 1201 573 1201 428 1201 454 1202 427 1202 574 1202 574 1203 427 1203 576 1203 574 1204 576 1204 388 1204 442 1205 411 1205 533 1205 442 1206 533 1206 443 1206 443 1207 533 1207 444 1207 444 1208 533 1208 386 1208 386 1209 533 1209 411 1209 427 1210 454 1210 577 1210 573 1211 572 1211 445 1211 411 1212 442 1212 532 1212 411 1213 533 1213 386 1213 411 1214 386 1214 533 1214 539 1215 563 1215 579 1215 3035 1216 580 1216 738 1216 3056 1217 717 1217 3053 1217 3040 1218 580 1218 3035 1218 3035 1219 3036 1219 3038 1219 3038 1220 3036 1220 3039 1220 743 1221 745 1221 3034 1221 743 1222 3034 1222 3033 1222 3037 1223 3033 1223 749 1223 2858 1224 821 1224 2998 1224 2998 1225 821 1225 820 1225 2864 1226 822 1226 2996 1226 2992 1227 2993 1227 1891 1227 2992 1228 1891 1228 2993 1228 828 1229 2965 1229 857 1229 2856 1230 899 1230 585 1230 2855 1231 910 1231 898 1231 2853 1232 919 1232 922 1232 2853 1233 922 1233 917 1233 2852 1234 586 1234 920 1234 587 1235 880 1235 2918 1235 587 1236 2918 1236 880 1236 2845 1237 2873 1237 2846 1237 2817 1238 830 1238 829 1238 2817 1239 829 1239 589 1239 589 1240 829 1240 2812 1240 589 1241 2812 1241 3513 1241 855 1242 3464 1242 591 1242 855 1243 591 1243 590 1243 590 1244 591 1244 2842 1244 590 1245 2842 1245 592 1245 592 1246 2842 1246 2921 1246 2759 1247 2760 1247 1876 1247 2764 1248 655 1248 593 1248 593 1249 655 1249 594 1249 2754 1250 1871 1250 2753 1250 2744 1251 970 1251 2720 1251 928 1252 2727 1252 1805 1252 939 1253 1863 1253 2697 1253 2697 1254 1863 1254 936 1254 739 1255 2716 1255 1861 1255 951 1256 661 1256 2694 1256 596 1257 954 1257 953 1257 2673 1258 1437 1258 2670 1258 1001 1259 2689 1259 932 1259 1740 1260 2677 1260 1442 1260 982 1261 3777 1261 2803 1261 2790 1262 4072 1262 2793 1262 2310 1263 2311 1263 740 1263 2700 1264 2308 1264 2307 1264 957 1265 599 1265 2306 1265 2344 1266 599 1266 957 1266 2342 1267 601 1267 1455 1267 602 1268 603 1268 2303 1268 2283 1269 3539 1269 2653 1269 2283 1270 2653 1270 2576 1270 605 1271 3931 1271 1003 1271 605 1272 1003 1272 1007 1272 605 1273 1007 1273 3933 1273 2272 1274 2058 1274 2273 1274 606 1275 2057 1275 1045 1275 1155 1276 2175 1276 1154 1276 1132 1277 607 1277 2266 1277 1066 1278 772 1278 608 1278 608 1279 1250 1279 1066 1279 1066 1280 1250 1280 1064 1280 1064 1281 2128 1281 2230 1281 2230 1282 2128 1282 1197 1282 1055 1283 609 1283 610 1283 610 1284 2126 1284 1055 1284 1055 1285 2126 1285 2127 1285 1055 1286 2127 1286 1056 1286 1056 1287 2127 1287 814 1287 814 1288 2127 1288 815 1288 1252 1289 2070 1289 1203 1289 1203 1290 1253 1290 1252 1290 1252 1291 1253 1291 1209 1291 1209 1292 1253 1292 2125 1292 1209 1293 2125 1293 611 1293 611 1294 2125 1294 1207 1294 613 1295 1214 1295 612 1295 612 1296 2122 1296 613 1296 613 1297 2122 1297 614 1297 614 1298 2123 1298 615 1298 615 1299 2123 1299 2068 1299 807 1300 616 1300 716 1300 2131 1301 617 1301 618 1301 807 1302 716 1302 714 1302 714 1303 716 1303 617 1303 617 1304 716 1304 715 1304 617 1305 715 1305 618 1305 708 1306 705 1306 2132 1306 809 1307 765 1307 804 1307 2132 1308 704 1308 708 1308 765 1309 708 1309 2121 1309 765 1310 2121 1310 804 1310 1196 1311 1198 1311 1062 1311 1062 1312 1198 1312 2118 1312 1062 1313 2118 1313 2208 1313 2208 1314 2118 1314 1248 1314 2208 1315 1248 1315 1164 1315 1057 1316 1625 1316 1200 1316 1057 1317 1200 1317 1058 1317 1249 1318 1201 1318 1058 1318 1350 1319 2047 1319 1072 1319 1072 1320 2047 1320 2049 1320 1072 1321 2049 1321 2048 1321 1072 1322 2048 1322 2055 1322 1287 1323 621 1323 620 1323 620 1324 621 1324 2046 1324 620 1325 2046 1325 1068 1325 1068 1326 2046 1326 621 1326 1068 1327 621 1327 1102 1327 623 1328 729 1328 1158 1328 2134 1329 624 1329 2011 1329 1158 1330 2044 1330 623 1330 624 1331 623 1331 2045 1331 624 1332 2045 1332 2011 1332 1335 1333 1048 1333 1116 1333 1116 1334 625 1334 1335 1334 1335 1335 625 1335 1356 1335 1356 1336 2043 1336 1358 1336 1358 1337 2043 1337 2023 1337 627 1338 626 1338 1108 1338 1108 1339 1106 1339 627 1339 627 1340 1106 1340 2042 1340 627 1341 2042 1341 1074 1341 1074 1342 2042 1342 628 1342 628 1343 2042 1343 2226 1343 1326 1344 2026 1344 2228 1344 2228 1345 1331 1345 1326 1345 1326 1346 1331 1346 2041 1346 1326 1347 2041 1347 629 1347 629 1348 2041 1348 1334 1348 629 1349 1334 1349 1100 1349 1100 1350 1334 1350 630 1350 631 1351 2029 1351 2031 1351 2031 1352 1359 1352 631 1352 631 1353 1359 1353 1047 1353 1047 1354 1359 1354 1337 1354 1047 1355 1337 1355 632 1355 632 1356 1337 1356 1109 1356 2137 1357 2136 1357 2040 1357 1160 1358 633 1358 733 1358 2137 1359 2040 1359 634 1359 634 1360 2040 1360 633 1360 633 1361 2040 1361 1344 1361 633 1362 1344 1362 733 1362 1495 1363 1496 1363 1908 1363 1908 1364 1496 1364 1495 1364 1887 1365 637 1365 639 1365 639 1366 637 1366 638 1366 639 1367 638 1367 1419 1367 1419 1368 638 1368 2828 1368 1419 1369 2828 1369 640 1369 640 1370 2828 1370 1422 1370 1422 1371 2828 1371 2839 1371 1422 1372 2839 1372 641 1372 641 1373 2839 1373 642 1373 641 1374 642 1374 1418 1374 1418 1375 642 1375 1881 1375 1881 1376 642 1376 2829 1376 1428 1377 2823 1377 644 1377 644 1378 2823 1378 643 1378 644 1379 643 1379 1423 1379 1423 1380 643 1380 2816 1380 1423 1381 2816 1381 1431 1381 1431 1382 2816 1382 645 1382 645 1383 2816 1383 2824 1383 645 1384 2824 1384 646 1384 646 1385 2824 1385 1426 1385 1426 1386 2824 1386 2818 1386 1426 1387 2818 1387 1415 1387 1415 1388 2818 1388 2820 1388 1875 1389 2755 1389 2783 1389 2765 1390 655 1390 2767 1390 1073 1391 2216 1391 2215 1391 2159 1392 1626 1392 1060 1392 958 1393 1612 1393 2694 1393 2799 1394 2798 1394 924 1394 924 1395 2798 1395 2459 1395 2792 1396 2795 1396 2796 1396 923 1397 2416 1397 2788 1397 2788 1398 2416 1398 2790 1398 1460 1399 2436 1399 1462 1399 1462 1400 2436 1400 2453 1400 1462 1401 1464 1401 2454 1401 2805 1402 1459 1402 2807 1402 712 1403 717 1403 3056 1403 3057 1404 3056 1404 1457 1404 619 1405 1450 1405 3060 1405 619 1406 3060 1406 3055 1406 3058 1407 3055 1407 3059 1407 1470 1408 1469 1408 1402 1408 1463 1409 1465 1409 3078 1409 3078 1410 1465 1410 1472 1410 670 1411 668 1411 1411 1411 669 1412 1405 1412 670 1412 669 1413 670 1413 1406 1413 1406 1414 670 1414 1411 1414 1395 1415 671 1415 1394 1415 1391 1416 672 1416 1393 1416 1393 1417 672 1417 1395 1417 1393 1418 1395 1418 1394 1418 1524 1419 1516 1419 1396 1419 1396 1420 1516 1420 1397 1420 1620 1421 1619 1421 1520 1421 1620 1422 1520 1422 1617 1422 3085 1423 3083 1423 1286 1423 1286 1424 3083 1424 1347 1424 1345 1425 3085 1425 1286 1425 1075 1426 1096 1426 3085 1426 1289 1427 1075 1427 1345 1427 1345 1428 1075 1428 3085 1428 1096 1429 1293 1429 1089 1429 1096 1430 1089 1430 3085 1430 3085 1431 1089 1431 673 1431 3085 1432 673 1432 1294 1432 3085 1433 1340 1433 680 1433 680 1434 1340 1434 1341 1434 676 1435 1607 1435 674 1435 1347 1436 3083 1436 674 1436 674 1437 3083 1437 676 1437 622 1438 734 1438 676 1438 678 1439 676 1439 680 1439 680 1440 1295 1440 675 1440 680 1441 675 1441 678 1441 1086 1442 2065 1442 676 1442 1291 1443 1086 1443 1078 1443 1078 1444 1086 1444 676 1444 1078 1445 676 1445 677 1445 677 1446 676 1446 678 1446 677 1447 678 1447 679 1447 622 1448 676 1448 2065 1448 676 1449 734 1449 1607 1449 1295 1450 680 1450 1342 1450 1340 1451 3085 1451 3084 1451 3084 1452 3085 1452 1294 1452 3082 1453 1610 1453 2354 1453 3082 1454 2354 1454 3081 1454 3081 1455 2354 1455 1890 1455 683 1456 1456 1456 3082 1456 1195 1457 1169 1457 3080 1457 3080 1458 1169 1458 682 1458 3080 1459 682 1459 3082 1459 1247 1460 683 1460 3082 1460 1190 1461 1247 1461 681 1461 681 1462 1247 1462 3082 1462 681 1463 3082 1463 1178 1463 1178 1464 3082 1464 682 1464 1178 1465 682 1465 1192 1465 684 1466 1259 1466 686 1466 686 1467 1259 1467 3080 1467 686 1468 3081 1468 1168 1468 1168 1469 3081 1469 1890 1469 1264 1470 685 1470 686 1470 1191 1471 1264 1471 1244 1471 1244 1472 1264 1472 686 1472 1244 1473 686 1473 1168 1473 1260 1474 687 1474 686 1474 1260 1475 686 1475 1187 1475 1187 1476 686 1476 685 1476 1187 1477 685 1477 1193 1477 1456 1478 1610 1478 3082 1478 1194 1479 1195 1479 1257 1479 1257 1480 1195 1480 3080 1480 1257 1481 3080 1481 1259 1481 687 1482 1175 1482 1258 1482 684 1483 686 1483 1258 1483 1258 1484 686 1484 687 1484 2290 1485 2320 1485 2285 1485 2285 1486 2320 1486 2291 1486 688 1487 2291 1487 2293 1487 688 1488 2293 1488 2287 1488 2287 1489 2293 1489 2294 1489 2287 1490 2294 1490 2327 1490 2286 1491 2327 1491 689 1491 2286 1492 689 1492 2330 1492 2330 1493 689 1493 2295 1493 690 1494 2300 1494 2296 1494 690 1495 2296 1495 2336 1495 2336 1496 2296 1496 2297 1496 691 1497 2297 1497 2298 1497 691 1498 2298 1498 692 1498 692 1499 2298 1499 693 1499 692 1500 693 1500 2288 1500 2288 1501 2299 1501 694 1501 694 1502 2299 1502 2301 1502 694 1503 2301 1503 1606 1503 2295 1504 2319 1504 3079 1504 2300 1505 2322 1505 2321 1505 1606 1506 2324 1506 1600 1506 2295 1507 3079 1507 2334 1507 1806 1508 1401 1508 695 1508 1807 1509 695 1509 1809 1509 1809 1510 695 1510 696 1510 1809 1511 696 1511 1488 1511 697 1512 1488 1512 1486 1512 697 1513 1486 1513 2723 1513 2723 1514 1486 1514 698 1514 2723 1515 698 1515 2724 1515 2724 1516 698 1516 699 1516 2724 1517 699 1517 1869 1517 1869 1518 699 1518 1484 1518 1869 1519 1484 1519 1814 1519 2740 1520 1482 1520 1480 1520 2740 1521 1480 1521 2734 1521 2734 1522 1480 1522 700 1522 2734 1523 700 1523 1813 1523 1815 1524 1811 1524 701 1524 1815 1525 701 1525 702 1525 1815 1526 702 1526 1806 1526 1806 1527 702 1527 1401 1527 706 1528 3058 1528 704 1528 706 1529 704 1529 2149 1529 2149 1530 704 1530 2132 1530 2191 1531 2121 1531 703 1531 703 1532 2121 1532 3059 1532 3059 1533 2121 1533 704 1533 3059 1534 704 1534 3058 1534 2133 1535 705 1535 707 1535 707 1536 705 1536 708 1536 3058 1537 706 1537 707 1537 707 1538 708 1538 1266 1538 1266 1539 708 1539 765 1539 1266 1540 765 1540 803 1540 765 1541 3023 1541 803 1541 1622 1542 1168 1542 2119 1542 2119 1543 619 1543 709 1543 1622 1544 2119 1544 2115 1544 2115 1545 2119 1545 709 1545 2119 1546 1890 1546 1450 1546 2119 1547 1168 1547 1890 1547 2119 1548 1450 1548 619 1548 1456 1549 710 1549 1457 1549 1456 1550 2120 1550 710 1550 1457 1551 710 1551 3057 1551 683 1552 2120 1552 1456 1552 2150 1553 618 1553 711 1553 711 1554 618 1554 715 1554 711 1555 715 1555 712 1555 718 1556 712 1556 617 1556 718 1557 617 1557 2130 1557 2130 1558 617 1558 2131 1558 3057 1559 710 1559 1269 1559 2120 1560 2111 1560 710 1560 710 1561 2111 1561 1269 1561 808 1562 714 1562 713 1562 713 1563 714 1563 794 1563 714 1564 617 1564 794 1564 794 1565 617 1565 712 1565 716 1566 2177 1566 715 1566 715 1567 2177 1567 717 1567 715 1568 717 1568 712 1568 716 1569 763 1569 2177 1569 712 1570 718 1570 711 1570 1361 1571 2039 1571 3051 1571 719 1572 3051 1572 2310 1572 1084 1573 1083 1573 3049 1573 720 1574 3052 1574 725 1574 2310 1575 3051 1575 2195 1575 2310 1576 2195 1576 3052 1576 3052 1577 2195 1577 721 1577 2310 1578 3052 1578 720 1578 1084 1579 723 1579 721 1579 1084 1580 721 1580 1149 1580 1149 1581 721 1581 2195 1581 1149 1582 2195 1582 3047 1582 3047 1583 2195 1583 3048 1583 723 1584 1094 1584 721 1584 721 1585 1094 1585 1284 1585 721 1586 1284 1586 2194 1586 2194 1587 2192 1587 721 1587 721 1588 2192 1588 724 1588 721 1589 724 1589 1360 1589 1332 1590 2027 1590 2025 1590 3052 1591 2025 1591 725 1591 1141 1592 725 1592 3044 1592 1360 1593 2028 1593 721 1593 721 1594 2028 1594 722 1594 721 1595 722 1595 3052 1595 3052 1596 722 1596 2025 1596 726 1597 3038 1597 728 1597 1621 1598 622 1598 2065 1598 726 1599 728 1599 2066 1599 622 1600 727 1600 728 1600 728 1601 727 1601 2066 1601 1157 1602 729 1602 730 1602 730 1603 729 1603 623 1603 742 1604 730 1604 3037 1604 730 1605 623 1605 1355 1605 1355 1606 623 1606 624 1606 1355 1607 624 1607 2202 1607 624 1608 2203 1608 2202 1608 737 1609 1616 1609 732 1609 731 1610 732 1610 1616 1610 3039 1611 728 1611 3038 1611 1159 1612 733 1612 2162 1612 2162 1613 733 1613 1344 1613 2162 1614 1344 1614 3040 1614 734 1615 728 1615 3039 1615 734 1616 622 1616 728 1616 2718 1617 2697 1617 2345 1617 2345 1618 2697 1618 936 1618 738 1619 580 1619 741 1619 3039 1620 736 1620 734 1620 740 1621 719 1621 2310 1621 2700 1622 2308 1622 936 1622 735 1623 2308 1623 1861 1623 734 1624 736 1624 2352 1624 2352 1625 736 1625 732 1625 936 1626 2308 1626 2345 1626 2345 1627 2308 1627 735 1627 736 1628 3039 1628 732 1628 732 1629 3039 1629 738 1629 732 1630 738 1630 737 1630 2701 1631 739 1631 1861 1631 2308 1632 2700 1632 1861 1632 1861 1633 2700 1633 2701 1633 740 1634 737 1634 719 1634 719 1635 737 1635 738 1635 719 1636 738 1636 741 1636 742 1637 3037 1637 2044 1637 742 1638 2044 1638 2164 1638 2164 1639 2044 1639 1158 1639 2012 1640 2045 1640 744 1640 744 1641 2045 1641 749 1641 749 1642 2045 1642 2044 1642 749 1643 2044 1643 3037 1643 1503 1644 1501 1644 747 1644 2313 1645 745 1645 1347 1645 1503 1646 2778 1646 1501 1646 747 1647 1796 1647 1503 1647 747 1648 746 1648 1796 1648 746 1649 2314 1649 752 1649 751 1650 746 1650 747 1650 751 1651 747 1651 1501 1651 749 1652 748 1652 744 1652 744 1653 748 1653 752 1653 2781 1654 2759 1654 751 1654 751 1655 2759 1655 1876 1655 751 1656 1876 1656 746 1656 2347 1657 746 1657 752 1657 2347 1658 752 1658 2346 1658 745 1659 2313 1659 750 1659 745 1660 750 1660 748 1660 748 1661 750 1661 2346 1661 746 1662 1876 1662 2314 1662 752 1663 748 1663 2346 1663 1592 1664 2346 1664 2353 1664 750 1665 2353 1665 2346 1665 2178 1666 1247 1666 2154 1666 2154 1667 1247 1667 1190 1667 1845 1668 2178 1668 753 1668 753 1669 2178 1669 2154 1669 753 1670 2154 1670 754 1670 754 1671 2154 1671 755 1671 756 1672 1191 1672 1244 1672 792 1673 760 1673 756 1673 1245 1674 2188 1674 758 1674 757 1675 792 1675 758 1675 758 1676 792 1676 756 1676 758 1677 756 1677 1245 1677 1245 1678 756 1678 1244 1678 759 1679 1190 1679 681 1679 3028 1680 790 1680 3029 1680 3029 1681 790 1681 759 1681 3029 1682 759 1682 681 1682 2189 1683 1264 1683 2153 1683 2153 1684 1264 1684 1191 1684 2189 1685 2153 1685 760 1685 2189 1686 760 1686 791 1686 761 1687 1250 1687 813 1687 813 1688 1250 1688 608 1688 2183 1689 1056 1689 762 1689 762 1690 1056 1690 814 1690 763 1691 716 1691 764 1691 764 1692 716 1692 616 1692 3023 1693 765 1693 810 1693 810 1694 765 1694 809 1694 1846 1695 2182 1695 1065 1695 766 1696 811 1696 2108 1696 2108 1697 811 1697 1846 1697 2108 1698 1846 1698 1065 1698 2151 1699 1268 1699 1237 1699 812 1700 767 1700 3017 1700 3017 1701 767 1701 2151 1701 2151 1702 1237 1702 3017 1702 3017 1703 1237 1703 2182 1703 768 1704 1274 1704 664 1704 768 1705 664 1705 1267 1705 2241 1706 3018 1706 768 1706 2241 1707 768 1707 2107 1707 2107 1708 768 1708 1267 1708 2107 1709 1267 1709 1626 1709 769 1710 1274 1710 3019 1710 3020 1711 770 1711 3019 1711 3019 1712 770 1712 1054 1712 3019 1713 1054 1713 769 1713 3015 1714 815 1714 1791 1714 1791 1715 815 1715 2127 1715 771 1716 772 1716 3016 1716 3016 1717 772 1717 1066 1717 774 1718 2248 1718 773 1718 2184 1719 1792 1719 775 1719 789 1720 774 1720 775 1720 775 1721 774 1721 773 1721 775 1722 773 1722 2184 1722 2184 1723 773 1723 776 1723 2184 1724 776 1724 1251 1724 2247 1725 777 1725 778 1725 2247 1726 778 1726 776 1726 776 1727 778 1727 1251 1727 1251 1728 778 1728 2158 1728 1251 1729 2158 1729 1848 1729 1848 1730 2158 1730 779 1730 1848 1731 779 1731 3030 1731 780 1732 1792 1732 786 1732 783 1733 2181 1733 1847 1733 781 1734 782 1734 1847 1734 1847 1735 782 1735 2157 1735 1847 1736 2157 1736 783 1736 783 1737 2157 1737 784 1737 783 1738 784 1738 786 1738 784 1739 785 1739 786 1739 786 1740 785 1740 787 1740 786 1741 787 1741 780 1741 780 1742 787 1742 2248 1742 780 1743 2248 1743 788 1743 2144 1744 2246 1744 785 1744 2144 1745 785 1745 784 1745 3030 1746 779 1746 781 1746 781 1747 779 1747 782 1747 2248 1748 774 1748 788 1748 788 1749 774 1749 789 1749 754 1750 755 1750 3028 1750 3028 1751 755 1751 790 1751 760 1752 792 1752 791 1752 791 1753 792 1753 757 1753 793 1754 1844 1754 713 1754 794 1755 2106 1755 2105 1755 799 1756 3027 1756 2105 1756 2105 1757 3027 1757 793 1757 2105 1758 793 1758 794 1758 794 1759 793 1759 713 1759 796 1760 1844 1760 795 1760 798 1761 800 1761 795 1761 795 1762 800 1762 797 1762 795 1763 797 1763 796 1763 3027 1764 799 1764 798 1764 798 1765 799 1765 800 1765 2188 1766 1246 1766 3026 1766 3026 1767 1246 1767 1265 1767 1265 1768 2104 1768 2152 1768 2152 1769 2253 1769 3025 1769 1265 1770 2152 1770 3026 1770 3026 1771 2152 1771 3025 1771 802 1772 2104 1772 1266 1772 803 1773 2188 1773 3024 1773 801 1774 2253 1774 3024 1774 3024 1775 2253 1775 802 1775 3024 1776 802 1776 803 1776 803 1777 802 1777 1266 1777 3025 1778 2253 1778 801 1778 2191 1779 2190 1779 3022 1779 3021 1780 804 1780 3022 1780 3022 1781 804 1781 2121 1781 3022 1782 2121 1782 2191 1782 805 1783 807 1783 806 1783 806 1784 807 1784 714 1784 806 1785 714 1785 808 1785 764 1786 616 1786 805 1786 805 1787 616 1787 807 1787 804 1788 3021 1788 809 1788 809 1789 3021 1789 810 1789 2241 1790 770 1790 3018 1790 3018 1791 770 1791 3020 1791 766 1792 767 1792 811 1792 811 1793 767 1793 812 1793 608 1794 772 1794 813 1794 813 1795 772 1795 771 1795 814 1796 815 1796 762 1796 762 1797 815 1797 3015 1797 2786 1798 2990 1798 955 1798 955 1799 2990 1799 816 1799 955 1800 816 1800 1274 1800 955 1801 1274 1801 956 1801 2989 1802 2991 1802 3012 1802 817 1803 2988 1803 3011 1803 3011 1804 2988 1804 3010 1804 2988 1805 817 1805 818 1805 818 1806 817 1806 1849 1806 1907 1807 2981 1807 2787 1807 2787 1808 2981 1808 3009 1808 3073 1809 1907 1809 2787 1809 821 1810 819 1810 2808 1810 881 1811 820 1811 821 1811 2997 1812 820 1812 822 1812 2008 1813 2996 1813 3007 1813 1907 1814 881 1814 2808 1814 2808 1815 881 1815 821 1815 2997 1816 822 1816 823 1816 821 1817 2997 1817 819 1817 819 1818 2997 1818 823 1818 819 1819 823 1819 2008 1819 2008 1820 823 1820 2996 1820 820 1821 881 1821 822 1821 822 1822 881 1822 824 1822 824 1823 1918 1823 3007 1823 824 1824 3007 1824 822 1824 822 1825 3007 1825 2996 1825 2959 1826 828 1826 857 1826 2959 1827 857 1827 825 1827 2959 1828 825 1828 827 1828 826 1829 834 1829 858 1829 858 1830 834 1830 827 1830 827 1831 834 1831 2959 1831 826 1832 861 1832 834 1832 834 1833 861 1833 2896 1833 861 1834 862 1834 2896 1834 2812 1835 829 1835 2961 1835 2961 1836 829 1836 830 1836 833 1837 832 1837 2961 1837 2961 1838 832 1838 2812 1838 2895 1839 831 1839 833 1839 833 1840 831 1840 832 1840 2958 1841 884 1841 834 1841 834 1842 884 1842 2959 1842 2960 1843 2962 1843 2961 1843 2961 1844 2962 1844 833 1844 2914 1845 2892 1845 2944 1845 2944 1846 2892 1846 2893 1846 835 1847 2915 1847 836 1847 836 1848 2915 1848 2947 1848 852 1849 2944 1849 2893 1849 852 1850 2893 1850 2945 1850 892 1851 836 1851 2875 1851 2875 1852 836 1852 2947 1852 2872 1853 838 1853 837 1853 837 1854 838 1854 2889 1854 2872 1855 837 1855 2903 1855 2992 1856 2963 1856 2923 1856 839 1857 2992 1857 2923 1857 839 1858 2923 1858 2916 1858 2963 1859 2992 1859 840 1859 2868 1860 841 1860 2995 1860 2995 1861 841 1861 842 1861 2995 1862 842 1862 2870 1862 2870 1863 2867 1863 2995 1863 844 1864 843 1864 2954 1864 2954 1865 843 1865 2951 1865 2941 1866 845 1866 2939 1866 2939 1867 845 1867 846 1867 856 1868 2920 1868 2881 1868 849 1869 850 1869 847 1869 851 1870 2881 1870 848 1870 848 1871 2881 1871 850 1871 848 1872 850 1872 849 1872 856 1873 2881 1873 851 1873 847 1874 850 1874 2890 1874 2840 1875 847 1875 2890 1875 852 1876 2913 1876 2944 1876 2944 1877 2913 1877 2914 1877 2951 1878 843 1878 2952 1878 2952 1879 843 1879 885 1879 853 1880 2940 1880 846 1880 846 1881 2940 1881 2939 1881 869 1882 895 1882 2941 1882 2941 1883 895 1883 845 1883 2862 1884 2864 1884 2932 1884 2862 1885 2932 1885 2908 1885 2864 1886 2950 1886 2883 1886 2864 1887 2883 1887 2932 1887 2950 1888 2864 1888 2863 1888 2880 1889 2935 1889 2938 1889 2938 1890 2935 1890 2887 1890 2940 1891 869 1891 2939 1891 2939 1892 869 1892 2941 1892 868 1893 870 1893 2880 1893 2880 1894 870 1894 2935 1894 854 1895 2861 1895 2860 1895 2943 1896 854 1896 873 1896 2943 1897 2861 1897 854 1897 2898 1898 854 1898 2860 1898 2956 1899 2966 1899 2809 1899 2956 1900 2809 1900 855 1900 891 1901 590 1901 592 1901 891 1902 592 1902 2891 1902 590 1903 891 1903 855 1903 855 1904 891 1904 2956 1904 2830 1905 2920 1905 856 1905 2830 1906 856 1906 2832 1906 2832 1907 856 1907 851 1907 2832 1908 851 1908 2833 1908 2833 1909 851 1909 848 1909 2833 1910 848 1910 849 1910 2833 1911 849 1911 2841 1911 2841 1912 849 1912 847 1912 2841 1913 847 1913 2840 1913 857 1914 2965 1914 2815 1914 857 1915 2815 1915 825 1915 825 1916 2815 1916 859 1916 825 1917 859 1917 827 1917 827 1918 859 1918 858 1918 858 1919 859 1919 860 1919 858 1920 860 1920 826 1920 826 1921 860 1921 861 1921 861 1922 860 1922 2826 1922 861 1923 2826 1923 862 1923 2900 1924 2902 1924 2858 1924 2918 1925 2859 1925 863 1925 2858 1926 2902 1926 863 1926 2858 1927 863 1927 2859 1927 2929 1928 2913 1928 2847 1928 865 1929 2904 1929 2871 1929 865 1930 866 1930 867 1930 2912 1931 2888 1931 878 1931 2871 1932 866 1932 865 1932 865 1933 867 1933 2912 1933 878 1934 2888 1934 889 1934 889 1935 2888 1935 2885 1935 2885 1936 838 1936 2904 1936 2885 1937 2904 1937 894 1937 2934 1938 2885 1938 895 1938 895 1939 869 1939 2934 1939 2934 1940 869 1940 868 1940 868 1941 869 1941 870 1941 870 1942 869 1942 2940 1942 2936 1943 870 1943 2876 1943 2885 1944 2934 1944 2937 1944 2885 1945 2937 1945 889 1945 889 1946 2937 1946 2886 1946 873 1947 2911 1947 880 1947 2876 1948 870 1948 2940 1948 864 1949 2861 1949 2942 1949 864 1950 2942 1950 895 1950 2861 1951 871 1951 2942 1951 2942 1952 871 1952 2882 1952 2882 1953 871 1953 872 1953 853 1954 2882 1954 880 1954 880 1955 2882 1955 873 1955 873 1956 2882 1956 872 1956 2861 1957 864 1957 874 1957 875 1958 881 1958 880 1958 875 1959 880 1959 2911 1959 881 1960 875 1960 876 1960 881 1961 876 1961 824 1961 824 1962 876 1962 877 1962 864 1963 877 1963 874 1963 2912 1964 878 1964 865 1964 865 1965 878 1965 2846 1965 865 1966 2917 1966 2874 1966 865 1967 2874 1967 1899 1967 865 1968 2846 1968 2917 1968 2917 1969 2846 1969 2873 1969 878 1970 2873 1970 2846 1970 889 1971 892 1971 878 1971 878 1972 892 1972 2922 1972 1899 1973 2874 1973 2916 1973 921 1974 2913 1974 852 1974 2930 1975 2929 1975 2847 1975 2945 1976 2946 1976 2931 1976 2945 1977 2931 1977 852 1977 852 1978 2931 1978 897 1978 2930 1979 2892 1979 2929 1979 2946 1980 2945 1980 2930 1980 2946 1981 2930 1981 879 1981 879 1982 2930 1982 890 1982 2955 1983 2876 1983 880 1983 880 1984 2876 1984 853 1984 853 1985 2876 1985 2940 1985 880 1986 2918 1986 2955 1986 2955 1987 2918 1987 2946 1987 2955 1988 2946 1988 879 1988 881 1989 2899 1989 880 1989 880 1990 2899 1990 2918 1990 881 1991 2901 1991 2899 1991 2847 1992 882 1992 2848 1992 882 1993 1899 1993 2875 1993 2922 1994 892 1994 2875 1994 882 1995 835 1995 883 1995 882 1996 883 1996 892 1996 824 1997 2908 1997 2851 1997 824 1998 2909 1998 2908 1998 2910 1999 864 1999 2950 1999 2950 2000 884 2000 887 2000 887 2001 884 2001 2958 2001 884 2002 2950 2002 864 2002 844 2003 2894 2003 588 2003 588 2004 2894 2004 2953 2004 588 2005 2953 2005 887 2005 887 2006 2953 2006 2884 2006 2851 2007 2908 2007 2884 2007 2952 2008 2851 2008 2884 2008 893 2009 885 2009 588 2009 893 2010 2952 2010 885 2010 2869 2011 2870 2011 2885 2011 865 2012 2905 2012 2869 2012 865 2013 2906 2013 2905 2013 2962 2014 2885 2014 2933 2014 2962 2015 2933 2015 2948 2015 2962 2016 2948 2016 2897 2016 2907 2017 893 2017 588 2017 2907 2018 588 2018 2897 2018 2933 2019 2865 2019 2948 2019 893 2020 2907 2020 900 2020 900 2021 2907 2021 2865 2021 895 2022 2878 2022 886 2022 895 2023 886 2023 864 2023 864 2024 886 2024 884 2024 2885 2025 2960 2025 2878 2025 2885 2026 2962 2026 2960 2026 887 2027 2958 2027 888 2027 887 2028 888 2028 588 2028 890 2029 882 2029 892 2029 890 2030 892 2030 891 2030 889 2031 2957 2031 892 2031 2876 2032 889 2032 2936 2032 2936 2033 889 2033 2886 2033 897 2034 881 2034 921 2034 2933 2035 2906 2035 2850 2035 2850 2036 2906 2036 865 2036 900 2037 2850 2037 2924 2037 2924 2038 2850 2038 865 2038 2865 2039 2933 2039 900 2039 900 2040 2933 2040 2850 2040 2844 2041 893 2041 588 2041 2844 2042 588 2042 2843 2042 893 2043 2844 2043 588 2043 588 2044 2844 2044 2843 2044 2952 2045 893 2045 2851 2045 2851 2046 893 2046 824 2046 824 2047 893 2047 1918 2047 2897 2048 588 2048 888 2048 2897 2049 888 2049 2962 2049 2869 2050 2885 2050 865 2050 865 2051 2885 2051 894 2051 894 2052 2904 2052 865 2052 2885 2053 2878 2053 895 2053 2910 2054 2909 2054 864 2054 864 2055 2909 2055 824 2055 864 2056 824 2056 877 2056 896 2057 1899 2057 2916 2057 2847 2058 2848 2058 2930 2058 2930 2059 2848 2059 882 2059 2930 2060 882 2060 890 2060 2931 2061 2901 2061 897 2061 897 2062 2901 2062 881 2062 896 2063 2916 2063 2922 2063 896 2064 2922 2064 2875 2064 896 2065 2875 2065 1899 2065 2913 2066 921 2066 2847 2066 2847 2067 921 2067 1899 2067 2847 2068 1899 2068 882 2068 897 2069 921 2069 852 2069 898 2070 899 2070 2854 2070 901 2071 585 2071 900 2071 900 2072 2497 2072 2498 2072 900 2073 2498 2073 901 2073 901 2074 2498 2074 2534 2074 2857 2075 2854 2075 899 2075 2505 2076 903 2076 2854 2076 1034 2077 2505 2077 2854 2077 1034 2078 2854 2078 901 2078 901 2079 2854 2079 2857 2079 901 2080 2857 2080 585 2080 2551 2081 907 2081 2854 2081 2521 2082 2551 2082 2854 2082 2521 2083 2854 2083 904 2083 904 2084 2854 2084 903 2084 2524 2085 905 2085 2854 2085 902 2086 2524 2086 2854 2086 902 2087 2854 2087 906 2087 906 2088 2854 2088 907 2088 2513 2089 910 2089 2854 2089 893 2090 898 2090 910 2090 908 2091 2854 2091 1033 2091 1033 2092 2854 2092 905 2092 2854 2093 908 2093 909 2093 2854 2094 909 2094 2513 2094 900 2095 585 2095 899 2095 900 2096 899 2096 893 2096 893 2097 899 2097 898 2097 893 2098 910 2098 2528 2098 893 2099 2528 2099 2927 2099 2927 2100 2528 2100 2532 2100 2527 2101 2927 2101 2532 2101 920 2102 921 2102 2611 2102 2638 2103 916 2103 917 2103 913 2104 921 2104 2629 2104 2629 2105 921 2105 2625 2105 921 2106 913 2106 2611 2106 2611 2107 913 2107 2639 2107 911 2108 2638 2108 917 2108 911 2109 917 2109 2611 2109 2611 2110 917 2110 586 2110 2611 2111 586 2111 920 2111 2618 2112 2652 2112 917 2112 915 2113 2618 2113 917 2113 915 2114 917 2114 2606 2114 2606 2115 917 2115 916 2115 2616 2116 2615 2116 917 2116 914 2117 2616 2117 917 2117 914 2118 917 2118 912 2118 912 2119 917 2119 2652 2119 2632 2120 919 2120 917 2120 1899 2121 922 2121 919 2121 2644 2122 917 2122 2617 2122 2617 2123 917 2123 2615 2123 917 2124 2644 2124 918 2124 917 2125 918 2125 2632 2125 919 2126 2620 2126 1899 2126 921 2127 920 2127 586 2127 921 2128 586 2128 917 2128 921 2129 917 2129 1899 2129 1899 2130 917 2130 922 2130 2806 2131 2438 2131 1459 2131 1459 2132 2438 2132 2439 2132 2801 2133 2803 2133 2440 2133 1462 2134 2454 2134 2436 2134 1462 2135 2436 2135 1460 2135 1460 2136 2436 2136 2435 2136 1460 2137 2435 2137 2802 2137 1462 2138 2453 2138 2804 2138 2804 2139 2453 2139 2451 2139 1460 2140 2804 2140 2441 2140 1525 2141 2800 2141 2789 2141 1525 2142 2789 2142 923 2142 923 2143 2789 2143 2421 2143 923 2144 2421 2144 2416 2144 2799 2145 2794 2145 2424 2145 2799 2146 2424 2146 2792 2146 2792 2147 2424 2147 2797 2147 2792 2148 2797 2148 2795 2148 924 2149 2459 2149 2415 2149 924 2150 2415 2150 1525 2150 1525 2151 2415 2151 2800 2151 2792 2152 2791 2152 2788 2152 2788 2153 2791 2153 2793 2153 2788 2154 2793 2154 2461 2154 3011 2155 1810 2155 817 2155 926 2156 2770 2156 925 2156 925 2157 2770 2157 657 2157 1798 2158 657 2158 2769 2158 2769 2159 657 2159 2770 2159 926 2160 925 2160 2771 2160 927 2161 1866 2161 653 2161 1866 2162 1810 2162 653 2162 927 2163 653 2163 654 2163 1871 2164 656 2164 657 2164 653 2165 695 2165 1808 2165 652 2166 2734 2166 1873 2166 3011 2167 652 2167 1873 2167 1810 2168 3011 2168 1812 2168 1812 2169 3011 2169 1873 2169 2740 2170 2742 2170 1482 2170 651 2171 1803 2171 1804 2171 651 2172 1804 2172 2742 2172 2742 2173 2740 2173 651 2173 1869 2174 595 2174 2724 2174 1869 2175 2720 2175 1868 2175 1868 2176 2720 2176 970 2176 1482 2177 2720 2177 1869 2177 1482 2178 2742 2178 2720 2178 925 2179 697 2179 1888 2179 1888 2180 697 2180 2723 2180 2734 2181 652 2181 1801 2181 1889 2182 1849 2182 817 2182 1849 2183 1889 2183 1866 2183 1866 2184 1889 2184 1810 2184 817 2185 1810 2185 1889 2185 1866 2186 927 2186 1849 2186 927 2187 1872 2187 2763 2187 1808 2188 2767 2188 653 2188 653 2189 2767 2189 655 2189 655 2190 1872 2190 653 2190 655 2191 2765 2191 594 2191 656 2192 2768 2192 1808 2192 1808 2193 2768 2193 2767 2193 656 2194 1871 2194 1870 2194 1870 2195 2768 2195 656 2195 1870 2196 1871 2196 2768 2196 925 2197 1888 2197 2771 2197 2771 2198 1888 2198 928 2198 654 2199 653 2199 927 2199 1872 2200 927 2200 653 2200 1798 2201 1871 2201 657 2201 2345 2202 2310 2202 2718 2202 2711 2203 1851 2203 2708 2203 720 2204 663 2204 2310 2204 2310 2205 663 2205 1857 2205 935 2206 1857 2206 720 2206 935 2207 720 2207 929 2207 929 2208 720 2208 1774 2208 1857 2209 663 2209 720 2209 1771 2210 1774 2210 1772 2210 3014 2211 938 2211 1772 2211 1772 2212 938 2212 1779 2212 1858 2213 1439 2213 1435 2213 1858 2214 1435 2214 1859 2214 1859 2215 1435 2215 930 2215 1001 2216 2670 2216 1437 2216 930 2217 931 2217 1860 2217 1001 2218 1860 2218 2670 2218 1860 2219 931 2219 2670 2219 1001 2220 932 2220 1860 2220 933 2221 2678 2221 934 2221 2711 2222 934 2222 2708 2222 2711 2223 2708 2223 1851 2223 934 2224 2711 2224 2715 2224 934 2225 2715 2225 1514 2225 1514 2226 2715 2226 1861 2226 1514 2227 1861 2227 1777 2227 1777 2228 1861 2228 937 2228 1777 2229 937 2229 1775 2229 1775 2230 937 2230 658 2230 1775 2231 658 2231 935 2231 937 2232 1863 2232 658 2232 936 2233 1863 2233 2700 2233 2700 2234 1863 2234 2701 2234 1863 2235 937 2235 2701 2235 1861 2236 1862 2236 937 2236 2716 2237 1862 2237 1861 2237 2708 2238 934 2238 2678 2238 2708 2239 2678 2239 1740 2239 1779 2240 938 2240 1440 2240 1774 2241 1790 2241 3014 2241 1790 2242 1774 2242 720 2242 720 2243 635 2243 1774 2243 720 2244 1774 2244 635 2244 2718 2245 2310 2245 1864 2245 935 2246 1864 2246 2310 2246 1863 2247 939 2247 658 2247 658 2248 939 2248 935 2248 3014 2249 1772 2249 1774 2249 935 2250 2310 2250 1857 2250 2713 2251 940 2251 2715 2251 2715 2252 940 2252 1861 2252 2786 2253 956 2253 947 2253 956 2254 2786 2254 955 2254 957 2255 946 2255 1852 2255 957 2256 660 2256 946 2256 1853 2257 1748 2257 2705 2257 665 2258 942 2258 2707 2258 942 2259 665 2259 1747 2259 1747 2260 665 2260 2706 2260 665 2261 2707 2261 2706 2261 660 2262 1856 2262 1521 2262 660 2263 1521 2263 946 2263 952 2264 941 2264 1856 2264 1856 2265 941 2265 1521 2265 943 2266 1769 2266 2703 2266 2703 2267 1769 2267 1855 2267 1855 2268 1769 2268 952 2268 952 2269 1769 2269 941 2269 943 2270 942 2270 1769 2270 2664 2271 1757 2271 949 2271 949 2272 1757 2272 942 2272 2688 2273 2685 2273 2662 2273 2684 2274 1744 2274 659 2274 659 2275 1744 2275 944 2275 2682 2276 2675 2276 945 2276 2682 2277 2662 2277 659 2277 659 2278 944 2278 2682 2278 945 2279 1741 2279 947 2279 1852 2280 946 2280 956 2280 956 2281 946 2281 947 2281 2786 2282 947 2282 1741 2282 2688 2283 662 2283 2685 2283 2685 2284 662 2284 1019 2284 942 2285 948 2285 1747 2285 942 2286 1747 2286 949 2286 1747 2287 948 2287 942 2287 943 2288 950 2288 1748 2288 1854 2289 2703 2289 950 2289 1854 2290 943 2290 2703 2290 1452 2291 2694 2291 952 2291 952 2292 661 2292 1855 2292 1855 2293 661 2293 951 2293 1855 2294 951 2294 2703 2294 2694 2295 661 2295 952 2295 1856 2296 957 2296 953 2296 1856 2297 953 2297 954 2297 956 2298 1852 2298 636 2298 956 2299 636 2299 1852 2299 1741 2300 945 2300 2675 2300 1741 2301 2675 2301 2676 2301 2707 2302 942 2302 943 2302 2707 2303 943 2303 1853 2303 1853 2304 943 2304 1748 2304 660 2305 957 2305 1856 2305 957 2306 1852 2306 956 2306 913 2307 2629 2307 2613 2307 2613 2308 2629 2308 2612 2308 911 2309 2639 2309 2642 2309 2591 2310 2632 2310 2634 2310 986 2311 2617 2311 2647 2311 914 2312 912 2312 985 2312 977 2313 967 2313 2564 2313 2282 2314 965 2314 976 2314 2656 2315 2576 2315 2653 2315 2575 2316 959 2316 604 2316 2656 2317 959 2317 2576 2317 2575 2318 3072 2318 960 2318 2575 2319 960 2319 961 2319 961 2320 960 2320 2659 2320 2659 2321 1447 2321 961 2321 961 2322 1447 2322 1449 2322 961 2323 1449 2323 962 2323 961 2324 962 2324 2571 2324 963 2325 2571 2325 962 2325 963 2326 962 2326 983 2326 2571 2327 963 2327 2588 2327 2588 2328 963 2328 983 2328 983 2329 965 2329 2588 2329 2576 2330 2579 2330 2586 2330 975 2331 2586 2331 964 2331 964 2332 2586 2332 965 2332 966 2333 2564 2333 967 2333 966 2334 967 2334 2596 2334 2596 2335 967 2335 969 2335 2596 2336 969 2336 968 2336 968 2337 969 2337 970 2337 968 2338 970 2338 987 2338 986 2339 2648 2339 971 2339 986 2340 971 2340 972 2340 972 2341 971 2341 2564 2341 972 2342 2564 2342 966 2342 971 2343 2648 2343 974 2343 2648 2344 974 2344 973 2344 2581 2345 3539 2345 2283 2345 2581 2346 2283 2346 2580 2346 2580 2347 2283 2347 2576 2347 3539 2348 2581 2348 2648 2348 2648 2349 2581 2349 974 2349 2580 2350 2576 2350 2586 2350 2580 2351 2586 2351 975 2351 975 2352 964 2352 2282 2352 2282 2353 976 2353 2561 2353 2280 2354 2561 2354 976 2354 2431 2355 2280 2355 976 2355 2561 2356 2280 2356 2583 2356 977 2357 2564 2357 1800 2357 1800 2358 2564 2358 2583 2358 2647 2359 2648 2359 986 2359 2658 2360 3072 2360 2656 2360 2653 2361 3539 2361 985 2361 985 2362 3539 2362 2648 2362 979 2363 984 2363 978 2363 746 2364 1613 2364 1796 2364 1796 2365 1613 2365 978 2365 979 2366 978 2366 1613 2366 980 2367 2450 2367 2343 2367 2343 2368 2450 2368 1613 2368 1613 2369 2450 2369 979 2369 1455 2370 1797 2370 2343 2370 2343 2371 1797 2371 980 2371 980 2372 1797 2372 1799 2372 980 2373 1799 2373 981 2373 981 2374 1799 2374 1800 2374 981 2375 1800 2375 2431 2375 3777 2376 982 2376 2803 2376 2803 2377 982 2377 981 2377 981 2378 982 2378 980 2378 965 2379 983 2379 976 2379 983 2380 962 2380 984 2380 962 2381 978 2381 984 2381 3072 2382 604 2382 2656 2382 2656 2383 604 2383 959 2383 2653 2384 985 2384 912 2384 2590 2385 2634 2385 1804 2385 1804 2386 2634 2386 987 2386 987 2387 2634 2387 988 2387 987 2388 988 2388 968 2388 2634 2389 2590 2389 2591 2389 2628 2390 2627 2390 1893 2390 1893 2391 2627 2391 1801 2391 1801 2392 2627 2392 989 2392 1801 2393 989 2393 1803 2393 1803 2394 989 2394 990 2394 1803 2395 990 2395 1804 2395 1804 2396 990 2396 2590 2396 2628 2397 1893 2397 1896 2397 2628 2398 1896 2398 2623 2398 2431 2399 1800 2399 2280 2399 2280 2400 1800 2400 2583 2400 1447 2401 2659 2401 991 2401 991 2402 2659 2402 992 2402 991 2403 992 2403 1499 2403 1499 2404 992 2404 2603 2404 1499 2405 2603 2405 1445 2405 1445 2406 2603 2406 2602 2406 1445 2407 2602 2407 993 2407 2640 2408 1446 2408 993 2408 2640 2409 993 2409 2602 2409 2640 2410 2610 2410 1446 2410 1446 2411 2610 2411 2609 2411 2609 2412 2925 2412 2787 2412 2787 2413 2925 2413 3073 2413 3073 2414 2925 2414 994 2414 2642 2415 2640 2415 911 2415 2575 2416 604 2416 3072 2416 3072 2417 2658 2417 915 2417 2926 2418 1907 2418 3073 2418 2591 2419 919 2419 2632 2419 2519 2420 2513 2420 2541 2420 1028 2421 1033 2421 2558 2421 902 2422 906 2422 1007 2422 1034 2423 2534 2423 1022 2423 997 2424 1441 2424 2496 2424 2473 2425 1013 2425 996 2425 2473 2426 996 2426 2495 2426 997 2427 2496 2427 1012 2427 1012 2428 2496 2428 2495 2428 998 2429 2496 2429 1441 2429 998 2430 1441 2430 999 2430 999 2431 1441 2431 1001 2431 999 2432 1001 2432 1000 2432 1000 2433 1001 2433 1437 2433 1000 2434 1437 2434 1029 2434 1028 2435 1004 2435 2477 2435 1028 2436 2477 2436 1002 2436 1002 2437 2477 2437 2496 2437 1002 2438 2496 2438 998 2438 2477 2439 1004 2439 2478 2439 1004 2440 2478 2440 1005 2440 1003 2441 3931 2441 1004 2441 1004 2442 3931 2442 2478 2442 2483 2443 2470 2443 2480 2443 2277 2444 2279 2444 2470 2444 1013 2445 2473 2445 2279 2445 2277 2446 2470 2446 2491 2446 2277 2447 2491 2447 2489 2447 1016 2448 2278 2448 2489 2448 2277 2449 2489 2449 2278 2449 1013 2450 2279 2450 2278 2450 1013 2451 2278 2451 1016 2451 2463 2452 1006 2452 2276 2452 1026 2453 1027 2453 1006 2453 2553 2454 2508 2454 1026 2454 2558 2455 1004 2455 1028 2455 3933 2456 2483 2456 2480 2456 2483 2457 2482 2457 2470 2457 2470 2458 2482 2458 2491 2458 1006 2459 2483 2459 1026 2459 1026 2460 2483 2460 1007 2460 1007 2461 2483 2461 3933 2461 1016 2462 1746 2462 1008 2462 2411 2463 1008 2463 1750 2463 1750 2464 1749 2464 1010 2464 1010 2465 1749 2465 2306 2465 1746 2466 1750 2466 1008 2466 2411 2467 1750 2467 1010 2467 1011 2468 1009 2468 1614 2468 1614 2469 1009 2469 2411 2469 1614 2470 2411 2470 1010 2470 1614 2471 2345 2471 735 2471 1614 2472 735 2472 1011 2472 1011 2473 1739 2473 2428 2473 2428 2474 1739 2474 1012 2474 2428 2475 1012 2475 1013 2475 2790 2476 2275 2476 4072 2476 4072 2477 2275 2477 2793 2477 2793 2478 2275 2478 2428 2478 2275 2479 2790 2479 2428 2479 2463 2480 2508 2480 2549 2480 2463 2481 2549 2481 2464 2481 2464 2482 2549 2482 2547 2482 2547 2483 1017 2483 2464 2483 2464 2484 1017 2484 1014 2484 2464 2485 1014 2485 1746 2485 2464 2486 1746 2486 2468 2486 1015 2487 2462 2487 1746 2487 1746 2488 2462 2488 2468 2488 1746 2489 1016 2489 1015 2489 2462 2490 1015 2490 2487 2490 2489 2491 2487 2491 1016 2491 2487 2492 1015 2492 1016 2492 1030 2493 1031 2493 1025 2493 1017 2494 2547 2494 1019 2494 1019 2495 2547 2495 1018 2495 1019 2496 1018 2496 2685 2496 2685 2497 1018 2497 1020 2497 2685 2498 1020 2498 1743 2498 1743 2499 1020 2499 1021 2499 1743 2500 1021 2500 1744 2500 1744 2501 1022 2501 1023 2501 1023 2502 1022 2502 2501 2502 1023 2503 2501 2503 1024 2503 1023 2504 1024 2504 1031 2504 1031 2505 1024 2505 1025 2505 1021 2506 2539 2506 1744 2506 1744 2507 2539 2507 1022 2507 1022 2508 2539 2508 1034 2508 2463 2509 2276 2509 2508 2509 2508 2510 2553 2510 2521 2510 2508 2511 2276 2511 1027 2511 2508 2512 1027 2512 1026 2512 2554 2513 1026 2513 1007 2513 2554 2514 1007 2514 906 2514 1435 2515 2541 2515 1029 2515 1029 2516 2541 2516 2512 2516 1029 2517 2512 2517 1000 2517 2541 2518 2545 2518 2519 2518 2545 2519 2541 2519 1435 2519 2545 2520 1435 2520 2518 2520 2518 2521 1435 2521 1439 2521 2518 2522 1439 2522 1440 2522 2518 2523 1440 2523 2527 2523 2527 2524 1440 2524 2785 2524 2527 2525 2785 2525 2526 2525 2526 2526 2785 2526 3074 2526 2526 2527 3074 2527 3075 2527 1013 2528 1012 2528 996 2528 996 2529 1012 2529 2495 2529 1031 2530 1030 2530 1902 2530 1902 2531 1030 2531 1032 2531 2525 2532 3074 2532 2928 2532 2529 2533 2520 2533 2528 2533 2528 2534 2520 2534 2532 2534 2519 2535 910 2535 2513 2535 1035 2536 2413 2536 1036 2536 1036 2537 2413 2537 2412 2537 1038 2538 1591 2538 1039 2538 1037 2539 1039 2539 1591 2539 1115 2540 1046 2540 1041 2540 2269 2541 1040 2541 1041 2541 1041 2542 1040 2542 625 2542 1041 2543 625 2543 1115 2543 1115 2544 625 2544 1116 2544 1045 2545 2271 2545 2268 2545 1043 2546 2270 2546 2020 2546 2020 2547 2270 2547 2058 2547 2019 2548 1042 2548 2257 2548 2257 2549 1042 2549 1043 2549 2257 2550 1043 2550 2020 2550 625 2551 2270 2551 2043 2551 2043 2552 2270 2552 1043 2552 2199 2553 2043 2553 1043 2553 625 2554 1040 2554 2270 2554 2270 2555 1040 2555 2273 2555 1339 2556 2268 2556 2060 2556 2060 2557 2263 2557 1109 2557 1339 2558 2060 2558 1337 2558 1337 2559 2060 2559 1109 2559 724 2560 2035 2560 1044 2560 2057 2561 1338 2561 2034 2561 2034 2562 1338 2562 1336 2562 724 2563 1044 2563 1336 2563 1336 2564 1044 2564 2034 2564 2271 2565 1045 2565 2272 2565 1047 2566 632 2566 2263 2566 2263 2567 2172 2567 1047 2567 1047 2568 2172 2568 2059 2568 1047 2569 2059 2569 1335 2569 1335 2570 2059 2570 1046 2570 1335 2571 1046 2571 1048 2571 1049 2572 2021 2572 1052 2572 1050 2573 1343 2573 2056 2573 2056 2574 1343 2574 1051 2574 1049 2575 1052 2575 1051 2575 1051 2576 1052 2576 2056 2576 2033 2577 2192 2577 1053 2577 1053 2578 2192 2578 1343 2578 1053 2579 1343 2579 1050 2579 1054 2580 1055 2580 1056 2580 1054 2581 1056 2581 769 2581 1056 2582 2183 2582 769 2582 1054 2583 1626 2583 2159 2583 1054 2584 2159 2584 1055 2584 1057 2585 1058 2585 2114 2585 2114 2586 1058 2586 1060 2586 2114 2587 1060 2587 1626 2587 1055 2588 2159 2588 1059 2588 1055 2589 1059 2589 609 2589 1201 2590 1060 2590 1058 2590 1163 2591 2209 2591 2206 2591 2206 2592 2209 2592 1164 2592 1163 2593 1625 2593 2209 2593 2238 2594 1061 2594 1163 2594 2238 2595 1163 2595 2206 2595 2204 2596 1062 2596 2205 2596 2204 2597 2205 2597 1623 2597 2208 2598 2207 2598 1062 2598 1062 2599 2207 2599 2205 2599 1067 2600 1064 2600 1063 2600 1063 2601 1064 2601 2230 2601 1065 2602 1066 2602 2108 2602 2108 2603 1066 2603 1064 2603 3016 2604 1066 2604 1065 2604 1064 2605 1067 2605 2108 2605 2108 2606 1067 2606 2204 2606 2211 2607 620 2607 1068 2607 2211 2608 2052 2608 1069 2608 620 2609 2211 2609 1069 2609 1070 2610 2220 2610 1071 2610 1071 2611 2212 2611 1070 2611 2218 2612 2219 2612 1070 2612 2218 2613 1070 2613 2212 2613 1071 2614 2214 2614 2212 2614 2212 2615 2214 2615 2160 2615 2212 2616 2160 2616 1102 2616 1071 2617 1350 2617 2214 2617 1072 2618 2217 2618 1350 2618 1072 2619 2216 2619 2217 2619 2224 2620 626 2620 1073 2620 1073 2621 626 2621 627 2621 2167 2622 627 2622 1074 2622 2167 2623 1074 2623 2196 2623 1074 2624 2197 2624 2196 2624 2167 2625 2216 2625 1073 2625 2167 2626 1073 2626 627 2626 2163 2627 3040 2627 633 2627 2163 2628 633 2628 2161 2628 2161 2629 633 2629 1160 2629 1076 2630 1075 2630 1290 2630 1290 2631 1075 2631 1289 2631 1076 2632 1290 2632 2255 2632 1076 2633 2255 2633 1077 2633 2170 2634 1291 2634 1078 2634 2260 2635 1145 2635 2170 2635 1147 2636 2260 2636 3049 2636 3049 2637 2260 2637 2170 2637 3049 2638 2170 2638 1078 2638 2255 2639 1081 2639 1079 2639 1079 2640 1081 2640 1082 2640 1079 2641 1082 2641 1080 2641 1289 2642 1345 2642 1081 2642 1081 2643 1345 2643 2201 2643 1081 2644 2201 2644 1082 2644 1082 2645 2201 2645 1839 2645 1083 2646 1084 2646 1085 2646 1085 2647 1086 2647 1087 2647 1087 2648 1086 2648 1291 2648 1085 2649 1087 2649 1083 2649 1083 2650 1087 2650 1145 2650 1083 2651 1145 2651 1146 2651 1088 2652 1089 2652 1090 2652 1090 2653 1089 2653 1293 2653 1090 2654 1097 2654 2256 2654 1088 2655 1090 2655 2015 2655 2015 2656 1090 2656 2256 2656 2015 2657 2256 2657 2013 2657 1093 2658 1098 2658 1091 2658 679 2659 678 2659 1091 2659 1091 2660 678 2660 1092 2660 1091 2661 1092 2661 1093 2661 1093 2662 1092 2662 1094 2662 1093 2663 1094 2663 1095 2663 1293 2664 1096 2664 1292 2664 1292 2665 1096 2665 2200 2665 1292 2666 2200 2666 1097 2666 1097 2667 2200 2667 1842 2667 1097 2668 1842 2668 2014 2668 1327 2669 677 2669 2171 2669 2171 2670 677 2670 679 2670 1327 2671 2171 2671 723 2671 723 2672 2171 2672 1098 2672 723 2673 1098 2673 1144 2673 2174 2674 629 2674 1099 2674 1099 2675 629 2675 1100 2675 2055 2676 2215 2676 1072 2676 1101 2677 1102 2677 621 2677 2047 2678 1350 2678 1103 2678 2236 2679 1104 2679 1103 2679 1103 2680 1104 2680 1101 2680 1103 2681 1101 2681 2047 2681 2047 2682 1101 2682 621 2682 1104 2683 2219 2683 1101 2683 1101 2684 2219 2684 2234 2684 621 2685 1287 2685 1288 2685 2173 2686 630 2686 1288 2686 1288 2687 630 2687 1334 2687 1288 2688 1334 2688 621 2688 2055 2689 2048 2689 1105 2689 1105 2690 2048 2690 1106 2690 1105 2691 1106 2691 1107 2691 1107 2692 1106 2692 1108 2692 2263 2693 632 2693 1109 2693 1839 2694 1346 2694 1110 2694 1110 2695 1346 2695 1353 2695 1353 2696 2054 2696 2166 2696 2166 2697 1113 2697 2254 2697 1353 2698 2166 2698 1110 2698 1110 2699 2166 2699 2254 2699 1355 2700 2202 2700 1111 2700 1111 2701 2202 2701 1839 2701 2054 2702 1355 2702 1112 2702 1112 2703 1355 2703 1111 2703 1112 2704 1111 2704 1113 2704 1113 2705 1111 2705 1114 2705 2254 2706 1113 2706 1114 2706 2255 2707 1079 2707 1077 2707 1077 2708 1079 2708 1080 2708 1097 2709 2014 2709 2256 2709 2256 2710 2014 2710 2013 2710 1115 2711 1116 2711 1046 2711 1046 2712 1116 2712 1048 2712 2264 2713 1128 2713 1119 2713 1120 2714 2198 2714 1333 2714 1117 2715 2264 2715 722 2715 722 2716 2264 2716 1119 2716 722 2717 1119 2717 1118 2717 1118 2718 1119 2718 1162 2718 1118 2719 1162 2719 1333 2719 2266 2720 607 2720 1162 2720 1162 2721 607 2721 2061 2721 1162 2722 2061 2722 1333 2722 1333 2723 2061 2723 1121 2723 1333 2724 1121 2724 1120 2724 1120 2725 1121 2725 1122 2725 1120 2726 1122 2726 1123 2726 2145 2727 2267 2727 607 2727 607 2728 2267 2728 2061 2728 2265 2729 2266 2729 1162 2729 1131 2730 722 2730 1124 2730 1125 2731 2198 2731 1126 2731 2258 2732 1122 2732 2165 2732 1127 2733 2258 2733 1126 2733 1126 2734 2258 2734 2165 2734 1126 2735 2165 2735 1125 2735 1125 2736 2165 2736 1129 2736 1125 2737 1129 2737 1124 2737 2145 2738 1132 2738 1129 2738 1129 2739 1132 2739 1130 2739 1129 2740 1130 2740 1124 2740 1124 2741 1130 2741 1161 2741 1124 2742 1161 2742 1131 2742 1131 2743 1161 2743 1128 2743 1131 2744 1128 2744 1143 2744 1130 2745 1132 2745 1133 2745 1130 2746 1133 2746 2146 2746 1122 2747 2258 2747 1123 2747 1123 2748 2258 2748 1127 2748 1362 2749 1325 2749 1321 2749 1362 2750 1321 2750 1134 2750 1134 2751 1321 2751 2168 2751 2168 2752 1321 2752 2053 2752 2053 2753 1321 2753 2216 2753 2167 2754 2196 2754 1135 2754 1135 2755 2196 2755 1837 2755 2167 2756 1135 2756 2169 2756 2169 2757 1135 2757 1136 2757 3044 2758 725 2758 1137 2758 2223 2759 1138 2759 2210 2759 2210 2760 1138 2760 3044 2760 2210 2761 3044 2761 1137 2761 1139 2762 725 2762 1141 2762 1140 2763 2052 2763 1308 2763 1308 2764 1139 2764 1141 2764 1308 2765 1141 2765 3043 2765 1308 2766 3043 2766 1142 2766 1308 2767 1142 2767 1140 2767 1128 2768 2264 2768 1143 2768 1143 2769 2264 2769 1117 2769 1144 2770 1098 2770 1095 2770 1095 2771 1098 2771 1093 2771 1145 2772 2260 2772 1146 2772 1146 2773 2260 2773 1147 2773 2195 2774 1328 2774 3048 2774 3048 2775 1328 2775 3041 2775 3041 2776 2051 2776 1148 2776 3041 2777 1148 2777 3048 2777 3048 2778 1148 2778 2259 2778 3048 2779 2259 2779 1153 2779 1330 2780 1149 2780 3047 2780 1150 2781 2259 2781 1151 2781 2051 2782 1330 2782 1151 2782 1151 2783 1330 2783 3047 2783 1151 2784 3047 2784 1150 2784 1150 2785 3047 2785 1152 2785 2259 2786 1150 2786 1153 2786 1153 2787 1150 2787 1152 2787 1315 2788 1310 2788 2175 2788 1315 2789 2175 2789 1156 2789 1315 2790 1156 2790 2235 2790 2222 2791 1154 2791 1310 2791 1310 2792 1154 2792 2175 2792 1156 2793 1155 2793 2214 2793 2214 2794 1155 2794 2160 2794 1155 2795 2221 2795 2160 2795 2164 2796 1158 2796 1157 2796 1157 2797 1158 2797 729 2797 733 2798 1159 2798 1160 2798 1160 2799 1159 2799 2161 2799 1310 2800 2213 2800 2160 2800 2212 2801 1102 2801 1101 2801 1161 2802 1130 2802 1119 2802 1119 2803 1130 2803 1162 2803 1625 2804 2147 2804 2209 2804 2110 2805 1272 2805 1164 2805 1200 2806 1625 2806 1163 2806 2206 2807 1164 2807 1199 2807 776 2808 773 2808 785 2808 785 2809 773 2809 787 2809 2158 2810 778 2810 2157 2810 2157 2811 778 2811 784 2811 2140 2812 1204 2812 2141 2812 2141 2813 1204 2813 2156 2813 1206 2814 1208 2814 1165 2814 1165 2815 1208 2815 1210 2815 2077 2816 1273 2816 2085 2816 2085 2817 1273 2817 2086 2817 1166 2818 1167 2818 2084 2818 2084 2819 1167 2819 2087 2819 1262 2820 1169 2820 2095 2820 2095 2821 1169 2821 1195 2821 1262 2822 2095 2822 1170 2822 1170 2823 2095 2823 1171 2823 1170 2824 1171 2824 2093 2824 1794 2825 1172 2825 2251 2825 687 2826 1260 2826 1173 2826 1173 2827 1260 2827 1261 2827 1794 2828 2251 2828 1261 2828 1261 2829 2251 2829 1173 2829 1194 2830 1257 2830 1255 2830 1194 2831 1255 2831 2096 2831 2096 2832 1255 2832 1174 2832 2096 2833 1174 2833 2094 2833 1176 2834 1258 2834 1175 2834 2098 2835 2097 2835 2252 2835 2252 2836 2097 2836 1176 2836 2252 2837 1176 2837 1175 2837 1179 2838 1178 2838 1177 2838 1177 2839 1178 2839 1192 2839 1179 2840 1177 2840 1180 2840 1180 2841 1177 2841 1181 2841 1180 2842 1181 2842 2099 2842 1193 2843 685 2843 1182 2843 1182 2844 685 2844 2187 2844 1182 2845 2187 2845 1183 2845 1183 2846 2187 2846 1184 2846 1183 2847 1184 2847 2103 2847 1192 2848 682 2848 2155 2848 2155 2849 682 2849 1263 2849 2155 2850 1263 2850 2100 2850 2100 2851 1263 2851 1185 2851 2100 2852 1185 2852 1186 2852 1188 2853 1187 2853 1189 2853 1189 2854 1187 2854 1193 2854 1189 2855 1183 2855 2102 2855 1188 2856 1189 2856 2186 2856 2186 2857 1189 2857 2102 2857 2186 2858 2102 2858 2101 2858 2154 2859 1190 2859 759 2859 1191 2860 756 2860 2153 2860 1177 2861 1192 2861 2155 2861 1193 2862 1182 2862 1189 2862 2095 2863 1195 2863 1194 2863 1622 2864 2117 2864 1168 2864 1198 2865 1196 2865 2109 2865 2231 2866 1197 2866 2109 2866 2109 2867 1197 2867 2128 2867 2109 2868 2128 2868 1198 2868 1164 2869 1248 2869 1199 2869 1199 2870 1248 2870 1200 2870 2148 2871 2237 2871 1199 2871 2148 2872 1199 2872 1200 2872 1201 2873 1249 2873 1202 2873 1202 2874 1249 2874 2126 2874 1202 2875 2126 2875 2242 2875 2242 2876 2126 2876 610 2876 2180 2877 1253 2877 1203 2877 2180 2878 1203 2878 2071 2878 2249 2879 1213 2879 1204 2879 2122 2880 612 2880 2249 2880 2249 2881 1204 2881 2122 2881 2122 2882 1204 2882 2140 2882 2122 2883 2140 2883 2125 2883 1205 2884 1207 2884 1206 2884 1206 2885 1207 2885 2125 2885 1206 2886 2125 2886 1208 2886 1208 2887 2125 2887 2140 2887 2143 2888 2142 2888 1208 2888 2143 2889 1208 2889 2140 2889 1213 2890 1214 2890 613 2890 1209 2891 611 2891 1212 2891 1212 2892 1165 2892 1209 2892 1209 2893 1165 2893 1210 2893 1209 2894 1210 2894 613 2894 2243 2895 2245 2895 2141 2895 2156 2896 1213 2896 613 2896 2156 2897 613 2897 2141 2897 2141 2898 613 2898 1210 2898 2141 2899 1210 2899 2243 2899 2073 2900 614 2900 615 2900 2073 2901 615 2901 1211 2901 611 2902 1207 2902 1212 2902 1212 2903 1207 2903 1205 2903 2249 2904 612 2904 1213 2904 1213 2905 612 2905 1214 2905 1202 2906 2159 2906 1060 2906 1060 2907 1201 2907 1202 2907 664 2908 2990 2908 1374 2908 1374 2909 2990 2909 2989 2909 1374 2910 2989 2910 1215 2910 1216 2911 1629 2911 1371 2911 1371 2912 1629 2912 664 2912 1371 2913 664 2913 1372 2913 1372 2914 664 2914 1374 2914 2988 2915 1237 2915 1218 2915 1629 2916 1978 2916 664 2916 664 2917 1978 2917 1631 2917 664 2918 1631 2918 1267 2918 1267 2919 1631 2919 1630 2919 1267 2920 1630 2920 1221 2920 1380 2921 1377 2921 1237 2921 1237 2922 1377 2922 1376 2922 1237 2923 1376 2923 1218 2923 1218 2924 1376 2924 1217 2924 1218 2925 1217 2925 2985 2925 2985 2926 1217 2926 1364 2926 1234 2927 1666 2927 1225 2927 1219 2928 1220 2928 1267 2928 1267 2929 1220 2929 1652 2929 1267 2930 1652 2930 1655 2930 1221 2931 1974 2931 1267 2931 1267 2932 1974 2932 1222 2932 1267 2933 1222 2933 1634 2933 1938 2934 1715 2934 1268 2934 1268 2935 1715 2935 1718 2935 1268 2936 1718 2936 1934 2936 1949 2937 1223 2937 1229 2937 1229 2938 1223 2938 1948 2938 1229 2939 1948 2939 1224 2939 1634 2940 1971 2940 1267 2940 1267 2941 1971 2941 1635 2941 1267 2942 1635 2942 1640 2942 1225 2943 1226 2943 1234 2943 1234 2944 1226 2944 1953 2944 1234 2945 1953 2945 1671 2945 1655 2946 1227 2946 1267 2946 1267 2947 1227 2947 1657 2947 1267 2948 1657 2948 1234 2948 1234 2949 1657 2949 1230 2949 1934 2950 1228 2950 1268 2950 1268 2951 1228 2951 1722 2951 1268 2952 1722 2952 1729 2952 1640 2953 1639 2953 1267 2953 1267 2954 1639 2954 1644 2954 1267 2955 1644 2955 1643 2955 1704 2956 1229 2956 1945 2956 1945 2957 1229 2957 1946 2957 1946 2958 1229 2958 1224 2958 1230 2959 1963 2959 1234 2959 1234 2960 1963 2960 1661 2960 1234 2961 1661 2961 1239 2961 1643 2962 1231 2962 1267 2962 1267 2963 1231 2963 1646 2963 1267 2964 1646 2964 1232 2964 1267 2965 1232 2965 1219 2965 1671 2966 1233 2966 1234 2966 1234 2967 1233 2967 1235 2967 1234 2968 1235 2968 2110 2968 1931 2969 1736 2969 1237 2969 1366 2970 1380 2970 1236 2970 1236 2971 1380 2971 1237 2971 1236 2972 1237 2972 1627 2972 1627 2973 1237 2973 1736 2973 1704 2974 1702 2974 1229 2974 1229 2975 1702 2975 1943 2975 1229 2976 1943 2976 1707 2976 1235 2977 1678 2977 2110 2977 2110 2978 1678 2978 1677 2978 2110 2979 1677 2979 1680 2979 1729 2980 1727 2980 1268 2980 1268 2981 1727 2981 1733 2981 1268 2982 1733 2982 1237 2982 1237 2983 1733 2983 1238 2983 1237 2984 1238 2984 1931 2984 1239 2985 1960 2985 1234 2985 1234 2986 1960 2986 1959 2986 1234 2987 1959 2987 1240 2987 1234 2988 1240 2988 1956 2988 1234 2989 1956 2989 1666 2989 1707 2990 1941 2990 1229 2990 1229 2991 1941 2991 1241 2991 1229 2992 1241 2992 2151 2992 2151 2993 1241 2993 1939 2993 2151 2994 1939 2994 1268 2994 1268 2995 1939 2995 1712 2995 1268 2996 1712 2996 1938 2996 1680 2997 1950 2997 2110 2997 2110 2998 1950 2998 1242 2998 2110 2999 1242 2999 1243 2999 1243 3000 1687 3000 2110 3000 2110 3001 1687 3001 1685 3001 2110 3002 1685 3002 1272 3002 1272 3003 1685 3003 1691 3003 1272 3004 1691 3004 1229 3004 1229 3005 1691 3005 1690 3005 1229 3006 1690 3006 1949 3006 1168 3007 2117 3007 1244 3007 2117 3008 1265 3008 1244 3008 1244 3009 1265 3009 1245 3009 1245 3010 1265 3010 1246 3010 1247 3011 1271 3011 683 3011 796 3012 797 3012 2178 3012 2178 3013 797 3013 1247 3013 1247 3014 797 3014 1271 3014 1791 3015 2127 3015 786 3015 1198 3016 2128 3016 1248 3016 1250 3017 761 3017 783 3017 1200 3018 1248 3018 1249 3018 2128 3019 1250 3019 1248 3019 1248 3020 1250 3020 783 3020 1248 3021 783 3021 1249 3021 1249 3022 783 3022 786 3022 1249 3023 786 3023 2126 3023 2126 3024 786 3024 2127 3024 2069 3025 1252 3025 1251 3025 1209 3026 2184 3026 1251 3026 1209 3027 1251 3027 1252 3027 614 3028 2073 3028 2184 3028 1209 3029 613 3029 2184 3029 2184 3030 613 3030 614 3030 2122 3031 2089 3031 2123 3031 2074 3032 2123 3032 2089 3032 1253 3033 1254 3033 2124 3033 2124 3034 1254 3034 2089 3034 1253 3035 2180 3035 1254 3035 2122 3036 2125 3036 2124 3036 2122 3037 2124 3037 2089 3037 1255 3038 1257 3038 1256 3038 1258 3039 1176 3039 2078 3039 1256 3040 1257 3040 1259 3040 1256 3041 1259 3041 2078 3041 2078 3042 1259 3042 684 3042 2078 3043 684 3043 1258 3043 1260 3044 1187 3044 1261 3044 1261 3045 1187 3045 1188 3045 1262 3046 1263 3046 1169 3046 1169 3047 1263 3047 682 3047 685 3048 1264 3048 2187 3048 2187 3049 1264 3049 2189 3049 1179 3050 3029 3050 1178 3050 1178 3051 3029 3051 681 3051 2104 3052 1265 3052 2116 3052 2114 3053 1626 3053 2112 3053 2112 3054 1626 3054 1267 3054 2204 3055 1623 3055 2151 3055 2151 3056 1623 3056 2205 3056 1624 3057 797 3057 2106 3057 2117 3058 1622 3058 2115 3058 1234 3059 1625 3059 2113 3059 2111 3060 2120 3060 1270 3060 2120 3061 1271 3061 1270 3061 1271 3062 2120 3062 683 3062 2207 3063 2208 3063 1272 3063 2083 3064 2091 3064 2084 3064 2084 3065 2091 3065 1166 3065 2250 3066 2086 3066 2079 3066 2079 3067 2086 3067 1273 3067 2990 3068 664 3068 816 3068 816 3069 664 3069 1274 3069 2182 3070 1237 3070 818 3070 818 3071 1237 3071 2988 3071 1278 3072 3084 3072 1275 3072 1275 3073 3084 3073 1294 3073 2018 3074 1276 3074 1277 3074 1277 3075 1276 3075 1278 3075 1277 3076 1278 3076 1275 3076 2194 3077 1279 3077 1280 3077 1295 3078 1342 3078 2261 3078 2261 3079 1342 3079 2193 3079 2194 3080 1280 3080 2193 3080 2193 3081 1280 3081 2261 3081 1282 3082 2016 3082 1281 3082 1294 3083 673 3083 2017 3083 2017 3084 673 3084 1283 3084 1282 3085 1281 3085 1283 3085 1283 3086 1281 3086 2017 3086 1285 3087 675 3087 2037 3087 2037 3088 675 3088 1295 3088 2036 3089 1284 3089 2262 3089 2262 3090 1284 3090 1285 3090 2262 3091 1285 3091 2037 3091 2163 3092 2162 3092 3040 3092 1287 3093 620 3093 1069 3093 1069 3094 1288 3094 1287 3094 2174 3095 1288 3095 1069 3095 1103 3096 1350 3096 1071 3096 1289 3097 1081 3097 1290 3097 1087 3098 1291 3098 2170 3098 1293 3099 1292 3099 1090 3099 2171 3100 679 3100 1091 3100 1294 3101 2017 3101 1275 3101 2037 3102 1295 3102 2261 3102 1651 3103 1653 3103 1308 3103 1301 3104 1139 3104 1308 3104 1709 3105 1315 3105 1321 3105 1315 3106 1296 3106 1696 3106 1309 3107 1297 3107 1308 3107 1297 3108 1298 3108 1308 3108 1308 3109 1298 3109 1299 3109 1308 3110 1299 3110 1300 3110 1308 3111 1632 3111 1302 3111 1308 3112 1302 3112 1929 3112 1308 3113 1929 3113 1301 3113 1308 3114 1636 3114 1637 3114 1308 3115 1637 3115 1983 3115 1983 3116 1981 3116 1308 3116 1308 3117 1981 3117 1303 3117 1308 3118 1303 3118 1633 3118 1308 3119 1633 3119 1632 3119 1308 3120 1653 3120 1648 3120 1308 3121 1648 3121 1649 3121 1308 3122 1649 3122 1989 3122 1308 3123 1989 3123 1304 3123 1308 3124 1304 3124 1305 3124 1305 3125 1987 3125 1308 3125 1308 3126 1987 3126 1985 3126 1308 3127 1985 3127 1641 3127 1308 3128 1641 3128 1636 3128 1300 3129 1662 3129 1308 3129 1308 3130 1662 3130 1994 3130 1994 3131 1993 3131 1308 3131 1308 3132 1993 3132 1992 3132 1308 3133 1992 3133 1306 3133 1308 3134 1306 3134 1651 3134 1996 3135 1670 3135 1310 3135 1310 3136 1670 3136 1307 3136 1310 3137 1307 3137 1667 3137 1308 3138 2213 3138 1309 3138 1309 3139 2213 3139 1310 3139 1309 3140 1310 3140 1311 3140 1311 3141 1310 3141 1667 3141 1679 3142 1681 3142 1310 3142 1681 3143 1676 3143 1310 3143 1310 3144 1676 3144 1312 3144 1310 3145 1312 3145 1674 3145 1310 3146 1674 3146 1313 3146 1313 3147 1314 3147 1310 3147 1310 3148 1314 3148 1996 3148 1696 3149 1697 3149 1315 3149 1315 3150 1697 3150 1316 3150 1315 3151 1316 3151 1693 3151 1315 3152 1693 3152 1686 3152 1686 3153 1317 3153 1315 3153 1315 3154 1317 3154 1999 3154 1315 3155 1999 3155 1310 3155 1310 3156 1999 3156 1318 3156 1310 3157 1318 3157 1679 3157 1709 3158 1705 3158 1315 3158 1315 3159 1705 3159 1319 3159 1319 3160 1701 3160 1315 3160 1315 3161 1701 3161 1703 3161 1315 3162 1703 3162 2002 3162 1315 3163 2002 3163 1700 3163 1700 3164 2001 3164 1315 3164 1315 3165 2001 3165 1296 3165 2005 3166 1717 3166 1321 3166 1321 3167 1717 3167 1719 3167 1321 3168 1719 3168 1320 3168 1320 3169 2004 3169 1321 3169 1321 3170 2004 3170 1713 3170 1321 3171 1713 3171 1714 3171 1321 3172 1714 3172 1322 3172 1321 3173 1322 3173 1709 3173 1321 3174 1737 3174 2007 3174 2007 3175 1732 3175 1321 3175 1321 3176 1732 3176 1734 3176 1321 3177 1734 3177 1728 3177 1321 3178 1728 3178 1323 3178 1323 3179 1723 3179 1321 3179 1321 3180 1723 3180 2005 3180 1737 3181 1321 3181 1324 3181 1324 3182 1321 3182 1628 3182 1628 3183 1321 3183 1325 3183 1137 3184 1326 3184 2210 3184 2210 3185 1326 3185 629 3185 2027 3186 1326 3186 1137 3186 629 3187 2174 3187 2210 3187 2210 3188 2174 3188 2052 3188 1285 3189 1092 3189 675 3189 675 3190 1092 3190 678 3190 673 3191 1089 3191 1283 3191 1283 3192 1089 3192 1088 3192 1327 3193 3049 3193 677 3193 677 3194 3049 3194 1078 3194 1096 3195 1075 3195 2200 3195 2200 3196 1075 3196 1076 3196 2039 3197 634 3197 1328 3197 1328 3198 634 3198 3041 3198 634 3199 633 3199 3041 3199 3041 3200 633 3200 3040 3200 667 3201 1286 3201 2050 3201 2050 3202 743 3202 1329 3202 1286 3203 667 3203 1345 3203 1345 3204 667 3204 1351 3204 667 3205 2050 3205 1352 3205 1352 3206 2050 3206 1329 3206 1149 3207 1330 3207 1085 3207 1085 3208 1330 3208 1086 3208 1086 3209 1330 3209 2065 3209 2024 3210 2042 3210 1333 3210 621 3211 2048 3211 2047 3211 1331 3212 1332 3212 1118 3212 1334 3213 1331 3213 621 3213 621 3214 1331 3214 1118 3214 621 3215 1118 3215 2048 3215 2048 3216 1118 3216 1333 3216 2048 3217 1333 3217 1106 3217 1106 3218 1333 3218 2042 3218 2028 3219 631 3219 1124 3219 1047 3220 1125 3220 1124 3220 1047 3221 1124 3221 631 3221 1356 3222 1838 3222 1125 3222 1047 3223 1335 3223 1125 3223 1125 3224 1335 3224 1356 3224 1338 3225 1337 3225 1336 3225 1336 3226 1337 3226 1359 3226 1359 3227 1360 3227 1336 3227 1338 3228 2057 3228 1339 3228 1338 3229 1339 3229 1337 3229 2193 3230 1342 3230 1343 3230 3084 3231 1278 3231 1051 3231 3084 3232 1051 3232 1340 3232 1340 3233 1051 3233 1341 3233 1342 3234 680 3234 1341 3234 1342 3235 1341 3235 1343 3235 1343 3236 1341 3236 1051 3236 2040 3237 741 3237 1344 3237 1344 3238 741 3238 580 3238 1344 3239 580 3239 3040 3239 2040 3240 1361 3240 741 3240 1351 3241 1353 3241 1345 3241 1345 3242 1353 3242 2201 3242 2201 3243 1353 3243 1346 3243 2050 3244 1347 3244 745 3244 2050 3245 1286 3245 1347 3245 2050 3246 745 3246 743 3246 2066 3247 1330 3247 2051 3247 2067 3248 1330 3248 2066 3248 1308 3249 2052 3249 1348 3249 1348 3250 2052 3250 2211 3250 727 3251 622 3251 1349 3251 1349 3252 622 3252 1621 3252 1621 3253 2065 3253 1349 3253 1068 3254 1102 3254 2213 3254 1315 3255 1350 3255 2063 3255 2064 3256 2216 3256 1321 3256 667 3257 2062 3257 1351 3257 667 3258 1352 3258 2062 3258 2054 3259 1353 3259 1354 3259 2203 3260 624 3260 3046 3260 3046 3261 624 3261 2134 3261 1838 3262 1356 3262 1358 3262 1838 3263 1358 3263 2022 3263 2023 3264 1357 3264 1358 3264 1358 3265 1357 3265 2022 3265 1840 3266 2197 3266 1074 3266 1840 3267 1074 3267 2225 3267 2225 3268 1074 3268 628 3268 1332 3269 1331 3269 2227 3269 2227 3270 1331 3270 2228 3270 1360 3271 1359 3271 2031 3271 1360 3272 2031 3272 2030 3272 1361 3273 2040 3273 2135 3273 2135 3274 2040 3274 2136 3274 725 3275 1139 3275 1301 3275 663 3276 1139 3276 1301 3276 663 3277 1301 3277 1139 3277 1325 3278 1362 3278 3003 3278 1325 3279 3003 3279 1628 3279 1363 3280 1894 3280 2974 3280 2974 3281 1894 3281 2987 3281 1364 3282 1217 3282 2974 3282 1364 3283 2974 3283 2987 3283 1380 3284 1366 3284 1365 3284 1365 3285 1366 3285 1922 3285 1365 3286 1922 3286 1909 3286 1909 3287 1922 3287 1923 3287 3014 3288 2982 3288 2785 3288 2785 3289 2982 3289 2928 3289 2928 3290 3074 3290 2785 3290 1215 3291 2989 3291 1367 3291 1892 3292 1368 3292 3012 3292 3012 3293 1368 3293 1367 3293 3012 3294 1367 3294 2989 3294 2969 3295 1368 3295 1892 3295 2969 3296 1892 3296 1901 3296 2969 3297 1901 3297 2970 3297 1895 3298 1429 3298 1369 3298 2970 3299 1901 3299 1895 3299 2970 3300 1895 3300 1369 3300 2976 3301 1898 3301 2975 3301 2975 3302 1898 3302 1897 3302 2975 3303 1897 3303 1370 3303 2975 3304 1370 3304 2978 3304 2978 3305 1370 3305 1894 3305 2978 3306 1894 3306 1363 3306 2971 3307 1589 3307 1371 3307 2971 3308 1371 3308 1372 3308 2971 3309 1372 3309 1374 3309 2971 3310 1374 3310 1373 3310 1373 3311 1374 3311 1215 3311 1373 3312 1215 3312 1367 3312 2974 3313 1217 3313 1375 3313 1217 3314 1376 3314 1375 3314 1375 3315 1376 3315 1377 3315 1375 3316 1377 3316 1378 3316 1378 3317 1377 3317 1380 3317 1378 3318 1380 3318 1379 3318 1379 3319 1380 3319 1365 3319 3009 3320 2981 3320 1381 3320 1381 3321 2981 3321 1382 3321 1381 3322 1382 3322 3003 3322 1381 3323 3003 3323 1843 3323 1517 3324 1383 3324 1384 3324 1384 3325 1383 3325 1757 3325 1384 3326 1757 3326 1385 3326 1385 3327 1757 3327 1763 3327 1385 3328 1763 3328 1386 3328 1386 3329 1763 3329 1764 3329 1386 3330 1764 3330 3071 3330 3071 3331 1764 3331 1756 3331 3071 3332 1756 3332 1387 3332 1387 3333 1756 3333 1765 3333 1387 3334 1765 3334 3070 3334 3070 3335 1765 3335 1766 3335 3070 3336 1766 3336 1388 3336 1388 3337 1766 3337 1755 3337 1388 3338 1755 3338 1389 3338 1389 3339 1755 3339 1754 3339 1389 3340 1754 3340 1390 3340 1390 3341 1754 3341 1753 3341 1390 3342 1753 3342 3067 3342 3067 3343 1753 3343 1767 3343 3067 3344 1767 3344 3069 3344 3069 3345 1767 3345 1519 3345 1391 3346 1393 3346 1789 3346 1392 3347 1598 3347 1526 3347 1392 3348 1393 3348 1598 3348 1598 3349 1393 3349 1394 3349 1598 3350 1394 3350 2315 3350 2315 3351 1394 3351 671 3351 1511 3352 1396 3352 1395 3352 671 3353 1395 3353 2315 3353 2315 3354 1395 3354 1396 3354 2315 3355 1396 3355 1397 3355 2315 3356 1397 3356 1398 3356 1398 3357 1397 3357 1520 3357 1398 3358 1520 3358 1619 3358 1399 3359 1400 3359 1395 3359 1395 3360 1400 3360 1505 3360 1395 3361 1505 3361 1506 3361 1506 3362 1509 3362 1395 3362 1395 3363 1509 3363 1510 3363 1395 3364 1510 3364 1511 3364 1468 3365 1401 3365 1402 3365 1402 3366 1401 3366 702 3366 1402 3367 702 3367 3062 3367 1402 3368 3062 3368 3077 3368 1476 3369 1403 3369 1404 3369 1476 3370 1404 3370 1406 3370 1601 3371 1405 3371 1404 3371 1404 3372 1405 3372 669 3372 1404 3373 669 3373 1406 3373 1473 3374 1823 3374 1407 3374 1473 3375 1407 3375 1412 3375 1412 3376 1407 3376 1827 3376 1412 3377 1827 3377 1413 3377 1413 3378 1827 3378 1824 3378 1413 3379 1824 3379 1414 3379 1414 3380 1824 3380 1825 3380 1414 3381 1825 3381 1408 3381 1408 3382 1825 3382 1818 3382 1408 3383 1818 3383 1409 3383 1409 3384 1818 3384 1410 3384 1409 3385 1410 3385 1903 3385 1903 3386 1410 3386 1819 3386 1817 3387 1406 3387 1411 3387 1409 3388 1903 3388 670 3388 1405 3389 1601 3389 670 3389 1602 3390 1470 3390 1402 3390 1602 3391 1402 3391 1601 3391 1409 3392 670 3392 1408 3392 1473 3393 1412 3393 670 3393 1402 3394 3078 3394 1601 3394 1601 3395 3078 3395 1472 3395 1601 3396 1472 3396 670 3396 670 3397 1472 3397 1473 3397 1412 3398 1413 3398 670 3398 670 3399 1413 3399 1414 3399 670 3400 1414 3400 1408 3400 1425 3401 1428 3401 1369 3401 1416 3402 2010 3402 2977 3402 2977 3403 2010 3403 1919 3403 1417 3404 1885 3404 1886 3404 1417 3405 1886 3405 2976 3405 2976 3406 1886 3406 1887 3406 2976 3407 1887 3407 639 3407 1418 3408 1881 3408 1429 3408 1429 3409 1881 3409 1882 3409 639 3410 1419 3410 2976 3410 2976 3411 1419 3411 640 3411 2976 3412 640 3412 1898 3412 1882 3413 1420 3413 1429 3413 1429 3414 1420 3414 1421 3414 1429 3415 1421 3415 1884 3415 640 3416 1422 3416 1898 3416 1898 3417 1422 3417 641 3417 641 3418 1418 3418 1898 3418 1898 3419 1418 3419 1429 3419 1415 3420 1369 3420 1429 3420 1433 3421 644 3421 1423 3421 1433 3422 1423 3422 1431 3422 1877 3423 1878 3423 1369 3423 1369 3424 1878 3424 1879 3424 1369 3425 1879 3425 1424 3425 1369 3426 1424 3426 1425 3426 1426 3427 1415 3427 646 3427 646 3428 1415 3428 645 3428 1369 3429 1415 3429 1877 3429 2968 3430 1427 3430 1910 3430 1427 3431 2968 3431 1369 3431 1427 3432 1369 3432 1433 3432 1433 3433 1369 3433 1428 3433 1433 3434 1428 3434 644 3434 2849 3435 880 3435 587 3435 1884 3436 1417 3436 1429 3436 1429 3437 1417 3437 2849 3437 2849 3438 1417 3438 587 3438 2977 3439 1919 3439 2976 3439 2976 3440 1919 3440 2849 3440 2976 3441 2849 3441 1417 3441 1417 3442 2849 3442 587 3442 2845 3443 1430 3443 1429 3443 1429 3444 1430 3444 1415 3444 1431 3445 645 3445 1433 3445 1433 3446 645 3446 1415 3446 1433 3447 1415 3447 1430 3447 1433 3448 1432 3448 1427 3448 2845 3449 1429 3449 1430 3449 1430 3450 1429 3450 2849 3450 1430 3451 2849 3451 1433 3451 1432 3452 864 3452 1433 3452 1432 3453 1433 3453 2849 3453 2009 3454 1427 3454 1432 3454 2009 3455 1432 3455 1434 3455 1434 3456 1432 3456 2849 3456 1434 3457 2849 3457 1919 3457 1435 3458 1029 3458 2691 3458 2691 3459 1029 3459 1436 3459 2672 3460 1436 3460 1029 3460 2672 3461 1029 3461 1437 3461 1012 3462 1740 3462 997 3462 3014 3463 2785 3463 938 3463 938 3464 2785 3464 1440 3464 1438 3465 2680 3465 1439 3465 1439 3466 2680 3466 1440 3466 1740 3467 1442 3467 997 3467 997 3468 1442 3468 1441 3468 1441 3469 1442 3469 1443 3469 1441 3470 1443 3470 1001 3470 1001 3471 1443 3471 2690 3471 2736 3472 962 3472 1449 3472 2736 3473 1449 3473 2730 3473 991 3474 1499 3474 1498 3474 1444 3475 2749 3475 1445 3475 1445 3476 2749 3476 1499 3476 993 3477 1444 3477 1445 3477 1493 3478 993 3478 1446 3478 1493 3479 1446 3479 2752 3479 2752 3480 1446 3480 2739 3480 2609 3481 2787 3481 3009 3481 2739 3482 1446 3482 1497 3482 1497 3483 1446 3483 2609 3483 1497 3484 2609 3484 3009 3484 991 3485 2748 3485 1447 3485 1447 3486 2748 3486 1448 3486 1447 3487 1448 3487 1449 3487 1449 3488 1448 3488 2730 3488 2694 3489 958 3489 1451 3489 1890 3490 2305 3490 1450 3490 2699 3491 596 3491 1452 3491 1452 3492 596 3492 953 3492 1452 3493 953 3493 2306 3493 2306 3494 953 3494 957 3494 2694 3495 1452 3495 958 3495 958 3496 1452 3496 2306 3496 958 3497 2306 3497 1749 3497 958 3498 1749 3498 1451 3498 1451 3499 1749 3499 950 3499 3059 3500 3054 3500 703 3500 703 3501 3054 3501 1454 3501 2344 3502 1454 3502 2129 3502 1450 3503 1453 3503 3054 3503 3054 3504 1453 3504 2129 3504 2305 3505 1453 3505 1450 3505 1454 3506 2344 3506 957 3506 1454 3507 3054 3507 2129 3507 2761 3508 593 3508 2763 3508 2763 3509 593 3509 594 3509 601 3510 927 3510 1455 3510 1871 3511 602 3511 2753 3511 602 3512 2303 3512 2753 3512 927 3513 2763 3513 1455 3513 1455 3514 2763 3514 594 3514 1455 3515 594 3515 602 3515 602 3516 594 3516 2765 3516 602 3517 2765 3517 2303 3517 1457 3518 2304 3518 1456 3518 1455 3519 602 3519 1797 3519 1797 3520 602 3520 1871 3520 1850 3521 927 3521 2342 3521 1456 3522 2304 3522 2350 3522 2350 3523 2304 3523 1039 3523 2304 3524 1457 3524 1039 3524 1039 3525 1457 3525 3053 3525 1039 3526 3053 3526 1038 3526 3053 3527 717 3527 2177 3527 2342 3528 1038 3528 1850 3528 1850 3529 1038 3529 3053 3529 1850 3530 3053 3530 2177 3530 2440 3531 1463 3531 1489 3531 2440 3532 1489 3532 2801 3532 1460 3533 2805 3533 2804 3533 2804 3534 2805 3534 1597 3534 2805 3535 2806 3535 1597 3535 1597 3536 2806 3536 1459 3536 1459 3537 2801 3537 1489 3537 1489 3538 1458 3538 1459 3538 1459 3539 1458 3539 1490 3539 1459 3540 1490 3540 1597 3540 1597 3541 1490 3541 1468 3541 1597 3542 1467 3542 1462 3542 1462 3543 1467 3543 1474 3543 1460 3544 2801 3544 2805 3544 2805 3545 2801 3545 1459 3545 1463 3546 2440 3546 1461 3546 1460 3547 2802 3547 2801 3547 1597 3548 1462 3548 2804 3548 1464 3549 1465 3549 1463 3549 1464 3550 1463 3550 1461 3550 1464 3551 1461 3551 2802 3551 1465 3552 1464 3552 1474 3552 1474 3553 1464 3553 1462 3553 1403 3554 1476 3554 1466 3554 1403 3555 1466 3555 1597 3555 1597 3556 1466 3556 1467 3556 1468 3557 1402 3557 1469 3557 1597 3558 1468 3558 1596 3558 1596 3559 1468 3559 1469 3559 1596 3560 1469 3560 1602 3560 1602 3561 1469 3561 1470 3561 1474 3562 1471 3562 1465 3562 1465 3563 1471 3563 1823 3563 1465 3564 1823 3564 1472 3564 1472 3565 1823 3565 1473 3565 1820 3566 1475 3566 1466 3566 1466 3567 1475 3567 1467 3567 1471 3568 1474 3568 1467 3568 1471 3569 1467 3569 1475 3569 1817 3570 1820 3570 1466 3570 1406 3571 1817 3571 1476 3571 1476 3572 1817 3572 1466 3572 3062 3573 702 3573 1477 3573 1477 3574 702 3574 701 3574 1477 3575 701 3575 3063 3575 3063 3576 701 3576 1811 3576 3063 3577 1811 3577 1478 3577 1478 3578 1811 3578 1813 3578 1478 3579 1813 3579 1479 3579 1479 3580 1813 3580 700 3580 1479 3581 700 3581 3064 3581 3064 3582 700 3582 1480 3582 3064 3583 1480 3583 1481 3583 1481 3584 1480 3584 1482 3584 1481 3585 1482 3585 3065 3585 3065 3586 1482 3586 1814 3586 3065 3587 1814 3587 1483 3587 1483 3588 1814 3588 1484 3588 1483 3589 1484 3589 3066 3589 3066 3590 1484 3590 699 3590 3066 3591 699 3591 1485 3591 1485 3592 699 3592 698 3592 1485 3593 698 3593 3061 3593 3061 3594 698 3594 1486 3594 696 3595 695 3595 1458 3595 1458 3596 695 3596 1490 3596 1488 3597 1489 3597 1486 3597 1486 3598 1489 3598 1463 3598 1486 3599 1463 3599 3061 3599 3061 3600 1463 3600 3078 3600 3061 3601 3078 3601 1487 3601 696 3602 1458 3602 1488 3602 1488 3603 1458 3603 1489 3603 1490 3604 695 3604 1468 3604 695 3605 1401 3605 1468 3605 1491 3606 2776 3606 1874 3606 1833 3607 1817 3607 1876 3607 649 3608 3009 3608 1496 3608 2314 3609 650 3609 1867 3609 2314 3610 1867 3610 1843 3610 2775 3611 1865 3611 1826 3611 2776 3612 2777 3612 1874 3612 1832 3613 1471 3613 1831 3613 1832 3614 1874 3614 2775 3614 1832 3615 2775 3615 1826 3615 1492 3616 647 3616 1825 3616 1826 3617 1500 3617 1407 3617 1407 3618 1500 3618 2728 3618 2750 3619 993 3619 648 3619 648 3620 993 3620 1493 3620 1825 3621 647 3621 2733 3621 1825 3622 2733 3622 1494 3622 1494 3623 2733 3623 648 3623 648 3624 1493 3624 1494 3624 3009 3625 649 3625 1497 3625 1835 3626 1496 3626 1843 3626 650 3627 1835 3627 1843 3627 1833 3628 1876 3628 2760 3628 2760 3629 1502 3629 1833 3629 1495 3630 1843 3630 1496 3630 1843 3631 1495 3631 1496 3631 1843 3632 1496 3632 1381 3632 1497 3633 649 3633 2738 3633 647 3634 1498 3634 1499 3634 1500 3635 1826 3635 2736 3635 1865 3636 2736 3636 1826 3636 2779 3637 1503 3637 1832 3637 751 3638 1501 3638 2783 3638 1831 3639 2783 3639 2755 3639 1831 3640 2755 3640 1832 3640 2783 3641 1831 3641 2784 3641 1501 3642 2755 3642 2783 3642 1832 3643 2755 3643 2779 3643 1833 3644 1502 3644 1831 3644 1831 3645 1502 3645 2784 3645 650 3646 1876 3646 1817 3646 650 3647 1817 3647 1835 3647 2314 3648 1876 3648 650 3648 650 3649 1843 3649 1867 3649 1832 3650 1503 3650 1491 3650 1832 3651 1491 3651 1874 3651 1381 3652 1496 3652 3009 3652 1399 3653 1904 3653 1400 3653 1400 3654 1904 3654 1504 3654 1400 3655 1504 3655 1505 3655 1505 3656 1504 3656 1507 3656 1505 3657 1507 3657 1506 3657 1506 3658 1507 3658 1508 3658 1506 3659 1508 3659 1509 3659 1509 3660 1508 3660 1780 3660 1509 3661 1780 3661 1510 3661 1510 3662 1780 3662 1781 3662 1510 3663 1781 3663 1511 3663 1511 3664 1781 3664 1512 3664 1511 3665 1512 3665 1513 3665 1523 3666 1784 3666 1527 3666 1527 3667 1784 3667 1786 3667 1396 3668 1511 3668 1524 3668 1524 3669 1511 3669 1513 3669 1524 3670 1513 3670 1522 3670 1522 3671 1513 3671 1514 3671 1784 3672 1523 3672 1514 3672 1514 3673 1523 3673 1522 3673 1392 3674 1527 3674 1786 3674 1392 3675 1786 3675 1789 3675 1392 3676 1789 3676 1393 3676 1515 3677 1758 3677 1516 3677 1516 3678 1758 3678 1383 3678 1516 3679 1383 3679 1397 3679 1397 3680 1383 3680 1517 3680 1397 3681 1517 3681 3076 3681 1528 3682 1521 3682 1518 3682 1518 3683 1521 3683 1759 3683 1761 3684 1617 3684 1519 3684 1519 3685 1617 3685 3069 3685 3069 3686 1617 3686 1520 3686 3069 3687 1520 3687 3068 3687 1758 3688 1515 3688 1759 3688 1759 3689 1515 3689 1518 3689 1617 3690 1761 3690 1528 3690 1528 3691 1761 3691 1521 3691 2788 3692 2799 3692 2792 3692 1522 3693 2461 3693 1524 3693 1522 3694 923 3694 2788 3694 923 3695 1522 3695 1523 3695 923 3696 1523 3696 1527 3696 1522 3697 2788 3697 2461 3697 1524 3698 2461 3698 2460 3698 924 3699 1525 3699 1518 3699 2796 3700 1516 3700 1524 3700 2796 3701 1524 3701 2460 3701 2796 3702 2460 3702 2792 3702 1526 3703 923 3703 1527 3703 1526 3704 1527 3704 1392 3704 1515 3705 924 3705 1518 3705 924 3706 1515 3706 2799 3706 1528 3707 1518 3707 1599 3707 1599 3708 1518 3708 1525 3708 1599 3709 1525 3709 1526 3709 1526 3710 1525 3710 923 3710 1516 3711 2796 3711 2794 3711 1516 3712 2794 3712 1515 3712 1515 3713 2794 3713 2799 3713 2799 3714 2788 3714 2800 3714 1529 3715 1930 3715 1927 3715 1927 3716 1930 3716 1735 3716 1738 3717 1530 3717 1531 3717 1531 3718 1530 3718 1731 3718 1532 3719 1533 3719 2006 3719 2006 3720 1533 3720 1726 3720 1932 3721 1534 3721 1730 3721 1730 3722 1534 3722 1721 3722 1724 3723 1933 3723 1725 3723 1725 3724 1933 3724 1535 3724 1720 3725 1935 3725 1536 3725 1536 3726 1935 3726 1716 3726 1936 3727 1937 3727 1537 3727 1537 3728 1937 3728 1711 3728 1538 3729 1539 3729 2003 3729 2003 3730 1539 3730 1940 3730 1540 3731 1710 3731 1541 3731 1541 3732 1710 3732 1706 3732 1708 3733 1942 3733 1542 3733 1542 3734 1942 3734 1543 3734 1544 3735 1944 3735 1699 3735 1699 3736 1944 3736 1545 3736 1546 3737 1698 3737 1547 3737 1547 3738 1698 3738 1548 3738 1947 3739 1694 3739 1549 3739 1549 3740 1694 3740 1695 3740 1550 3741 1552 3741 1551 3741 1551 3742 1552 3742 1553 3742 1692 3743 1554 3743 2000 3743 2000 3744 1554 3744 1684 3744 1688 3745 1682 3745 1689 3745 1689 3746 1682 3746 1683 3746 1555 3747 1557 3747 1556 3747 1556 3748 1557 3748 1998 3748 1558 3749 1675 3749 1559 3749 1559 3750 1675 3750 1997 3750 1560 3751 1561 3751 1562 3751 1562 3752 1561 3752 1673 3752 1951 3753 1563 3753 1564 3753 1564 3754 1563 3754 1565 3754 1672 3755 1952 3755 1995 3755 1995 3756 1952 3756 1669 3756 1954 3757 1567 3757 1566 3757 1566 3758 1567 3758 1568 3758 1955 3759 1569 3759 1668 3759 1668 3760 1569 3760 1570 3760 1957 3761 1958 3761 1665 3761 1665 3762 1958 3762 1664 3762 1961 3763 1659 3763 1571 3763 1571 3764 1659 3764 1660 3764 1663 3765 1962 3765 1572 3765 1572 3766 1962 3766 1656 3766 1964 3767 1573 3767 1658 3767 1658 3768 1573 3768 1574 3768 1965 3769 1966 3769 1991 3769 1991 3770 1966 3770 1990 3770 1967 3771 1968 3771 1654 3771 1654 3772 1968 3772 1575 3772 1576 3773 1577 3773 1650 3773 1650 3774 1577 3774 1647 3774 1988 3775 1969 3775 1578 3775 1578 3776 1969 3776 1579 3776 1645 3777 1970 3777 1986 3777 1986 3778 1970 3778 1984 3778 1580 3779 1581 3779 1642 3779 1642 3780 1581 3780 1582 3780 1583 3781 1972 3781 1638 3781 1638 3782 1972 3782 1982 3782 1973 3783 1584 3783 1980 3783 1980 3784 1584 3784 1979 3784 1585 3785 1975 3785 1586 3785 1586 3786 1975 3786 1587 3786 1976 3787 1977 3787 1588 3787 1588 3788 1977 3788 1928 3788 1216 3789 1371 3789 1926 3789 1926 3790 1371 3790 1589 3790 1926 3791 1589 3791 2972 3791 1914 3792 1921 3792 2972 3792 2972 3793 1921 3793 1926 3793 2395 3794 2397 3794 2351 3794 2351 3795 2397 3795 2399 3795 2351 3796 2399 3796 1594 3796 1037 3797 2357 3797 2356 3797 598 3798 2366 3798 1603 3798 731 3799 2364 3799 2366 3799 2379 3800 1590 3800 2353 3800 2353 3801 1590 3801 2376 3801 2353 3802 2376 3802 1592 3802 2406 3803 2409 3803 600 3803 600 3804 2409 3804 2405 3804 2342 3805 2404 3805 1591 3805 1591 3806 2404 3806 2406 3806 2404 3807 2342 3807 2343 3807 2343 3808 2289 3808 2407 3808 1592 3809 2371 3809 2372 3809 1592 3810 2372 3810 597 3810 1608 3811 2369 3811 2378 3811 1594 3812 1593 3812 2390 3812 2284 3813 2391 3813 2331 3813 2331 3814 2391 3814 2398 3814 2384 3815 2387 3815 2312 3815 2312 3816 2387 3816 1604 3816 1616 3817 1595 3817 2384 3817 2385 3818 1595 3818 2328 3818 2323 3819 1404 3819 1403 3819 2323 3820 1403 3820 1597 3820 1600 3821 2315 3821 1398 3821 2318 3822 1599 3822 1526 3822 2318 3823 1526 3823 1598 3823 1610 3824 2341 3824 1606 3824 2407 3825 2289 3825 2341 3825 2407 3826 2341 3826 2405 3826 2405 3827 2341 3827 600 3827 2369 3828 2339 3828 2343 3828 2343 3829 2339 3829 2289 3829 2369 3830 2336 3830 2338 3830 1608 3831 2378 3831 2377 3831 1608 3832 2377 3832 2379 3832 2322 3833 1347 3833 2348 3833 1347 3834 2322 3834 1609 3834 1609 3835 2322 3835 2335 3835 1600 3836 1601 3836 2322 3836 1600 3837 1602 3837 1601 3837 1600 3838 2322 3838 2348 3838 1600 3839 2348 3839 3079 3839 1605 3840 2334 3840 1603 3840 1603 3841 2334 3841 598 3841 598 3842 2334 3842 1607 3842 1607 3843 2334 3843 2348 3843 2348 3844 2334 3844 3079 3844 2328 3845 2327 3845 2334 3845 2328 3846 2334 3846 1604 3846 1604 3847 2334 3847 2312 3847 2312 3848 2334 3848 1605 3848 2312 3849 1605 3849 2367 3849 2391 3850 2284 3850 2333 3850 2391 3851 2333 3851 2328 3851 2395 3852 2317 3852 2331 3852 2317 3853 1606 3853 1600 3853 2395 3854 2349 3854 2317 3854 2317 3855 2349 3855 1890 3855 1600 3856 1398 3856 2317 3856 1600 3857 3079 3857 2315 3857 2379 3858 1609 3858 1608 3858 1608 3859 1609 3859 2335 3859 1609 3860 2379 3860 2353 3860 601 3861 2342 3861 2343 3861 2342 3862 601 3862 2343 3862 1037 3863 2356 3863 1610 3863 1610 3864 2356 3864 2341 3864 2341 3865 2356 3865 2358 3865 2341 3866 2358 3866 2355 3866 2341 3867 2355 3867 600 3867 600 3868 2355 3868 2361 3868 2351 3869 2349 3869 2395 3869 2398 3870 1611 3870 2331 3870 2331 3871 1611 3871 2395 3871 2311 3872 2328 3872 1595 3872 2328 3873 2311 3873 1614 3873 2366 3874 598 3874 731 3874 731 3875 598 3875 1607 3875 2398 3876 1594 3876 2399 3876 2389 3877 1593 3877 2398 3877 2398 3878 1593 3878 1594 3878 2406 3879 600 3879 1591 3879 1591 3880 600 3880 1037 3880 2361 3881 2357 3881 600 3881 600 3882 2357 3882 1037 3882 1010 3883 599 3883 2391 3883 2391 3884 1612 3884 1010 3884 1612 3885 2391 3885 2309 3885 1614 3886 1010 3886 2309 3886 1010 3887 1612 3887 2309 3887 2407 3888 2404 3888 2343 3888 2343 3889 2302 3889 2369 3889 2369 3890 2302 3890 1615 3890 2343 3891 1613 3891 1615 3891 2343 3892 1615 3892 2302 3892 1614 3893 2309 3893 2307 3893 2369 3894 2338 3894 2339 3894 1614 3895 2307 3895 2328 3895 2328 3896 2307 3896 2391 3896 2391 3897 2307 3897 2309 3897 597 3898 2369 3898 1615 3898 597 3899 1615 3899 1613 3899 2384 3900 2312 3900 1616 3900 1616 3901 2312 3901 731 3901 2367 3902 2364 3902 2312 3902 2312 3903 2364 3903 731 3903 2378 3904 1592 3904 2376 3904 2374 3905 2371 3905 2378 3905 2378 3906 2371 3906 1592 3906 1528 3907 1599 3907 1618 3907 1528 3908 1618 3908 1617 3908 1398 3909 1619 3909 1618 3909 1618 3910 1619 3910 1620 3910 1618 3911 1620 3911 1617 3911 3038 3912 2066 3912 3035 3912 2066 3913 2051 3913 3035 3913 3035 3914 2051 3914 3040 3914 3037 3915 2054 3915 3033 3915 743 3916 3033 3916 1354 3916 1354 3917 3033 3917 2054 3917 3058 3918 2104 3918 3055 3918 619 3919 3055 3919 2116 3919 2116 3920 3055 3920 2104 3920 2208 3921 1164 3921 1272 3921 3057 3922 1624 3922 3056 3922 1624 3923 2106 3923 3056 3923 3056 3924 2106 3924 712 3924 1236 3925 1627 3925 1924 3925 1924 3926 1627 3926 1324 3926 1628 3927 3003 3927 3004 3927 1628 3928 3004 3928 1924 3928 1628 3929 1924 3929 1324 3929 725 3930 1301 3930 3005 3930 3005 3931 1301 3931 1925 3931 1978 3932 1629 3932 1929 3932 1929 3933 1629 3933 1925 3933 1929 3934 1925 3934 1301 3934 1975 3935 1630 3935 1587 3935 1587 3936 1630 3936 1632 3936 1632 3937 1630 3937 1631 3937 1632 3938 1631 3938 1302 3938 1631 3939 1976 3939 1302 3939 1302 3940 1976 3940 1588 3940 1584 3941 1974 3941 1979 3941 1979 3942 1974 3942 1303 3942 1974 3943 1221 3943 1303 3943 1303 3944 1221 3944 1633 3944 1221 3945 1585 3945 1633 3945 1633 3946 1585 3946 1586 3946 1972 3947 1634 3947 1982 3947 1982 3948 1634 3948 1983 3948 1634 3949 1222 3949 1983 3949 1983 3950 1222 3950 1981 3950 1222 3951 1973 3951 1981 3951 1981 3952 1973 3952 1980 3952 1581 3953 1635 3953 1582 3953 1582 3954 1635 3954 1636 3954 1971 3955 1637 3955 1635 3955 1635 3956 1637 3956 1636 3956 1971 3957 1583 3957 1637 3957 1637 3958 1583 3958 1638 3958 1970 3959 1639 3959 1984 3959 1984 3960 1639 3960 1985 3960 1639 3961 1640 3961 1985 3961 1985 3962 1640 3962 1641 3962 1640 3963 1580 3963 1641 3963 1641 3964 1580 3964 1642 3964 1579 3965 1643 3965 1578 3965 1578 3966 1643 3966 1305 3966 1643 3967 1644 3967 1305 3967 1305 3968 1644 3968 1987 3968 1644 3969 1645 3969 1987 3969 1987 3970 1645 3970 1986 3970 1577 3971 1646 3971 1647 3971 1647 3972 1646 3972 1989 3972 1646 3973 1231 3973 1989 3973 1989 3974 1231 3974 1304 3974 1231 3975 1969 3975 1304 3975 1304 3976 1969 3976 1988 3976 1968 3977 1219 3977 1575 3977 1575 3978 1219 3978 1648 3978 1219 3979 1232 3979 1648 3979 1648 3980 1232 3980 1649 3980 1232 3981 1576 3981 1649 3981 1649 3982 1576 3982 1650 3982 1966 3983 1652 3983 1990 3983 1990 3984 1652 3984 1651 3984 1651 3985 1652 3985 1653 3985 1653 3986 1652 3986 1220 3986 1220 3987 1967 3987 1653 3987 1653 3988 1967 3988 1654 3988 1573 3989 1227 3989 1574 3989 1574 3990 1227 3990 1992 3990 1227 3991 1655 3991 1992 3991 1992 3992 1655 3992 1306 3992 1655 3993 1965 3993 1306 3993 1306 3994 1965 3994 1991 3994 1962 3995 1230 3995 1656 3995 1656 3996 1230 3996 1994 3996 1230 3997 1657 3997 1994 3997 1994 3998 1657 3998 1993 3998 1657 3999 1964 3999 1993 3999 1993 4000 1964 4000 1658 4000 1659 4001 1661 4001 1660 4001 1660 4002 1661 4002 1300 4002 1963 4003 1662 4003 1661 4003 1661 4004 1662 4004 1300 4004 1963 4005 1663 4005 1662 4005 1662 4006 1663 4006 1572 4006 1958 4007 1960 4007 1664 4007 1664 4008 1960 4008 1298 4008 1960 4009 1239 4009 1298 4009 1298 4010 1239 4010 1299 4010 1239 4011 1961 4011 1299 4011 1299 4012 1961 4012 1571 4012 1569 4013 1240 4013 1570 4013 1570 4014 1240 4014 1309 4014 1240 4015 1959 4015 1309 4015 1309 4016 1959 4016 1297 4016 1959 4017 1957 4017 1297 4017 1297 4018 1957 4018 1665 4018 1567 4019 1666 4019 1568 4019 1568 4020 1666 4020 1667 4020 1666 4021 1956 4021 1667 4021 1667 4022 1956 4022 1311 4022 1956 4023 1955 4023 1311 4023 1311 4024 1955 4024 1668 4024 1952 4025 1226 4025 1669 4025 1669 4026 1226 4026 1670 4026 1226 4027 1225 4027 1670 4027 1670 4028 1225 4028 1307 4028 1225 4029 1954 4029 1307 4029 1307 4030 1954 4030 1566 4030 1563 4031 1671 4031 1565 4031 1565 4032 1671 4032 1314 4032 1314 4033 1671 4033 1996 4033 1996 4034 1671 4034 1953 4034 1953 4035 1672 4035 1996 4035 1996 4036 1672 4036 1995 4036 1561 4037 1235 4037 1673 4037 1673 4038 1235 4038 1674 4038 1235 4039 1233 4039 1674 4039 1674 4040 1233 4040 1313 4040 1233 4041 1951 4041 1313 4041 1313 4042 1951 4042 1564 4042 1675 4043 1677 4043 1997 4043 1997 4044 1677 4044 1676 4044 1677 4045 1678 4045 1676 4045 1676 4046 1678 4046 1312 4046 1678 4047 1560 4047 1312 4047 1312 4048 1560 4048 1562 4048 1557 4049 1950 4049 1998 4049 1998 4050 1950 4050 1679 4050 1680 4051 1681 4051 1950 4051 1950 4052 1681 4052 1679 4052 1680 4053 1558 4053 1681 4053 1681 4054 1558 4054 1559 4054 1682 4055 1243 4055 1683 4055 1683 4056 1243 4056 1999 4056 1243 4057 1242 4057 1999 4057 1999 4058 1242 4058 1318 4058 1242 4059 1555 4059 1318 4059 1318 4060 1555 4060 1556 4060 1554 4061 1685 4061 1684 4061 1684 4062 1685 4062 1686 4062 1685 4063 1687 4063 1686 4063 1686 4064 1687 4064 1317 4064 1687 4065 1688 4065 1317 4065 1317 4066 1688 4066 1689 4066 1552 4067 1690 4067 1553 4067 1553 4068 1690 4068 1316 4068 1690 4069 1691 4069 1316 4069 1316 4070 1691 4070 1693 4070 1691 4071 1692 4071 1693 4071 1693 4072 1692 4072 2000 4072 1694 4073 1223 4073 1695 4073 1695 4074 1223 4074 1696 4074 1223 4075 1949 4075 1696 4075 1696 4076 1949 4076 1697 4076 1949 4077 1550 4077 1697 4077 1697 4078 1550 4078 1551 4078 1698 4079 1224 4079 1548 4079 1548 4080 1224 4080 2001 4080 2001 4081 1224 4081 1948 4081 2001 4082 1948 4082 1296 4082 1948 4083 1947 4083 1296 4083 1296 4084 1947 4084 1549 4084 1699 4085 1545 4085 2002 4085 2002 4086 1545 4086 1945 4086 2002 4087 1945 4087 1700 4087 1700 4088 1945 4088 1946 4088 1946 4089 1546 4089 1700 4089 1700 4090 1546 4090 1547 4090 1542 4091 1543 4091 1701 4091 1701 4092 1543 4092 1702 4092 1701 4093 1702 4093 1703 4093 1703 4094 1702 4094 1704 4094 1703 4095 1704 4095 1544 4095 1544 4096 1704 4096 1944 4096 1541 4097 1706 4097 1705 4097 1705 4098 1706 4098 1707 4098 1705 4099 1707 4099 1943 4099 1705 4100 1943 4100 1319 4100 1319 4101 1943 4101 1708 4101 1708 4102 1943 4102 1942 4102 2003 4103 1940 4103 1322 4103 1322 4104 1940 4104 1241 4104 1322 4105 1241 4105 1709 4105 1709 4106 1241 4106 1941 4106 1709 4107 1941 4107 1540 4107 1540 4108 1941 4108 1710 4108 1937 4109 1712 4109 1711 4109 1711 4110 1712 4110 1713 4110 1713 4111 1712 4111 1714 4111 1714 4112 1712 4112 1939 4112 1714 4113 1939 4113 1538 4113 1538 4114 1939 4114 1539 4114 1935 4115 1715 4115 1716 4115 1716 4116 1715 4116 1320 4116 1715 4117 1938 4117 1320 4117 1320 4118 1938 4118 2004 4118 1938 4119 1936 4119 2004 4119 2004 4120 1936 4120 1537 4120 1933 4121 1934 4121 1535 4121 1535 4122 1934 4122 1717 4122 1934 4123 1718 4123 1717 4123 1717 4124 1718 4124 1719 4124 1718 4125 1720 4125 1719 4125 1719 4126 1720 4126 1536 4126 1534 4127 1722 4127 1721 4127 1721 4128 1722 4128 1723 4128 1723 4129 1722 4129 1228 4129 1723 4130 1228 4130 2005 4130 1228 4131 1724 4131 2005 4131 2005 4132 1724 4132 1725 4132 1533 4133 1727 4133 1726 4133 1726 4134 1727 4134 1728 4134 1727 4135 1729 4135 1728 4135 1728 4136 1729 4136 1323 4136 1729 4137 1932 4137 1323 4137 1323 4138 1932 4138 1730 4138 1530 4139 1238 4139 1731 4139 1731 4140 1238 4140 1732 4140 1238 4141 1733 4141 1732 4141 1732 4142 1733 4142 1734 4142 1733 4143 1532 4143 1734 4143 1734 4144 1532 4144 2006 4144 1930 4145 1736 4145 1735 4145 1735 4146 1736 4146 1737 4146 1737 4147 1736 4147 1931 4147 1737 4148 1931 4148 2007 4148 1931 4149 1738 4149 2007 4149 2007 4150 1738 4150 1531 4150 940 4151 1739 4151 1011 4151 940 4152 1011 4152 1861 4152 1861 4153 1011 4153 735 4153 940 4154 2713 4154 1739 4154 1739 4155 2713 4155 1012 4155 1012 4156 2713 4156 2712 4156 1740 4157 1012 4157 2708 4157 2708 4158 1012 4158 2709 4158 2709 4159 1012 4159 2712 4159 1023 4160 1031 4160 2786 4160 2676 4161 1023 4161 1741 4161 1741 4162 1023 4162 2786 4162 1747 4163 1746 4163 1014 4163 1747 4164 1014 4164 2667 4164 1742 4165 2686 4165 1743 4165 1743 4166 2686 4166 2685 4166 1744 4167 1742 4167 1743 4167 944 4168 1744 4168 1023 4168 944 4169 1023 4169 2681 4169 2681 4170 1023 4170 2676 4170 1019 4171 2687 4171 1017 4171 1017 4172 2687 4172 1745 4172 1017 4173 1745 4173 1014 4173 1014 4174 1745 4174 2667 4174 2706 4175 2704 4175 2705 4175 1746 4176 1747 4176 2706 4176 1746 4177 2706 4177 2705 4177 1746 4178 2705 4178 1750 4178 1750 4179 2705 4179 1748 4179 950 4180 1749 4180 1748 4180 1748 4181 1749 4181 1750 4181 1751 4182 1761 4182 1752 4182 1752 4183 1761 4183 1519 4183 1752 4184 1519 4184 1767 4184 945 4185 1753 4185 1754 4185 945 4186 1754 4186 1755 4186 2662 4187 1765 4187 1756 4187 2662 4188 1756 4188 1764 4188 1762 4189 1757 4189 1383 4189 1762 4190 1383 4190 1768 4190 1768 4191 1383 4191 1758 4191 1770 4192 1758 4192 1759 4192 1770 4193 1759 4193 1760 4193 1760 4194 1759 4194 1521 4194 1751 4195 946 4195 1761 4195 1761 4196 946 4196 1521 4196 1760 4197 1521 4197 941 4197 1752 4198 946 4198 1751 4198 1757 4199 1762 4199 942 4199 1757 4200 2664 4200 1763 4200 1763 4201 2664 4201 1764 4201 1764 4202 2664 4202 2688 4202 1764 4203 2688 4203 2662 4203 2662 4204 2682 4204 1765 4204 1765 4205 2682 4205 1766 4205 1766 4206 2682 4206 945 4206 1766 4207 945 4207 1755 4207 945 4208 947 4208 1753 4208 1753 4209 947 4209 1767 4209 1767 4210 947 4210 1752 4210 1752 4211 947 4211 946 4211 942 4212 1762 4212 1768 4212 942 4213 1768 4213 1769 4213 1770 4214 1769 4214 1758 4214 1758 4215 1769 4215 1768 4215 1760 4216 941 4216 1769 4216 1760 4217 1769 4217 1770 4217 1778 4218 1774 4218 1771 4218 1779 4219 1859 4219 1773 4219 1773 4220 1859 4220 930 4220 1773 4221 930 4221 1860 4221 1773 4222 1860 4222 1782 4222 1860 4223 932 4223 1782 4223 1782 4224 932 4224 933 4224 1783 4225 933 4225 934 4225 1774 4226 1778 4226 1788 4226 1774 4227 1788 4227 929 4227 1787 4228 1775 4228 1786 4228 1786 4229 1775 4229 935 4229 1786 4230 935 4230 1788 4230 1788 4231 935 4231 929 4231 1785 4232 1777 4232 1775 4232 1785 4233 1775 4233 1787 4233 1776 4234 934 4234 1514 4234 1785 4235 1514 4235 1777 4235 1783 4236 934 4236 1776 4236 672 4237 1771 4237 1904 4237 1771 4238 672 4238 1778 4238 1778 4239 672 4239 1391 4239 1778 4240 1391 4240 1788 4240 1788 4241 1391 4241 1789 4241 1771 4242 1772 4242 1904 4242 1904 4243 1772 4243 1779 4243 1904 4244 1779 4244 1504 4244 1504 4245 1779 4245 1507 4245 1507 4246 1779 4246 1773 4246 1507 4247 1773 4247 1508 4247 1508 4248 1773 4248 1780 4248 1780 4249 1773 4249 1782 4249 1780 4250 1782 4250 1781 4250 1781 4251 1782 4251 1512 4251 1512 4252 1782 4252 933 4252 1512 4253 933 4253 1513 4253 1513 4254 933 4254 1783 4254 1513 4255 1783 4255 1514 4255 1514 4256 1783 4256 1776 4256 1784 4257 1514 4257 1785 4257 1784 4258 1785 4258 1786 4258 1786 4259 1785 4259 1787 4259 1786 4260 1788 4260 1789 4260 2982 4261 3014 4261 1915 4261 1915 4262 3014 4262 1790 4262 1915 4263 1790 4263 720 4263 1915 4264 720 4264 725 4264 768 4265 3019 4265 1274 4265 2183 4266 581 4266 1274 4266 780 4267 775 4267 1792 4267 1274 4268 581 4268 957 4268 1274 4269 957 4269 956 4269 2188 4270 2189 4270 758 4270 957 4271 581 4271 582 4271 582 4272 581 4272 1793 4272 581 4273 2183 4273 1792 4273 581 4274 1792 4274 1793 4274 1793 4275 1792 4275 2073 4275 2073 4276 2074 4276 1793 4276 1793 4277 2074 4277 2185 4277 1793 4278 2185 4278 2076 4278 2076 4279 2097 4279 1793 4279 1793 4280 2097 4280 1794 4280 1793 4281 1794 4281 2186 4281 1454 4282 957 4282 2190 4282 3022 4283 2190 4283 3023 4283 2188 4284 1793 4284 1184 4284 1184 4285 1793 4285 2186 4285 582 4286 1793 4286 957 4286 957 4287 1793 4287 2190 4287 2190 4288 1793 4288 2188 4288 3024 4289 2188 4289 3026 4289 962 4290 2736 4290 1865 4290 2774 4291 1795 4291 2776 4291 1865 4292 2774 4292 962 4292 962 4293 2774 4293 2776 4293 962 4294 2776 4294 978 4294 978 4295 2776 4295 1491 4295 1503 4296 1796 4296 1491 4296 1491 4297 1796 4297 978 4297 1798 4298 1799 4298 1797 4298 1798 4299 1797 4299 1871 4299 1799 4300 1798 4300 2769 4300 1799 4301 2769 4301 1800 4301 2771 4302 1800 4302 2772 4302 2772 4303 1800 4303 2769 4303 3011 4304 1893 4304 652 4304 652 4305 1893 4305 1801 4305 1802 4306 2735 4306 1803 4306 1803 4307 2735 4307 1801 4307 1804 4308 987 4308 2743 4308 2743 4309 987 4309 2722 4309 970 4310 2722 4310 987 4310 1868 4311 970 4311 969 4311 1868 4312 969 4312 2746 4312 1800 4313 2771 4313 928 4313 1800 4314 928 4314 977 4314 977 4315 928 4315 1805 4315 977 4316 1805 4316 967 4316 967 4317 1805 4317 2726 4317 967 4318 2726 4318 969 4318 969 4319 2726 4319 2746 4319 1807 4320 1808 4320 695 4320 1806 4321 695 4321 653 4321 1809 4322 656 4322 1808 4322 1809 4323 1808 4323 1807 4323 697 4324 925 4324 1488 4324 1488 4325 925 4325 657 4325 1488 4326 657 4326 656 4326 1488 4327 656 4327 1809 4327 1810 4328 1812 4328 1815 4328 1815 4329 1812 4329 1811 4329 1811 4330 1812 4330 1813 4330 1813 4331 1812 4331 1873 4331 1813 4332 1873 4332 2734 4332 1814 4333 1482 4333 1869 4333 1810 4334 1815 4334 1806 4334 1810 4335 1806 4335 653 4335 1816 4336 1817 4336 1411 4336 668 4337 1828 4337 1411 4337 1411 4338 1828 4338 1829 4338 1411 4339 1829 4339 1816 4339 1818 4340 2738 4340 1410 4340 1410 4341 2738 4341 1819 4341 668 4342 1819 4342 1828 4342 1820 4343 1817 4343 1821 4343 1820 4344 1821 4344 1475 4344 1475 4345 1821 4345 1834 4345 1475 4346 1834 4346 1471 4346 1471 4347 1830 4347 1823 4347 1823 4348 1830 4348 1822 4348 1823 4349 1822 4349 1407 4349 1824 4350 1827 4350 1492 4350 1824 4351 1492 4351 1825 4351 1818 4352 1825 4352 1494 4352 1818 4353 1494 4353 2738 4353 1407 4354 1822 4354 1826 4354 1827 4355 1407 4355 2728 4355 1827 4356 2728 4356 1492 4356 2738 4357 649 4357 1819 4357 1819 4358 649 4358 1828 4358 1828 4359 649 4359 1496 4359 1828 4360 1496 4360 1829 4360 1829 4361 1496 4361 1835 4361 1826 4362 1822 4362 1830 4362 1826 4363 1830 4363 1832 4363 1834 4364 1831 4364 1471 4364 1471 4365 1832 4365 1830 4365 1821 4366 1833 4366 1831 4366 1821 4367 1831 4367 1834 4367 1816 4368 1835 4368 1817 4368 1821 4369 1817 4369 1833 4369 1829 4370 1835 4370 1816 4370 1843 4371 1836 4371 3050 4371 2197 4372 1836 4372 1837 4372 1837 4373 1836 4373 1362 4373 1837 4374 1362 4374 1135 4374 2198 4375 1120 4375 1126 4375 1836 4376 1843 4376 1362 4376 1362 4377 1843 4377 3003 4377 2198 4378 1838 4378 1836 4378 1839 4379 1076 4379 1082 4379 2198 4380 1836 4380 2024 4380 2024 4381 1836 4381 2197 4381 2024 4382 2197 4382 1840 4382 1838 4383 2199 4383 1836 4383 1836 4384 2199 4384 1042 4384 1836 4385 1042 4385 1049 4385 1836 4386 1839 4386 3050 4386 1049 4387 1276 4387 1836 4387 1836 4388 1276 4388 1282 4388 1836 4389 1282 4389 2015 4389 752 4390 2314 4390 1841 4390 2012 4391 1841 4391 2203 4391 1839 4392 1836 4392 1842 4392 1842 4393 1836 4393 2015 4393 1110 4394 1111 4394 1839 4394 3050 4395 1839 4395 1841 4395 3050 4396 1841 4396 2314 4396 2314 4397 1843 4397 3050 4397 2182 4398 818 4398 1849 4398 2176 4399 763 4399 806 4399 808 4400 1844 4400 3032 4400 3032 4401 2176 4401 808 4401 808 4402 2176 4402 806 4402 1845 4403 753 4403 3029 4403 1845 4404 1180 4404 3032 4404 1845 4405 3032 4405 1844 4405 795 4406 1844 4406 793 4406 761 4407 3016 4407 2181 4407 1180 4408 1185 4408 3032 4408 3032 4409 1185 4409 1170 4409 3032 4410 1170 4410 1174 4410 1846 4411 3017 4411 2182 4411 1174 4412 2179 4412 3032 4412 3032 4413 2179 4413 2081 4413 3032 4414 2081 4414 2180 4414 3031 4415 1849 4415 927 4415 2180 4416 2069 4416 3032 4416 3032 4417 2069 4417 1848 4417 3032 4418 1848 4418 3031 4418 1848 4419 1847 4419 2181 4419 1848 4420 2181 4420 3031 4420 3031 4421 2181 4421 1849 4421 1849 4422 2181 4422 2182 4422 1850 4423 2176 4423 927 4423 3032 4424 3031 4424 2176 4424 2176 4425 3031 4425 927 4425 1854 4426 950 4426 943 4426 1868 4427 595 4427 1869 4427 647 4428 1492 4428 1498 4428 1875 4429 2783 4429 2755 4429 1415 4430 2820 4430 1877 4430 1877 4431 2820 4431 2819 4431 1877 4432 2819 4432 1878 4432 1878 4433 2819 4433 2825 4433 1878 4434 2825 4434 1879 4434 1879 4435 2825 4435 2821 4435 1879 4436 2821 4436 1424 4436 1424 4437 2821 4437 2822 4437 1424 4438 2822 4438 1425 4438 1425 4439 2822 4439 1880 4439 1425 4440 1880 4440 1428 4440 1428 4441 1880 4441 2823 4441 1881 4442 2829 4442 1882 4442 1882 4443 2829 4443 1883 4443 1882 4444 1883 4444 1420 4444 1420 4445 1883 4445 1421 4445 1421 4446 1883 4446 2838 4446 1421 4447 2838 4447 1884 4447 1884 4448 2838 4448 1417 4448 1417 4449 2838 4449 2834 4449 1417 4450 2834 4450 1885 4450 1885 4451 2834 4451 2835 4451 1885 4452 2835 4452 2831 4452 1885 4453 2831 4453 1886 4453 1886 4454 2831 4454 1887 4454 1887 4455 2831 4455 637 4455 1607 4456 734 4456 2352 4456 1610 4457 1456 4457 2350 4457 1892 4458 3013 4458 1901 4458 1901 4459 3013 4459 2786 4459 1891 4460 1898 4460 2993 4460 1893 4461 3011 4461 1894 4461 1894 4462 3011 4462 3010 4462 1894 4463 3010 4463 2987 4463 2987 4464 3010 4464 2986 4464 2991 4465 583 4465 3012 4465 3012 4466 583 4466 1892 4466 1892 4467 583 4467 3013 4467 1429 4468 1895 4468 1902 4468 2993 4469 1898 4469 1429 4469 1896 4470 1893 4470 995 4470 995 4471 1893 4471 1894 4471 995 4472 1894 4472 1899 4472 1899 4473 1894 4473 1370 4473 1899 4474 1370 4474 1897 4474 1899 4475 1897 4475 1898 4475 1899 4476 1898 4476 1891 4476 1902 4477 865 4477 1900 4477 1902 4478 1900 4478 1429 4478 1429 4479 1900 4479 2994 4479 1429 4480 1900 4480 2993 4480 2786 4481 1031 4481 1901 4481 1901 4482 1031 4482 1902 4482 1899 4483 1891 4483 2993 4483 1899 4484 2993 4484 865 4484 1900 4485 865 4485 2993 4485 1429 4486 2994 4486 1900 4486 1901 4487 1902 4487 1895 4487 670 4488 1903 4488 668 4488 668 4489 1903 4489 1819 4489 1904 4490 1399 4490 672 4490 672 4491 1399 4491 1395 4491 1906 4492 2977 4492 2973 4492 2973 4493 1909 4493 1906 4493 1906 4494 1909 4494 3000 4494 1416 4495 2977 4495 1905 4495 2979 4496 1905 4496 2977 4496 2979 4497 2977 4497 1906 4497 1907 4498 3008 4498 2010 4498 1907 4499 2010 4499 666 4499 1907 4500 666 4500 2981 4500 2981 4501 666 4501 1905 4501 1905 4502 666 4502 1416 4502 1416 4503 666 4503 2010 4503 3003 4504 1382 4504 1908 4504 3000 4505 1908 4505 1382 4505 3004 4506 3003 4506 1923 4506 1923 4507 3003 4507 1908 4507 1909 4508 1923 4508 1908 4508 1909 4509 1908 4509 3000 4509 1912 4510 1910 4510 1911 4510 3002 4511 1914 4511 2972 4511 1910 4512 1912 4512 2968 4512 2968 4513 1912 4513 2972 4513 1913 4514 3002 4514 2972 4514 1913 4515 2972 4515 1912 4515 1921 4516 1914 4516 3002 4516 635 4517 725 4517 3005 4517 3002 4518 1915 4518 1921 4518 1921 4519 1915 4519 635 4519 1921 4520 635 4520 3005 4520 725 4521 635 4521 1915 4521 1916 4522 1911 4522 1910 4522 1427 4523 1918 4523 2928 4523 1427 4524 2928 4524 1916 4524 1427 4525 1916 4525 1910 4525 1911 4526 1916 4526 2982 4526 2982 4527 1916 4527 2928 4527 1917 4528 1427 4528 2009 4528 2009 4529 2008 4529 1917 4529 1917 4530 2008 4530 3007 4530 1917 4531 3007 4531 3006 4531 1917 4532 3006 4532 1427 4532 1427 4533 3006 4533 1918 4533 1919 4534 1920 4534 2808 4534 2808 4535 819 4535 1919 4535 1919 4536 819 4536 1434 4536 2010 4537 3008 4537 1920 4537 2010 4538 1920 4538 1919 4538 1921 4539 3005 4539 1925 4539 3004 4540 1923 4540 1922 4540 1924 4541 3004 4541 1922 4541 1366 4542 1236 4542 1922 4542 1922 4543 1236 4543 1924 4543 1921 4544 1925 4544 1926 4544 1926 4545 1925 4545 1629 4545 1926 4546 1629 4546 1216 4546 1627 4547 1529 4547 1324 4547 1324 4548 1529 4548 1927 4548 1977 4549 1978 4549 1928 4549 1928 4550 1978 4550 1929 4550 1529 4551 1627 4551 1930 4551 1930 4552 1627 4552 1736 4552 1738 4553 1931 4553 1530 4553 1530 4554 1931 4554 1238 4554 1532 4555 1733 4555 1533 4555 1533 4556 1733 4556 1727 4556 1932 4557 1729 4557 1534 4557 1534 4558 1729 4558 1722 4558 1724 4559 1228 4559 1933 4559 1933 4560 1228 4560 1934 4560 1720 4561 1718 4561 1935 4561 1935 4562 1718 4562 1715 4562 1936 4563 1938 4563 1937 4563 1937 4564 1938 4564 1712 4564 1539 4565 1939 4565 1940 4565 1940 4566 1939 4566 1241 4566 1710 4567 1941 4567 1706 4567 1706 4568 1941 4568 1707 4568 1942 4569 1943 4569 1543 4569 1543 4570 1943 4570 1702 4570 1944 4571 1704 4571 1545 4571 1545 4572 1704 4572 1945 4572 1546 4573 1946 4573 1698 4573 1698 4574 1946 4574 1224 4574 1947 4575 1948 4575 1694 4575 1694 4576 1948 4576 1223 4576 1550 4577 1949 4577 1552 4577 1552 4578 1949 4578 1690 4578 1692 4579 1691 4579 1554 4579 1554 4580 1691 4580 1685 4580 1688 4581 1687 4581 1682 4581 1682 4582 1687 4582 1243 4582 1555 4583 1242 4583 1557 4583 1557 4584 1242 4584 1950 4584 1558 4585 1680 4585 1675 4585 1675 4586 1680 4586 1677 4586 1560 4587 1678 4587 1561 4587 1561 4588 1678 4588 1235 4588 1951 4589 1233 4589 1563 4589 1563 4590 1233 4590 1671 4590 1672 4591 1953 4591 1952 4591 1952 4592 1953 4592 1226 4592 1954 4593 1225 4593 1567 4593 1567 4594 1225 4594 1666 4594 1955 4595 1956 4595 1569 4595 1569 4596 1956 4596 1240 4596 1957 4597 1959 4597 1958 4597 1958 4598 1959 4598 1960 4598 1961 4599 1239 4599 1659 4599 1659 4600 1239 4600 1661 4600 1663 4601 1963 4601 1962 4601 1962 4602 1963 4602 1230 4602 1964 4603 1657 4603 1573 4603 1573 4604 1657 4604 1227 4604 1965 4605 1655 4605 1966 4605 1966 4606 1655 4606 1652 4606 1967 4607 1220 4607 1968 4607 1968 4608 1220 4608 1219 4608 1576 4609 1232 4609 1577 4609 1577 4610 1232 4610 1646 4610 1969 4611 1231 4611 1579 4611 1579 4612 1231 4612 1643 4612 1645 4613 1644 4613 1970 4613 1970 4614 1644 4614 1639 4614 1580 4615 1640 4615 1581 4615 1581 4616 1640 4616 1635 4616 1583 4617 1971 4617 1972 4617 1972 4618 1971 4618 1634 4618 1973 4619 1222 4619 1584 4619 1584 4620 1222 4620 1974 4620 1585 4621 1221 4621 1975 4621 1975 4622 1221 4622 1630 4622 1976 4623 1631 4623 1977 4623 1977 4624 1631 4624 1978 4624 1928 4625 1929 4625 1588 4625 1588 4626 1929 4626 1302 4626 1587 4627 1632 4627 1586 4627 1586 4628 1632 4628 1633 4628 1979 4629 1303 4629 1980 4629 1980 4630 1303 4630 1981 4630 1982 4631 1983 4631 1638 4631 1638 4632 1983 4632 1637 4632 1582 4633 1636 4633 1642 4633 1642 4634 1636 4634 1641 4634 1984 4635 1985 4635 1986 4635 1986 4636 1985 4636 1987 4636 1304 4637 1988 4637 1305 4637 1305 4638 1988 4638 1578 4638 1647 4639 1989 4639 1650 4639 1650 4640 1989 4640 1649 4640 1575 4641 1648 4641 1654 4641 1654 4642 1648 4642 1653 4642 1990 4643 1651 4643 1991 4643 1991 4644 1651 4644 1306 4644 1574 4645 1992 4645 1658 4645 1658 4646 1992 4646 1993 4646 1656 4647 1994 4647 1572 4647 1572 4648 1994 4648 1662 4648 1660 4649 1300 4649 1571 4649 1571 4650 1300 4650 1299 4650 1664 4651 1298 4651 1665 4651 1665 4652 1298 4652 1297 4652 1311 4653 1668 4653 1570 4653 1311 4654 1570 4654 1309 4654 1568 4655 1667 4655 1566 4655 1566 4656 1667 4656 1307 4656 1669 4657 1670 4657 1995 4657 1995 4658 1670 4658 1996 4658 1565 4659 1314 4659 1564 4659 1564 4660 1314 4660 1313 4660 1673 4661 1674 4661 1562 4661 1562 4662 1674 4662 1312 4662 1997 4663 1676 4663 1559 4663 1559 4664 1676 4664 1681 4664 1998 4665 1679 4665 1556 4665 1556 4666 1679 4666 1318 4666 1683 4667 1999 4667 1689 4667 1689 4668 1999 4668 1317 4668 1693 4669 2000 4669 1686 4669 1686 4670 2000 4670 1684 4670 1553 4671 1316 4671 1551 4671 1551 4672 1316 4672 1697 4672 1695 4673 1696 4673 1549 4673 1549 4674 1696 4674 1296 4674 1548 4675 2001 4675 1547 4675 1547 4676 2001 4676 1700 4676 1699 4677 2002 4677 1544 4677 1544 4678 2002 4678 1703 4678 1542 4679 1701 4679 1708 4679 1708 4680 1701 4680 1319 4680 1541 4681 1705 4681 1540 4681 1540 4682 1705 4682 1709 4682 2003 4683 1322 4683 1538 4683 1538 4684 1322 4684 1714 4684 2004 4685 1537 4685 1711 4685 2004 4686 1711 4686 1713 4686 1716 4687 1320 4687 1536 4687 1536 4688 1320 4688 1719 4688 1535 4689 1717 4689 1725 4689 1725 4690 1717 4690 2005 4690 1721 4691 1723 4691 1730 4691 1730 4692 1723 4692 1323 4692 1726 4693 1728 4693 2006 4693 2006 4694 1728 4694 1734 4694 1731 4695 1732 4695 1531 4695 1531 4696 1732 4696 2007 4696 1735 4697 1737 4697 1927 4697 1927 4698 1737 4698 1324 4698 2008 4699 2009 4699 819 4699 819 4700 2009 4700 1434 4700 3045 4701 2011 4701 2012 4701 2012 4702 2011 4702 2045 4702 2013 4703 2014 4703 2015 4703 2015 4704 2014 4704 1842 4704 2018 4705 2016 4705 1276 4705 1276 4706 2016 4706 1282 4706 1277 4707 1275 4707 2017 4707 1281 4708 2016 4708 1277 4708 1277 4709 2016 4709 2018 4709 2019 4710 2021 4710 1042 4710 1042 4711 2021 4711 1049 4711 2257 4712 2020 4712 1052 4712 1052 4713 2020 4713 2056 4713 1052 4714 2021 4714 2257 4714 2257 4715 2021 4715 2019 4715 2022 4716 1357 4716 1838 4716 1838 4717 1357 4717 2199 4717 2199 4718 1357 4718 2023 4718 2199 4719 2023 4719 2043 4719 3042 4720 2226 4720 2024 4720 2024 4721 2226 4721 2042 4721 2229 4722 2026 4722 2027 4722 2027 4723 2026 4723 1326 4723 1360 4724 2030 4724 2028 4724 2028 4725 2030 4725 2032 4725 2028 4726 2032 4726 2029 4726 2028 4727 2029 4727 631 4727 2030 4728 2031 4728 2032 4728 2032 4729 2031 4729 2029 4729 2192 4730 2033 4730 724 4730 724 4731 2033 4731 2035 4731 1053 4732 1050 4732 2034 4732 2033 4733 1053 4733 2035 4733 2035 4734 1053 4734 1044 4734 1284 4735 2036 4735 2194 4735 2194 4736 2036 4736 1279 4736 2262 4737 2037 4737 2261 4737 2036 4738 2262 4738 1279 4738 1279 4739 2262 4739 1280 4739 723 4740 1144 4740 1094 4740 1094 4741 1144 4741 1095 4741 2038 4742 2137 4742 2039 4742 2039 4743 2137 4743 634 4743 2041 4744 1331 4744 1334 4744 1356 4745 625 4745 2043 4745 623 4746 2044 4746 2045 4746 2049 4747 2047 4747 2048 4747 1151 4748 1148 4748 2051 4748 1140 4749 2210 4749 2052 4749 2053 4750 2216 4750 2167 4750 2054 4751 1112 4751 2166 4751 1105 4752 1073 4752 2215 4752 2215 4753 2055 4753 1105 4753 2058 4754 2056 4754 2020 4754 2058 4755 1045 4755 2057 4755 2056 4756 2058 4756 2057 4756 2056 4757 2057 4757 1050 4757 1050 4758 2057 4758 2034 4758 2058 4759 2272 4759 1045 4759 2269 4760 1041 4760 2059 4760 2268 4761 2172 4761 2060 4761 2268 4762 2271 4762 2269 4762 2268 4763 2269 4763 2172 4763 2172 4764 2269 4764 2059 4764 1129 4765 2165 4765 2061 4765 2061 4766 2165 4766 1121 4766 1351 4767 1354 4767 1353 4767 1352 4768 1329 4768 2062 4768 2062 4769 1329 4769 1354 4769 2062 4770 1354 4770 1351 4770 1321 4771 1315 4771 2064 4771 2064 4772 1315 4772 2063 4772 2063 4773 2217 4773 2064 4773 1350 4774 1315 4774 2214 4774 1308 4775 1348 4775 2213 4775 2211 4776 1068 4776 2213 4776 2213 4777 1348 4777 2211 4777 2067 4778 1349 4778 1330 4778 1330 4779 1349 4779 2065 4779 2066 4780 727 4780 1349 4780 2066 4781 1349 4781 2067 4781 2180 4782 2071 4782 2069 4782 2069 4783 2071 4783 2072 4783 2074 4784 2075 4784 2068 4784 2074 4785 2068 4785 2123 4785 2069 4786 2072 4786 2070 4786 2069 4787 2070 4787 1252 4787 2071 4788 1203 4788 2072 4788 2072 4789 1203 4789 2070 4789 1211 4790 2075 4790 2073 4790 2073 4791 2075 4791 2074 4791 2068 4792 2075 4792 615 4792 615 4793 2075 4793 1211 4793 2179 4794 2090 4794 2081 4794 2081 4795 2090 4795 2082 4795 2076 4796 2092 4796 2079 4796 1256 4797 2078 4797 2077 4797 2077 4798 2078 4798 1273 4798 2076 4799 2079 4799 2078 4799 2078 4800 2079 4800 1273 4800 2138 4801 2080 4801 1167 4801 2138 4802 1167 4802 2077 4802 2077 4803 1167 4803 1256 4803 1256 4804 1167 4804 1166 4804 1256 4805 1166 4805 2179 4805 2179 4806 1166 4806 2091 4806 2179 4807 2091 4807 2090 4807 2081 4808 2082 4808 2083 4808 2081 4809 2083 4809 1254 4809 2083 4810 2084 4810 1254 4810 1254 4811 2084 4811 2087 4811 1254 4812 2087 4812 2089 4812 2089 4813 2087 4813 2085 4813 2089 4814 2085 4814 2086 4814 2244 4815 2139 4815 2085 4815 2244 4816 2085 4816 2087 4816 2088 4817 2185 4817 2250 4817 2250 4818 2185 4818 2089 4818 2250 4819 2089 4819 2086 4819 2090 4820 2091 4820 2082 4820 2082 4821 2091 4821 2083 4821 2088 4822 2092 4822 2185 4822 2185 4823 2092 4823 2076 4823 2079 4824 2092 4824 2250 4824 2250 4825 2092 4825 2088 4825 1170 4826 2093 4826 1174 4826 1174 4827 2093 4827 2094 4827 1194 4828 2096 4828 2095 4828 2095 4829 2096 4829 1171 4829 2093 4830 1171 4830 2094 4830 2094 4831 1171 4831 2096 4831 2098 4832 1172 4832 2097 4832 2097 4833 1172 4833 1794 4833 2252 4834 1175 4834 1173 4834 2251 4835 1172 4835 2252 4835 2252 4836 1172 4836 2098 4836 1180 4837 2099 4837 1185 4837 1185 4838 2099 4838 1186 4838 2099 4839 1181 4839 1186 4839 1186 4840 1181 4840 2100 4840 2101 4841 2103 4841 2186 4841 2186 4842 2103 4842 1184 4842 1183 4843 2103 4843 2102 4843 2102 4844 2103 4844 2101 4844 2104 4845 802 4845 2152 4845 797 4846 2105 4846 2106 4846 2107 4847 1626 4847 1054 4847 2151 4848 2108 4848 2204 4848 1173 4849 1175 4849 687 4849 1196 4850 1062 4850 2204 4850 2204 4851 2109 4851 1196 4851 1067 4852 2109 4852 2204 4852 1625 4853 1234 4853 2147 4853 2147 4854 1234 4854 2110 4854 2239 4855 2233 4855 2147 4855 2239 4856 2147 4856 2110 4856 2240 4857 2232 4857 1164 4857 2240 4858 1164 4858 2209 4858 2151 4859 1272 4859 1229 4859 1272 4860 2151 4860 2207 4860 2207 4861 2151 4861 2205 4861 1624 4862 1269 4862 1270 4862 1270 4863 1269 4863 2111 4863 1624 4864 1271 4864 797 4864 1271 4865 1624 4865 1270 4865 2113 4866 1057 4866 2114 4866 2113 4867 2112 4867 1234 4867 1234 4868 2112 4868 1267 4868 2112 4869 2113 4869 2114 4869 2117 4870 2116 4870 1265 4870 2116 4871 2115 4871 709 4871 2115 4872 2116 4872 2117 4872 1058 4873 1200 4873 1249 4873 2118 4874 1198 4874 1248 4874 708 4875 704 4875 2121 4875 614 4876 2122 4876 2123 4876 1253 4877 2124 4877 2125 4877 1064 4878 1250 4878 2128 4878 1594 4879 2129 4879 2351 4879 1453 4880 2351 4880 2129 4880 618 4881 2150 4881 2131 4881 2131 4882 2150 4882 2130 4882 2149 4883 2132 4883 2133 4883 2133 4884 2132 4884 705 4884 2011 4885 3045 4885 2134 4885 2134 4886 3045 4886 3046 4886 2135 4887 2136 4887 2038 4887 2038 4888 2136 4888 2137 4888 2138 4889 2077 4889 2139 4889 2139 4890 2077 4890 2085 4890 2244 4891 2087 4891 2080 4891 2080 4892 2087 4892 1167 4892 2080 4893 2138 4893 2244 4893 2244 4894 2138 4894 2139 4894 2143 4895 2140 4895 2245 4895 2245 4896 2140 4896 2141 4896 2243 4897 1210 4897 2142 4897 2142 4898 1210 4898 1208 4898 2142 4899 2143 4899 2243 4899 2243 4900 2143 4900 2245 4900 2247 4901 776 4901 2246 4901 2246 4902 776 4902 785 4902 2144 4903 784 4903 777 4903 777 4904 784 4904 778 4904 777 4905 2247 4905 2144 4905 2144 4906 2247 4906 2246 4906 2265 4907 1162 4907 2146 4907 2146 4908 1162 4908 1130 4908 2145 4909 1129 4909 2267 4909 2267 4910 1129 4910 2061 4910 2146 4911 1133 4911 2265 4911 2265 4912 1133 4912 2266 4912 2240 4913 2209 4913 2233 4913 2233 4914 2209 4914 2147 4914 2239 4915 2110 4915 2232 4915 2232 4916 2110 4916 1164 4916 2148 4917 1200 4917 1061 4917 1061 4918 1200 4918 1163 4918 2238 4919 2206 4919 2237 4919 2237 4920 2206 4920 1199 4920 2149 4921 2133 4921 706 4921 706 4922 2133 4922 707 4922 711 4923 718 4923 2150 4923 2150 4924 718 4924 2130 4924 2231 4925 2109 4925 1063 4925 1063 4926 2109 4926 1067 4926 766 4927 2108 4927 767 4927 767 4928 2108 4928 2151 4928 2241 4929 2107 4929 1054 4929 800 4930 799 4930 797 4930 797 4931 799 4931 2105 4931 2253 4932 2152 4932 802 4932 760 4933 2153 4933 756 4933 790 4934 755 4934 759 4934 759 4935 755 4935 2154 4935 1183 4936 1189 4936 1182 4936 2100 4937 1181 4937 2155 4937 2155 4938 1181 4938 1177 4938 1213 4939 2156 4939 1204 4939 1212 4940 1205 4940 1165 4940 1165 4941 1205 4941 1206 4941 2248 4942 787 4942 773 4942 782 4943 779 4943 2157 4943 2157 4944 779 4944 2158 4944 1059 4945 2159 4945 2242 4945 2242 4946 2159 4946 1202 4946 2222 4947 1310 4947 2221 4947 2221 4948 1310 4948 2160 4948 1156 4949 2214 4949 2235 4949 2235 4950 2214 4950 1315 4950 2218 4951 2212 4951 2234 4951 2234 4952 2212 4952 1101 4952 2236 4953 1103 4953 2220 4953 2220 4954 1103 4954 1071 4954 1159 4955 2162 4955 2161 4955 2161 4956 2162 4956 2163 4956 742 4957 2164 4957 730 4957 730 4958 2164 4958 1157 4958 1122 4959 1121 4959 2165 4959 1046 4960 2059 4960 1041 4960 1073 4961 1105 4961 2224 4961 2224 4962 1105 4962 1107 4962 1113 4963 2166 4963 1112 4963 2053 4964 2167 4964 2168 4964 2168 4965 2167 4965 2169 4965 2210 4966 1140 4966 2223 4966 2223 4967 1140 4967 1142 4967 2259 4968 1148 4968 1151 4968 1145 4969 1087 4969 2170 4969 1098 4970 2171 4970 1091 4970 2263 4971 2060 4971 2172 4971 1128 4972 1161 4972 1119 4972 1288 4973 2174 4973 2173 4973 2173 4974 2174 4974 1099 4974 1097 4975 1090 4975 1292 4975 2255 4976 1290 4976 1081 4976 1133 4977 1132 4977 2266 4977 2145 4978 607 4978 1132 4978 2221 4979 1155 4979 1154 4979 1156 4980 2175 4980 1155 4980 2236 4981 2220 4981 1104 4981 1104 4982 2220 4982 1070 4982 2219 4983 1104 4983 1070 4983 763 4984 2176 4984 2177 4984 2177 4985 2176 4985 1850 4985 713 4986 1844 4986 808 4986 2178 4987 1845 4987 796 4987 796 4988 1845 4988 1844 4988 1179 4989 1180 4989 3029 4989 3029 4990 1180 4990 1845 4990 1262 4991 1170 4991 1263 4991 1263 4992 1170 4992 1185 4992 1256 4993 2179 4993 1255 4993 1255 4994 2179 4994 1174 4994 1254 4995 2180 4995 2081 4995 1251 4996 1848 4996 2069 4996 761 4997 2181 4997 783 4997 1065 4998 2182 4998 3016 4998 3016 4999 2182 4999 2181 4999 1274 5000 769 5000 2183 5000 2183 5001 1791 5001 1792 5001 1792 5002 1791 5002 786 5002 1792 5003 2184 5003 2073 5003 2185 5004 2074 5004 2089 5004 2076 5005 2078 5005 2097 5005 2097 5006 2078 5006 1176 5006 1794 5007 1261 5007 2186 5007 2186 5008 1261 5008 1188 5008 1184 5009 2187 5009 2188 5009 2188 5010 2187 5010 2189 5010 2188 5011 1245 5011 1246 5011 2188 5012 803 5012 2190 5012 2190 5013 803 5013 3023 5013 2190 5014 2191 5014 1454 5014 1454 5015 2191 5015 703 5015 1137 5016 725 5016 2027 5016 2027 5017 725 5017 2025 5017 1332 5018 2025 5018 1118 5018 1118 5019 2025 5019 722 5019 1124 5020 722 5020 2028 5020 1336 5021 1360 5021 724 5021 1343 5022 2192 5022 2193 5022 2193 5023 2192 5023 2194 5023 1285 5024 1284 5024 1092 5024 1092 5025 1284 5025 1094 5025 1327 5026 723 5026 3049 5026 3049 5027 723 5027 1084 5027 1085 5028 1084 5028 1149 5028 1328 5029 2195 5029 2039 5029 2039 5030 2195 5030 3051 5030 1361 5031 3051 5031 741 5031 741 5032 3051 5032 719 5032 1837 5033 2196 5033 2197 5033 2198 5034 2024 5034 1333 5034 2198 5035 1125 5035 1838 5035 1042 5036 2199 5036 1043 5036 1049 5037 1051 5037 1276 5037 1276 5038 1051 5038 1278 5038 1282 5039 1283 5039 2015 5039 2015 5040 1283 5040 1088 5040 1842 5041 2200 5041 1839 5041 1839 5042 2200 5042 1076 5042 1839 5043 2201 5043 1346 5043 1839 5044 2202 5044 1841 5044 1841 5045 2202 5045 2203 5045 1841 5046 2012 5046 752 5046 752 5047 2012 5047 744 5047 2113 5048 1625 5048 1057 5048 2174 5049 1069 5049 2052 5049 2213 5050 1102 5050 2160 5050 2063 5051 1350 5051 2217 5051 1072 5052 2215 5052 2216 5052 2064 5053 2217 5053 2216 5053 2234 5054 2219 5054 2218 5054 2222 5055 2221 5055 1154 5055 1099 5056 1100 5056 2173 5056 2173 5057 1100 5057 630 5057 1138 5058 2223 5058 3043 5058 3043 5059 2223 5059 1142 5059 1134 5060 2168 5060 1136 5060 1136 5061 2168 5061 2169 5061 1107 5062 1108 5062 2224 5062 2224 5063 1108 5063 626 5063 2225 5064 628 5064 3042 5064 3042 5065 628 5065 2226 5065 2227 5066 2228 5066 2229 5066 2229 5067 2228 5067 2026 5067 2242 5068 610 5068 1059 5068 1059 5069 610 5069 609 5069 1063 5070 2230 5070 2231 5070 2231 5071 2230 5071 1197 5071 2237 5072 2148 5072 2238 5072 2238 5073 2148 5073 1061 5073 2232 5074 2240 5074 2239 5074 2239 5075 2240 5075 2233 5075 770 5076 2241 5076 1054 5076 1173 5077 2251 5077 2252 5077 2017 5078 1281 5078 1277 5078 2261 5079 1280 5079 2262 5079 2034 5080 1044 5080 1053 5080 606 5081 1045 5081 2268 5081 606 5082 2268 5082 2057 5082 2273 5083 2269 5083 2271 5083 2273 5084 2271 5084 2272 5084 2268 5085 1339 5085 2057 5085 2269 5086 2273 5086 1040 5086 2058 5087 2270 5087 2273 5087 2276 5088 1006 5088 1027 5088 1005 5089 2478 5089 1004 5089 2277 5090 2278 5090 2279 5090 3933 5091 2480 5091 605 5091 605 5092 2480 5092 3931 5092 973 5093 974 5093 2648 5093 964 5094 965 5094 2282 5094 2291 5095 688 5095 2332 5095 2332 5096 2284 5096 2291 5096 2284 5097 2285 5097 2291 5097 688 5098 2287 5098 2332 5098 2332 5099 2287 5099 2329 5099 690 5100 2336 5100 2335 5100 2297 5101 691 5101 2337 5101 2337 5102 2336 5102 2297 5102 691 5103 692 5103 2337 5103 2337 5104 692 5104 2340 5104 2340 5105 692 5105 2289 5105 2289 5106 692 5106 2288 5106 2288 5107 694 5107 2341 5107 2291 5108 1618 5108 2293 5108 2293 5109 2292 5109 2294 5109 2294 5110 2292 5110 1598 5110 2294 5111 1598 5111 2327 5111 2327 5112 1598 5112 2316 5112 2327 5113 2316 5113 689 5113 2316 5114 2319 5114 689 5114 689 5115 2319 5115 2295 5115 2321 5116 2297 5116 2296 5116 2297 5117 1404 5117 2298 5117 2298 5118 2325 5118 693 5118 693 5119 2325 5119 1596 5119 693 5120 1596 5120 2288 5120 2288 5121 1596 5121 2326 5121 2288 5122 2326 5122 2299 5122 2326 5123 2324 5123 2299 5123 2299 5124 2324 5124 2301 5124 2335 5125 2300 5125 690 5125 2334 5126 2330 5126 2295 5126 2300 5127 2321 5127 2296 5127 2341 5128 694 5128 1606 5128 2317 5129 2320 5129 2290 5129 2301 5130 2324 5130 1606 5130 602 5131 2303 5131 603 5131 927 5132 601 5132 2342 5132 2306 5133 599 5133 2344 5133 2694 5134 1612 5134 958 5134 2308 5135 2700 5135 2307 5135 740 5136 2311 5136 2345 5136 2345 5137 2311 5137 2310 5137 746 5138 597 5138 2314 5138 2314 5139 597 5139 746 5139 2318 5140 1598 5140 2292 5140 1598 5141 2315 5141 2316 5141 2292 5142 2293 5142 2318 5142 2316 5143 2315 5143 3079 5143 2319 5144 2316 5144 3079 5144 1398 5145 1618 5145 2317 5145 2317 5146 1618 5146 2291 5146 1618 5147 1599 5147 2318 5147 1618 5148 2318 5148 2293 5148 2291 5149 2320 5149 2317 5149 2297 5150 2321 5150 2322 5150 1601 5151 1404 5151 2322 5151 2322 5152 1404 5152 2297 5152 1404 5153 2323 5153 2298 5153 1602 5154 1600 5154 2326 5154 2324 5155 2326 5155 1600 5155 2325 5156 2298 5156 2323 5156 2325 5157 2323 5157 1597 5157 1597 5158 1596 5158 2325 5158 1596 5159 1602 5159 2326 5159 2286 5160 2334 5160 2327 5160 2328 5161 2329 5161 2287 5161 2328 5162 2287 5162 2327 5162 2332 5163 2329 5163 2333 5163 2333 5164 2329 5164 2328 5164 2286 5165 2330 5165 2334 5165 2332 5166 2333 5166 2284 5166 2331 5167 2285 5167 2284 5167 2285 5168 2331 5168 2290 5168 2317 5169 2290 5169 2331 5169 2300 5170 2335 5170 2322 5170 1608 5171 2335 5171 2336 5171 2337 5172 2338 5172 2336 5172 1608 5173 2336 5173 2369 5173 2337 5174 2340 5174 2338 5174 2338 5175 2340 5175 2339 5175 2288 5176 2341 5176 2289 5176 2339 5177 2340 5177 2289 5177 2343 5178 2342 5178 1455 5178 1591 5179 1038 5179 2342 5179 2344 5180 2390 5180 599 5180 2344 5181 599 5181 1010 5181 2344 5182 1010 5182 2306 5182 2344 5183 2129 5183 1594 5183 2390 5184 2344 5184 1594 5184 1616 5185 737 5185 1595 5185 1595 5186 737 5186 740 5186 1595 5187 740 5187 2311 5187 2311 5188 740 5188 2345 5188 2311 5189 2345 5189 1614 5189 2347 5190 597 5190 1613 5190 2347 5191 1613 5191 746 5191 2347 5192 2346 5192 1592 5192 597 5193 2347 5193 1592 5193 2348 5194 1347 5194 674 5194 2348 5195 674 5195 1607 5195 2353 5196 2313 5196 1609 5196 1609 5197 2313 5197 1347 5197 2317 5198 1890 5198 1606 5198 1606 5199 1890 5199 2354 5199 1606 5200 2354 5200 1610 5200 2349 5201 2305 5201 1890 5201 2350 5202 1039 5202 1037 5202 1037 5203 1610 5203 2350 5203 2305 5204 2349 5204 2351 5204 2305 5205 2351 5205 1453 5205 2352 5206 732 5206 731 5206 731 5207 1607 5207 2352 5207 2313 5208 2353 5208 750 5208 2362 5209 2357 5209 2361 5209 2362 5210 2359 5210 2357 5210 2360 5211 2358 5211 2356 5211 2360 5212 2356 5212 2359 5212 2359 5213 2356 5213 2357 5213 2361 5214 2355 5214 2360 5214 2360 5215 2355 5215 2358 5215 2360 5216 2359 5216 2361 5216 2359 5217 2362 5217 2361 5217 2363 5218 1603 5218 2366 5218 2363 5219 2366 5219 2365 5219 2367 5220 1605 5220 2363 5220 2363 5221 1605 5221 1603 5221 2368 5222 2364 5222 2367 5222 2368 5223 2365 5223 2364 5223 2364 5224 2365 5224 2366 5224 2363 5225 2365 5225 2367 5225 2365 5226 2368 5226 2367 5226 2370 5227 2369 5227 597 5227 2370 5228 597 5228 2375 5228 2375 5229 597 5229 2372 5229 2374 5230 2378 5230 2370 5230 2370 5231 2378 5231 2369 5231 2373 5232 2371 5232 2374 5232 2373 5233 2375 5233 2371 5233 2371 5234 2375 5234 2372 5234 2370 5235 2375 5235 2374 5235 2375 5236 2373 5236 2374 5236 2382 5237 2378 5237 2376 5237 2382 5238 2376 5238 2383 5238 2380 5239 2377 5239 2382 5239 2382 5240 2377 5240 2378 5240 2381 5241 1590 5241 2379 5241 2381 5242 2379 5242 2380 5242 2380 5243 2379 5243 2377 5243 2381 5244 2383 5244 1590 5244 1590 5245 2383 5245 2376 5245 2381 5246 2380 5246 2383 5246 2380 5247 2382 5247 2383 5247 2387 5248 2384 5248 2388 5248 2386 5249 2328 5249 2387 5249 2387 5250 2328 5250 1604 5250 2386 5251 2385 5251 2328 5251 2385 5252 2388 5252 1595 5252 1595 5253 2388 5253 2384 5253 2388 5254 2385 5254 2386 5254 2386 5255 2387 5255 2388 5255 2392 5256 1593 5256 2389 5256 2392 5257 2393 5257 1593 5257 1593 5258 2393 5258 2390 5258 2394 5259 2391 5259 599 5259 2394 5260 599 5260 2393 5260 2393 5261 599 5261 2390 5261 2389 5262 2398 5262 2394 5262 2394 5263 2398 5263 2391 5263 2389 5264 2394 5264 2393 5264 2393 5265 2392 5265 2389 5265 2396 5266 2397 5266 2395 5266 2396 5267 2395 5267 2401 5267 2401 5268 2395 5268 1611 5268 2396 5269 2402 5269 2397 5269 2397 5270 2402 5270 2399 5270 2400 5271 2398 5271 2399 5271 2400 5272 2399 5272 2402 5272 2401 5273 1611 5273 2400 5273 2400 5274 1611 5274 2398 5274 2396 5275 2401 5275 2402 5275 2401 5276 2400 5276 2402 5276 2403 5277 2404 5277 2408 5277 2408 5278 2404 5278 2407 5278 2403 5279 2410 5279 2404 5279 2404 5280 2410 5280 2406 5280 2409 5281 2406 5281 2410 5281 2408 5282 2407 5282 2409 5282 2409 5283 2407 5283 2405 5283 2403 5284 2408 5284 2410 5284 2408 5285 2409 5285 2410 5285 2411 5286 2414 5286 2429 5286 1009 5287 2414 5287 2411 5287 2428 5288 2427 5288 1011 5288 1008 5289 2411 5289 2459 5289 2426 5290 2274 5290 2798 5290 2798 5291 2274 5291 2459 5291 2425 5292 1035 5292 1036 5292 1008 5293 2426 5293 1016 5293 1016 5294 2426 5294 2425 5294 1016 5295 2425 5295 1036 5295 2412 5296 1013 5296 1036 5296 1036 5297 1013 5297 1016 5297 2412 5298 2413 5298 1013 5298 1013 5299 2413 5299 2418 5299 1013 5300 2418 5300 2419 5300 1013 5301 2419 5301 2428 5301 2457 5302 2415 5302 2429 5302 2421 5303 2414 5303 2416 5303 2429 5304 2414 5304 2457 5304 2414 5305 2458 5305 2457 5305 2429 5306 2415 5306 2459 5306 2423 5307 2425 5307 2426 5307 2423 5308 2426 5308 2424 5308 2414 5309 2427 5309 2416 5309 2798 5310 2424 5310 2426 5310 2425 5311 2423 5311 2417 5311 2425 5312 2417 5312 2418 5312 2418 5313 2417 5313 2422 5313 2416 5314 2427 5314 2790 5314 2797 5315 2458 5315 2791 5315 2797 5316 2791 5316 2795 5316 2417 5317 2795 5317 2422 5317 2793 5318 2791 5318 2790 5318 2461 5319 2793 5319 2419 5319 2422 5320 2420 5320 2418 5320 2418 5321 2420 5321 2419 5321 2419 5322 2420 5322 2461 5322 2413 5323 1035 5323 2418 5323 2418 5324 1035 5324 2425 5324 2788 5325 2790 5325 2791 5325 2788 5326 2791 5326 2800 5326 2800 5327 2791 5327 2458 5327 2800 5328 2458 5328 2789 5328 2789 5329 2458 5329 2414 5329 2421 5330 2789 5330 2414 5330 2800 5331 2415 5331 2457 5331 2800 5332 2457 5332 2458 5332 2800 5333 2458 5333 2799 5333 2799 5334 2458 5334 2797 5334 2798 5335 2799 5335 2797 5335 2792 5336 2795 5336 2791 5336 2460 5337 2461 5337 2420 5337 2460 5338 2420 5338 2422 5338 2460 5339 2422 5339 2792 5339 2792 5340 2422 5340 2795 5340 2797 5341 2424 5341 2798 5341 2796 5342 2795 5342 2417 5342 2794 5343 2796 5343 2423 5343 2423 5344 2796 5344 2417 5344 2794 5345 2423 5345 2424 5345 2459 5346 2274 5346 1008 5346 2426 5347 1008 5347 2274 5347 2427 5348 2428 5348 2790 5348 2419 5349 2793 5349 2428 5349 2411 5350 2429 5350 2459 5350 1011 5351 2427 5351 1009 5351 1009 5352 2427 5352 2414 5352 2452 5353 2430 5353 2444 5353 2447 5354 2452 5354 2444 5354 2450 5355 2442 5355 979 5355 979 5356 2442 5356 2451 5356 2437 5357 2281 5357 2436 5357 2436 5358 2281 5358 2434 5358 2445 5359 2444 5359 2430 5359 984 5360 2437 5360 983 5360 983 5361 2437 5361 2445 5361 983 5362 2445 5362 2430 5362 2452 5363 976 5363 983 5363 2452 5364 983 5364 2430 5364 2452 5365 2447 5365 2431 5365 2431 5366 2447 5366 2446 5366 2431 5367 2446 5367 2449 5367 2431 5368 2449 5368 981 5368 984 5369 979 5369 2434 5369 2445 5370 2446 5370 2444 5370 2444 5371 2446 5371 2447 5371 2432 5372 2451 5372 2442 5372 2434 5373 2451 5373 2453 5373 2443 5374 2441 5374 2807 5374 2455 5375 2433 5375 2443 5375 2442 5376 2441 5376 2432 5376 2443 5377 2435 5377 2441 5377 2433 5378 2455 5378 2446 5378 2433 5379 2446 5379 2445 5379 2433 5380 2445 5380 2454 5380 2434 5381 2453 5381 2436 5381 2437 5382 2454 5382 2445 5382 2435 5383 2436 5383 2441 5383 2436 5384 2454 5384 2437 5384 2440 5385 2449 5385 2456 5385 2456 5386 2449 5386 2446 5386 2456 5387 2446 5387 2455 5387 2439 5388 2438 5388 2442 5388 2439 5389 2448 5389 982 5389 982 5390 2803 5390 2807 5390 2440 5391 2803 5391 2449 5391 2442 5392 2448 5392 2439 5392 2436 5393 1460 5393 2441 5393 2804 5394 2451 5394 2432 5394 2804 5395 2432 5395 2441 5395 1459 5396 2439 5396 982 5396 2807 5397 1459 5397 982 5397 2805 5398 2807 5398 2441 5398 2805 5399 2441 5399 2806 5399 2806 5400 2441 5400 2442 5400 2806 5401 2442 5401 2438 5401 2802 5402 2435 5402 2443 5402 2802 5403 2443 5403 1464 5403 1464 5404 2443 5404 2433 5404 2454 5405 1464 5405 2433 5405 1461 5406 2440 5406 2456 5406 2802 5407 1461 5407 2455 5407 2455 5408 1461 5408 2456 5408 2802 5409 2455 5409 2443 5409 2802 5410 2443 5410 2801 5410 2801 5411 2443 5411 2807 5411 2801 5412 2807 5412 2803 5412 2448 5413 980 5413 982 5413 2449 5414 2803 5414 981 5414 2434 5415 2281 5415 984 5415 2437 5416 984 5416 2281 5416 980 5417 2448 5417 2450 5417 2450 5418 2448 5418 2442 5418 979 5419 2451 5419 2434 5419 976 5420 2452 5420 2431 5420 2486 5421 2468 5421 2462 5421 2486 5422 2462 5422 2466 5422 2466 5423 2462 5423 2488 5423 2484 5424 2463 5424 2486 5424 2486 5425 2463 5425 2464 5425 2485 5426 1006 5426 2469 5426 1006 5427 2485 5427 2483 5427 2483 5428 2485 5428 2467 5428 2482 5429 2481 5429 2491 5429 2491 5430 2481 5430 2465 5430 2490 5431 2489 5431 2465 5431 2465 5432 2489 5432 2491 5432 2489 5433 2488 5433 2487 5433 2486 5434 2466 5434 2469 5434 2469 5435 2465 5435 2481 5435 2466 5436 2465 5436 2469 5436 2467 5437 2485 5437 2469 5437 2467 5438 2469 5438 2481 5438 2484 5439 2486 5439 2469 5439 2465 5440 2466 5440 2488 5440 2465 5441 2488 5441 2490 5441 2476 5442 2470 5442 2471 5442 2471 5443 2470 5443 2279 5443 2472 5444 2480 5444 2476 5444 2476 5445 2480 5445 2470 5445 2479 5446 3931 5446 2472 5446 3931 5447 2479 5447 2475 5447 3931 5448 2475 5448 2478 5448 2474 5449 2478 5449 2475 5449 2477 5450 2474 5450 2496 5450 2496 5451 2474 5451 2494 5451 2492 5452 2473 5452 2493 5452 2473 5453 2471 5453 2279 5453 2472 5454 2476 5454 2475 5454 2475 5455 2479 5455 2472 5455 2493 5456 2494 5456 2474 5456 2493 5457 2474 5457 2475 5457 2493 5458 2475 5458 2476 5458 2493 5459 2476 5459 2471 5459 2493 5460 2471 5460 2492 5460 2474 5461 2477 5461 2478 5461 2472 5462 3931 5462 2480 5462 2481 5463 2482 5463 2467 5463 2467 5464 2482 5464 2483 5464 2469 5465 1006 5465 2484 5465 2484 5466 1006 5466 2463 5466 2486 5467 2464 5467 2468 5467 2488 5468 2462 5468 2487 5468 2488 5469 2489 5469 2490 5469 2471 5470 2473 5470 2492 5470 2493 5471 2473 5471 2495 5471 2493 5472 2495 5472 2494 5472 2494 5473 2495 5473 2496 5473 2497 5474 2499 5474 2498 5474 2498 5475 2499 5475 2504 5475 2531 5476 1025 5476 1024 5476 2531 5477 1024 5477 2500 5477 2500 5478 1024 5478 2501 5478 2500 5479 2501 5479 2503 5479 2503 5480 2501 5480 1022 5480 2503 5481 1022 5481 2533 5481 2530 5482 2502 5482 1030 5482 1030 5483 2502 5483 2497 5483 1030 5484 2497 5484 1032 5484 1034 5485 901 5485 2534 5485 1022 5486 2534 5486 2535 5486 1022 5487 2535 5487 2533 5487 2500 5488 2502 5488 2531 5488 2531 5489 2502 5489 2530 5489 2502 5490 2500 5490 2499 5490 2499 5491 2500 5491 2503 5491 2499 5492 2503 5492 2504 5492 2504 5493 2503 5493 2533 5493 2535 5494 2504 5494 2533 5494 2536 5495 2509 5495 2505 5495 2505 5496 2509 5496 903 5496 2538 5497 2539 5497 1021 5497 2538 5498 1021 5498 2506 5498 2506 5499 1021 5499 1020 5499 2506 5500 1020 5500 2510 5500 2510 5501 1020 5501 1018 5501 2510 5502 1018 5502 2507 5502 2507 5503 1018 5503 2547 5503 2507 5504 2547 5504 2546 5504 2538 5505 2537 5505 2539 5505 2539 5506 2537 5506 1034 5506 2549 5507 2508 5507 2548 5507 2521 5508 904 5508 2508 5508 2508 5509 904 5509 2509 5509 2508 5510 2509 5510 2548 5510 2536 5511 2538 5511 2509 5511 2509 5512 2538 5512 2506 5512 2509 5513 2506 5513 2510 5513 2546 5514 2548 5514 2507 5514 2507 5515 2548 5515 2509 5515 2507 5516 2509 5516 2510 5516 2537 5517 2538 5517 2536 5517 909 5518 908 5518 2542 5518 2542 5519 908 5519 2515 5519 2517 5520 998 5520 999 5520 2517 5521 999 5521 2516 5521 2516 5522 999 5522 1000 5522 2516 5523 1000 5523 2511 5523 2511 5524 1000 5524 2512 5524 2511 5525 2512 5525 2514 5525 2514 5526 2512 5526 2541 5526 2514 5527 2541 5527 2540 5527 1028 5528 1002 5528 2560 5528 2560 5529 2515 5529 1028 5529 1028 5530 2515 5530 908 5530 2541 5531 2513 5531 2542 5531 2541 5532 2542 5532 2540 5532 2540 5533 2542 5533 2514 5533 2514 5534 2542 5534 2515 5534 2514 5535 2515 5535 2511 5535 2511 5536 2515 5536 2516 5536 2516 5537 2515 5537 2517 5537 2517 5538 2515 5538 2560 5538 2529 5539 2528 5539 2543 5539 2543 5540 2528 5540 910 5540 2532 5541 2518 5541 2527 5541 2532 5542 2520 5542 2518 5542 2518 5543 2520 5543 2544 5543 2518 5544 2544 5544 2545 5544 2544 5545 2543 5545 2545 5545 2545 5546 2543 5546 2519 5546 2520 5547 2529 5547 2544 5547 2544 5548 2529 5548 2543 5548 2550 5549 2523 5549 2551 5549 2551 5550 2523 5550 907 5550 2554 5551 906 5551 2523 5551 2554 5552 2523 5552 2522 5552 2554 5553 2522 5553 1026 5553 1026 5554 2522 5554 2552 5554 2552 5555 2550 5555 2553 5555 2553 5556 2550 5556 2521 5556 2550 5557 2552 5557 2523 5557 2523 5558 2552 5558 2522 5558 2555 5559 2557 5559 2524 5559 2524 5560 2557 5560 905 5560 2558 5561 1033 5561 2557 5561 2558 5562 2557 5562 2559 5562 1004 5563 2559 5563 2556 5563 1004 5564 2556 5564 1003 5564 2556 5565 2555 5565 1007 5565 1007 5566 2555 5566 902 5566 2557 5567 2555 5567 2559 5567 2559 5568 2555 5568 2556 5568 3075 5569 3074 5569 2525 5569 3075 5570 2525 5570 2526 5570 2526 5571 2525 5571 2927 5571 2499 5572 2497 5572 2502 5572 2927 5573 2527 5573 2526 5573 2530 5574 1030 5574 1025 5574 2530 5575 1025 5575 2531 5575 2498 5576 2504 5576 2534 5576 2534 5577 2504 5577 2535 5577 2536 5578 2505 5578 1034 5578 2536 5579 1034 5579 2537 5579 909 5580 2542 5580 2513 5580 2543 5581 910 5581 2519 5581 903 5582 2509 5582 904 5582 2546 5583 2547 5583 2548 5583 2548 5584 2547 5584 2549 5584 2521 5585 2550 5585 2551 5585 1026 5586 2552 5586 2553 5586 907 5587 2523 5587 906 5587 902 5588 2555 5588 2524 5588 1003 5589 2556 5589 1007 5589 905 5590 2557 5590 1033 5590 2558 5591 2559 5591 1004 5591 2560 5592 1002 5592 998 5592 2560 5593 998 5593 2517 5593 2568 5594 2561 5594 2582 5594 2561 5595 2567 5595 2282 5595 2585 5596 975 5596 2567 5596 2567 5597 975 5597 2282 5597 2565 5598 2580 5598 2585 5598 2585 5599 2580 5599 975 5599 2566 5600 2581 5600 2565 5600 2581 5601 2566 5601 2562 5601 2581 5602 2562 5602 974 5602 2563 5603 974 5603 2562 5603 971 5604 2563 5604 2564 5604 2564 5605 2563 5605 2584 5605 2562 5606 2565 5606 2585 5606 2582 5607 2584 5607 2563 5607 2582 5608 2563 5608 2562 5608 2582 5609 2562 5609 2585 5609 2565 5610 2562 5610 2566 5610 2582 5611 2585 5611 2567 5611 2582 5612 2567 5612 2568 5612 2587 5613 965 5613 2569 5613 2569 5614 965 5614 2586 5614 965 5615 2570 5615 2588 5615 2589 5616 2571 5616 2572 5616 2572 5617 2571 5617 2570 5617 961 5618 2589 5618 2574 5618 961 5619 2574 5619 2575 5619 2573 5620 959 5620 2574 5620 959 5621 2573 5621 2576 5621 2576 5622 2573 5622 2577 5622 2579 5623 2578 5623 2586 5623 2586 5624 2578 5624 2569 5624 2589 5625 2572 5625 2574 5625 2573 5626 2569 5626 2578 5626 2572 5627 2569 5627 2573 5627 2572 5628 2573 5628 2574 5628 2577 5629 2573 5629 2578 5629 2569 5630 2572 5630 2570 5630 2569 5631 2570 5631 2587 5631 2574 5632 959 5632 2575 5632 2578 5633 2579 5633 2577 5633 2577 5634 2579 5634 2576 5634 2565 5635 2581 5635 2580 5635 2563 5636 971 5636 974 5636 2582 5637 2561 5637 2583 5637 2582 5638 2583 5638 2584 5638 2584 5639 2583 5639 2564 5639 2567 5640 2561 5640 2568 5640 2570 5641 965 5641 2587 5641 2570 5642 2571 5642 2588 5642 2589 5643 961 5643 2571 5643 2621 5644 2620 5644 919 5644 2631 5645 2621 5645 919 5645 2630 5646 2590 5646 990 5646 2630 5647 990 5647 2592 5647 2592 5648 990 5648 989 5648 2592 5649 989 5649 2594 5649 2594 5650 989 5650 2627 5650 2594 5651 2627 5651 2626 5651 2630 5652 2593 5652 2590 5652 2590 5653 2593 5653 2591 5653 995 5654 2620 5654 2623 5654 2628 5655 2623 5655 2622 5655 2628 5656 2622 5656 2595 5656 2595 5657 2622 5657 2626 5657 2631 5658 2630 5658 2621 5658 2621 5659 2630 5659 2592 5659 2621 5660 2592 5660 2594 5660 2593 5661 2630 5661 2631 5661 2622 5662 2621 5662 2626 5662 2626 5663 2621 5663 2594 5663 918 5664 2644 5664 2633 5664 2633 5665 2644 5665 2643 5665 2600 5666 966 5666 2596 5666 2600 5667 2596 5667 2597 5667 2597 5668 2596 5668 968 5668 2597 5669 968 5669 2599 5669 2599 5670 968 5670 988 5670 2599 5671 988 5671 2598 5671 2598 5672 988 5672 2634 5672 2598 5673 2634 5673 2601 5673 986 5674 972 5674 2645 5674 2645 5675 2643 5675 986 5675 986 5676 2643 5676 2644 5676 2634 5677 2632 5677 2633 5677 2634 5678 2633 5678 2601 5678 2601 5679 2633 5679 2598 5679 2598 5680 2633 5680 2643 5680 2598 5681 2643 5681 2599 5681 2599 5682 2643 5682 2597 5682 2597 5683 2643 5683 2600 5683 2600 5684 2643 5684 2645 5684 2637 5685 2661 5685 2638 5685 2638 5686 2661 5686 916 5686 2635 5687 2640 5687 2602 5687 2635 5688 2602 5688 2604 5688 2604 5689 2602 5689 2603 5689 2604 5690 2603 5690 2607 5690 2607 5691 2603 5691 992 5691 2607 5692 992 5692 2605 5692 2605 5693 992 5693 2659 5693 2605 5694 2659 5694 2608 5694 2635 5695 2636 5695 2640 5695 2640 5696 2636 5696 911 5696 960 5697 3072 5697 2660 5697 915 5698 2606 5698 3072 5698 3072 5699 2606 5699 2661 5699 3072 5700 2661 5700 2660 5700 2637 5701 2635 5701 2661 5701 2661 5702 2635 5702 2604 5702 2661 5703 2604 5703 2607 5703 2661 5704 2607 5704 2605 5704 2661 5705 2605 5705 2660 5705 2660 5706 2605 5706 2608 5706 2636 5707 2635 5707 2637 5707 2613 5708 2614 5708 913 5708 2925 5709 2609 5709 2625 5709 2625 5710 2609 5710 2629 5710 2629 5711 2609 5711 2610 5711 2629 5712 2610 5712 2612 5712 2612 5713 2610 5713 2640 5713 2612 5714 2640 5714 2641 5714 911 5715 2611 5715 2639 5715 2642 5716 2639 5716 2614 5716 2642 5717 2614 5717 2641 5717 2612 5718 2641 5718 2614 5718 2614 5719 2613 5719 2612 5719 2615 5720 2616 5720 2646 5720 2646 5721 2616 5721 2651 5721 2650 5722 2651 5722 985 5722 985 5723 2651 5723 914 5723 2647 5724 2617 5724 2646 5724 2647 5725 2646 5725 2649 5725 2648 5726 2649 5726 2650 5726 2648 5727 2650 5727 985 5727 2650 5728 2649 5728 2651 5728 2651 5729 2649 5729 2646 5729 2652 5730 2618 5730 2619 5730 2619 5731 2618 5731 2655 5731 2657 5732 2655 5732 2658 5732 2658 5733 2655 5733 915 5733 2653 5734 912 5734 2619 5734 2653 5735 2619 5735 2654 5735 2653 5736 2654 5736 2656 5736 2656 5737 2654 5737 2657 5737 2655 5738 2657 5738 2654 5738 2654 5739 2619 5739 2655 5739 3073 5740 994 5740 2926 5740 2926 5741 994 5741 2925 5741 2926 5742 2925 5742 2624 5742 2620 5743 2621 5743 2622 5743 2620 5744 2622 5744 2623 5744 2626 5745 2627 5745 2595 5745 2595 5746 2627 5746 2628 5746 2591 5747 2593 5747 919 5747 919 5748 2593 5748 2631 5748 2633 5749 2632 5749 918 5749 911 5750 2636 5750 2637 5750 911 5751 2637 5751 2638 5751 2614 5752 2639 5752 913 5752 2641 5753 2640 5753 2642 5753 2645 5754 972 5754 966 5754 2645 5755 966 5755 2600 5755 2615 5756 2646 5756 2617 5756 2647 5757 2649 5757 2648 5757 914 5758 2651 5758 2616 5758 2652 5759 2619 5759 912 5759 915 5760 2655 5760 2618 5760 2656 5761 2657 5761 2658 5761 2608 5762 2659 5762 2660 5762 2660 5763 2659 5763 960 5763 2661 5764 2606 5764 916 5764 2675 5765 2682 5765 2674 5765 2674 5766 2682 5766 2683 5766 2674 5767 2683 5767 2681 5767 2681 5768 2676 5768 2674 5768 944 5769 2681 5769 2683 5769 2662 5770 2663 5770 2684 5770 2662 5771 2684 5771 659 5771 1742 5772 2684 5772 2663 5772 1742 5773 2663 5773 2686 5773 2666 5774 2688 5774 2664 5774 2666 5775 2664 5775 2668 5775 2668 5776 2664 5776 949 5776 2668 5777 949 5777 2665 5777 2687 5778 662 5778 2666 5778 2665 5779 2667 5779 2668 5779 2668 5780 2667 5780 1745 5780 2668 5781 1745 5781 2666 5781 2666 5782 1745 5782 2687 5782 2677 5783 2678 5783 2669 5783 2678 5784 933 5784 2669 5784 933 5785 932 5785 2669 5785 2669 5786 932 5786 2689 5786 2677 5787 2669 5787 1442 5787 1442 5788 2669 5788 1443 5788 1443 5789 2669 5789 2690 5789 2690 5790 2669 5790 2689 5790 1001 5791 2690 5791 2689 5791 2670 5792 931 5792 2673 5792 2673 5793 931 5793 2671 5793 2671 5794 931 5794 930 5794 2671 5795 2691 5795 1436 5795 2671 5796 1436 5796 2673 5796 2672 5797 2673 5797 1436 5797 1859 5798 1779 5798 2692 5798 2692 5799 1779 5799 2679 5799 1438 5800 2692 5800 2679 5800 1438 5801 2679 5801 2680 5801 2676 5802 2675 5802 2674 5802 1747 5803 2665 5803 949 5803 2665 5804 1747 5804 2667 5804 2678 5805 2677 5805 1740 5805 2679 5806 1779 5806 1440 5806 2679 5807 1440 5807 2680 5807 944 5808 2683 5808 2682 5808 1742 5809 1744 5809 2684 5809 2663 5810 2685 5810 2686 5810 2685 5811 2663 5811 2662 5811 2687 5812 1019 5812 662 5812 2688 5813 2666 5813 662 5813 2672 5814 1437 5814 2673 5814 2671 5815 930 5815 2691 5815 2691 5816 930 5816 1435 5816 1859 5817 2692 5817 1858 5817 1438 5818 1439 5818 1858 5818 1438 5819 1858 5819 2692 5819 1862 5820 2716 5820 937 5820 937 5821 2716 5821 2693 5821 2716 5822 2701 5822 2693 5822 2716 5823 739 5823 2701 5823 2698 5824 2703 5824 951 5824 951 5825 2694 5825 1451 5825 1451 5826 2698 5826 951 5826 2695 5827 2707 5827 2696 5827 2696 5828 2707 5828 1853 5828 2706 5829 2695 5829 2696 5829 2706 5830 2696 5830 2704 5830 2711 5831 2710 5831 2714 5831 2711 5832 2714 5832 2715 5832 2709 5833 2712 5833 2710 5833 2712 5834 2714 5834 2710 5834 2717 5835 935 5835 939 5835 939 5836 2697 5836 2718 5836 2717 5837 939 5837 2718 5837 1856 5838 954 5838 952 5838 952 5839 954 5839 2702 5839 2699 5840 952 5840 2702 5840 954 5841 2699 5841 2702 5841 954 5842 596 5842 2699 5842 1451 5843 950 5843 2698 5843 2699 5844 1452 5844 952 5844 2698 5845 950 5845 2703 5845 2696 5846 1853 5846 2704 5846 2704 5847 1853 5847 2705 5847 2706 5848 2707 5848 2695 5848 2710 5849 2711 5849 2708 5849 2710 5850 2708 5850 2709 5850 2712 5851 2713 5851 2714 5851 2714 5852 2713 5852 2715 5852 2693 5853 2701 5853 937 5853 2718 5854 1864 5854 2717 5854 2717 5855 1864 5855 935 5855 2740 5856 2734 5856 2741 5856 2741 5857 2734 5857 2719 5857 1802 5858 2741 5858 2719 5858 1802 5859 2719 5859 2735 5859 2744 5860 2720 5860 2721 5860 2721 5861 2720 5861 2742 5861 2744 5862 2721 5862 2722 5862 2722 5863 2721 5863 2743 5863 2727 5864 1888 5864 2723 5864 2727 5865 2723 5865 2725 5865 2723 5866 2724 5866 2725 5866 2725 5867 2724 5867 595 5867 2725 5868 595 5868 2745 5868 1805 5869 2727 5869 2725 5869 1805 5870 2725 5870 2726 5870 2726 5871 2725 5871 2746 5871 2746 5872 2725 5872 2745 5872 1868 5873 2746 5873 2745 5873 2747 5874 1492 5874 2728 5874 2747 5875 2728 5875 2729 5875 1500 5876 2731 5876 2729 5876 1500 5877 2729 5877 2728 5877 1498 5878 2747 5878 2748 5878 2748 5879 2747 5879 1448 5879 1448 5880 2747 5880 2729 5880 1448 5881 2729 5881 2730 5881 2730 5882 2729 5882 2731 5882 647 5883 2732 5883 2733 5883 2733 5884 2732 5884 2750 5884 2733 5885 2750 5885 648 5885 1444 5886 2750 5886 2732 5886 1444 5887 2732 5887 2749 5887 2738 5888 1494 5888 2737 5888 2737 5889 1494 5889 2751 5889 2751 5890 2752 5890 2737 5890 2737 5891 2752 5891 2739 5891 2751 5892 1493 5892 2752 5892 2719 5893 2734 5893 1801 5893 2719 5894 1801 5894 2735 5894 1888 5895 2727 5895 928 5895 2736 5896 2731 5896 1500 5896 2731 5897 2736 5897 2730 5897 2739 5898 1497 5898 2737 5898 2737 5899 1497 5899 2738 5899 1802 5900 1803 5900 651 5900 1802 5901 651 5901 2741 5901 2740 5902 2741 5902 651 5902 2721 5903 2742 5903 2743 5903 2743 5904 2742 5904 1804 5904 2722 5905 970 5905 2744 5905 2745 5906 595 5906 1868 5906 1492 5907 2747 5907 1498 5907 2748 5908 991 5908 1498 5908 2732 5909 647 5909 2749 5909 2749 5910 647 5910 1499 5910 1444 5911 993 5911 2750 5911 1493 5912 2751 5912 1494 5912 2768 5913 2754 5913 2766 5913 2768 5914 2766 5914 2767 5914 2303 5915 2765 5915 2766 5915 2754 5916 2303 5916 2766 5916 2754 5917 2753 5917 2303 5917 2780 5918 2779 5918 2756 5918 2756 5919 2779 5919 2755 5919 2756 5920 1501 5920 2778 5920 2780 5921 2756 5921 2778 5921 926 5922 2773 5922 2757 5922 926 5923 2757 5923 2770 5923 2769 5924 2773 5924 2772 5924 2757 5925 2773 5925 2769 5925 2758 5926 2775 5926 2777 5926 2777 5927 2775 5927 1874 5927 2774 5928 2758 5928 2777 5928 2774 5929 2777 5929 1795 5929 2781 5930 2783 5930 2782 5930 1502 5931 2760 5931 2782 5931 1502 5932 2782 5932 2784 5932 2760 5933 2781 5933 2782 5933 2760 5934 2759 5934 2781 5934 2762 5935 1872 5935 2764 5935 2764 5936 593 5936 2761 5936 2762 5937 2764 5937 2761 5937 2761 5938 2763 5938 1872 5938 2761 5939 1872 5939 2762 5939 2764 5940 1872 5940 655 5940 2766 5941 2765 5941 2767 5941 2754 5942 2768 5942 1871 5942 2769 5943 2770 5943 2757 5943 2773 5944 926 5944 2772 5944 2772 5945 926 5945 2771 5945 2774 5946 1865 5946 2775 5946 2774 5947 2775 5947 2758 5947 2777 5948 2776 5948 1795 5948 2778 5949 1503 5949 2779 5949 2778 5950 2779 5950 2780 5950 2756 5951 2755 5951 1501 5951 2781 5952 751 5952 2783 5952 2782 5953 2783 5953 2784 5953 1920 5954 3008 5954 2808 5954 2808 5955 3008 5955 1907 5955 1918 5956 3006 5956 3007 5956 2809 5957 2837 5957 2810 5957 2809 5958 2810 5958 855 5958 855 5959 2810 5959 3464 5959 2964 5960 2827 5960 831 5960 831 5961 2827 5961 2811 5961 831 5962 2811 5962 832 5962 832 5963 2811 5963 3513 5963 832 5964 3513 5964 2812 5964 2866 5965 2813 5965 2814 5965 2814 5966 2813 5966 2949 5966 2823 5967 859 5967 2815 5967 2815 5968 643 5968 2823 5968 2965 5969 2816 5969 643 5969 2965 5970 643 5970 2815 5970 2818 5971 2824 5971 2817 5971 2818 5972 589 5972 2820 5972 589 5973 2818 5973 2817 5973 2820 5974 589 5974 3513 5974 2827 5975 2819 5975 2811 5975 2811 5976 2820 5976 3513 5976 2820 5977 2811 5977 2819 5977 860 5978 1880 5978 2822 5978 1880 5979 860 5979 2823 5979 859 5980 2823 5980 860 5980 2919 5981 584 5981 2879 5981 2824 5982 2816 5982 584 5982 2824 5983 584 5983 2817 5983 584 5984 2965 5984 2879 5984 2879 5985 2965 5985 828 5985 2919 5986 830 5986 2817 5986 2919 5987 2817 5987 584 5987 2816 5988 2965 5988 584 5988 2895 5989 2896 5989 2964 5989 2964 5990 2896 5990 862 5990 2825 5991 2964 5991 2821 5991 860 5992 2822 5992 2826 5992 2826 5993 2822 5993 2821 5993 2826 5994 2821 5994 2964 5994 2964 5995 862 5995 2826 5995 2819 5996 2827 5996 2825 5996 2825 5997 2827 5997 2964 5997 637 5998 2833 5998 2841 5998 637 5999 2841 5999 638 5999 2828 6000 2967 6000 2839 6000 642 6001 591 6001 2829 6001 591 6002 642 6002 2842 6002 2829 6003 591 6003 3464 6003 2810 6004 2829 6004 3464 6004 2829 6005 2810 6005 1883 6005 2810 6006 2837 6006 1883 6006 2831 6007 2835 6007 2830 6007 2830 6008 2835 6008 2834 6008 2832 6009 2831 6009 2830 6009 2831 6010 2832 6010 637 6010 637 6011 2832 6011 2833 6011 2834 6012 2877 6012 2836 6012 2837 6013 2834 6013 2838 6013 2837 6014 2838 6014 1883 6014 2834 6015 2837 6015 2877 6015 2877 6016 2837 6016 2966 6016 2920 6017 2830 6017 2836 6017 2836 6018 2830 6018 2834 6018 642 6019 2839 6019 2842 6019 2842 6020 2839 6020 2967 6020 2840 6021 2967 6021 2828 6021 2840 6022 2828 6022 2841 6022 2841 6023 2828 6023 638 6023 2967 6024 2921 6024 2842 6024 2840 6025 2921 6025 2967 6025 2891 6026 2921 6026 2890 6026 2973 6027 1365 6027 1909 6027 2845 6028 2846 6028 2873 6028 1433 6029 864 6029 1432 6029 587 6030 880 6030 2849 6030 2852 6031 920 6031 586 6031 2853 6032 917 6032 919 6032 2855 6033 898 6033 2854 6033 2855 6034 2854 6034 910 6034 2856 6035 585 6035 2857 6035 2856 6036 2857 6036 899 6036 2929 6037 2892 6037 2914 6037 2931 6038 2902 6038 2901 6038 2899 6039 2901 6039 2900 6039 2858 6040 2899 6040 2900 6040 2858 6041 2998 6041 2899 6041 2899 6042 2998 6042 2858 6042 2899 6043 2859 6043 2918 6043 2911 6044 854 6044 875 6044 2898 6045 2860 6045 876 6045 876 6046 2860 6046 877 6046 877 6047 2860 6047 874 6047 2861 6048 874 6048 2860 6048 2910 6049 2950 6049 2863 6049 2910 6050 2863 6050 2909 6050 2863 6051 2864 6051 2909 6051 2862 6052 2908 6052 2909 6052 2909 6053 2864 6053 2862 6053 2908 6054 2932 6054 2884 6054 885 6055 843 6055 588 6055 588 6056 843 6056 844 6056 2897 6057 2813 6057 2866 6057 2897 6058 2866 6058 2907 6058 2865 6059 2907 6059 2814 6059 2814 6060 2907 6060 2866 6060 2933 6061 841 6061 2906 6061 2905 6062 2906 6062 2868 6062 2995 6063 2867 6063 2905 6063 2868 6064 2995 6064 2905 6064 2867 6065 2870 6065 2869 6065 866 6066 2871 6066 2903 6066 2903 6067 2871 6067 2872 6067 2903 6068 837 6068 866 6068 866 6069 837 6069 867 6069 867 6070 837 6070 2912 6070 2889 6071 2912 6071 837 6071 2917 6072 2873 6072 840 6072 840 6073 2873 6073 2963 6073 839 6074 2916 6074 2874 6074 840 6075 2992 6075 2874 6075 2874 6076 2992 6076 839 6076 2947 6077 2915 6077 2875 6077 2875 6078 2915 6078 882 6078 882 6079 2915 6079 835 6079 873 6080 854 6080 2911 6080 870 6081 2936 6081 2935 6081 2935 6082 2936 6082 2887 6082 2877 6083 2966 6083 2956 6083 2881 6084 2920 6084 2876 6084 2876 6085 2920 6085 2836 6085 2876 6086 2836 6086 2877 6086 2876 6087 2877 6087 889 6087 889 6088 2877 6088 2956 6088 828 6089 2959 6089 2879 6089 2879 6090 2959 6090 886 6090 2879 6091 886 6091 2878 6091 2961 6092 830 6092 2878 6092 2878 6093 830 6093 2919 6093 2878 6094 2919 6094 2879 6094 2880 6095 2938 6095 2934 6095 2934 6096 2938 6096 2937 6096 2946 6097 863 6097 2902 6097 2946 6098 2902 6098 2931 6098 2955 6099 879 6099 2881 6099 2881 6100 879 6100 850 6100 872 6101 871 6101 873 6101 873 6102 871 6102 2943 6102 846 6103 845 6103 2882 6103 2882 6104 845 6104 2942 6104 2884 6105 2932 6105 887 6105 887 6106 2932 6106 2883 6106 2884 6107 2954 6107 2952 6107 2952 6108 2954 6108 2951 6108 892 6109 2957 6109 891 6109 891 6110 2957 6110 2956 6110 2922 6111 2923 6111 2963 6111 2922 6112 2963 6112 878 6112 2885 6113 842 6113 841 6113 2885 6114 841 6114 2933 6114 2865 6115 2814 6115 2948 6115 2948 6116 2814 6116 2949 6116 2886 6117 2937 6117 2887 6117 2887 6118 2937 6118 2938 6118 2885 6119 2888 6119 838 6119 838 6120 2888 6120 2889 6120 891 6121 2891 6121 890 6121 850 6122 879 6122 2890 6122 2890 6123 879 6123 890 6123 2890 6124 890 6124 2891 6124 2930 6125 2945 6125 2892 6125 2892 6126 2945 6126 2893 6126 835 6127 836 6127 883 6127 883 6128 836 6128 892 6128 844 6129 2954 6129 2894 6129 2894 6130 2954 6130 2953 6130 834 6131 2896 6131 888 6131 833 6132 2962 6132 2895 6132 2895 6133 2962 6133 888 6133 2895 6134 888 6134 2896 6134 2897 6135 2948 6135 2813 6135 2813 6136 2948 6136 2949 6136 2898 6137 876 6137 875 6137 2898 6138 875 6138 854 6138 2899 6139 2858 6139 2859 6139 2900 6140 2901 6140 2902 6140 2872 6141 2871 6141 2904 6141 2905 6142 2867 6142 2869 6142 2868 6143 2906 6143 841 6143 2889 6144 2888 6144 2912 6144 2914 6145 2913 6145 2929 6145 840 6146 2874 6146 2917 6146 2963 6147 2873 6147 878 6147 2921 6148 2840 6148 2890 6148 592 6149 2921 6149 2891 6149 2916 6150 2923 6150 2922 6150 900 6151 2924 6151 2497 6151 2497 6152 2924 6152 865 6152 2497 6153 865 6153 1902 6153 2620 6154 995 6154 1899 6154 921 6155 2926 6155 2625 6155 2625 6156 2926 6156 2624 6156 2625 6157 2624 6157 2925 6157 2926 6158 921 6158 1907 6158 921 6159 881 6159 1907 6159 2928 6160 1918 6160 2525 6160 2525 6161 1918 6161 893 6161 2525 6162 893 6162 2927 6162 2880 6163 2934 6163 868 6163 2936 6164 2886 6164 2887 6164 846 6165 2882 6165 853 6165 2942 6166 845 6166 895 6166 2943 6167 871 6167 2861 6167 863 6168 2946 6168 2918 6168 842 6169 2885 6169 2870 6169 887 6170 2883 6170 2950 6170 2953 6171 2954 6171 2884 6171 2881 6172 2876 6172 2955 6172 2956 6173 2957 6173 889 6173 834 6174 888 6174 2958 6174 886 6175 2959 6175 884 6175 2960 6176 2961 6176 2878 6176 2904 6177 838 6177 2872 6177 2895 6178 2964 6178 831 6178 2966 6179 2837 6179 2809 6179 1369 6180 2968 6180 2970 6180 2968 6181 1368 6181 2969 6181 2968 6182 2969 6182 2970 6182 2972 6183 1367 6183 2968 6183 2968 6184 1367 6184 1368 6184 1373 6185 1367 6185 2972 6185 2971 6186 2972 6186 1589 6186 1373 6187 2972 6187 2971 6187 1379 6188 1365 6188 2973 6188 2973 6189 2974 6189 1375 6189 2973 6190 1375 6190 1378 6190 2973 6191 1378 6191 1379 6191 2973 6192 2977 6192 1363 6192 2973 6193 1363 6193 2974 6193 2978 6194 1363 6194 2977 6194 2975 6195 2977 6195 2976 6195 2978 6196 2977 6196 2975 6196 1905 6197 2979 6197 2981 6197 2981 6198 2979 6198 2984 6198 2984 6199 2979 6199 1906 6199 2984 6200 1906 6200 2980 6200 2999 6201 2980 6201 3000 6201 3000 6202 2980 6202 1906 6202 1382 6203 2981 6203 2999 6203 2999 6204 2981 6204 2984 6204 2999 6205 2984 6205 2980 6205 3002 6206 1913 6206 3001 6206 3001 6207 1913 6207 1912 6207 3001 6208 1912 6208 2983 6208 2982 6209 2983 6209 1911 6209 1911 6210 2983 6210 1912 6210 2982 6211 1915 6211 3001 6211 2982 6212 3001 6212 2983 6212 2986 6213 2988 6213 1218 6213 2986 6214 1218 6214 2985 6214 2986 6215 2985 6215 2987 6215 2986 6216 3010 6216 2988 6216 2991 6217 2989 6217 583 6217 583 6218 2989 6218 2990 6218 583 6219 2990 6219 3013 6219 2995 6220 1900 6220 2994 6220 2995 6221 2994 6221 1900 6221 2864 6222 2996 6222 823 6222 2864 6223 823 6223 822 6223 2998 6224 820 6224 2997 6224 2858 6225 2998 6225 2997 6225 2858 6226 2997 6226 821 6226 2999 6227 3000 6227 1382 6227 1915 6228 3002 6228 3001 6228 2987 6229 2985 6229 1364 6229 2990 6230 2786 6230 3013 6230 3015 6231 1791 6231 762 6231 762 6232 1791 6232 2183 6232 771 6233 3016 6233 813 6233 813 6234 3016 6234 761 6234 812 6235 3017 6235 811 6235 811 6236 3017 6236 1846 6236 768 6237 3018 6237 3019 6237 3019 6238 3018 6238 3020 6238 3021 6239 3022 6239 810 6239 810 6240 3022 6240 3023 6240 763 6241 764 6241 806 6241 806 6242 764 6242 805 6242 801 6243 3024 6243 3025 6243 3025 6244 3024 6244 3026 6244 798 6245 795 6245 3027 6245 3027 6246 795 6246 793 6246 2189 6247 791 6247 758 6247 758 6248 791 6248 757 6248 3028 6249 3029 6249 754 6249 754 6250 3029 6250 753 6250 789 6251 775 6251 788 6251 788 6252 775 6252 780 6252 1848 6253 3030 6253 1847 6253 1847 6254 3030 6254 781 6254 745 6255 748 6255 3034 6255 738 6256 3039 6256 3035 6256 3035 6257 3039 6257 3036 6257 730 6258 1355 6258 3037 6258 3037 6259 1355 6259 2054 6259 743 6260 1354 6260 1329 6260 726 6261 2066 6261 3038 6261 3040 6262 2051 6262 3041 6262 2027 6263 1332 6263 2229 6263 2229 6264 1332 6264 2227 6264 2024 6265 1840 6265 3042 6265 3042 6266 1840 6266 2225 6266 1134 6267 1136 6267 1362 6267 1362 6268 1136 6268 1135 6268 1141 6269 3044 6269 3043 6269 3043 6270 3044 6270 1138 6270 2135 6271 2038 6271 1361 6271 1361 6272 2038 6272 2039 6272 2012 6273 2203 6273 3045 6273 3045 6274 2203 6274 3046 6274 3047 6275 3048 6275 1152 6275 1152 6276 3048 6276 1153 6276 3049 6277 1083 6277 1147 6277 1147 6278 1083 6278 1146 6278 1143 6279 1117 6279 1131 6279 1131 6280 1117 6280 722 6280 1126 6281 1120 6281 1127 6281 1127 6282 1120 6282 1123 6282 1077 6283 1080 6283 1076 6283 1076 6284 1080 6284 1082 6284 1111 6285 1110 6285 1114 6285 1114 6286 1110 6286 2254 6286 3053 6287 1457 6287 3056 6287 1450 6288 3054 6288 3060 6288 3057 6289 1269 6289 1624 6289 712 6290 2106 6290 794 6290 707 6291 1266 6291 3058 6291 3058 6292 1266 6292 2104 6292 619 6293 2116 6293 709 6293 3054 6294 3059 6294 3060 6294 3060 6295 3059 6295 3055 6295 748 6296 749 6296 3034 6296 3034 6297 749 6297 3033 6297 1477 6298 3061 6298 3062 6298 3062 6299 3061 6299 1487 6299 3062 6300 1487 6300 3077 6300 1477 6301 3063 6301 3061 6301 3061 6302 3063 6302 1478 6302 3061 6303 1478 6303 1479 6303 3064 6304 1481 6304 1479 6304 1479 6305 1481 6305 3065 6305 1479 6306 3065 6306 1483 6306 1483 6307 3066 6307 1479 6307 1479 6308 3066 6308 1485 6308 1479 6309 1485 6309 3061 6309 3068 6310 3076 6310 1517 6310 3067 6311 3069 6311 1386 6311 1386 6312 3069 6312 1385 6312 3068 6313 1517 6313 3069 6313 3069 6314 1517 6314 1384 6314 3069 6315 1384 6315 1385 6315 3071 6316 1387 6316 3070 6316 3070 6317 1388 6317 3071 6317 3071 6318 1388 6318 1389 6318 3071 6319 1389 6319 1386 6319 1386 6320 1389 6320 1390 6320 1386 6321 1390 6321 3067 6321 2644 6322 2617 6322 986 6322 995 6323 2623 6323 1896 6323 1032 6324 2497 6324 1902 6324 1028 6325 908 6325 1033 6325 3076 6326 3068 6326 1397 6326 1397 6327 3068 6327 1520 6327 1487 6328 3078 6328 3077 6328 3077 6329 3078 6329 1402 6329 3080 6330 3082 6330 686 6330 686 6331 3082 6331 3081 6331 3083 6332 3085 6332 676 6332 676 6333 3085 6333 680 6333 3087 6334 3341 6334 3086 6334 3087 6335 3086 6335 3340 6335 3088 6336 3339 6336 3137 6336 3088 6337 3137 6337 3338 6337 3089 6338 3138 6338 3337 6338 3334 6339 3336 6339 3139 6339 3334 6340 3139 6340 3335 6340 3333 6341 3140 6341 3090 6341 3333 6342 3090 6342 3141 6342 3331 6343 3142 6343 3143 6343 3331 6344 3143 6344 3091 6344 3328 6345 3330 6345 3092 6345 3093 6346 3152 6346 3326 6346 3325 6347 3094 6347 3324 6347 3095 6348 3096 6348 3097 6348 3095 6349 3097 6349 3154 6349 3098 6350 3099 6350 3100 6350 3098 6351 3100 6351 3155 6351 3320 6352 3157 6352 3156 6352 3320 6353 3156 6353 3321 6353 3198 6354 3254 6354 3253 6354 3251 6355 3252 6355 3307 6355 3103 6356 3102 6356 3276 6356 3245 6357 3186 6357 3244 6357 3240 6358 3112 6358 3115 6358 3381 6359 3127 6359 3106 6359 3231 6360 3381 6360 3383 6360 3203 6361 3107 6361 3436 6361 3435 6362 3434 6362 3247 6362 3302 6363 3301 6363 3108 6363 3302 6364 3108 6364 3432 6364 3430 6365 3431 6365 3205 6365 3129 6366 3109 6366 3399 6366 3396 6367 3388 6367 3110 6367 3388 6368 3396 6368 3105 6368 3388 6369 3105 6369 3236 6369 3396 6370 3272 6370 3105 6370 3178 6371 3104 6371 3388 6371 3110 6372 3388 6372 3104 6372 3110 6373 3104 6373 3271 6373 3129 6374 3274 6374 3109 6374 3129 6375 3399 6375 3396 6375 3129 6376 3396 6376 3110 6376 3397 6377 3267 6377 3343 6377 3285 6378 3115 6378 3112 6378 3428 6379 3285 6379 3112 6379 3428 6380 3112 6380 3114 6380 3111 6381 3397 6381 3343 6381 3285 6382 3428 6382 3343 6382 3343 6383 3428 6383 3390 6383 3343 6384 3390 6384 3111 6384 3111 6385 3390 6385 3392 6385 3111 6386 3392 6386 3391 6386 3392 6387 3390 6387 3242 6387 3392 6388 3242 6388 3427 6388 3427 6389 3242 6389 3213 6389 3397 6390 3113 6390 3267 6390 3270 6391 3242 6391 3390 6391 3242 6392 3270 6392 3269 6392 3388 6393 3178 6393 3389 6393 3428 6394 3270 6394 3386 6394 3390 6395 3386 6395 3270 6395 3113 6396 3393 6396 3211 6396 3398 6397 3109 6397 3394 6397 3287 6398 3408 6398 3286 6398 3412 6399 3415 6399 3248 6399 3410 6400 3416 6400 3121 6400 3182 6401 3286 6401 3408 6401 3182 6402 3408 6402 3122 6402 3122 6403 3408 6403 3406 6403 3415 6404 3342 6404 3248 6404 3416 6405 3410 6405 3409 6405 3416 6406 3409 6406 3407 6406 3418 6407 3116 6407 3409 6407 3409 6408 3116 6408 3407 6408 3407 6409 3116 6409 3422 6409 3415 6410 3416 6410 3342 6410 3342 6411 3416 6411 3407 6411 3342 6412 3407 6412 3408 6412 3342 6413 3408 6413 3287 6413 3342 6414 3204 6414 3248 6414 3424 6415 3404 6415 3263 6415 3263 6416 3404 6416 3264 6416 3404 6417 3260 6417 3264 6417 3117 6418 3403 6418 3425 6418 3183 6419 3420 6419 3400 6419 3183 6420 3400 6420 3117 6420 3119 6421 3118 6421 3128 6421 3403 6422 3117 6422 3400 6422 3260 6423 3404 6423 3403 6423 3260 6424 3403 6424 3128 6424 3128 6425 3403 6425 3119 6425 3119 6426 3403 6426 3400 6426 3119 6427 3400 6427 3401 6427 3307 6428 3264 6428 3260 6428 3118 6429 3120 6429 3128 6429 3248 6430 3247 6430 3434 6430 3412 6431 3434 6431 3121 6431 3286 6432 3265 6432 3294 6432 3248 6433 3434 6433 3412 6433 3294 6434 3288 6434 3286 6434 3434 6435 3419 6435 3121 6435 3419 6436 3434 6436 3421 6436 3421 6437 3434 6437 3294 6437 3421 6438 3294 6438 3265 6438 3421 6439 3265 6439 3122 6439 3197 6440 3126 6440 3123 6440 3123 6441 3183 6441 3125 6441 3123 6442 3125 6442 3197 6442 3125 6443 3183 6443 3431 6443 3431 6444 3183 6444 3423 6444 3126 6445 3197 6445 3124 6445 3126 6446 3124 6446 3120 6446 3264 6447 3307 6447 3252 6447 3252 6448 3307 6448 3431 6448 3252 6449 3431 6449 3262 6449 3262 6450 3431 6450 3423 6450 3349 6451 3282 6451 3130 6451 3106 6452 3127 6452 3231 6452 3255 6453 3304 6453 3128 6453 3128 6454 3304 6454 3305 6454 3380 6455 3106 6455 3284 6455 3305 6456 3274 6456 3129 6456 3384 6457 3130 6457 3129 6457 3129 6458 3130 6458 3305 6458 3305 6459 3130 6459 3284 6459 3149 6460 3148 6460 3380 6460 3149 6461 3380 6461 3284 6461 3146 6462 3174 6462 3347 6462 3377 6463 3128 6463 3308 6463 3344 6464 3308 6464 3345 6464 3231 6465 3305 6465 3284 6465 3231 6466 3284 6466 3106 6466 3231 6467 3383 6467 3174 6467 3231 6468 3174 6468 3305 6468 3305 6469 3174 6469 3308 6469 3305 6470 3308 6470 3128 6470 3267 6471 3107 6471 3131 6471 3346 6472 3277 6472 3133 6472 3374 6473 3375 6473 3278 6473 3132 6474 3180 6474 3133 6474 3204 6475 3342 6475 3180 6475 3180 6476 3342 6476 3133 6476 3278 6477 3281 6477 3246 6477 3278 6478 3246 6478 3374 6478 3374 6479 3246 6479 3348 6479 3312 6480 3267 6480 3131 6480 3312 6481 3131 6481 3281 6481 3281 6482 3131 6482 3132 6482 3281 6483 3132 6483 3246 6483 3246 6484 3132 6484 3133 6484 3259 6485 3133 6485 3342 6485 3146 6486 3348 6486 3147 6486 3147 6487 3348 6487 3246 6487 3175 6488 3267 6488 3312 6488 3350 6489 3312 6489 3163 6489 3278 6490 3279 6490 3281 6490 3281 6491 3279 6491 3309 6491 3281 6492 3309 6492 3148 6492 3148 6493 3309 6493 3311 6493 3277 6494 3346 6494 3134 6494 3134 6495 3346 6495 3345 6495 3134 6496 3145 6496 3135 6496 3135 6497 3277 6497 3134 6497 3181 6498 3230 6498 3144 6498 3275 6499 3229 6499 3145 6499 3276 6500 3135 6500 3257 6500 3144 6501 3136 6501 3341 6501 3136 6502 3102 6502 3341 6502 3341 6503 3102 6503 3257 6503 3086 6504 3257 6504 3340 6504 3144 6505 3341 6505 3135 6505 3135 6506 3341 6506 3340 6506 3257 6507 3086 6507 3341 6507 3135 6508 3338 6508 3137 6508 3135 6509 3137 6509 3144 6509 3137 6510 3339 6510 3144 6510 3144 6511 3339 6511 3135 6511 3135 6512 3339 6512 3338 6512 3144 6513 3138 6513 3135 6513 3135 6514 3138 6514 3337 6514 3138 6515 3144 6515 3135 6515 3138 6516 3135 6516 3337 6516 3135 6517 3335 6517 3139 6517 3135 6518 3139 6518 3144 6518 3144 6519 3139 6519 3336 6519 3144 6520 3336 6520 3135 6520 3135 6521 3336 6521 3335 6521 3135 6522 3141 6522 3090 6522 3135 6523 3090 6523 3144 6523 3090 6524 3140 6524 3144 6524 3144 6525 3140 6525 3135 6525 3135 6526 3140 6526 3141 6526 3091 6527 3135 6527 3332 6527 3142 6528 3332 6528 3144 6528 3144 6529 3332 6529 3135 6529 3135 6530 3091 6530 3143 6530 3135 6531 3143 6531 3144 6531 3144 6532 3143 6532 3142 6532 3145 6533 3329 6533 3092 6533 3145 6534 3092 6534 3135 6534 3144 6535 3330 6535 3145 6535 3145 6536 3330 6536 3329 6536 3135 6537 3092 6537 3144 6537 3092 6538 3330 6538 3144 6538 3327 6539 3144 6539 3145 6539 3181 6540 3144 6540 3327 6540 3229 6541 3181 6541 3145 6541 3145 6542 3181 6542 3327 6542 3257 6543 3135 6543 3340 6543 3144 6544 3146 6544 3147 6544 3144 6545 3147 6545 3136 6545 3280 6546 3148 6546 3149 6546 3151 6547 3280 6547 3149 6547 3151 6548 3149 6548 3283 6548 3233 6549 3150 6549 3161 6549 3185 6550 3244 6550 3151 6550 3162 6551 3152 6551 3151 6551 3151 6552 3152 6552 3326 6552 3186 6553 3152 6553 3162 6553 3152 6554 3186 6554 3185 6554 3152 6555 3185 6555 3326 6555 3153 6556 3162 6556 3094 6556 3153 6557 3324 6557 3283 6557 3283 6558 3324 6558 3151 6558 3151 6559 3324 6559 3094 6559 3151 6560 3094 6560 3162 6560 3283 6561 3154 6561 3097 6561 3153 6562 3283 6562 3162 6562 3162 6563 3283 6563 3097 6563 3097 6564 3096 6564 3162 6564 3323 6565 3154 6565 3283 6565 3096 6566 3323 6566 3162 6566 3162 6567 3323 6567 3283 6567 3322 6568 3155 6568 3283 6568 3100 6569 3162 6569 3283 6569 3100 6570 3283 6570 3155 6570 3100 6571 3099 6571 3162 6571 3162 6572 3099 6572 3150 6572 3099 6573 3322 6573 3150 6573 3150 6574 3322 6574 3283 6574 3283 6575 3321 6575 3156 6575 3283 6576 3156 6576 3150 6576 3150 6577 3157 6577 3283 6577 3283 6578 3157 6578 3321 6578 3156 6579 3157 6579 3150 6579 3158 6580 3150 6580 3283 6580 3150 6581 3158 6581 3283 6581 3150 6582 3159 6582 3283 6582 3283 6583 3159 6583 3150 6583 3161 6584 3150 6584 3160 6584 3160 6585 3150 6585 3283 6585 3184 6586 3161 6586 3283 6586 3283 6587 3161 6587 3160 6587 3185 6588 3151 6588 3326 6588 3150 6589 3282 6589 3164 6589 3150 6590 3164 6590 3162 6590 3163 6591 3164 6591 3349 6591 3349 6592 3164 6592 3282 6592 3194 6593 3352 6593 3196 6593 3196 6594 3352 6594 3355 6594 3209 6595 3360 6595 3193 6595 3193 6596 3360 6596 3317 6596 3165 6597 3359 6597 3358 6597 3165 6598 3358 6598 3357 6598 3357 6599 3358 6599 3351 6599 3357 6600 3351 6600 3353 6600 3168 6601 3167 6601 3351 6601 3168 6602 3351 6602 3169 6602 3169 6603 3351 6603 3358 6603 3169 6604 3358 6604 3166 6604 3365 6605 3316 6605 3362 6605 3362 6606 3316 6606 3201 6606 3369 6607 3191 6607 3368 6607 3368 6608 3191 6608 3318 6608 3170 6609 3172 6609 3173 6609 3173 6610 3172 6610 3171 6610 3368 6611 3172 6611 3369 6611 3369 6612 3172 6612 3170 6612 3362 6613 3173 6613 3365 6613 3365 6614 3173 6614 3171 6614 3380 6615 3310 6615 3382 6615 3374 6616 3174 6616 3376 6616 3376 6617 3375 6617 3374 6617 3106 6618 3380 6618 3382 6618 3310 6619 3279 6619 3376 6619 3310 6620 3376 6620 3382 6620 3382 6621 3376 6621 3174 6621 3382 6622 3174 6622 3383 6622 3175 6623 3177 6623 3385 6623 3177 6624 3130 6624 3385 6624 3385 6625 3130 6625 3176 6625 3385 6626 3176 6626 3384 6626 3301 6627 3178 6627 3108 6627 3235 6628 3433 6628 3394 6628 3394 6629 3433 6629 3426 6629 3433 6630 3272 6630 3426 6630 3235 6631 3394 6631 3109 6631 3272 6632 3433 6632 3273 6632 3273 6633 3433 6633 3108 6633 3273 6634 3108 6634 3178 6634 3377 6635 3308 6635 3179 6635 3308 6636 3133 6636 3179 6636 3179 6637 3133 6637 3379 6637 3179 6638 3379 6638 3259 6638 3124 6639 3306 6639 3255 6639 3255 6640 3306 6640 3304 6640 3132 6641 3247 6641 3180 6641 3180 6642 3247 6642 3204 6642 3247 6643 3248 6643 3204 6643 3230 6644 3181 6644 3229 6644 3276 6645 3257 6645 3102 6645 3419 6646 3250 6646 3116 6646 3250 6647 3422 6647 3116 6647 3266 6648 3286 6648 3182 6648 3266 6649 3182 6649 3122 6649 3252 6650 3263 6650 3264 6650 3254 6651 3183 6651 3117 6651 3305 6652 3234 6652 3274 6652 3235 6653 3274 6653 3234 6653 3107 6654 3290 6654 3131 6654 3233 6655 3161 6655 3184 6655 3244 6656 3185 6656 3186 6656 3219 6657 3190 6657 3195 6657 3195 6658 3190 6658 3319 6658 3319 6659 3190 6659 3188 6659 3225 6660 3226 6660 3201 6660 3292 6661 3295 6661 3225 6661 3225 6662 3295 6662 3220 6662 3192 6663 3318 6663 3193 6663 3220 6664 3318 6664 3191 6664 3316 6665 3313 6665 3194 6665 3194 6666 3313 6666 3192 6666 3194 6667 3192 6667 3193 6667 3195 6668 3209 6668 3219 6668 3219 6669 3209 6669 3232 6669 3319 6670 3188 6670 3189 6670 3319 6671 3189 6671 3196 6671 3210 6672 3194 6672 3196 6672 3210 6673 3196 6673 3189 6673 3306 6674 3197 6674 3227 6674 3227 6675 3198 6675 3187 6675 3187 6676 3303 6676 3299 6676 3429 6677 3253 6677 3198 6677 3429 6678 3198 6678 3197 6678 3197 6679 3198 6679 3227 6679 3187 6680 3198 6680 3205 6680 3205 6681 3198 6681 3253 6681 3197 6682 3306 6682 3124 6682 3208 6683 3306 6683 3227 6683 3235 6684 3234 6684 3220 6684 3432 6685 3199 6685 3302 6685 3302 6686 3199 6686 3220 6686 3220 6687 3199 6687 3432 6687 3220 6688 3432 6688 3235 6688 3297 6689 3200 6689 3220 6689 3297 6690 3220 6690 3295 6690 3220 6691 3200 6691 3302 6691 3297 6692 3302 6692 3200 6692 3225 6693 3239 6693 3292 6693 3214 6694 3239 6694 3225 6694 3239 6695 3214 6695 3292 6695 3243 6696 3203 6696 3202 6696 3201 6697 3203 6697 3225 6697 3225 6698 3203 6698 3243 6698 3243 6699 3202 6699 3214 6699 3225 6700 3243 6700 3214 6700 3201 6701 3268 6701 3203 6701 3290 6702 3107 6702 3268 6702 3268 6703 3107 6703 3203 6703 3249 6704 3293 6704 3435 6704 3228 6705 3249 6705 3215 6705 3435 6706 3247 6706 3215 6706 3435 6707 3215 6707 3249 6707 3249 6708 3294 6708 3293 6708 3294 6709 3249 6709 3228 6709 3298 6710 3101 6710 3228 6710 3298 6711 3228 6711 3300 6711 3300 6712 3228 6712 3187 6712 3300 6713 3187 6713 3299 6713 3228 6714 3101 6714 3294 6714 3288 6715 3294 6715 3298 6715 3298 6716 3294 6716 3101 6716 3187 6717 3251 6717 3303 6717 3303 6718 3251 6718 3307 6718 3307 6719 3251 6719 3205 6719 3205 6720 3251 6720 3187 6720 3253 6721 3429 6721 3205 6721 3205 6722 3429 6722 3430 6722 3227 6723 3219 6723 3208 6723 3206 6724 3207 6724 3232 6724 3232 6725 3207 6725 3219 6725 3207 6726 3206 6726 3208 6726 3219 6727 3207 6727 3208 6727 3189 6728 3103 6728 3210 6728 3215 6729 3247 6729 3103 6729 3215 6730 3103 6730 3189 6730 3232 6731 3209 6731 3193 6731 3232 6732 3193 6732 3206 6732 3193 6733 3233 6733 3206 6733 3194 6734 3245 6734 3316 6734 3193 6735 3318 6735 3233 6735 3210 6736 3245 6736 3194 6736 3234 6737 3206 6737 3220 6737 3220 6738 3206 6738 3318 6738 3318 6739 3206 6739 3233 6739 3268 6740 3201 6740 3316 6740 3268 6741 3316 6741 3245 6741 3247 6742 3291 6742 3103 6742 3103 6743 3291 6743 3210 6743 3210 6744 3291 6744 3290 6744 3210 6745 3290 6745 3245 6745 3245 6746 3290 6746 3268 6746 3436 6747 3211 6747 3212 6747 3269 6748 3214 6748 3289 6748 3436 6749 3212 6749 3213 6749 3211 6750 3436 6750 3107 6750 3211 6751 3107 6751 3113 6751 3436 6752 3213 6752 3289 6752 3289 6753 3213 6753 3269 6753 3269 6754 3270 6754 3241 6754 3115 6755 3214 6755 3241 6755 3241 6756 3214 6756 3269 6756 3372 6757 3215 6757 3370 6757 3370 6758 3215 6758 3189 6758 3373 6759 3187 6759 3216 6759 3216 6760 3187 6760 3228 6760 3217 6761 3219 6761 3218 6761 3218 6762 3219 6762 3227 6762 3363 6763 3225 6763 3220 6763 3363 6764 3220 6764 3366 6764 3222 6765 3221 6765 3223 6765 3223 6766 3221 6766 3224 6766 3370 6767 3221 6767 3372 6767 3372 6768 3221 6768 3222 6768 3218 6769 3223 6769 3217 6769 3217 6770 3223 6770 3224 6770 3225 6771 3363 6771 3226 6771 3226 6772 3363 6772 3362 6772 3226 6773 3362 6773 3201 6773 3191 6774 3369 6774 3220 6774 3220 6775 3369 6775 3366 6775 3187 6776 3373 6776 3227 6776 3227 6777 3373 6777 3218 6777 3215 6778 3372 6778 3228 6778 3228 6779 3372 6779 3216 6779 3308 6780 3174 6780 3275 6780 3275 6781 3174 6781 3230 6781 3229 6782 3275 6782 3230 6782 3127 6783 3381 6783 3231 6783 3233 6784 3284 6784 3130 6784 3184 6785 3284 6785 3233 6785 3237 6786 3236 6786 3105 6786 3238 6787 3271 6787 3104 6787 3178 6788 3301 6788 3238 6788 3240 6789 3114 6789 3112 6789 3240 6790 3115 6790 3241 6790 3256 6791 3213 6791 3242 6791 3256 6792 3269 6792 3213 6792 3107 6793 3267 6793 3268 6793 3312 6794 3281 6794 3186 6794 3186 6795 3281 6795 3244 6795 3245 6796 3244 6796 3186 6796 3133 6797 3276 6797 3246 6797 3246 6798 3276 6798 3102 6798 3103 6799 3276 6799 3102 6799 3419 6800 3421 6800 3250 6800 3307 6801 3252 6801 3251 6801 3253 6802 3254 6802 3198 6802 3113 6803 3107 6803 3268 6803 3268 6804 3267 6804 3113 6804 3242 6805 3269 6805 3256 6805 3301 6806 3271 6806 3238 6806 3105 6807 3273 6807 3237 6807 3235 6808 3109 6808 3274 6808 3120 6809 3124 6809 3255 6809 3262 6810 3263 6810 3252 6810 3421 6811 3422 6811 3250 6811 3279 6812 3278 6812 3258 6812 3378 6813 3259 6813 3287 6813 3287 6814 3259 6814 3342 6814 3128 6815 3378 6815 3260 6815 3260 6816 3378 6816 3287 6816 3260 6817 3287 6817 3299 6817 3261 6818 3384 6818 3110 6818 3110 6819 3384 6819 3129 6819 3343 6820 3261 6820 3285 6820 3285 6821 3261 6821 3110 6821 3285 6822 3110 6822 3295 6822 3295 6823 3110 6823 3296 6823 3120 6824 3255 6824 3128 6824 3423 6825 3183 6825 3254 6825 3254 6826 3117 6826 3423 6826 3265 6827 3286 6827 3266 6827 3266 6828 3122 6828 3265 6828 3241 6829 3270 6829 3114 6829 3241 6830 3114 6830 3240 6830 3238 6831 3104 6831 3178 6831 3273 6832 3236 6832 3237 6832 3273 6833 3105 6833 3272 6833 3144 6834 3230 6834 3146 6834 3146 6835 3230 6835 3174 6835 3134 6836 3345 6836 3145 6836 3145 6837 3345 6837 3308 6837 3145 6838 3308 6838 3275 6838 3135 6839 3276 6839 3133 6839 3135 6840 3133 6840 3277 6840 3102 6841 3136 6841 3246 6841 3136 6842 3147 6842 3246 6842 3278 6843 3375 6843 3258 6843 3151 6844 3244 6844 3281 6844 3151 6845 3281 6845 3280 6845 3280 6846 3281 6846 3148 6846 3164 6847 3163 6847 3162 6847 3162 6848 3163 6848 3312 6848 3162 6849 3312 6849 3186 6849 3150 6850 3233 6850 3130 6850 3150 6851 3130 6851 3282 6851 3184 6852 3283 6852 3284 6852 3283 6853 3149 6853 3284 6853 3271 6854 3297 6854 3110 6854 3110 6855 3297 6855 3296 6855 3295 6856 3115 6856 3285 6856 3307 6857 3260 6857 3303 6857 3286 6858 3288 6858 3300 6858 3286 6859 3300 6859 3287 6859 3302 6860 3271 6860 3301 6860 3205 6861 3431 6861 3307 6861 3202 6862 3289 6862 3214 6862 3131 6863 3290 6863 3291 6863 3131 6864 3291 6864 3132 6864 3115 6865 3292 6865 3214 6865 3132 6866 3291 6866 3247 6866 3115 6867 3295 6867 3292 6867 3296 6868 3297 6868 3295 6868 3288 6869 3298 6869 3300 6869 3300 6870 3299 6870 3287 6870 3271 6871 3302 6871 3297 6871 3260 6872 3299 6872 3303 6872 3305 6873 3206 6873 3234 6873 3304 6874 3208 6874 3206 6874 3304 6875 3206 6875 3305 6875 3208 6876 3304 6876 3306 6876 3347 6877 3174 6877 3348 6877 3348 6878 3174 6878 3374 6878 3344 6879 3133 6879 3308 6879 3311 6880 3309 6880 3310 6880 3311 6881 3310 6881 3380 6881 3350 6882 3130 6882 3177 6882 3350 6883 3177 6883 3312 6883 3354 6884 3194 6884 3356 6884 3356 6885 3194 6885 3193 6885 3367 6886 3192 6886 3364 6886 3364 6887 3192 6887 3313 6887 3371 6888 3188 6888 3190 6888 3371 6889 3190 6889 3314 6889 3361 6890 3195 6890 3319 6890 3361 6891 3319 6891 3315 6891 3194 6892 3354 6892 3353 6892 3194 6893 3353 6893 3352 6893 3364 6894 3313 6894 3365 6894 3365 6895 3313 6895 3316 6895 3193 6896 3317 6896 3359 6896 3193 6897 3359 6897 3356 6897 3368 6898 3318 6898 3367 6898 3367 6899 3318 6899 3192 6899 3219 6900 3217 6900 3190 6900 3190 6901 3217 6901 3314 6901 3360 6902 3209 6902 3166 6902 3166 6903 3209 6903 3361 6903 3361 6904 3209 6904 3195 6904 3188 6905 3371 6905 3189 6905 3189 6906 3371 6906 3370 6906 3315 6907 3319 6907 3167 6907 3167 6908 3319 6908 3196 6908 3167 6909 3196 6909 3355 6909 3320 6910 3321 6910 3157 6910 3098 6911 3155 6911 3322 6911 3098 6912 3322 6912 3099 6912 3095 6913 3154 6913 3323 6913 3095 6914 3323 6914 3096 6914 3325 6915 3324 6915 3153 6915 3325 6916 3153 6916 3094 6916 3093 6917 3326 6917 3152 6917 3328 6918 3092 6918 3329 6918 3328 6919 3329 6919 3330 6919 3331 6920 3091 6920 3332 6920 3331 6921 3332 6921 3142 6921 3333 6922 3141 6922 3140 6922 3334 6923 3335 6923 3336 6923 3089 6924 3337 6924 3138 6924 3088 6925 3338 6925 3339 6925 3087 6926 3340 6926 3341 6926 3378 6927 3128 6927 3377 6927 3261 6928 3343 6928 3267 6928 3261 6929 3267 6929 3175 6929 3133 6930 3344 6930 3346 6930 3346 6931 3344 6931 3345 6931 3146 6932 3347 6932 3348 6932 3311 6933 3380 6933 3148 6933 3163 6934 3349 6934 3350 6934 3350 6935 3349 6935 3130 6935 3352 6936 3351 6936 3355 6936 3355 6937 3351 6937 3167 6937 3351 6938 3352 6938 3353 6938 3357 6939 3353 6939 3354 6939 3168 6940 3315 6940 3167 6940 3356 6941 3165 6941 3354 6941 3354 6942 3165 6942 3357 6942 3169 6943 3361 6943 3168 6943 3168 6944 3361 6944 3315 6944 3165 6945 3356 6945 3359 6945 3358 6946 3359 6946 3317 6946 3169 6947 3166 6947 3361 6947 3360 6948 3166 6948 3317 6948 3317 6949 3166 6949 3358 6949 3173 6950 3362 6950 3363 6950 3171 6951 3364 6951 3365 6951 3366 6952 3170 6952 3363 6952 3363 6953 3170 6953 3173 6953 3172 6954 3367 6954 3171 6954 3171 6955 3367 6955 3364 6955 3170 6956 3366 6956 3369 6956 3172 6957 3368 6957 3367 6957 3221 6958 3370 6958 3371 6958 3222 6959 3216 6959 3372 6959 3314 6960 3224 6960 3371 6960 3371 6961 3224 6961 3221 6961 3223 6962 3373 6962 3222 6962 3222 6963 3373 6963 3216 6963 3224 6964 3314 6964 3217 6964 3223 6965 3218 6965 3373 6965 3376 6966 3258 6966 3375 6966 3258 6967 3376 6967 3279 6967 3309 6968 3279 6968 3310 6968 3179 6969 3378 6969 3377 6969 3179 6970 3259 6970 3378 6970 3259 6971 3379 6971 3133 6971 3381 6972 3106 6972 3382 6972 3381 6973 3382 6973 3383 6973 3177 6974 3175 6974 3312 6974 3385 6975 3261 6975 3175 6975 3385 6976 3384 6976 3261 6976 3384 6977 3176 6977 3130 6977 3395 6978 3387 6978 3396 6978 3396 6979 3387 6979 3272 6979 3388 6980 3389 6980 3178 6980 3428 6981 3386 6981 3390 6981 3427 6982 3391 6982 3392 6982 3212 6983 3211 6983 3391 6983 3391 6984 3211 6984 3393 6984 3397 6985 3111 6985 3393 6985 3393 6986 3111 6986 3391 6986 3394 6987 3426 6987 3398 6987 3398 6988 3426 6988 3395 6988 3396 6989 3399 6989 3395 6989 3395 6990 3399 6990 3398 6990 3397 6991 3393 6991 3113 6991 3109 6992 3398 6992 3399 6992 3123 6993 3401 6993 3420 6993 3403 6994 3404 6994 3402 6994 3406 6995 3405 6995 3407 6995 3420 6996 3401 6996 3400 6996 3403 6997 3402 6997 3425 6997 3425 6998 3402 6998 3424 6998 3424 6999 3402 6999 3404 6999 3408 7000 3405 7000 3406 7000 3407 7001 3405 7001 3408 7001 3409 7002 3410 7002 3418 7002 3411 7003 3401 7003 3123 7003 3120 7004 3417 7004 3126 7004 3123 7005 3126 7005 3411 7005 3411 7006 3126 7006 3417 7006 3411 7007 3417 7007 3119 7007 3119 7008 3417 7008 3118 7008 3121 7009 3416 7009 3414 7009 3412 7010 3121 7010 3413 7010 3413 7011 3121 7011 3414 7011 3413 7012 3414 7012 3415 7012 3415 7013 3414 7013 3416 7013 3412 7014 3413 7014 3415 7014 3401 7015 3411 7015 3119 7015 3118 7016 3417 7016 3120 7016 3418 7017 3121 7017 3419 7017 3410 7018 3121 7018 3418 7018 3419 7019 3116 7019 3418 7019 3420 7020 3183 7020 3123 7020 3421 7021 3122 7021 3406 7021 3406 7022 3407 7022 3421 7022 3421 7023 3407 7023 3422 7023 3262 7024 3423 7024 3424 7024 3262 7025 3424 7025 3263 7025 3423 7026 3117 7026 3424 7026 3424 7027 3117 7027 3425 7027 3387 7028 3395 7028 3426 7028 3387 7029 3426 7029 3272 7029 3427 7030 3213 7030 3212 7030 3427 7031 3212 7031 3391 7031 3428 7032 3114 7032 3270 7032 3388 7033 3236 7033 3273 7033 3388 7034 3273 7034 3178 7034 3429 7035 3125 7035 3430 7035 3430 7036 3125 7036 3431 7036 3197 7037 3125 7037 3429 7037 3108 7038 3433 7038 3432 7038 3432 7039 3433 7039 3235 7039 3293 7040 3294 7040 3434 7040 3293 7041 3434 7041 3435 7041 3203 7042 3436 7042 3289 7042 3203 7043 3289 7043 3202 7043 3458 7044 3484 7044 3452 7044 3483 7045 3463 7045 3468 7045 3483 7046 3468 7046 3482 7046 3457 7047 3443 7047 3478 7047 3449 7048 3443 7048 3457 7048 3438 7049 3484 7049 3458 7049 3453 7050 3467 7050 3481 7050 3447 7051 3481 7051 3467 7051 3444 7052 3466 7052 3455 7052 3448 7053 3438 7053 3457 7053 3447 7054 3481 7054 3452 7054 3460 7055 3462 7055 3445 7055 3445 7056 3462 7056 3439 7056 3439 7057 3467 7057 3441 7057 3441 7058 3467 7058 3472 7058 3441 7059 3472 7059 3475 7059 3475 7060 3442 7060 3440 7060 3440 7061 3442 7061 3443 7061 3440 7062 3443 7062 3474 7062 3439 7063 3453 7063 3444 7063 3439 7064 3444 7064 3445 7064 3445 7065 3444 7065 3460 7065 3460 7066 3456 7066 3446 7066 3446 7067 3456 7067 3459 7067 3459 7068 3456 7068 3482 7068 3459 7069 3482 7069 3474 7069 3474 7070 3482 7070 3478 7070 3481 7071 3447 7071 3454 7071 3454 7072 3447 7072 3469 7072 3484 7073 3473 7073 3452 7073 3452 7074 3473 7074 3447 7074 3438 7075 3448 7075 3484 7075 3457 7076 3449 7076 3448 7076 3449 7077 3457 7077 3477 7077 3449 7078 3477 7078 3464 7078 3483 7079 3463 7079 3477 7079 3477 7080 3463 7080 3464 7080 3476 7081 3437 7081 3450 7081 3450 7082 3437 7082 3471 7082 3450 7083 3471 7083 3483 7083 3483 7084 3471 7084 3463 7084 3455 7085 3470 7085 3476 7085 3476 7086 3470 7086 3437 7086 3455 7087 3451 7087 3470 7087 3451 7088 3480 7088 3454 7088 3451 7089 3454 7089 3469 7089 3477 7090 3478 7090 3482 7090 3453 7091 3481 7091 3480 7091 3453 7092 3480 7092 3444 7092 3483 7093 3477 7093 3482 7093 3481 7094 3454 7094 3480 7094 3478 7095 3457 7095 3438 7095 3479 7096 3481 7096 3453 7096 3460 7097 3444 7097 3455 7097 3460 7098 3455 7098 3476 7098 3460 7099 3476 7099 3456 7099 3477 7100 3457 7100 3478 7100 3478 7101 3438 7101 3458 7101 3479 7102 3458 7102 3452 7102 3479 7103 3452 7103 3481 7103 3456 7104 3450 7104 3483 7104 3456 7105 3483 7105 3482 7105 3475 7106 3478 7106 3458 7106 3460 7107 3446 7107 3465 7107 3460 7108 3465 7108 3462 7108 3446 7109 3461 7109 3465 7109 3462 7110 3465 7110 3466 7110 3462 7111 3466 7111 3469 7111 3462 7112 3469 7112 3439 7112 3468 7113 3463 7113 3461 7113 3451 7114 3466 7114 3470 7114 3465 7115 3470 7115 3466 7115 3447 7116 3472 7116 3467 7116 3439 7117 3469 7117 3467 7117 3467 7118 3469 7118 3447 7118 3472 7119 3442 7119 3475 7119 3472 7120 3448 7120 3442 7120 3449 7121 3443 7121 3448 7121 3443 7122 3449 7122 3464 7122 3442 7123 3448 7123 3443 7123 3463 7124 3468 7124 3464 7124 3464 7125 3468 7125 3474 7125 3464 7126 3474 7126 3443 7126 3466 7127 3451 7127 3469 7127 3437 7128 3470 7128 3465 7128 3471 7129 3437 7129 3465 7129 3471 7130 3465 7130 3461 7130 3471 7131 3461 7131 3463 7131 3473 7132 3484 7132 3472 7132 3473 7133 3472 7133 3447 7133 3472 7134 3484 7134 3448 7134 3459 7135 3474 7135 3468 7135 3459 7136 3468 7136 3461 7136 3459 7137 3461 7137 3446 7137 3453 7138 3439 7138 3441 7138 3453 7139 3441 7139 3479 7139 3479 7140 3441 7140 3475 7140 3479 7141 3475 7141 3458 7141 3475 7142 3440 7142 3478 7142 3478 7143 3440 7143 3474 7143 3466 7144 3451 7144 3455 7144 3466 7145 3480 7145 3451 7145 3481 7146 3447 7146 3467 7146 3481 7147 3467 7147 3453 7147 3449 7148 3457 7148 3443 7148 3478 7149 3443 7149 3457 7149 3482 7150 3468 7150 3463 7150 3482 7151 3463 7151 3483 7151 3476 7152 3437 7152 3456 7152 3480 7153 3466 7153 3444 7153 3456 7154 3437 7154 3450 7154 3524 7155 3531 7155 3488 7155 3486 7156 3487 7156 3510 7156 3486 7157 3510 7157 3530 7157 3485 7158 3527 7158 3499 7158 3512 7159 3527 7159 3485 7159 3498 7160 3531 7160 3524 7160 3506 7161 3528 7161 3525 7161 3495 7162 3504 7162 3497 7162 3509 7163 3498 7163 3485 7163 3506 7164 3528 7164 3488 7164 3492 7165 3500 7165 3529 7165 3500 7166 3516 7166 3489 7166 3489 7167 3505 7167 3490 7167 3519 7168 3527 7168 3501 7168 3490 7169 3505 7169 3525 7169 3490 7170 3525 7170 3508 7170 3490 7171 3508 7171 3518 7171 3518 7172 3508 7172 3491 7172 3491 7173 3507 7173 3519 7173 3519 7174 3507 7174 3527 7174 3489 7175 3525 7175 3495 7175 3489 7176 3495 7176 3500 7176 3500 7177 3495 7177 3529 7177 3492 7178 3529 7178 3530 7178 3492 7179 3530 7179 3523 7179 3528 7180 3506 7180 3496 7180 3496 7181 3506 7181 3505 7181 3531 7182 3493 7182 3488 7182 3488 7183 3493 7183 3506 7183 3498 7184 3509 7184 3531 7184 3485 7185 3512 7185 3509 7185 3512 7186 3485 7186 3522 7186 3512 7187 3522 7187 3513 7187 3486 7188 3487 7188 3522 7188 3522 7189 3487 7189 3513 7189 3520 7190 3514 7190 3521 7190 3521 7191 3514 7191 3515 7191 3521 7192 3515 7192 3486 7192 3486 7193 3515 7193 3487 7193 3497 7194 3494 7194 3520 7194 3520 7195 3494 7195 3514 7195 3497 7196 3511 7196 3494 7196 3511 7197 3526 7197 3496 7197 3511 7198 3496 7198 3505 7198 3522 7199 3523 7199 3486 7199 3525 7200 3528 7200 3526 7200 3525 7201 3526 7201 3495 7201 3528 7202 3496 7202 3526 7202 3499 7203 3485 7203 3498 7203 3517 7204 3528 7204 3525 7204 3495 7205 3497 7205 3520 7205 3495 7206 3520 7206 3529 7206 3522 7207 3485 7207 3523 7207 3523 7208 3485 7208 3499 7208 3499 7209 3498 7209 3524 7209 3517 7210 3524 7210 3488 7210 3517 7211 3488 7211 3528 7211 3529 7212 3521 7212 3486 7212 3529 7213 3486 7213 3530 7213 3523 7214 3530 7214 3486 7214 3519 7215 3523 7215 3499 7215 3519 7216 3499 7216 3491 7216 3491 7217 3524 7217 3518 7217 3518 7218 3524 7218 3517 7218 3500 7219 3502 7219 3503 7219 3500 7220 3503 7220 3516 7220 3516 7221 3503 7221 3504 7221 3516 7222 3504 7222 3489 7222 3489 7223 3504 7223 3505 7223 3510 7224 3487 7224 3502 7224 3511 7225 3504 7225 3494 7225 3503 7226 3494 7226 3504 7226 3506 7227 3508 7227 3525 7227 3505 7228 3506 7228 3525 7228 3508 7229 3507 7229 3491 7229 3508 7230 3509 7230 3507 7230 3512 7231 3527 7231 3509 7231 3527 7232 3512 7232 3513 7232 3507 7233 3509 7233 3527 7233 3487 7234 3510 7234 3513 7234 3513 7235 3510 7235 3501 7235 3513 7236 3501 7236 3527 7236 3504 7237 3511 7237 3505 7237 3514 7238 3494 7238 3503 7238 3515 7239 3514 7239 3503 7239 3515 7240 3503 7240 3502 7240 3515 7241 3502 7241 3487 7241 3493 7242 3531 7242 3508 7242 3493 7243 3508 7243 3506 7243 3508 7244 3531 7244 3509 7244 3492 7245 3501 7245 3510 7245 3492 7246 3510 7246 3502 7246 3492 7247 3502 7247 3500 7247 3525 7248 3489 7248 3490 7248 3525 7249 3490 7249 3517 7249 3517 7250 3490 7250 3518 7250 3519 7251 3501 7251 3523 7251 3523 7252 3501 7252 3492 7252 3504 7253 3511 7253 3497 7253 3504 7254 3526 7254 3511 7254 3491 7255 3499 7255 3524 7255 3528 7256 3506 7256 3525 7256 3512 7257 3485 7257 3527 7257 3499 7258 3527 7258 3485 7258 3530 7259 3510 7259 3486 7259 3486 7260 3510 7260 3487 7260 3520 7261 3514 7261 3529 7261 3526 7262 3504 7262 3495 7262 3529 7263 3514 7263 3521 7263 3643 7264 3576 7264 3532 7264 3532 7265 3576 7265 3626 7265 3833 7266 3619 7266 3641 7266 3641 7267 3619 7267 3624 7267 3772 7268 3774 7268 3614 7268 3763 7269 3579 7269 3765 7269 3759 7270 3757 7270 3760 7270 3760 7271 3757 7271 3580 7271 3751 7272 3752 7272 3749 7272 3749 7273 3752 7273 3610 7273 3721 7274 3711 7274 3587 7274 3720 7275 3719 7275 3630 7275 3718 7276 3533 7276 3639 7276 3781 7277 2281 7277 3703 7277 3702 7278 3701 7278 3598 7278 3603 7279 3613 7279 3698 7279 3697 7280 3696 7280 3601 7280 3622 7281 3649 7281 3733 7281 3535 7282 3695 7282 3654 7282 3535 7283 3654 7283 3695 7283 3694 7284 3690 7284 3693 7284 3685 7285 3536 7285 3537 7285 3680 7286 3558 7286 3536 7286 3680 7287 3536 7287 3681 7287 3679 7288 3779 7288 3640 7288 3678 7289 2576 7289 2653 7289 3678 7290 2653 7290 3539 7290 3616 7291 3777 7291 3637 7291 3616 7292 3637 7292 3636 7292 3632 7293 3646 7293 3647 7293 3604 7294 3645 7294 3540 7294 3703 7295 3634 7295 3781 7295 3781 7296 3634 7296 2281 7296 3570 7297 3577 7297 3541 7297 3565 7298 3566 7298 3567 7298 3712 7299 3713 7299 3706 7299 3706 7300 3713 7300 3789 7300 3706 7301 3789 7301 3542 7301 3542 7302 3789 7302 3543 7302 3542 7303 3543 7303 3715 7303 3715 7304 3543 7304 3786 7304 3710 7305 3544 7305 3545 7305 3545 7306 3544 7306 3708 7306 3545 7307 3708 7307 3790 7307 3790 7308 3708 7308 3547 7308 3790 7309 3547 7309 3546 7309 3546 7310 3547 7310 3716 7310 3677 7311 3810 7311 3548 7311 3548 7312 3810 7312 3811 7312 3548 7313 3811 7313 3589 7313 3552 7314 3549 7314 3794 7314 3794 7315 3549 7315 3796 7315 3550 7316 3664 7316 3677 7316 3677 7317 3664 7317 3810 7317 3664 7318 3550 7318 3551 7318 3551 7319 3550 7319 3652 7319 3551 7320 3652 7320 3552 7320 3552 7321 3652 7321 3651 7321 3552 7322 3651 7322 3549 7322 3588 7323 3670 7323 3553 7323 3554 7324 3556 7324 3648 7324 3648 7325 3556 7325 3795 7325 3797 7326 3791 7326 3588 7326 3588 7327 3791 7327 3555 7327 3588 7328 3555 7328 3670 7328 3553 7329 3670 7329 3658 7329 3658 7330 3670 7330 3669 7330 3556 7331 3554 7331 3653 7331 3556 7332 3653 7332 3671 7332 3671 7333 3653 7333 3557 7333 3671 7334 3557 7334 3669 7334 3669 7335 3557 7335 3658 7335 3682 7336 3559 7336 3564 7336 3536 7337 3684 7337 3681 7337 3536 7338 3558 7338 3830 7338 3681 7339 3684 7339 3830 7339 3825 7340 3684 7340 3536 7340 3563 7341 3822 7341 3682 7341 3684 7342 3825 7342 3563 7342 3563 7343 3825 7343 3822 7343 3684 7344 3560 7344 3830 7344 3830 7345 3560 7345 3814 7345 3814 7346 3560 7346 3684 7346 3814 7347 3684 7347 3561 7347 3563 7348 3561 7348 3684 7348 3828 7349 3562 7349 3559 7349 3559 7350 3562 7350 3813 7350 3559 7351 3813 7351 3564 7351 3681 7352 3830 7352 3558 7352 3536 7353 3689 7353 3821 7353 3832 7354 3689 7354 3830 7354 3830 7355 3689 7355 3536 7355 3821 7356 3689 7356 3832 7356 3821 7357 3562 7357 3536 7357 3536 7358 3562 7358 3828 7358 3685 7359 3537 7359 3536 7359 3537 7360 3828 7360 3536 7360 3537 7361 3536 7361 3828 7361 3559 7362 3682 7362 3822 7362 3563 7363 3682 7363 3816 7363 3563 7364 3816 7364 3561 7364 3564 7365 3813 7365 3682 7365 3682 7366 3813 7366 3816 7366 3566 7367 3565 7367 3569 7367 3569 7368 3565 7368 3568 7368 3566 7369 3569 7369 3607 7369 3607 7370 3569 7370 3611 7370 3568 7371 3565 7371 3608 7371 3608 7372 3565 7372 3567 7372 3568 7373 3608 7373 3611 7373 3568 7374 3611 7374 3569 7374 3570 7375 3541 7375 3573 7375 3573 7376 3541 7376 3572 7376 3570 7377 3573 7377 3585 7377 3585 7378 3573 7378 3583 7378 3572 7379 3541 7379 3571 7379 3571 7380 3541 7380 3577 7380 3573 7381 3572 7381 3583 7381 3618 7382 3747 7382 3574 7382 3744 7383 3575 7383 3574 7383 3574 7384 3575 7384 3734 7384 3738 7385 3740 7385 3737 7385 3576 7386 3741 7386 3742 7386 3740 7387 3738 7387 3742 7387 3740 7388 3742 7388 3741 7388 3714 7389 3585 7389 3583 7389 3584 7390 3570 7390 3585 7390 3578 7391 3582 7391 3571 7391 3571 7392 3577 7392 3578 7392 3578 7393 3577 7393 3584 7393 3584 7394 3577 7394 3570 7394 3572 7395 3571 7395 3699 7395 3572 7396 3699 7396 3583 7396 3756 7397 3785 7397 3757 7397 3578 7398 3755 7398 3580 7398 3701 7399 3756 7399 3755 7399 3785 7400 3764 7400 3586 7400 3785 7401 3586 7401 3714 7401 3762 7402 3579 7402 3578 7402 3578 7403 3579 7403 3701 7403 3701 7404 3579 7404 3763 7404 3762 7405 3584 7405 3767 7405 3767 7406 3584 7406 3586 7406 3578 7407 3580 7407 3757 7407 3714 7408 3699 7408 3582 7408 3582 7409 3699 7409 3571 7409 3699 7410 3714 7410 3583 7410 3578 7411 3584 7411 3762 7411 3584 7412 3585 7412 3714 7412 3584 7413 3714 7413 3586 7413 3578 7414 3701 7414 3755 7414 3763 7415 3764 7415 3701 7415 3701 7416 3764 7416 3785 7416 3701 7417 3785 7417 3756 7417 3785 7418 3581 7418 3757 7418 3581 7419 3578 7419 3757 7419 3797 7420 3721 7420 3589 7420 3588 7421 3587 7421 3797 7421 3797 7422 3587 7422 3721 7422 3589 7423 3591 7423 3548 7423 3548 7424 3591 7424 3588 7424 3587 7425 3590 7425 3589 7425 3587 7426 3589 7426 3721 7426 3589 7427 3590 7427 3591 7427 3588 7428 3590 7428 3587 7428 3588 7429 3591 7429 3590 7429 3793 7430 3792 7430 3592 7430 3592 7431 3792 7431 3812 7431 3812 7432 3792 7432 3811 7432 3793 7433 3592 7433 3809 7433 3599 7434 3803 7434 3593 7434 3593 7435 3803 7435 3594 7435 3594 7436 3555 7436 3791 7436 3596 7437 3605 7437 3595 7437 3596 7438 3595 7438 3794 7438 3794 7439 3595 7439 3552 7439 3597 7440 3795 7440 3556 7440 3599 7441 3705 7441 3700 7441 3598 7442 3802 7442 3801 7442 3599 7443 3598 7443 3803 7443 3803 7444 3598 7444 3801 7444 3802 7445 3598 7445 3702 7445 3802 7446 3702 7446 3600 7446 3600 7447 3702 7447 3700 7447 3700 7448 3702 7448 3598 7448 3700 7449 3598 7449 3599 7449 3600 7450 3700 7450 3705 7450 3600 7451 3705 7451 3635 7451 3707 7452 3534 7452 3783 7452 3601 7453 3809 7453 3808 7453 3707 7454 3793 7454 3601 7454 3601 7455 3793 7455 3809 7455 3601 7456 3698 7456 3707 7456 3707 7457 3698 7457 3603 7457 3808 7458 3602 7458 3697 7458 3603 7459 3602 7459 3617 7459 3698 7460 3601 7460 3697 7460 3601 7461 3808 7461 3697 7461 3783 7462 3534 7462 3617 7462 3603 7463 3534 7463 3707 7463 3698 7464 3697 7464 3603 7464 3603 7465 3697 7465 3602 7465 3617 7466 3534 7466 3603 7466 3660 7467 3661 7467 3663 7467 3663 7468 3661 7468 3686 7468 3666 7469 3667 7469 3687 7469 3675 7470 3645 7470 3604 7470 3675 7471 3604 7471 3616 7471 3616 7472 3604 7472 3718 7472 3605 7473 3645 7473 3829 7473 3829 7474 3645 7474 3625 7474 3625 7475 3645 7475 3675 7475 3645 7476 3605 7476 3718 7476 3645 7477 3718 7477 3604 7477 3718 7478 3605 7478 3596 7478 3718 7479 3596 7479 3778 7479 3616 7480 3718 7480 3778 7480 3616 7481 3606 7481 3777 7481 3616 7482 3778 7482 3606 7482 3611 7483 3609 7483 3607 7483 3607 7484 3609 7484 3615 7484 3613 7485 3566 7485 3607 7485 3566 7486 3613 7486 3567 7486 3567 7487 3613 7487 3717 7487 3567 7488 3717 7488 3608 7488 3611 7489 3608 7489 3612 7489 3748 7490 3615 7490 3752 7490 3788 7491 3610 7491 3752 7491 3610 7492 3787 7492 3750 7492 3696 7493 3748 7493 3750 7493 3770 7494 3615 7494 3769 7494 3696 7495 3614 7495 3774 7495 3696 7496 3774 7496 3769 7496 3614 7497 3787 7497 3768 7497 3768 7498 3787 7498 3717 7498 3613 7499 3770 7499 3773 7499 3613 7500 3773 7500 3768 7500 3787 7501 3610 7501 3788 7501 3717 7502 3612 7502 3608 7502 3611 7503 3612 7503 3609 7503 3609 7504 3612 7504 3717 7504 3717 7505 3613 7505 3768 7505 3613 7506 3607 7506 3615 7506 3613 7507 3615 7507 3770 7507 3787 7508 3614 7508 3696 7508 3787 7509 3696 7509 3750 7509 3696 7510 3769 7510 3615 7510 3696 7511 3615 7511 3748 7511 3752 7512 3615 7512 3788 7512 3602 7513 3805 7513 3821 7513 3709 7514 3602 7514 3832 7514 3832 7515 3602 7515 3821 7515 3609 7516 3616 7516 3776 7516 3602 7517 3709 7517 3615 7517 3602 7518 3615 7518 3617 7518 3616 7519 3609 7519 3675 7519 3675 7520 3609 7520 3633 7520 3609 7521 3776 7521 3617 7521 3609 7522 3617 7522 3615 7522 3618 7523 3733 7523 3732 7523 3725 7524 3619 7524 3631 7524 3745 7525 3642 7525 3732 7525 3642 7526 3745 7526 3725 7526 3642 7527 3725 7527 3631 7527 3626 7528 3625 7528 3620 7528 3620 7529 3625 7529 3633 7529 3633 7530 3737 7530 3620 7530 3638 7531 3676 7531 3631 7531 3638 7532 3631 7532 3739 7532 3622 7533 3624 7533 3619 7533 3631 7534 3624 7534 3739 7534 3638 7535 3739 7535 3621 7535 3638 7536 3621 7536 3633 7536 3693 7537 3747 7537 3627 7537 3747 7538 3657 7538 3623 7538 3623 7539 3657 7539 3625 7539 3623 7540 3625 7540 3576 7540 3619 7541 3624 7541 3631 7541 3627 7542 3642 7542 3693 7542 3675 7543 3633 7543 3625 7543 3625 7544 3626 7544 3576 7544 3732 7545 3642 7545 3627 7545 3732 7546 3627 7546 3618 7546 3747 7547 3618 7547 3627 7547 3657 7548 3747 7548 3693 7548 3691 7549 3690 7549 3693 7549 3733 7550 3622 7550 3731 7550 3733 7551 3731 7551 3732 7551 3731 7552 3622 7552 3619 7552 3733 7553 3576 7553 3622 7553 3735 7554 3737 7554 3576 7554 3576 7555 3737 7555 3633 7555 3576 7556 3633 7556 3622 7556 3622 7557 3633 7557 3621 7557 3775 7558 3582 7558 3600 7558 3814 7559 3800 7559 3802 7559 3582 7560 3775 7560 3628 7560 3582 7561 3628 7561 3638 7561 3600 7562 3578 7562 3802 7562 3600 7563 3582 7563 3578 7563 3676 7564 3638 7564 3628 7564 3632 7565 3676 7565 3628 7565 3629 7566 3720 7566 3630 7566 3647 7567 3720 7567 3629 7567 3674 7568 3630 7568 3597 7568 3703 7569 3720 7569 3628 7569 3703 7570 3628 7570 3781 7570 3629 7571 3630 7571 3674 7571 3676 7572 3647 7572 3631 7572 3631 7573 3647 7573 3629 7573 3720 7574 3647 7574 3632 7574 3720 7575 3632 7575 3628 7575 3632 7576 3647 7576 3676 7576 3630 7577 3720 7577 3597 7577 3540 7578 3633 7578 3639 7578 3779 7579 3719 7579 3640 7579 3640 7580 3639 7580 3533 7580 3638 7581 2653 7581 3646 7581 3646 7582 2653 7582 2576 7582 2653 7583 3638 7583 3633 7583 2653 7584 3633 7584 3539 7584 3539 7585 3633 7585 3540 7585 3582 7586 3638 7586 3634 7586 3582 7587 3634 7587 3644 7587 3635 7588 3714 7588 3784 7588 3784 7589 3714 7589 3582 7589 3644 7590 3784 7590 3582 7590 3779 7591 3638 7591 3719 7591 3779 7592 3780 7592 3638 7592 3638 7593 3780 7593 3634 7593 3533 7594 3779 7594 3640 7594 3639 7595 3637 7595 3533 7595 3637 7596 3609 7596 3636 7596 3717 7597 3704 7597 3609 7597 3636 7598 3609 7598 3704 7598 3719 7599 3638 7599 3646 7599 3719 7600 3646 7600 3640 7600 3640 7601 3646 7601 2576 7601 3540 7602 3639 7602 3640 7602 3540 7603 3640 7603 3539 7603 3539 7604 3640 7604 2576 7604 3533 7605 3778 7605 3639 7605 3633 7606 3609 7606 3639 7606 3639 7607 3609 7607 3637 7607 3833 7608 3667 7608 3666 7608 3833 7609 3666 7609 3629 7609 3833 7610 3629 7610 3641 7610 3833 7611 3641 7611 3667 7611 3667 7612 3641 7612 3674 7612 3674 7613 3641 7613 3629 7613 3687 7614 3815 7614 3666 7614 3666 7615 3815 7615 3642 7615 3666 7616 3642 7616 3631 7616 3666 7617 3631 7617 3629 7617 3657 7618 3655 7618 3686 7618 3829 7619 3625 7619 3661 7619 3661 7620 3625 7620 3657 7620 3657 7621 3686 7621 3661 7621 3532 7622 3661 7622 3643 7622 3643 7623 3661 7623 3660 7623 3605 7624 3532 7624 3643 7624 3605 7625 3643 7625 3660 7625 3661 7626 3532 7626 3829 7626 3829 7627 3532 7627 3605 7627 3781 7628 2281 7628 3644 7628 3781 7629 3644 7629 3634 7629 3781 7630 3634 7630 3703 7630 3604 7631 3540 7631 3645 7631 3647 7632 3646 7632 3632 7632 3616 7633 3636 7633 3777 7633 3658 7634 3550 7634 3553 7634 3553 7635 3550 7635 3677 7635 3796 7636 3549 7636 3648 7636 3648 7637 3549 7637 3554 7637 3651 7638 3649 7638 3653 7638 3557 7639 3650 7639 3652 7639 3649 7640 3651 7640 3652 7640 3649 7641 3652 7641 3650 7641 3650 7642 3557 7642 3653 7642 3650 7643 3653 7643 3649 7643 3656 7644 3693 7644 3642 7644 3815 7645 3816 7645 3655 7645 3695 7646 3655 7646 3654 7646 3654 7647 3655 7647 3657 7647 3655 7648 3695 7648 3815 7648 3815 7649 3695 7649 3642 7649 3654 7650 3692 7650 3695 7650 3695 7651 3692 7651 3656 7651 3654 7652 3657 7652 3692 7652 3693 7653 3692 7653 3657 7653 3695 7654 3656 7654 3642 7654 3535 7655 3550 7655 3658 7655 3535 7656 3652 7656 3550 7656 3535 7657 3658 7657 3557 7657 3652 7658 3535 7658 3557 7658 3687 7659 3799 7659 3817 7659 3659 7660 3799 7660 3687 7660 3659 7661 3687 7661 3688 7661 3815 7662 3687 7662 3817 7662 3538 7663 3686 7663 3807 7663 3807 7664 3686 7664 3819 7664 3538 7665 3665 7665 3663 7665 3665 7666 3538 7666 3807 7666 3663 7667 3686 7667 3538 7667 3663 7668 3662 7668 3660 7668 3664 7669 3662 7669 3663 7669 3662 7670 3664 7670 3551 7670 3662 7671 3605 7671 3660 7671 3662 7672 3595 7672 3605 7672 3595 7673 3662 7673 3551 7673 3595 7674 3551 7674 3552 7674 3663 7675 3665 7675 3664 7675 3659 7676 3688 7676 3668 7676 3688 7677 3687 7677 3668 7677 3687 7678 3667 7678 3668 7678 3672 7679 3668 7679 3667 7679 3671 7680 3669 7680 3672 7680 3672 7681 3669 7681 3668 7681 3670 7682 3659 7682 3668 7682 3670 7683 3668 7683 3669 7683 3556 7684 3671 7684 3672 7684 3556 7685 3672 7685 3673 7685 3673 7686 3672 7686 3667 7686 3673 7687 3667 7687 3674 7687 3651 7688 3653 7688 3549 7688 3549 7689 3653 7689 3554 7689 3548 7690 3588 7690 3677 7690 3677 7691 3588 7691 3553 7691 3678 7692 3539 7692 2576 7692 3679 7693 3640 7693 3779 7693 3680 7694 3681 7694 3558 7694 3665 7695 3537 7695 3685 7695 3687 7696 3688 7696 3816 7696 3687 7697 3816 7697 3688 7697 3691 7698 3692 7698 3690 7698 3692 7699 3691 7699 3656 7699 3691 7700 3693 7700 3656 7700 3692 7701 3693 7701 3690 7701 3694 7702 3693 7702 3690 7702 3733 7703 3649 7703 3622 7703 3601 7704 3696 7704 3697 7704 3698 7705 3613 7705 3603 7705 3598 7706 3701 7706 3702 7706 3637 7707 3606 7707 3778 7707 3637 7708 3778 7708 3533 7708 3720 7709 3779 7709 3597 7709 3597 7710 3779 7710 3596 7710 3596 7711 3779 7711 3778 7711 3778 7712 3779 7712 3533 7712 3703 7713 3634 7713 3720 7713 3720 7714 3634 7714 3780 7714 3784 7715 3644 7715 3781 7715 3777 7716 3636 7716 3782 7716 3782 7717 3636 7717 3704 7717 3542 7718 3715 7718 3705 7718 3542 7719 3705 7719 3706 7719 3716 7720 3547 7720 3707 7720 3707 7721 3547 7721 3708 7721 3707 7722 3708 7722 3544 7722 3706 7723 3705 7723 3712 7723 3712 7724 3705 7724 3599 7724 3712 7725 3599 7725 3544 7725 3544 7726 3599 7726 3793 7726 3544 7727 3793 7727 3707 7727 3830 7728 3709 7728 3832 7728 3709 7729 3722 7729 3710 7729 3830 7730 3831 7730 3713 7730 3713 7731 3723 7731 3722 7731 3713 7732 3722 7732 3830 7732 3830 7733 3722 7733 3709 7733 3722 7734 3724 7734 3710 7734 3544 7735 3711 7735 3712 7735 3724 7736 3722 7736 3712 7736 3712 7737 3722 7737 3723 7737 3712 7738 3723 7738 3713 7738 3724 7739 3711 7739 3710 7739 3710 7740 3711 7740 3544 7740 3711 7741 3724 7741 3712 7741 3635 7742 3705 7742 3715 7742 3786 7743 3785 7743 3715 7743 3715 7744 3785 7744 3714 7744 3714 7745 3635 7745 3715 7745 3717 7746 3716 7746 3707 7746 3717 7747 3707 7747 3783 7747 3717 7748 3783 7748 3704 7748 3716 7749 3717 7749 3787 7749 3716 7750 3787 7750 3546 7750 3718 7751 3639 7751 3778 7751 3778 7752 3533 7752 3718 7752 3630 7753 3719 7753 3720 7753 3587 7754 3711 7754 3721 7754 3591 7755 3722 7755 3723 7755 3591 7756 3723 7756 3722 7756 3623 7757 3744 7757 3574 7757 3623 7758 3574 7758 3747 7758 3727 7759 3725 7759 3746 7759 3746 7760 3725 7760 3745 7760 3727 7761 3746 7761 3726 7761 3726 7762 3728 7762 3727 7762 3740 7763 3741 7763 3620 7763 3620 7764 3741 7764 3626 7764 3739 7765 3624 7765 3729 7765 3729 7766 3624 7766 3743 7766 3729 7767 3743 7767 3730 7767 3730 7768 3736 7768 3729 7768 3622 7769 3621 7769 3730 7769 3730 7770 3621 7770 3736 7770 3742 7771 3738 7771 3735 7771 3735 7772 3738 7772 3737 7772 3731 7773 3728 7773 3726 7773 3731 7774 3726 7774 3732 7774 3575 7775 3733 7775 3734 7775 3734 7776 3733 7776 3618 7776 3734 7777 3618 7777 3574 7777 3619 7778 3727 7778 3731 7778 3731 7779 3727 7779 3728 7779 3575 7780 3576 7780 3733 7780 3622 7781 3730 7781 3624 7781 3742 7782 3735 7782 3576 7782 3621 7783 3729 7783 3736 7783 3739 7784 3729 7784 3621 7784 3737 7785 3740 7785 3620 7785 3626 7786 3741 7786 3576 7786 3624 7787 3730 7787 3743 7787 3576 7788 3575 7788 3744 7788 3576 7789 3744 7789 3623 7789 3725 7790 3727 7790 3619 7790 3732 7791 3726 7791 3745 7791 3745 7792 3726 7792 3746 7792 3754 7793 3750 7793 3753 7793 3753 7794 3750 7794 3748 7794 3754 7795 3749 7795 3750 7795 3750 7796 3749 7796 3610 7796 3751 7797 3753 7797 3752 7797 3752 7798 3753 7798 3748 7798 3754 7799 3753 7799 3749 7799 3749 7800 3753 7800 3751 7800 3761 7801 3755 7801 3756 7801 3761 7802 3756 7802 3758 7802 3761 7803 3760 7803 3755 7803 3755 7804 3760 7804 3580 7804 3759 7805 3758 7805 3757 7805 3757 7806 3758 7806 3756 7806 3759 7807 3760 7807 3758 7807 3758 7808 3760 7808 3761 7808 3766 7809 3767 7809 3586 7809 3767 7810 3765 7810 3762 7810 3762 7811 3765 7811 3579 7811 3763 7812 3766 7812 3764 7812 3764 7813 3766 7813 3586 7813 3763 7814 3765 7814 3766 7814 3766 7815 3765 7815 3767 7815 3773 7816 3770 7816 3771 7816 3773 7817 3772 7817 3768 7817 3768 7818 3772 7818 3614 7818 3774 7819 3771 7819 3769 7819 3769 7820 3771 7820 3770 7820 3774 7821 3772 7821 3771 7821 3771 7822 3772 7822 3773 7822 3775 7823 3635 7823 3781 7823 3775 7824 3781 7824 3628 7824 3600 7825 3635 7825 3775 7825 3616 7826 3777 7826 3776 7826 3776 7827 3777 7827 3782 7827 3783 7828 3617 7828 3776 7828 3776 7829 3782 7829 3783 7829 3606 7830 3637 7830 3777 7830 3779 7831 3720 7831 3780 7831 3703 7832 2281 7832 3634 7832 3644 7833 2281 7833 3781 7833 3704 7834 3783 7834 3782 7834 3784 7835 3781 7835 3635 7835 3790 7836 3788 7836 3709 7836 3831 7837 3581 7837 3785 7837 3831 7838 3785 7838 3786 7838 3546 7839 3787 7839 3790 7839 3790 7840 3787 7840 3788 7840 3709 7841 3788 7841 3615 7841 3543 7842 3831 7842 3786 7842 3789 7843 3831 7843 3543 7843 3713 7844 3831 7844 3789 7844 3710 7845 3545 7845 3709 7845 3709 7846 3545 7846 3790 7846 3655 7847 3816 7847 3813 7847 3599 7848 3593 7848 3811 7848 3811 7849 3593 7849 3594 7849 3797 7850 3589 7850 3791 7850 3791 7851 3589 7851 3811 7851 3791 7852 3811 7852 3594 7852 3599 7853 3811 7853 3792 7853 3599 7854 3792 7854 3793 7854 3597 7855 3596 7855 3794 7855 3794 7856 3796 7856 3648 7856 3648 7857 3795 7857 3794 7857 3794 7858 3795 7858 3597 7858 3804 7859 3798 7859 3683 7859 3800 7860 3798 7860 3802 7860 3684 7861 3659 7861 3683 7861 3659 7862 3684 7862 3683 7862 3659 7863 3683 7863 3799 7863 3800 7864 3683 7864 3798 7864 3683 7865 3800 7865 3799 7865 3803 7866 3801 7866 3804 7866 3804 7867 3801 7867 3802 7867 3804 7868 3802 7868 3798 7868 3555 7869 3594 7869 3804 7869 3594 7870 3803 7870 3804 7870 3659 7871 3670 7871 3683 7871 3683 7872 3670 7872 3804 7872 3804 7873 3670 7873 3555 7873 3805 7874 3602 7874 3806 7874 3805 7875 3806 7875 3810 7875 3810 7876 3806 7876 3592 7876 3592 7877 3806 7877 3602 7877 3807 7878 3685 7878 3537 7878 3807 7879 3537 7879 3665 7879 3665 7880 3685 7880 3810 7880 3685 7881 3807 7881 3805 7881 3685 7882 3805 7882 3810 7882 3602 7883 3808 7883 3592 7883 3592 7884 3808 7884 3809 7884 3810 7885 3592 7885 3812 7885 3664 7886 3665 7886 3810 7886 3811 7887 3810 7887 3812 7887 3562 7888 3821 7888 3820 7888 3820 7889 3821 7889 3805 7889 3820 7890 3805 7890 3807 7890 3562 7891 3820 7891 3813 7891 3813 7892 3820 7892 3819 7892 3818 7893 3561 7893 3817 7893 3817 7894 3561 7894 3816 7894 3814 7895 3561 7895 3818 7895 3799 7896 3800 7896 3818 7896 3818 7897 3800 7897 3814 7897 3817 7898 3816 7898 3815 7898 3655 7899 3813 7899 3819 7899 3686 7900 3655 7900 3819 7900 3820 7901 3807 7901 3819 7901 3817 7902 3799 7902 3818 7902 3823 7903 3826 7903 3825 7903 3825 7904 3826 7904 3822 7904 3822 7905 3826 7905 3827 7905 3822 7906 3827 7906 3559 7906 3827 7907 3824 7907 3559 7907 3559 7908 3824 7908 3828 7908 3536 7909 3824 7909 3823 7909 3536 7910 3823 7910 3825 7910 3826 7911 3823 7911 3827 7911 3827 7912 3823 7912 3824 7912 3828 7913 3824 7913 3536 7913 3597 7914 3556 7914 3674 7914 3674 7915 3556 7915 3673 7915 3831 7916 3830 7916 3814 7916 3578 7917 3581 7917 3802 7917 3831 7918 3814 7918 3802 7918 3831 7919 3802 7919 3581 7919 3641 7920 3624 7920 3833 7920 3833 7921 3624 7921 3619 7921 3532 7922 3626 7922 3576 7922 3532 7923 3576 7923 3643 7923 3940 7924 3865 7924 3939 7924 3939 7925 3865 7925 3919 7925 3934 7926 4137 7926 3935 7926 3935 7927 4137 7927 4136 7927 4065 7928 4069 7928 3907 7928 4059 7929 3871 7929 4061 7929 4055 7930 3869 7930 3834 7930 3834 7931 3869 7931 3835 7931 4051 7932 4049 7932 3836 7932 3836 7933 4049 7933 3906 7933 4021 7934 4009 7934 3881 7934 4018 7935 3930 7935 3923 7935 4085 7936 2274 7936 4081 7936 3894 7937 4001 7937 3892 7937 3897 7938 3912 7938 3998 7938 3898 7939 3913 7939 3899 7939 4034 7940 3945 7940 4033 7940 3954 7941 3996 7941 3949 7941 3954 7942 3949 7942 3996 7942 3995 7943 3991 7943 3992 7943 3985 7944 3838 7944 4103 7944 3980 7945 3979 7945 3838 7945 3980 7946 3838 7946 3978 7946 3976 7947 3977 7947 3932 7947 3976 7948 3932 7948 4079 7948 3975 7949 3933 7949 1007 7949 3975 7950 1007 7950 1003 7950 3975 7951 1003 7951 3931 7951 4073 7952 4072 7952 4077 7952 4073 7953 4077 7953 3926 7953 3924 7954 3928 7954 3942 7954 3941 7955 3904 7955 3929 7955 4081 7956 4082 7956 4085 7956 4085 7957 4082 7957 2274 7957 3860 7958 3868 7958 3840 7958 3856 7959 3855 7959 3857 7959 4007 7960 4089 7960 4003 7960 4003 7961 4089 7961 4088 7961 4003 7962 4088 7962 4002 7962 4002 7963 4088 7963 3841 7963 4002 7964 3841 7964 4012 7964 4012 7965 3841 7965 4010 7965 4005 7966 4006 7966 3842 7966 3842 7967 4006 7967 3843 7967 3842 7968 3843 7968 4091 7968 4091 7969 3843 7969 3844 7969 4091 7970 3844 7970 4090 7970 4090 7971 3844 7971 4013 7971 3974 7972 4109 7972 3845 7972 3845 7973 4109 7973 4110 7973 3845 7974 4110 7974 4098 7974 3847 7975 3846 7975 3888 7975 3888 7976 3846 7976 3848 7976 3972 7977 3962 7977 3974 7977 3974 7978 3962 7978 4109 7978 3962 7979 3972 7979 3958 7979 3958 7980 3972 7980 3947 7980 3958 7981 3947 7981 3847 7981 3847 7982 3947 7982 3946 7982 3847 7983 3946 7983 3846 7983 3884 7984 3968 7984 3973 7984 3944 7985 3889 7985 3943 7985 3943 7986 3889 7986 4131 7986 3880 7987 3886 7987 3884 7987 3884 7988 3886 7988 4101 7988 3884 7989 4101 7989 3968 7989 3973 7990 3968 7990 3955 7990 3955 7991 3968 7991 3967 7991 3889 7992 3944 7992 3948 7992 3889 7993 3948 7993 3969 7993 3969 7994 3948 7994 3956 7994 3969 7995 3956 7995 3967 7995 3967 7996 3956 7996 3955 7996 3981 7997 3849 7997 3853 7997 3838 7998 3984 7998 3978 7998 3838 7999 3979 7999 3850 7999 3978 8000 3984 8000 3850 8000 4124 8001 3984 8001 3838 8001 3982 8002 4121 8002 3981 8002 3984 8003 4124 8003 3982 8003 3982 8004 4124 8004 4121 8004 3984 8005 3986 8005 3850 8005 3850 8006 3986 8006 4116 8006 4116 8007 3986 8007 3984 8007 4116 8008 3984 8008 4118 8008 3982 8009 4118 8009 3984 8009 4127 8010 4119 8010 3849 8010 3849 8011 4119 8011 3851 8011 3849 8012 3851 8012 3853 8012 3978 8013 3850 8013 3979 8013 3838 8014 3852 8014 3915 8014 4135 8015 3852 8015 3850 8015 3850 8016 3852 8016 3838 8016 3915 8017 3852 8017 4135 8017 3915 8018 4119 8018 3838 8018 3838 8019 4119 8019 4127 8019 3985 8020 4103 8020 3838 8020 4103 8021 4127 8021 3838 8021 4103 8022 3838 8022 4127 8022 3849 8023 3981 8023 4121 8023 3982 8024 3981 8024 4112 8024 3982 8025 4112 8025 4118 8025 3853 8026 3851 8026 3981 8026 3981 8027 3851 8027 4112 8027 3855 8028 3856 8028 3859 8028 3859 8029 3856 8029 3858 8029 3855 8030 3859 8030 3905 8030 3905 8031 3859 8031 3911 8031 3858 8032 3856 8032 3908 8032 3908 8033 3856 8033 3857 8033 3858 8034 3908 8034 3911 8034 3858 8035 3911 8035 3859 8035 3860 8036 3840 8036 3862 8036 3862 8037 3840 8037 3861 8037 3860 8038 3862 8038 3878 8038 3878 8039 3862 8039 3876 8039 3861 8040 3840 8040 3875 8040 3875 8041 3840 8041 3868 8041 3862 8042 3861 8042 3876 8042 3916 8043 4045 8043 4023 8043 3863 8044 3864 8044 4023 8044 4023 8045 3864 8045 4031 8045 3867 8046 4040 8046 4026 8046 3865 8047 4041 8047 3866 8047 4040 8048 3867 8048 3866 8048 4040 8049 3866 8049 4041 8049 4020 8050 3878 8050 3876 8050 3877 8051 3860 8051 3878 8051 3870 8052 3874 8052 3875 8052 3875 8053 3868 8053 3870 8053 3870 8054 3868 8054 3877 8054 3877 8055 3868 8055 3860 8055 3861 8056 3875 8056 3999 8056 3861 8057 3999 8057 3876 8057 4054 8058 3872 8058 3869 8058 3870 8059 4052 8059 3835 8059 4001 8060 4054 8060 4052 8060 3872 8061 3879 8061 4058 8061 3872 8062 4058 8062 4020 8062 4057 8063 3871 8063 3870 8063 3870 8064 3871 8064 4001 8064 4001 8065 3871 8065 4059 8065 4057 8066 3877 8066 4062 8066 4062 8067 3877 8067 4058 8067 3870 8068 3835 8068 3869 8068 4020 8069 3999 8069 3874 8069 3874 8070 3999 8070 3875 8070 3999 8071 4020 8071 3876 8071 3870 8072 3877 8072 4057 8072 3877 8073 3878 8073 4020 8073 3877 8074 4020 8074 4058 8074 3870 8075 4001 8075 4052 8075 4059 8076 3879 8076 4001 8076 4001 8077 3879 8077 3872 8077 4001 8078 3872 8078 4054 8078 3872 8079 3873 8079 3869 8079 3873 8080 3870 8080 3869 8080 3880 8081 4021 8081 4098 8081 3884 8082 3881 8082 3880 8082 3880 8083 3881 8083 4021 8083 4098 8084 3882 8084 3845 8084 3845 8085 3882 8085 3884 8085 3881 8086 3883 8086 4098 8086 3881 8087 4098 8087 4021 8087 4098 8088 3883 8088 3882 8088 3884 8089 3883 8089 3881 8089 3884 8090 3882 8090 3883 8090 3896 8091 4095 8091 4108 8091 4108 8092 4095 8092 4107 8092 4107 8093 4095 8093 4110 8093 3896 8094 4108 8094 4106 8094 4096 8095 3890 8095 4094 8095 4094 8096 3890 8096 3885 8096 3885 8097 4101 8097 3886 8097 4097 8098 4133 8098 3887 8098 4097 8099 3887 8099 3888 8099 3888 8100 3887 8100 3847 8100 4130 8101 4131 8101 3889 8101 4096 8102 3893 8102 4000 8102 3892 8103 3891 8103 3997 8103 4096 8104 3892 8104 3890 8104 3890 8105 3892 8105 3997 8105 3891 8106 3892 8106 3894 8106 3891 8107 3894 8107 3922 8107 3922 8108 3894 8108 4000 8108 4000 8109 3894 8109 3892 8109 4000 8110 3892 8110 4096 8110 3922 8111 4000 8111 3893 8111 3922 8112 3893 8112 4011 8112 3895 8113 3901 8113 4075 8113 3899 8114 4106 8114 4105 8114 3895 8115 3896 8115 3899 8115 3899 8116 3896 8116 4106 8116 3899 8117 3998 8117 3895 8117 3895 8118 3998 8118 3897 8118 4105 8119 3900 8119 3898 8119 3897 8120 3900 8120 3902 8120 3998 8121 3899 8121 3898 8121 3899 8122 4105 8122 3898 8122 4075 8123 3901 8123 3902 8123 3897 8124 3901 8124 3895 8124 3998 8125 3898 8125 3897 8125 3897 8126 3898 8126 3900 8126 3902 8127 3901 8127 3897 8127 3960 8128 3957 8128 3961 8128 3961 8129 3957 8129 3988 8129 3965 8130 3964 8130 3989 8130 3903 8131 3904 8131 3941 8131 3903 8132 3941 8132 4073 8132 4073 8133 3941 8133 4016 8133 4133 8134 3904 8134 4132 8134 4132 8135 3904 8135 3938 8135 3938 8136 3904 8136 3903 8136 3904 8137 4133 8137 4016 8137 3904 8138 4016 8138 3941 8138 4016 8139 4133 8139 4097 8139 4016 8140 4097 8140 4017 8140 4073 8141 4016 8141 4017 8141 4073 8142 4076 8142 4072 8142 4073 8143 4017 8143 4076 8143 3911 8144 3910 8144 3905 8144 3905 8145 3910 8145 3914 8145 3912 8146 3855 8146 3905 8146 3855 8147 3912 8147 3857 8147 3857 8148 3912 8148 4019 8148 3857 8149 4019 8149 3908 8149 3911 8150 3908 8150 3909 8150 4047 8151 3914 8151 4049 8151 4087 8152 3906 8152 4049 8152 3906 8153 4014 8153 4046 8153 3913 8154 4047 8154 4046 8154 4064 8155 3914 8155 4066 8155 3913 8156 3907 8156 4069 8156 3913 8157 4069 8157 4066 8157 3907 8158 4014 8158 4063 8158 4063 8159 4014 8159 4019 8159 3912 8160 4064 8160 4068 8160 3912 8161 4068 8161 4063 8161 4014 8162 3906 8162 4087 8162 4019 8163 3909 8163 3908 8163 3911 8164 3909 8164 3910 8164 3910 8165 3909 8165 4019 8165 4019 8166 3912 8166 4063 8166 3912 8167 3905 8167 3914 8167 3912 8168 3914 8168 4064 8168 4014 8169 3907 8169 3913 8169 4014 8170 3913 8170 4046 8170 3913 8171 4066 8171 3914 8171 3913 8172 3914 8172 4047 8172 4049 8173 3914 8173 4087 8173 3900 8174 4104 8174 3915 8174 4092 8175 3900 8175 4135 8175 4135 8176 3900 8176 3915 8176 3910 8177 4073 8177 4074 8177 3900 8178 4092 8178 3914 8178 3900 8179 3914 8179 3902 8179 4073 8180 3910 8180 3903 8180 3903 8181 3910 8181 3918 8181 3910 8182 4074 8182 3902 8182 3910 8183 3902 8183 3914 8183 3916 8184 4033 8184 3921 8184 3917 8185 4137 8185 3937 8185 4043 8186 3953 8186 3921 8186 3953 8187 4043 8187 3917 8187 3953 8188 3917 8188 3937 8188 3919 8189 3938 8189 4026 8189 4026 8190 3938 8190 3918 8190 3927 8191 4037 8191 4026 8191 3927 8192 4026 8192 3918 8192 3927 8193 3971 8193 3937 8193 3927 8194 3937 8194 4038 8194 4034 8195 4136 8195 4137 8195 3937 8196 4136 8196 4038 8196 3927 8197 4038 8197 4039 8197 3992 8198 4045 8198 3920 8198 4045 8199 4093 8199 4042 8199 4042 8200 4093 8200 3938 8200 4042 8201 3938 8201 3865 8201 4137 8202 4136 8202 3937 8202 3920 8203 3953 8203 3992 8203 3903 8204 3918 8204 3938 8204 3938 8205 3919 8205 3865 8205 3921 8206 3953 8206 3920 8206 3921 8207 3920 8207 3916 8207 4045 8208 3916 8208 3920 8208 4093 8209 4045 8209 3992 8209 3993 8210 3991 8210 3992 8210 4033 8211 4034 8211 4032 8211 4033 8212 4032 8212 3921 8212 4032 8213 4034 8213 4137 8213 4033 8214 3865 8214 4034 8214 4035 8215 4037 8215 3865 8215 3865 8216 4037 8216 3927 8216 3865 8217 3927 8217 4034 8217 4034 8218 3927 8218 4039 8218 4071 8219 3874 8219 3922 8219 4116 8220 4115 8220 3891 8220 3874 8221 4071 8221 4070 8221 3874 8222 4070 8222 3927 8222 3922 8223 3870 8223 3891 8223 3922 8224 3874 8224 3870 8224 3971 8225 3927 8225 4070 8225 3924 8226 3971 8226 4070 8226 4128 8227 4018 8227 3923 8227 3942 8228 4018 8228 4128 8228 3936 8229 3923 8229 4130 8229 4081 8230 4018 8230 4070 8230 4081 8231 4070 8231 4085 8231 4128 8232 3923 8232 3936 8232 3971 8233 3942 8233 3937 8233 3937 8234 3942 8234 4128 8234 4018 8235 3942 8235 3924 8235 4018 8236 3924 8236 4070 8236 3924 8237 3942 8237 3971 8237 3923 8238 4018 8238 4130 8238 3929 8239 3918 8239 4015 8239 3977 8240 3930 8240 3932 8240 3932 8241 4015 8241 4079 8241 3927 8242 1007 8242 3928 8242 3928 8243 1007 8243 3933 8243 1007 8244 3927 8244 1003 8244 1003 8245 3927 8245 3918 8245 1003 8246 3918 8246 3929 8246 3929 8247 3931 8247 1003 8247 3874 8248 3927 8248 4082 8248 3874 8249 4082 8249 3925 8249 4011 8250 4020 8250 4086 8250 4086 8251 4020 8251 3874 8251 3925 8252 4086 8252 3874 8252 4080 8253 3927 8253 3930 8253 4080 8254 3930 8254 4079 8254 4079 8255 3930 8255 3977 8255 3927 8256 4080 8256 4082 8256 4015 8257 4078 8257 4079 8257 4015 8258 4077 8258 4078 8258 4077 8259 3910 8259 3926 8259 4019 8260 4083 8260 3910 8260 3926 8261 3910 8261 4083 8261 3930 8262 3927 8262 3928 8262 3930 8263 3928 8263 3932 8263 3932 8264 3928 8264 3933 8264 3929 8265 4015 8265 3932 8265 3929 8266 3932 8266 3931 8266 3931 8267 3932 8267 3933 8267 3918 8268 3910 8268 4015 8268 4015 8269 3910 8269 4077 8269 3934 8270 3964 8270 3965 8270 3934 8271 3965 8271 4128 8271 3934 8272 4128 8272 3935 8272 3934 8273 3935 8273 3964 8273 3964 8274 3935 8274 3936 8274 3936 8275 3935 8275 4128 8275 3989 8276 3951 8276 3965 8276 3965 8277 3951 8277 3953 8277 3965 8278 3953 8278 3937 8278 3965 8279 3937 8279 4128 8279 4093 8280 3950 8280 3988 8280 4132 8281 3938 8281 3957 8281 3957 8282 3938 8282 4093 8282 4093 8283 3988 8283 3957 8283 3939 8284 3957 8284 3940 8284 3940 8285 3957 8285 3960 8285 4133 8286 3939 8286 3940 8286 4133 8287 3940 8287 3960 8287 3957 8288 3939 8288 4132 8288 4132 8289 3939 8289 4133 8289 4085 8290 2274 8290 3925 8290 4085 8291 3925 8291 4082 8291 4085 8292 4082 8292 4081 8292 3941 8293 3929 8293 3904 8293 3942 8294 3928 8294 3924 8294 4073 8295 3926 8295 4072 8295 3955 8296 3972 8296 3973 8296 3973 8297 3972 8297 3974 8297 3848 8298 3846 8298 3943 8298 3943 8299 3846 8299 3944 8299 3946 8300 3945 8300 3948 8300 3956 8301 3837 8301 3947 8301 3945 8302 3946 8302 3947 8302 3945 8303 3947 8303 3837 8303 3837 8304 3956 8304 3948 8304 3837 8305 3948 8305 3945 8305 3952 8306 3992 8306 3953 8306 3951 8307 4112 8307 3950 8307 3996 8308 3950 8308 3949 8308 3949 8309 3950 8309 4093 8309 3950 8310 3996 8310 3951 8310 3951 8311 3996 8311 3953 8311 3949 8312 3994 8312 3996 8312 3996 8313 3994 8313 3952 8313 3949 8314 4093 8314 3994 8314 3992 8315 3994 8315 4093 8315 3996 8316 3952 8316 3953 8316 3954 8317 3972 8317 3955 8317 3954 8318 3947 8318 3972 8318 3954 8319 3955 8319 3956 8319 3947 8320 3954 8320 3956 8320 3989 8321 4099 8321 4111 8321 3983 8322 4099 8322 3989 8322 3983 8323 3989 8323 3990 8323 3951 8324 3989 8324 4111 8324 3854 8325 3988 8325 4114 8325 4114 8326 3988 8326 4113 8326 3854 8327 3963 8327 3961 8327 3963 8328 3854 8328 4114 8328 3961 8329 3988 8329 3854 8329 3961 8330 3959 8330 3960 8330 3962 8331 3959 8331 3961 8331 3959 8332 3962 8332 3958 8332 3959 8333 4133 8333 3960 8333 3959 8334 3887 8334 4133 8334 3887 8335 3959 8335 3958 8335 3887 8336 3958 8336 3847 8336 3961 8337 3963 8337 3962 8337 3983 8338 3990 8338 3966 8338 3990 8339 3989 8339 3966 8339 3989 8340 3964 8340 3966 8340 3970 8341 3966 8341 3964 8341 3969 8342 3967 8342 3970 8342 3970 8343 3967 8343 3966 8343 3968 8344 3983 8344 3966 8344 3968 8345 3966 8345 3967 8345 3889 8346 3969 8346 3970 8346 3889 8347 3970 8347 4129 8347 4129 8348 3970 8348 3964 8348 4129 8349 3964 8349 3936 8349 3946 8350 3948 8350 3846 8350 3846 8351 3948 8351 3944 8351 3845 8352 3884 8352 3974 8352 3974 8353 3884 8353 3973 8353 3975 8354 3931 8354 3933 8354 3976 8355 4079 8355 3977 8355 3980 8356 3978 8356 3979 8356 3963 8357 4103 8357 3985 8357 3989 8358 3990 8358 4112 8358 3989 8359 4112 8359 3990 8359 3993 8360 3994 8360 3991 8360 3994 8361 3993 8361 3952 8361 3993 8362 3992 8362 3952 8362 3994 8363 3992 8363 3991 8363 3995 8364 3992 8364 3991 8364 4033 8365 3945 8365 4034 8365 3899 8366 3913 8366 3898 8366 3998 8367 3912 8367 3897 8367 3892 8368 4001 8368 3894 8368 4077 8369 4076 8369 4017 8369 4077 8370 4017 8370 4078 8370 4018 8371 4080 8371 4130 8371 4130 8372 4080 8372 4079 8372 4130 8373 4079 8373 4097 8373 4097 8374 4079 8374 4017 8374 4081 8375 4082 8375 4018 8375 4018 8376 4082 8376 4080 8376 4086 8377 3925 8377 4085 8377 4072 8378 3926 8378 4084 8378 4084 8379 3926 8379 4083 8379 4002 8380 4012 8380 3893 8380 4002 8381 3893 8381 4003 8381 4013 8382 3844 8382 3895 8382 3895 8383 3844 8383 3843 8383 3895 8384 3843 8384 4006 8384 4003 8385 3893 8385 4007 8385 4007 8386 3893 8386 4096 8386 4007 8387 4096 8387 4006 8387 4006 8388 4096 8388 3896 8388 4006 8389 3896 8389 3895 8389 3850 8390 4092 8390 4135 8390 4092 8391 4004 8391 4005 8391 3850 8392 4134 8392 4089 8392 4089 8393 4008 8393 4004 8393 4089 8394 4004 8394 3850 8394 3850 8395 4004 8395 4092 8395 4004 8396 4022 8396 4005 8396 4006 8397 4009 8397 4007 8397 4022 8398 4004 8398 4007 8398 4007 8399 4004 8399 4008 8399 4007 8400 4008 8400 4089 8400 4022 8401 4009 8401 4005 8401 4005 8402 4009 8402 4006 8402 4009 8403 4022 8403 4007 8403 4011 8404 3893 8404 4012 8404 4010 8405 3872 8405 4012 8405 4012 8406 3872 8406 4020 8406 4020 8407 4011 8407 4012 8407 4019 8408 4013 8408 3895 8408 4019 8409 3895 8409 4075 8409 4019 8410 4075 8410 4083 8410 4013 8411 4019 8411 4014 8411 4013 8412 4014 8412 4090 8412 4016 8413 4015 8413 4017 8413 4017 8414 4015 8414 4016 8414 3923 8415 3930 8415 4018 8415 3881 8416 4009 8416 4021 8416 3882 8417 4004 8417 4008 8417 3882 8418 4008 8418 4004 8418 4042 8419 3863 8419 4023 8419 4042 8420 4023 8420 4045 8420 4024 8421 3917 8421 4044 8421 4044 8422 3917 8422 4043 8422 4024 8423 4044 8423 4030 8423 4030 8424 4025 8424 4024 8424 4040 8425 4041 8425 4026 8425 4026 8426 4041 8426 3919 8426 4038 8427 4136 8427 4029 8427 4029 8428 4136 8428 4028 8428 4029 8429 4028 8429 4027 8429 4027 8430 4036 8430 4029 8430 4034 8431 4039 8431 4027 8431 4027 8432 4039 8432 4036 8432 3866 8433 3867 8433 4035 8433 4035 8434 3867 8434 4037 8434 4032 8435 4025 8435 4030 8435 4032 8436 4030 8436 3921 8436 3864 8437 4033 8437 4031 8437 4031 8438 4033 8438 3916 8438 4031 8439 3916 8439 4023 8439 4137 8440 4024 8440 4032 8440 4032 8441 4024 8441 4025 8441 3864 8442 3865 8442 4033 8442 4034 8443 4027 8443 4136 8443 3866 8444 4035 8444 3865 8444 4039 8445 4029 8445 4036 8445 3867 8446 4026 8446 4037 8446 4038 8447 4029 8447 4039 8447 3919 8448 4041 8448 3865 8448 4136 8449 4027 8449 4028 8449 3865 8450 3864 8450 3863 8450 3865 8451 3863 8451 4042 8451 3917 8452 4024 8452 4137 8452 3921 8453 4030 8453 4043 8453 4043 8454 4030 8454 4044 8454 4050 8455 4046 8455 4048 8455 4048 8456 4046 8456 4047 8456 4050 8457 3836 8457 4046 8457 4046 8458 3836 8458 3906 8458 4051 8459 4048 8459 4049 8459 4049 8460 4048 8460 4047 8460 4050 8461 4048 8461 3836 8461 3836 8462 4048 8462 4051 8462 4056 8463 4052 8463 4054 8463 4056 8464 4054 8464 4053 8464 4056 8465 3834 8465 4052 8465 4052 8466 3834 8466 3835 8466 4055 8467 4053 8467 3869 8467 3869 8468 4053 8468 4054 8468 4055 8469 3834 8469 4053 8469 4053 8470 3834 8470 4056 8470 4060 8471 4062 8471 4058 8471 4062 8472 4061 8472 4057 8472 4057 8473 4061 8473 3871 8473 4059 8474 4060 8474 3879 8474 3879 8475 4060 8475 4058 8475 4059 8476 4061 8476 4060 8476 4060 8477 4061 8477 4062 8477 4068 8478 4064 8478 4067 8478 4068 8479 4065 8479 4063 8479 4063 8480 4065 8480 3907 8480 4069 8481 4067 8481 4066 8481 4066 8482 4067 8482 4064 8482 4069 8483 4065 8483 4067 8483 4067 8484 4065 8484 4068 8484 4071 8485 4011 8485 4085 8485 4071 8486 4085 8486 4070 8486 3922 8487 4011 8487 4071 8487 4073 8488 4072 8488 4074 8488 4074 8489 4072 8489 4084 8489 4075 8490 3902 8490 4074 8490 4074 8491 4084 8491 4075 8491 4076 8492 4077 8492 4072 8492 4078 8493 4017 8493 4079 8493 4081 8494 2274 8494 4082 8494 3925 8495 2274 8495 4085 8495 4083 8496 4075 8496 4084 8496 4086 8497 4085 8497 4011 8497 4091 8498 4087 8498 4092 8498 4134 8499 3873 8499 3872 8499 4134 8500 3872 8500 4010 8500 4090 8501 4014 8501 4091 8501 4091 8502 4014 8502 4087 8502 4092 8503 4087 8503 3914 8503 3841 8504 4134 8504 4010 8504 4088 8505 4134 8505 3841 8505 4089 8506 4134 8506 4088 8506 4005 8507 3842 8507 4092 8507 4092 8508 3842 8508 4091 8508 3950 8509 4112 8509 3851 8509 4096 8510 4094 8510 4110 8510 4110 8511 4094 8511 3885 8511 3880 8512 4098 8512 3886 8512 3886 8513 4098 8513 4110 8513 3886 8514 4110 8514 3885 8514 4096 8515 4110 8515 4095 8515 4096 8516 4095 8516 3896 8516 4130 8517 4097 8517 3888 8517 3888 8518 3848 8518 3943 8518 3943 8519 4131 8519 3888 8519 3888 8520 4131 8520 4130 8520 4100 8521 3987 8521 3839 8521 4115 8522 3987 8522 3891 8522 3984 8523 3983 8523 3839 8523 3983 8524 3984 8524 3839 8524 3983 8525 3839 8525 4099 8525 4115 8526 3839 8526 3987 8526 3839 8527 4115 8527 4099 8527 3890 8528 3997 8528 4100 8528 4100 8529 3997 8529 3891 8529 4100 8530 3891 8530 3987 8530 4101 8531 3885 8531 4100 8531 3885 8532 3890 8532 4100 8532 3983 8533 3968 8533 3839 8533 3839 8534 3968 8534 4100 8534 4100 8535 3968 8535 4101 8535 4104 8536 3900 8536 4102 8536 4104 8537 4102 8537 4109 8537 4109 8538 4102 8538 4108 8538 4108 8539 4102 8539 3900 8539 4114 8540 3985 8540 4103 8540 4114 8541 4103 8541 3963 8541 3963 8542 3985 8542 4109 8542 3985 8543 4114 8543 4104 8543 3985 8544 4104 8544 4109 8544 3900 8545 4105 8545 4108 8545 4108 8546 4105 8546 4106 8546 4109 8547 4108 8547 4107 8547 3962 8548 3963 8548 4109 8548 4110 8549 4109 8549 4107 8549 4119 8550 3915 8550 4120 8550 4120 8551 3915 8551 4104 8551 4120 8552 4104 8552 4114 8552 4119 8553 4120 8553 3851 8553 3851 8554 4120 8554 4113 8554 4117 8555 4118 8555 4111 8555 4111 8556 4118 8556 4112 8556 4116 8557 4118 8557 4117 8557 4099 8558 4115 8558 4117 8558 4117 8559 4115 8559 4116 8559 4111 8560 4112 8560 3951 8560 3950 8561 3851 8561 4113 8561 3988 8562 3950 8562 4113 8562 4120 8563 4114 8563 4113 8563 4111 8564 4099 8564 4117 8564 4123 8565 4125 8565 4124 8565 4124 8566 4125 8566 4121 8566 4121 8567 4125 8567 4126 8567 4121 8568 4126 8568 3849 8568 4126 8569 4122 8569 3849 8569 3849 8570 4122 8570 4127 8570 3838 8571 4122 8571 4123 8571 3838 8572 4123 8572 4124 8572 4125 8573 4123 8573 4126 8573 4126 8574 4123 8574 4122 8574 4127 8575 4122 8575 3838 8575 4130 8576 3889 8576 3936 8576 3936 8577 3889 8577 4129 8577 4134 8578 3850 8578 4116 8578 3870 8579 3873 8579 3891 8579 4134 8580 4116 8580 3891 8580 4134 8581 3891 8581 3873 8581 3935 8582 4136 8582 3934 8582 3934 8583 4136 8583 4137 8583 3939 8584 3919 8584 3865 8584 3939 8585 3865 8585 3940 8585 4138 8586 4156 8586 4155 8586 4138 8587 4155 8587 4420 8587 4158 8588 4246 8588 4139 8588 4247 8589 4414 8589 4164 8589 4164 8590 4414 8590 4417 8590 4162 8591 4415 8591 4413 8591 4385 8592 4412 8592 4283 8592 4391 8593 4239 8593 4392 8593 4392 8594 4239 8594 4391 8594 4314 8595 4230 8595 4395 8595 4405 8596 4140 8596 4234 8596 4342 8597 4413 8597 4141 8597 4141 8598 4413 8598 4341 8598 4378 8599 4414 8599 4142 8599 4142 8600 4414 8600 4343 8600 4246 8601 4143 8601 4377 8601 4375 8602 4138 8602 4144 8602 4144 8603 4138 8603 4145 8603 4241 8604 4363 8604 4359 8604 4241 8605 4359 8605 4374 8605 4373 8606 4360 8606 4372 8606 4373 8607 4372 8607 4371 8607 4368 8608 4339 8608 4367 8608 4367 8609 4339 8609 4370 8609 4146 8610 4369 8610 4365 8610 4147 8611 4380 8611 4383 8611 4147 8612 4383 8612 4352 8612 4399 8613 4191 8613 4400 8613 4400 8614 4191 8614 4190 8614 4331 8615 4148 8615 4149 8615 4149 8616 4148 8616 4150 8616 4325 8617 4151 8617 4297 8617 4297 8618 4151 8618 4393 8618 4297 8619 4393 8619 4326 8619 4204 8620 4366 8620 4206 8620 4252 8621 4254 8621 4152 8621 4152 8622 4254 8622 4256 8622 4250 8623 4154 8623 4153 8623 4206 8624 4153 8624 4207 8624 4357 8625 4158 8625 4139 8625 4419 8626 4420 8626 4250 8626 4250 8627 4420 8627 4154 8627 4157 8628 4158 8628 4357 8628 4157 8629 4357 8629 4257 8629 4257 8630 4357 8630 4256 8630 4154 8631 4420 8631 4155 8631 4154 8632 4155 8632 4245 8632 4245 8633 4155 8633 4156 8633 4245 8634 4418 8634 4154 8634 4154 8635 4418 8635 4157 8635 4157 8636 4418 8636 4158 8636 4417 8637 4416 8637 4248 8637 4333 8638 4159 8638 4199 8638 4333 8639 4199 8639 4189 8639 4276 8640 4160 8640 4185 8640 4185 8641 4160 8641 4361 8641 4185 8642 4361 8642 4181 8642 4181 8643 4361 8643 4358 8643 4181 8644 4358 8644 4178 8644 4364 8645 4189 8645 4161 8645 4364 8646 4161 8646 4248 8646 4161 8647 4417 8647 4248 8647 4415 8648 4162 8648 4358 8648 4358 8649 4162 8649 4178 8649 4178 8650 4162 8650 4163 8650 4178 8651 4163 8651 4161 8651 4161 8652 4163 8652 4415 8652 4247 8653 4164 8653 4415 8653 4415 8654 4164 8654 4161 8654 4161 8655 4164 8655 4417 8655 4165 8656 4167 8656 4168 8656 4170 8657 4179 8657 4166 8657 4166 8658 4179 8658 4178 8658 4166 8659 4178 8659 4167 8659 4167 8660 4178 8660 4161 8660 4167 8661 4161 8661 4168 8661 4168 8662 4161 8662 4188 8662 4166 8663 4167 8663 4171 8663 4171 8664 4167 8664 4165 8664 4170 8665 4166 8665 4171 8665 4180 8666 4179 8666 4169 8666 4169 8667 4179 8667 4170 8667 4169 8668 4170 8668 4171 8668 4188 8669 4172 8669 4168 8669 4168 8670 4172 8670 4173 8670 4168 8671 4173 8671 4165 8671 4169 8672 4347 8672 4174 8672 4171 8673 4165 8673 4347 8673 4171 8674 4347 8674 4169 8674 4174 8675 4173 8675 4176 8675 4173 8676 4172 8676 4176 8676 4176 8677 4172 8677 4175 8677 4176 8678 4175 8678 4177 8678 4177 8679 4175 8679 4293 8679 4177 8680 4293 8680 4169 8680 4169 8681 4293 8681 4180 8681 4176 8682 4177 8682 4174 8682 4177 8683 4169 8683 4174 8683 4180 8684 4293 8684 4270 8684 4183 8685 4181 8685 4178 8685 4178 8686 4179 8686 4183 8686 4183 8687 4179 8687 4180 8687 4183 8688 4180 8688 4182 8688 4182 8689 4180 8689 4270 8689 4181 8690 4183 8690 4187 8690 4182 8691 4353 8691 4183 8691 4147 8692 4186 8692 4187 8692 4147 8693 4187 8693 4351 8693 4272 8694 4352 8694 4182 8694 4182 8695 4352 8695 4353 8695 4186 8696 4147 8696 4352 8696 4186 8697 4352 8697 4272 8697 4353 8698 4351 8698 4183 8698 4183 8699 4351 8699 4187 8699 4184 8700 4185 8700 4186 8700 4186 8701 4185 8701 4181 8701 4186 8702 4181 8702 4187 8702 4161 8703 4189 8703 4188 8703 4188 8704 4189 8704 4193 8704 4188 8705 4193 8705 4172 8705 4172 8706 4193 8706 4194 8706 4172 8707 4194 8707 4175 8707 4175 8708 4194 8708 4312 8708 4193 8709 4189 8709 4192 8709 4194 8710 4349 8710 4197 8710 4197 8711 4349 8711 4190 8711 4197 8712 4190 8712 4196 8712 4196 8713 4190 8713 4191 8713 4196 8714 4191 8714 4192 8714 4192 8715 4191 8715 4350 8715 4192 8716 4350 8716 4193 8716 4193 8717 4350 8717 4195 8717 4193 8718 4195 8718 4194 8718 4194 8719 4195 8719 4349 8719 4199 8720 4200 8720 4189 8720 4189 8721 4200 8721 4196 8721 4189 8722 4196 8722 4192 8722 4196 8723 4200 8723 4197 8723 4197 8724 4200 8724 4198 8724 4199 8725 4159 8725 4200 8725 4200 8726 4159 8726 4334 8726 4200 8727 4334 8727 4198 8727 4198 8728 4334 8728 4201 8728 4202 8729 4309 8729 4201 8729 4201 8730 4309 8730 4197 8730 4201 8731 4197 8731 4198 8731 4334 8732 4332 8732 4201 8732 4201 8733 4332 8733 4202 8733 4332 8734 4203 8734 4202 8734 4202 8735 4203 8735 4304 8735 4304 8736 4203 8736 4305 8736 4305 8737 4203 8737 4205 8737 4204 8738 4206 8738 4203 8738 4203 8739 4206 8739 4205 8739 4300 8740 4305 8740 4205 8740 4300 8741 4205 8741 4301 8741 4301 8742 4205 8742 4206 8742 4301 8743 4206 8743 4207 8743 4301 8744 4207 8744 4302 8744 4302 8745 4207 8745 4153 8745 4302 8746 4153 8746 4298 8746 4298 8747 4153 8747 4296 8747 4208 8748 4223 8748 4209 8748 4296 8749 4153 8749 4154 8749 4154 8750 4212 8750 4296 8750 4296 8751 4212 8751 4208 8751 4296 8752 4208 8752 4295 8752 4295 8753 4208 8753 4209 8753 4211 8754 4213 8754 4212 8754 4157 8755 4210 8755 4217 8755 4217 8756 4214 8756 4157 8756 4157 8757 4214 8757 4211 8757 4157 8758 4211 8758 4154 8758 4154 8759 4211 8759 4212 8759 4213 8760 4211 8760 4220 8760 4220 8761 4211 8761 4218 8761 4218 8762 4211 8762 4214 8762 4216 8763 4219 8763 4354 8763 4208 8764 4212 8764 4215 8764 4215 8765 4212 8765 4213 8765 4215 8766 4213 8766 4220 8766 4217 8767 4354 8767 4218 8767 4354 8768 4217 8768 4216 8768 4216 8769 4217 8769 4210 8769 4216 8770 4210 8770 4222 8770 4215 8771 4221 8771 4219 8771 4220 8772 4218 8772 4221 8772 4220 8773 4221 8773 4215 8773 4225 8774 4216 8774 4222 8774 4223 8775 4208 8775 4215 8775 4215 8776 4224 8776 4223 8776 4223 8777 4224 8777 4225 8777 4223 8778 4225 8778 4226 8778 4226 8779 4225 8779 4222 8779 4219 8780 4225 8780 4224 8780 4219 8781 4216 8781 4225 8781 4224 8782 4215 8782 4219 8782 4237 8783 4223 8783 4227 8783 4227 8784 4223 8784 4226 8784 4237 8785 4227 8785 4239 8785 4338 8786 4229 8786 4228 8786 4228 8787 4229 8787 4320 8787 4237 8788 4228 8788 4407 8788 4237 8789 4407 8789 4229 8789 4229 8790 4338 8790 4237 8790 4237 8791 4338 8791 4230 8791 4237 8792 4230 8792 4238 8792 4238 8793 4395 8793 4230 8793 4238 8794 4230 8794 4338 8794 4239 8795 4227 8795 4233 8795 4233 8796 4227 8796 4240 8796 4240 8797 4227 8797 4231 8797 4235 8798 4240 8798 4412 8798 4294 8799 4236 8799 4231 8799 4231 8800 4236 8800 4234 8800 4231 8801 4234 8801 4235 8801 4231 8802 4235 8802 4412 8802 4231 8803 4412 8803 4240 8803 4388 8804 4233 8804 4232 8804 4232 8805 4233 8805 4240 8805 4240 8806 4411 8806 4232 8806 4240 8807 4233 8807 4411 8807 4410 8808 4243 8808 4409 8808 4410 8809 4409 8809 4390 8809 4243 8810 4410 8810 4409 8810 4243 8811 4409 8811 4240 8811 4240 8812 4409 8812 4233 8812 4236 8813 4140 8813 4234 8813 4234 8814 4140 8814 4405 8814 4240 8815 4234 8815 4236 8815 4236 8816 4234 8816 4140 8816 4234 8817 4240 8817 4235 8817 4409 8818 4239 8818 4233 8818 4406 8819 4338 8819 4240 8819 4406 8820 4402 8820 4236 8820 4237 8821 4238 8821 4294 8821 4294 8822 4238 8822 4406 8822 4294 8823 4406 8823 4236 8823 4236 8824 4402 8824 4406 8824 4236 8825 4406 8825 4240 8825 4408 8826 4239 8826 4337 8826 4239 8827 4408 8827 4228 8827 4239 8828 4228 8828 4237 8828 4409 8829 4243 8829 4239 8829 4239 8830 4243 8830 4337 8830 4408 8831 4337 8831 4228 8831 4228 8832 4337 8832 4338 8832 4238 8833 4338 8833 4406 8833 4240 8834 4373 8834 4371 8834 4240 8835 4241 8835 4374 8835 4240 8836 4371 8836 4345 8836 4240 8837 4345 8837 4243 8837 4345 8838 4371 8838 4242 8838 4345 8839 4242 8839 4344 8839 4374 8840 4242 8840 4373 8840 4374 8841 4373 8841 4240 8841 4242 8842 4374 8842 4344 8842 4344 8843 4374 8843 4241 8843 4344 8844 4241 8844 4240 8844 4358 8845 4344 8845 4415 8845 4415 8846 4344 8846 4244 8846 4139 8847 4345 8847 4357 8847 4246 8848 4245 8848 4139 8848 4139 8849 4245 8849 4345 8849 4345 8850 4245 8850 4156 8850 4345 8851 4156 8851 4335 8851 4250 8852 4335 8852 4419 8852 4419 8853 4335 8853 4156 8853 4419 8854 4156 8854 4138 8854 4357 8855 4345 8855 4358 8855 4358 8856 4345 8856 4344 8856 4416 8857 4244 8857 4248 8857 4248 8858 4244 8858 4340 8858 4415 8859 4244 8859 4247 8859 4247 8860 4244 8860 4416 8860 4247 8861 4416 8861 4414 8861 4248 8862 4340 8862 4249 8862 4248 8863 4249 8863 4250 8863 4250 8864 4249 8864 4335 8864 4251 8865 4252 8865 4152 8865 4251 8866 4152 8866 4278 8866 4278 8867 4152 8867 4361 8867 4278 8868 4361 8868 4160 8868 4279 8869 4254 8869 4251 8869 4251 8870 4254 8870 4252 8870 4256 8871 4254 8871 4253 8871 4253 8872 4254 8872 4279 8872 4253 8873 4279 8873 4255 8873 4255 8874 4279 8874 4280 8874 4256 8875 4253 8875 4257 8875 4257 8876 4253 8876 4261 8876 4257 8877 4261 8877 4262 8877 4262 8878 4258 8878 4257 8878 4157 8879 4257 8879 4210 8879 4210 8880 4257 8880 4258 8880 4210 8881 4258 8881 4222 8881 4222 8882 4258 8882 4259 8882 4222 8883 4259 8883 4226 8883 4226 8884 4259 8884 4292 8884 4259 8885 4148 8885 4260 8885 4258 8886 4150 8886 4259 8886 4259 8887 4150 8887 4148 8887 4260 8888 4148 8888 4330 8888 4260 8889 4330 8889 4261 8889 4261 8890 4330 8890 4329 8890 4261 8891 4329 8891 4262 8891 4258 8892 4262 8892 4150 8892 4260 8893 4263 8893 4259 8893 4259 8894 4263 8894 4267 8894 4259 8895 4267 8895 4292 8895 4292 8896 4267 8896 4270 8896 4270 8897 4267 8897 4264 8897 4290 8898 4263 8898 4271 8898 4288 8899 4267 8899 4289 8899 4289 8900 4267 8900 4263 8900 4289 8901 4263 8901 4290 8901 4265 8902 4266 8902 4284 8902 4286 8903 4264 8903 4285 8903 4285 8904 4264 8904 4267 8904 4264 8905 4286 8905 4271 8905 4267 8906 4288 8906 4269 8906 4285 8907 4267 8907 4268 8907 4268 8908 4267 8908 4269 8908 4268 8909 4269 8909 4265 8909 4265 8910 4269 8910 4266 8910 4286 8911 4282 8911 4271 8911 4271 8912 4282 8912 4284 8912 4284 8913 4266 8913 4290 8913 4284 8914 4290 8914 4271 8914 4271 8915 4272 8915 4264 8915 4264 8916 4272 8916 4182 8916 4264 8917 4182 8917 4270 8917 4271 8918 4277 8918 4272 8918 4272 8919 4277 8919 4274 8919 4272 8920 4274 8920 4273 8920 4273 8921 4274 8921 4275 8921 4273 8922 4275 8922 4184 8922 4184 8923 4275 8923 4276 8923 4184 8924 4276 8924 4185 8924 4160 8925 4276 8925 4278 8925 4278 8926 4276 8926 4275 8926 4277 8927 4278 8927 4274 8927 4274 8928 4278 8928 4275 8928 4281 8929 4251 8929 4277 8929 4277 8930 4251 8930 4278 8930 4279 8931 4251 8931 4280 8931 4280 8932 4251 8932 4281 8932 4281 8933 4263 8933 4280 8933 4280 8934 4263 8934 4260 8934 4280 8935 4260 8935 4255 8935 4261 8936 4253 8936 4260 8936 4260 8937 4253 8937 4255 8937 4263 8938 4281 8938 4271 8938 4271 8939 4281 8939 4277 8939 4273 8940 4184 8940 4272 8940 4272 8941 4184 8941 4186 8941 4286 8942 4283 8942 4282 8942 4282 8943 4283 8943 4284 8943 4284 8944 4283 8944 4386 8944 4284 8945 4386 8945 4265 8945 4265 8946 4386 8946 4385 8946 4265 8947 4385 8947 4268 8947 4268 8948 4385 8948 4285 8948 4285 8949 4385 8949 4384 8949 4285 8950 4384 8950 4286 8950 4286 8951 4384 8951 4283 8951 4287 8952 4266 8952 4269 8952 4287 8953 4269 8953 4387 8953 4387 8954 4269 8954 4288 8954 4387 8955 4288 8955 4388 8955 4388 8956 4288 8956 4289 8956 4388 8957 4289 8957 4291 8957 4291 8958 4289 8958 4290 8958 4291 8959 4290 8959 4287 8959 4287 8960 4290 8960 4266 8960 4270 8961 4293 8961 4231 8961 4270 8962 4231 8962 4292 8962 4292 8963 4231 8963 4227 8963 4292 8964 4227 8964 4226 8964 4231 8965 4293 8965 4294 8965 4294 8966 4293 8966 4175 8966 4294 8967 4175 8967 4237 8967 4237 8968 4175 8968 4312 8968 4237 8969 4312 8969 4209 8969 4237 8970 4209 8970 4223 8970 4306 8971 4307 8971 4312 8971 4312 8972 4307 8972 4209 8972 4308 8973 4303 8973 4307 8973 4307 8974 4303 8974 4295 8974 4307 8975 4295 8975 4209 8975 4295 8976 4297 8976 4296 8976 4303 8977 4325 8977 4295 8977 4295 8978 4325 8978 4297 8978 4325 8979 4303 8979 4302 8979 4325 8980 4302 8980 4299 8980 4326 8981 4298 8981 4296 8981 4326 8982 4296 8982 4297 8982 4298 8983 4326 8983 4299 8983 4298 8984 4299 8984 4302 8984 4300 8985 4301 8985 4303 8985 4303 8986 4301 8986 4302 8986 4308 8987 4304 8987 4303 8987 4303 8988 4304 8988 4305 8988 4303 8989 4305 8989 4300 8989 4202 8990 4304 8990 4309 8990 4309 8991 4304 8991 4308 8991 4307 8992 4323 8992 4324 8992 4306 8993 4316 8993 4315 8993 4306 8994 4315 8994 4307 8994 4307 8995 4315 8995 4313 8995 4307 8996 4313 8996 4323 8996 4319 8997 4308 8997 4324 8997 4324 8998 4308 8998 4307 8998 4309 8999 4310 8999 4306 8999 4306 9000 4310 9000 4316 9000 4308 9001 4319 9001 4311 9001 4308 9002 4311 9002 4318 9002 4318 9003 4317 9003 4308 9003 4308 9004 4317 9004 4309 9004 4309 9005 4317 9005 4310 9005 4318 9006 4311 9006 4321 9006 4318 9007 4321 9007 4313 9007 4313 9008 4321 9008 4323 9008 4197 9009 4309 9009 4194 9009 4194 9010 4309 9010 4306 9010 4194 9011 4306 9011 4312 9011 4314 9012 4318 9012 4313 9012 4314 9013 4313 9013 4315 9013 4314 9014 4315 9014 4395 9014 4395 9015 4315 9015 4316 9015 4395 9016 4316 9016 4396 9016 4396 9017 4316 9017 4310 9017 4396 9018 4310 9018 4317 9018 4396 9019 4317 9019 4397 9019 4397 9020 4317 9020 4318 9020 4397 9021 4318 9021 4314 9021 4324 9022 4394 9022 4319 9022 4319 9023 4394 9023 4311 9023 4311 9024 4394 9024 4320 9024 4311 9025 4320 9025 4321 9025 4321 9026 4320 9026 4322 9026 4321 9027 4322 9027 4323 9027 4323 9028 4322 9028 4324 9028 4324 9029 4322 9029 4394 9029 4325 9030 4328 9030 4151 9030 4326 9031 4393 9031 4327 9031 4326 9032 4327 9032 4299 9032 4299 9033 4327 9033 4328 9033 4299 9034 4328 9034 4325 9034 4149 9035 4150 9035 4262 9035 4149 9036 4262 9036 4390 9036 4390 9037 4262 9037 4329 9037 4390 9038 4329 9038 4389 9038 4389 9039 4329 9039 4330 9039 4389 9040 4330 9040 4331 9040 4331 9041 4330 9041 4148 9041 4204 9042 4203 9042 4366 9042 4366 9043 4203 9043 4332 9043 4366 9044 4332 9044 4364 9044 4364 9045 4332 9045 4333 9045 4334 9046 4159 9046 4332 9046 4332 9047 4159 9047 4333 9047 4370 9048 4369 9048 4336 9048 4370 9049 4336 9049 4339 9049 4339 9050 4336 9050 4249 9050 4249 9051 4336 9051 4335 9051 4335 9052 4336 9052 4369 9052 4335 9053 4369 9053 4337 9053 4337 9054 4369 9054 4338 9054 4369 9055 4370 9055 4338 9055 4338 9056 4370 9056 4339 9056 4338 9057 4339 9057 4249 9057 4244 9058 4338 9058 4340 9058 4249 9059 4340 9059 4338 9059 4141 9060 4343 9060 4342 9060 4141 9061 4341 9061 4240 9061 4240 9062 4341 9062 4379 9062 4344 9063 4379 9063 4342 9063 4142 9064 4244 9064 4378 9064 4378 9065 4244 9065 4344 9065 4342 9066 4343 9066 4344 9066 4344 9067 4343 9067 4378 9067 4142 9068 4338 9068 4244 9068 4379 9069 4344 9069 4240 9069 4338 9070 4142 9070 4343 9070 4338 9071 4343 9071 4240 9071 4240 9072 4343 9072 4141 9072 4143 9073 4376 9073 4345 9073 4337 9074 4375 9074 4144 9074 4335 9075 4144 9075 4145 9075 4335 9076 4145 9076 4345 9076 4144 9077 4335 9077 4337 9077 4345 9078 4145 9078 4143 9078 4375 9079 4143 9079 4145 9079 4243 9080 4377 9080 4143 9080 4345 9081 4376 9081 4243 9081 4243 9082 4376 9082 4377 9082 4243 9083 4143 9083 4375 9083 4243 9084 4375 9084 4337 9084 4174 9085 4405 9085 4173 9085 4173 9086 4405 9086 4404 9086 4173 9087 4404 9087 4346 9087 4173 9088 4346 9088 4165 9088 4165 9089 4346 9089 4403 9089 4165 9090 4403 9090 4347 9090 4347 9091 4403 9091 4348 9091 4347 9092 4348 9092 4174 9092 4174 9093 4348 9093 4405 9093 4400 9094 4190 9094 4401 9094 4401 9095 4190 9095 4349 9095 4401 9096 4349 9096 4402 9096 4402 9097 4349 9097 4398 9097 4398 9098 4349 9098 4195 9098 4398 9099 4195 9099 4350 9099 4398 9100 4350 9100 4399 9100 4399 9101 4350 9101 4191 9101 4351 9102 4381 9102 4380 9102 4351 9103 4380 9103 4147 9103 4352 9104 4383 9104 4382 9104 4352 9105 4382 9105 4353 9105 4353 9106 4382 9106 4381 9106 4353 9107 4381 9107 4351 9107 4392 9108 4218 9108 4355 9108 4355 9109 4218 9109 4354 9109 4355 9110 4354 9110 4391 9110 4391 9111 4354 9111 4219 9111 4391 9112 4219 9112 4356 9112 4356 9113 4219 9113 4221 9113 4356 9114 4221 9114 4392 9114 4392 9115 4221 9115 4218 9115 4218 9116 4214 9116 4217 9116 4256 9117 4357 9117 4152 9117 4152 9118 4357 9118 4372 9118 4362 9119 4357 9119 4358 9119 4362 9120 4372 9120 4357 9120 4358 9121 4363 9121 4359 9121 4152 9122 4372 9122 4360 9122 4152 9123 4363 9123 4361 9123 4361 9124 4363 9124 4358 9124 4359 9125 4360 9125 4358 9125 4358 9126 4360 9126 4362 9126 4360 9127 4359 9127 4152 9127 4152 9128 4359 9128 4363 9128 4366 9129 4250 9129 4153 9129 4366 9130 4153 9130 4206 9130 4333 9131 4189 9131 4364 9131 4364 9132 4248 9132 4368 9132 4368 9133 4248 9133 4250 9133 4364 9134 4368 9134 4367 9134 4367 9135 4365 9135 4146 9135 4364 9136 4146 9136 4366 9136 4366 9137 4146 9137 4365 9137 4366 9138 4365 9138 4250 9138 4367 9139 4146 9139 4364 9139 4365 9140 4367 9140 4250 9140 4250 9141 4367 9141 4368 9141 4365 9142 4369 9142 4336 9142 4365 9143 4336 9143 4146 9143 4146 9144 4336 9144 4369 9144 4367 9145 4370 9145 4368 9145 4368 9146 4370 9146 4339 9146 4371 9147 4372 9147 4242 9147 4242 9148 4372 9148 4362 9148 4242 9149 4362 9149 4360 9149 4242 9150 4360 9150 4373 9150 4374 9151 4359 9151 4241 9151 4241 9152 4359 9152 4363 9152 4145 9153 4138 9153 4375 9153 4143 9154 4246 9154 4376 9154 4376 9155 4246 9155 4377 9155 4378 9156 4343 9156 4414 9156 4341 9157 4413 9157 4379 9157 4379 9158 4413 9158 4342 9158 4382 9159 4380 9159 4381 9159 4382 9160 4383 9160 4380 9160 4283 9161 4384 9161 4385 9161 4385 9162 4386 9162 4283 9162 4388 9163 4291 9163 4287 9163 4388 9164 4287 9164 4387 9164 4390 9165 4389 9165 4331 9165 4390 9166 4331 9166 4149 9166 4391 9167 4356 9167 4392 9167 4391 9168 4392 9168 4355 9168 4151 9169 4327 9169 4393 9169 4151 9170 4328 9170 4327 9170 4320 9171 4394 9171 4322 9171 4395 9172 4396 9172 4397 9172 4395 9173 4397 9173 4314 9173 4402 9174 4398 9174 4399 9174 4402 9175 4399 9175 4400 9175 4402 9176 4400 9176 4401 9176 4405 9177 4348 9177 4403 9177 4405 9178 4403 9178 4346 9178 4405 9179 4346 9179 4404 9179 4395 9180 4238 9180 4314 9180 4314 9181 4238 9181 4230 9181 4320 9182 4229 9182 4407 9182 4320 9183 4407 9183 4228 9183 4390 9184 4409 9184 4410 9184 4388 9185 4232 9185 4411 9185 4388 9186 4411 9186 4233 9186 4283 9187 4412 9187 4385 9187 4162 9188 4413 9188 4163 9188 4163 9189 4413 9189 4415 9189 4414 9190 4416 9190 4417 9190 4245 9191 4246 9191 4418 9191 4418 9192 4246 9192 4158 9192 4419 9193 4138 9193 4420 9193 4435 9194 4424 9194 4422 9194 4425 9195 4454 9195 4424 9195 4434 9196 4421 9196 4425 9196 4425 9197 4421 9197 4454 9197 4422 9198 4424 9198 4454 9198 4430 9199 4428 9199 4431 9199 4426 9200 4421 9200 4434 9200 4426 9201 4456 9201 4421 9201 4456 9202 4423 9202 4427 9202 4428 9203 4427 9203 4423 9203 4428 9204 4455 9204 4427 9204 4430 9205 4455 9205 4428 9205 4429 9206 4455 9206 4430 9206 4429 9207 4422 9207 4455 9207 4429 9208 4435 9208 4422 9208 4433 9209 4423 9209 4456 9209 4433 9210 4456 9210 4426 9210 4425 9211 4424 9211 4445 9211 4445 9212 4424 9212 4435 9212 4435 9213 4429 9213 4441 9213 4441 9214 4429 9214 4443 9214 4443 9215 4429 9215 4430 9215 4443 9216 4430 9216 4431 9216 4432 9217 4431 9217 4428 9217 4432 9218 4428 9218 4423 9218 4432 9219 4423 9219 4433 9219 4434 9220 4448 9220 4426 9220 4425 9221 4448 9221 4434 9221 4431 9222 4432 9222 4437 9222 4432 9223 4433 9223 4436 9223 4450 9224 4439 9224 4436 9224 4438 9225 4440 9225 4435 9225 4436 9226 4439 9226 4437 9226 4436 9227 4437 9227 4432 9227 4442 9228 4439 9228 4440 9228 4438 9229 4435 9229 4441 9229 4444 9230 4437 9230 4439 9230 4444 9231 4439 9231 4442 9231 4442 9232 4440 9232 4438 9232 4442 9233 4438 9233 4441 9233 4442 9234 4441 9234 4443 9234 4444 9235 4442 9235 4443 9235 4444 9236 4443 9236 4431 9236 4431 9237 4437 9237 4444 9237 4446 9238 4448 9238 4425 9238 4449 9239 4448 9239 4453 9239 4453 9240 4448 9240 4446 9240 4446 9241 4425 9241 4445 9241 4451 9242 4446 9242 4445 9242 4447 9243 4433 9243 4426 9243 4440 9244 4453 9244 4446 9244 4440 9245 4446 9245 4451 9245 4451 9246 4445 9246 4435 9246 4449 9247 4447 9247 4426 9247 4449 9248 4426 9248 4448 9248 4447 9249 4449 9249 4450 9249 4453 9250 4450 9250 4449 9250 4440 9251 4450 9251 4453 9251 4440 9252 4452 9252 4450 9252 4455 9253 4422 9253 4454 9253 4454 9254 4421 9254 4455 9254 4421 9255 4456 9255 4455 9255 4456 9256 4427 9256 4455 9256 4466 9257 4469 9257 4460 9257 4469 9258 4464 9258 4460 9258 4464 9259 4457 9259 4460 9259 4463 9260 4457 9260 4464 9260 4463 9261 4459 9261 4457 9261 4465 9262 4489 9262 4461 9262 4468 9263 4489 9263 4465 9263 4489 9264 4468 9264 4466 9264 4472 9265 4458 9265 4463 9265 4458 9266 4459 9266 4463 9266 4458 9267 4471 9267 4488 9267 4488 9268 4471 9268 4490 9268 4471 9269 4462 9269 4490 9269 4470 9270 4490 9270 4462 9270 4470 9271 4461 9271 4490 9271 4465 9272 4461 9272 4470 9272 4489 9273 4466 9273 4460 9273 4471 9274 4458 9274 4472 9274 4463 9275 4464 9275 4467 9275 4467 9276 4464 9276 4469 9276 4467 9277 4469 9277 4473 9277 4469 9278 4466 9278 4468 9278 4468 9279 4465 9279 4470 9279 4462 9280 4471 9280 4474 9280 4463 9281 4467 9281 4481 9281 4468 9282 4475 9282 4469 9282 4470 9283 4478 9283 4468 9283 4470 9284 4462 9284 4479 9284 4479 9285 4478 9285 4470 9285 4485 9286 4476 9286 4474 9286 4475 9287 4486 9287 4473 9287 4485 9288 4477 9288 4476 9288 4477 9289 4486 9289 4475 9289 4462 9290 4474 9290 4476 9290 4478 9291 4477 9291 4475 9291 4473 9292 4469 9292 4475 9292 4479 9293 4462 9293 4476 9293 4479 9294 4476 9294 4477 9294 4478 9295 4475 9295 4468 9295 4479 9296 4477 9296 4478 9296 4487 9297 4483 9297 4486 9297 4482 9298 4480 9298 4481 9298 4481 9299 4480 9299 4463 9299 4480 9300 4472 9300 4463 9300 4483 9301 4481 9301 4467 9301 4487 9302 4482 9302 4481 9302 4474 9303 4471 9303 4484 9303 4484 9304 4471 9304 4472 9304 4484 9305 4482 9305 4487 9305 4482 9306 4484 9306 4480 9306 4487 9307 4481 9307 4483 9307 4483 9308 4467 9308 4473 9308 4480 9309 4484 9309 4472 9309 4484 9310 4487 9310 4485 9310 4486 9311 4485 9311 4487 9311 4488 9312 4459 9312 4458 9312 4461 9313 4489 9313 4490 9313 4489 9314 4460 9314 4490 9314 4490 9315 4460 9315 4457 9315 4457 9316 4459 9316 4490 9316 4459 9317 4488 9317 4490 9317 4499 9318 4537 9318 4491 9318 4499 9319 4491 9319 4515 9319 4505 9320 4503 9320 4513 9320 4513 9321 4503 9321 4512 9321 4562 9322 4563 9322 4568 9322 4555 9323 4521 9323 4509 9323 4563 9324 4550 9324 4519 9324 4519 9325 4550 9325 4493 9325 4530 9326 4564 9326 4493 9326 4493 9327 4564 9327 4519 9327 4564 9328 4530 9328 4532 9328 4564 9329 4532 9329 4492 9329 4553 9330 4494 9330 4529 9330 4495 9331 4554 9331 4553 9331 4495 9332 4553 9332 4549 9332 4549 9333 4553 9333 4529 9333 4555 9334 4554 9334 4495 9334 4521 9335 4555 9335 4495 9335 4550 9336 4563 9336 4505 9336 4505 9337 4563 9337 4562 9337 4521 9338 4505 9338 4513 9338 4521 9339 4513 9339 4509 9339 4550 9340 4505 9340 4521 9340 4565 9341 4588 9341 4566 9341 4588 9342 4590 9342 4566 9342 4565 9343 4518 9343 4588 9343 4567 9344 4498 9344 4518 9344 4498 9345 4587 9345 4539 9345 4587 9346 4581 9346 4586 9346 4524 9347 4586 9347 4581 9347 4586 9348 4524 9348 4585 9348 4524 9349 4584 9349 4585 9349 4583 9350 4584 9350 4524 9350 4587 9351 4497 9351 4581 9351 4568 9352 4503 9352 4567 9352 4512 9353 4498 9353 4567 9353 4512 9354 4567 9354 4503 9354 4512 9355 4587 9355 4498 9355 4512 9356 4497 9356 4587 9356 4496 9357 4567 9357 4518 9357 4507 9358 4587 9358 4559 9358 4559 9359 4587 9359 4586 9359 4559 9360 4586 9360 4558 9360 4558 9361 4586 9361 4585 9361 4585 9362 4526 9362 4558 9362 4558 9363 4526 9363 4541 9363 4550 9364 4573 9364 4574 9364 4550 9365 4574 9365 4493 9365 4493 9366 4574 9366 4575 9366 4493 9367 4575 9367 4530 9367 4575 9368 4572 9368 4530 9368 4502 9369 4533 9369 4494 9369 4571 9370 4570 9370 4544 9370 4571 9371 4544 9371 4545 9371 4499 9372 4566 9372 4591 9372 4591 9373 4566 9373 4590 9373 4545 9374 4500 9374 4514 9374 4516 9375 4499 9375 4515 9375 4544 9376 4564 9376 4500 9376 4544 9377 4500 9377 4545 9377 4578 9378 4502 9378 4543 9378 4584 9379 4583 9379 4523 9379 4511 9380 4556 9380 4535 9380 4556 9381 4543 9381 4535 9381 4582 9382 4538 9382 4523 9382 4501 9383 4538 9383 4582 9383 4556 9384 4578 9384 4543 9384 4494 9385 4553 9385 4556 9385 4548 9386 4494 9386 4556 9386 4548 9387 4556 9387 4511 9387 4492 9388 4500 9388 4564 9388 4491 9389 4560 9389 4516 9389 4491 9390 4516 9390 4515 9390 4508 9391 4512 9391 4503 9391 4579 9392 4497 9392 4508 9392 4520 9393 4577 9393 4502 9393 4520 9394 4502 9394 4578 9394 4520 9395 4576 9395 4577 9395 4579 9396 4508 9396 4576 9396 4508 9397 4568 9397 4573 9397 4573 9398 4568 9398 4574 9398 4569 9399 4574 9399 4568 9399 4569 9400 4575 9400 4574 9400 4575 9401 4569 9401 4570 9401 4570 9402 4572 9402 4575 9402 4570 9403 4571 9403 4572 9403 4497 9404 4512 9404 4508 9404 4508 9405 4503 9405 4568 9405 4580 9406 4579 9406 4576 9406 4504 9407 4522 9407 4552 9407 4522 9408 4501 9408 4582 9408 4522 9409 4582 9409 4552 9409 4540 9410 4509 9410 4507 9410 4540 9411 4559 9411 4551 9411 4558 9412 4552 9412 4559 9412 4559 9413 4552 9413 4551 9413 4552 9414 4557 9414 4504 9414 4558 9415 4557 9415 4552 9415 4540 9416 4507 9416 4559 9416 4505 9417 4539 9417 4507 9417 4506 9418 4560 9418 4525 9418 4517 9419 4561 9419 4506 9419 4517 9420 4506 9420 4525 9420 4517 9421 4562 9421 4561 9421 4539 9422 4562 9422 4517 9422 4539 9423 4505 9423 4562 9423 4507 9424 4513 9424 4505 9424 4509 9425 4513 9425 4507 9425 4550 9426 4521 9426 4508 9426 4550 9427 4508 9427 4573 9427 4507 9428 4539 9428 4587 9428 4567 9429 4562 9429 4568 9429 4579 9430 4555 9430 4509 9430 4579 9431 4509 9431 4497 9431 4497 9432 4509 9432 4540 9432 4591 9433 4537 9433 4499 9433 4537 9434 4591 9434 4491 9434 4536 9435 4500 9435 4546 9435 4536 9436 4546 9436 4514 9436 4514 9437 4546 9437 4545 9437 4523 9438 4538 9438 4522 9438 4522 9439 4538 9439 4501 9439 4548 9440 4511 9440 4510 9440 4510 9441 4535 9441 4543 9441 4535 9442 4510 9442 4511 9442 4513 9443 4512 9443 4505 9443 4505 9444 4512 9444 4503 9444 4536 9445 4514 9445 4546 9445 4536 9446 4546 9446 4500 9446 4500 9447 4546 9447 4514 9447 4562 9448 4567 9448 4496 9448 4496 9449 4561 9449 4562 9449 4561 9450 4496 9450 4565 9450 4561 9451 4565 9451 4506 9451 4506 9452 4565 9452 4566 9452 4506 9453 4566 9453 4499 9453 4506 9454 4499 9454 4516 9454 4589 9455 4517 9455 4528 9455 4518 9456 4517 9456 4588 9456 4588 9457 4517 9457 4589 9457 4498 9458 4539 9458 4518 9458 4518 9459 4539 9459 4517 9459 4527 9460 4560 9460 4591 9460 4591 9461 4560 9461 4491 9461 4564 9462 4544 9462 4570 9462 4564 9463 4570 9463 4519 9463 4519 9464 4569 9464 4568 9464 4519 9465 4568 9465 4563 9465 4545 9466 4546 9466 4547 9466 4547 9467 4546 9467 4492 9467 4555 9468 4579 9468 4580 9468 4580 9469 4554 9469 4555 9469 4554 9470 4580 9470 4520 9470 4554 9471 4520 9471 4553 9471 4553 9472 4520 9472 4578 9472 4553 9473 4578 9473 4556 9473 4534 9474 4495 9474 4549 9474 4576 9475 4495 9475 4577 9475 4577 9476 4495 9476 4534 9476 4508 9477 4521 9477 4576 9477 4576 9478 4521 9478 4495 9478 4502 9479 4494 9479 4510 9479 4510 9480 4494 9480 4548 9480 4523 9481 4522 9481 4531 9481 4531 9482 4522 9482 4504 9482 4552 9483 4582 9483 4583 9483 4552 9484 4583 9484 4524 9484 4552 9485 4524 9485 4551 9485 4551 9486 4524 9486 4581 9486 4551 9487 4581 9487 4540 9487 4540 9488 4581 9488 4497 9488 4531 9489 4504 9489 4525 9489 4531 9490 4525 9490 4527 9490 4528 9491 4558 9491 4589 9491 4589 9492 4558 9492 4541 9492 4526 9493 4527 9493 4590 9493 4526 9494 4531 9494 4527 9494 4525 9495 4557 9495 4528 9495 4494 9496 4533 9496 4492 9496 4547 9497 4492 9497 4533 9497 4534 9498 4549 9498 4542 9498 4534 9499 4533 9499 4502 9499 4572 9500 4547 9500 4533 9500 4572 9501 4533 9501 4534 9501 4529 9502 4532 9502 4549 9502 4530 9503 4549 9503 4532 9503 4558 9504 4528 9504 4557 9504 4525 9505 4504 9505 4557 9505 4541 9506 4526 9506 4589 9506 4532 9507 4529 9507 4494 9507 4494 9508 4492 9508 4532 9508 4542 9509 4572 9509 4534 9509 4590 9510 4589 9510 4526 9510 4527 9511 4525 9511 4560 9511 4530 9512 4542 9512 4549 9512 4572 9513 4542 9513 4530 9513 4492 9514 4546 9514 4500 9514 4516 9515 4560 9515 4506 9515 4496 9516 4518 9516 4565 9516 4569 9517 4519 9517 4570 9517 4547 9518 4572 9518 4571 9518 4545 9519 4547 9519 4571 9519 4502 9520 4577 9520 4534 9520 4543 9521 4502 9521 4510 9521 4580 9522 4576 9522 4520 9522 4583 9523 4582 9523 4523 9523 4531 9524 4526 9524 4584 9524 4523 9525 4531 9525 4584 9525 4526 9526 4585 9526 4584 9526 4590 9527 4588 9527 4589 9527 4527 9528 4591 9528 4590 9528 4678 9529 4677 9529 4654 9529 4592 9530 4607 9530 4623 9530 4593 9531 4634 9531 4622 9531 4612 9532 4619 9532 4617 9532 4612 9533 4617 9533 4618 9533 4663 9534 4611 9534 4664 9534 4664 9535 4611 9535 4650 9535 4654 9536 4648 9536 4614 9536 4650 9537 4649 9537 4624 9537 4596 9538 4624 9538 4649 9538 4624 9539 4596 9539 4661 9539 4661 9540 4596 9540 4594 9540 4661 9541 4594 9541 4595 9541 4676 9542 4630 9542 4597 9542 4647 9543 4676 9543 4597 9543 4647 9544 4626 9544 4676 9544 4648 9545 4626 9545 4647 9545 4654 9546 4626 9546 4648 9546 4648 9547 4618 9547 4614 9547 4650 9548 4612 9548 4618 9548 4650 9549 4618 9549 4648 9549 4611 9550 4612 9550 4650 9550 4662 9551 4687 9551 4598 9551 4662 9552 4686 9552 4687 9552 4663 9553 4685 9553 4686 9553 4681 9554 4685 9554 4628 9554 4679 9555 4682 9555 4599 9555 4682 9556 4679 9556 4683 9556 4603 9557 4683 9557 4679 9557 4681 9558 4628 9558 4599 9558 4664 9559 4619 9559 4663 9559 4619 9560 4685 9560 4663 9560 4619 9561 4628 9561 4685 9561 4617 9562 4678 9562 4628 9562 4617 9563 4628 9563 4619 9563 4662 9564 4663 9564 4686 9564 4681 9565 4599 9565 4682 9565 4615 9566 4681 9566 4656 9566 4656 9567 4681 9567 4682 9567 4656 9568 4682 9568 4684 9568 4683 9569 4639 9569 4684 9569 4684 9570 4639 9570 4657 9570 4688 9571 4640 9571 4629 9571 4650 9572 4670 9572 4649 9572 4649 9573 4670 9573 4600 9573 4649 9574 4600 9574 4601 9574 4649 9575 4601 9575 4596 9575 4596 9576 4601 9576 4643 9576 4674 9577 4641 9577 4630 9577 4630 9578 4641 9578 4633 9578 4669 9579 4667 9579 4668 9579 4669 9580 4668 9580 4625 9580 4602 9581 4598 9581 4688 9581 4688 9582 4598 9582 4687 9582 4668 9583 4620 9583 4635 9583 4644 9584 4620 9584 4668 9584 4658 9585 4602 9585 4621 9585 4621 9586 4602 9586 4636 9586 4625 9587 4668 9587 4635 9587 4660 9588 4602 9588 4658 9588 4667 9589 4661 9589 4668 9589 4668 9590 4661 9590 4644 9590 4674 9591 4622 9591 4604 9591 4674 9592 4604 9592 4606 9592 4683 9593 4603 9593 4605 9593 4683 9594 4605 9594 4623 9594 4655 9595 4604 9595 4634 9595 4634 9596 4604 9596 4593 9596 4607 9597 4592 9597 4651 9597 4651 9598 4592 9598 4605 9598 4605 9599 4592 9599 4623 9599 4593 9600 4604 9600 4622 9600 4676 9601 4606 9601 4655 9601 4655 9602 4606 9602 4604 9602 4603 9603 4653 9603 4605 9603 4605 9604 4653 9604 4651 9604 4630 9605 4676 9605 4655 9605 4646 9606 4630 9606 4655 9606 4646 9607 4655 9607 4634 9607 4595 9608 4644 9608 4661 9608 4629 9609 4660 9609 4658 9609 4616 9610 4629 9610 4658 9610 4616 9611 4658 9611 4621 9611 4677 9612 4678 9612 4617 9612 4677 9613 4673 9613 4675 9613 4675 9614 4672 9614 4606 9614 4674 9615 4606 9615 4672 9615 4677 9616 4671 9616 4673 9616 4677 9617 4617 9617 4671 9617 4671 9618 4617 9618 4670 9618 4670 9619 4617 9619 4664 9619 4670 9620 4664 9620 4600 9620 4665 9621 4601 9621 4600 9621 4666 9622 4601 9622 4665 9622 4667 9623 4669 9623 4666 9623 4666 9624 4669 9624 4601 9624 4619 9625 4664 9625 4617 9625 4600 9626 4664 9626 4665 9626 4608 9627 4627 9627 4653 9627 4627 9628 4607 9628 4651 9628 4627 9629 4651 9629 4653 9629 4613 9630 4656 9630 4652 9630 4652 9631 4656 9631 4684 9631 4652 9632 4657 9632 4653 9632 4653 9633 4657 9633 4631 9633 4653 9634 4631 9634 4608 9634 4684 9635 4657 9635 4652 9635 4613 9636 4615 9636 4656 9636 4612 9637 4615 9637 4613 9637 4612 9638 4637 9638 4615 9638 4660 9639 4629 9639 4610 9639 4609 9640 4659 9640 4660 9640 4609 9641 4660 9641 4610 9641 4637 9642 4659 9642 4609 9642 4611 9643 4659 9643 4637 9643 4637 9644 4612 9644 4611 9644 4613 9645 4618 9645 4612 9645 4614 9646 4618 9646 4613 9646 4650 9647 4648 9647 4670 9647 4671 9648 4670 9648 4648 9648 4637 9649 4685 9649 4615 9649 4685 9650 4681 9650 4615 9650 4678 9651 4654 9651 4614 9651 4678 9652 4614 9652 4613 9652 4688 9653 4636 9653 4602 9653 4621 9654 4636 9654 4688 9654 4621 9655 4688 9655 4616 9655 4620 9656 4644 9656 4625 9656 4627 9657 4623 9657 4607 9657 4646 9658 4634 9658 4622 9658 4634 9659 4593 9659 4622 9659 4618 9660 4617 9660 4619 9660 4618 9661 4619 9661 4612 9661 4593 9662 4622 9662 4634 9662 4611 9663 4663 9663 4662 9663 4662 9664 4659 9664 4611 9664 4659 9665 4662 9665 4660 9665 4660 9666 4662 9666 4598 9666 4660 9667 4598 9667 4602 9667 4687 9668 4609 9668 4638 9668 4686 9669 4637 9669 4609 9669 4686 9670 4609 9670 4687 9670 4685 9671 4637 9671 4686 9671 4688 9672 4629 9672 4616 9672 4661 9673 4667 9673 4624 9673 4624 9674 4667 9674 4666 9674 4624 9675 4665 9675 4664 9675 4624 9676 4664 9676 4650 9676 4645 9677 4625 9677 4595 9677 4654 9678 4677 9678 4626 9678 4675 9679 4626 9679 4677 9679 4626 9680 4675 9680 4676 9680 4676 9681 4675 9681 4606 9681 4673 9682 4647 9682 4672 9682 4672 9683 4647 9683 4641 9683 4641 9684 4647 9684 4642 9684 4671 9685 4648 9685 4673 9685 4673 9686 4648 9686 4647 9686 4674 9687 4630 9687 4622 9687 4622 9688 4630 9688 4646 9688 4623 9689 4627 9689 4680 9689 4680 9690 4627 9690 4608 9690 4653 9691 4603 9691 4652 9691 4652 9692 4603 9692 4679 9692 4652 9693 4679 9693 4599 9693 4652 9694 4599 9694 4613 9694 4613 9695 4599 9695 4628 9695 4680 9696 4608 9696 4629 9696 4680 9697 4629 9697 4640 9697 4632 9698 4638 9698 4639 9698 4632 9699 4640 9699 4687 9699 4639 9700 4680 9700 4640 9700 4639 9701 4640 9701 4632 9701 4631 9702 4657 9702 4610 9702 4610 9703 4657 9703 4638 9703 4645 9704 4595 9704 4630 9704 4645 9705 4630 9705 4633 9705 4641 9706 4642 9706 4643 9706 4643 9707 4645 9707 4641 9707 4641 9708 4645 9708 4633 9708 4596 9709 4597 9709 4594 9709 4631 9710 4610 9710 4629 9710 4629 9711 4608 9711 4631 9711 4594 9712 4597 9712 4630 9712 4630 9713 4595 9713 4594 9713 4596 9714 4643 9714 4642 9714 4596 9715 4642 9715 4597 9715 4625 9716 4635 9716 4620 9716 4687 9717 4638 9717 4632 9717 4657 9718 4639 9718 4638 9718 4595 9719 4625 9719 4644 9719 4597 9720 4642 9720 4647 9720 4665 9721 4624 9721 4666 9721 4645 9722 4643 9722 4669 9722 4625 9723 4645 9723 4669 9723 4643 9724 4601 9724 4669 9724 4675 9725 4673 9725 4672 9725 4641 9726 4674 9726 4672 9726 4678 9727 4613 9727 4628 9727 4680 9728 4639 9728 4683 9728 4623 9729 4680 9729 4683 9729 4684 9730 4682 9730 4683 9730 4640 9731 4688 9731 4687 9731 4703 9732 4701 9732 4704 9732 4705 9733 4700 9733 4691 9733 4698 9734 4699 9734 4700 9734 4689 9735 4697 9735 4704 9735 4689 9736 4704 9736 4690 9736 4690 9737 4704 9737 4696 9737 4690 9738 4696 9738 4695 9738 4695 9739 4696 9739 4692 9739 4701 9740 4705 9740 4704 9740 4693 9741 4695 9741 4692 9741 4697 9742 4694 9742 4693 9742 4693 9743 4694 9743 4695 9743 4695 9744 4689 9744 4690 9744 4689 9745 4694 9745 4697 9745 4689 9746 4695 9746 4694 9746 4693 9747 4702 9747 4697 9747 4691 9748 4692 9748 4696 9748 4693 9749 4692 9749 4702 9749 4696 9750 4705 9750 4691 9750 4696 9751 4704 9751 4705 9751 4697 9752 4703 9752 4704 9752 4703 9753 4697 9753 4702 9753 4691 9754 4700 9754 4692 9754 4698 9755 4700 9755 4701 9755 4698 9756 4701 9756 4699 9756 4699 9757 4703 9757 4702 9757 4699 9758 4702 9758 4700 9758 4700 9759 4705 9759 4701 9759 4699 9760 4701 9760 4703 9760 4692 9761 4700 9761 4702 9761 4706 9762 5182 9762 4731 9762 4731 9763 5182 9763 5179 9763 4727 9764 5179 9764 5177 9764 4727 9765 5177 9765 4728 9765 4707 9766 5173 9766 4706 9766 5168 9767 5151 9767 5031 9767 4827 9768 5055 9768 4830 9768 5054 9769 5055 9769 4827 9769 5054 9770 4827 9770 4831 9770 4832 9771 5067 9771 4831 9771 4831 9772 5067 9772 5054 9772 4708 9773 5067 9773 4832 9773 5067 9774 4708 9774 5053 9774 4708 9775 5066 9775 5053 9775 4709 9776 5066 9776 4708 9776 4709 9777 4710 9777 5057 9777 4711 9778 5058 9778 4710 9778 4710 9779 5058 9779 5057 9779 4830 9780 5062 9780 5058 9780 4830 9781 5058 9781 4711 9781 5055 9782 5062 9782 4830 9782 4712 9783 5033 9783 4834 9783 5033 9784 4712 9784 5020 9784 5020 9785 4712 9785 5036 9785 4835 9786 5036 9786 4712 9786 4835 9787 5019 9787 5036 9787 4840 9788 5019 9788 4835 9788 5018 9789 5019 9789 4840 9789 4713 9790 5018 9790 4840 9790 5023 9791 5018 9791 4713 9791 4714 9792 5023 9792 4713 9792 4714 9793 4838 9793 5025 9793 4715 9794 5025 9794 4838 9794 4715 9795 5032 9795 5025 9795 4834 9796 5033 9796 5032 9796 4834 9797 5032 9797 4715 9797 4743 9798 4997 9798 4742 9798 4742 9799 4997 9799 4717 9799 4742 9800 4717 9800 4744 9800 4744 9801 4717 9801 5002 9801 4744 9802 5002 9802 5107 9802 5107 9803 5002 9803 5049 9803 5105 9804 5106 9804 5000 9804 5105 9805 5000 9805 4999 9805 5105 9806 4999 9806 4719 9806 4719 9807 4999 9807 4718 9807 4980 9808 4890 9808 4977 9808 4977 9809 4890 9809 4720 9809 4977 9810 4720 9810 4982 9810 4982 9811 4720 9811 4721 9811 4982 9812 4721 9812 4722 9812 4722 9813 4721 9813 4723 9813 4722 9814 4723 9814 4979 9814 4979 9815 4723 9815 4890 9815 4979 9816 4890 9816 4980 9816 4973 9817 4886 9817 4724 9817 4973 9818 4724 9818 4725 9818 4725 9819 4724 9819 4889 9819 4725 9820 4889 9820 4976 9820 4976 9821 4889 9821 4887 9821 4976 9822 4887 9822 4726 9822 4726 9823 4887 9823 4886 9823 4726 9824 4886 9824 4973 9824 4968 9825 4731 9825 5179 9825 4968 9826 5179 9826 4727 9826 4968 9827 4727 9827 4967 9827 4967 9828 4727 9828 4728 9828 4965 9829 4728 9829 4729 9829 4965 9830 4729 9830 4966 9830 4966 9831 4729 9831 5175 9831 4966 9832 5175 9832 4963 9832 4963 9833 5175 9833 4730 9833 4963 9834 4730 9834 4964 9834 4964 9835 4730 9835 5173 9835 4964 9836 5173 9836 4707 9836 4707 9837 4706 9837 4936 9837 4731 9838 4936 9838 4706 9838 4765 9839 5169 9839 5086 9839 4732 9840 4737 9840 5114 9840 5180 9841 4849 9841 5181 9841 5181 9842 4836 9842 4737 9842 4735 9843 5179 9843 5181 9843 5181 9844 4737 9844 4735 9844 4735 9845 4737 9845 4732 9845 5135 9846 4733 9846 5133 9846 4733 9847 5135 9847 4833 9847 4833 9848 5135 9848 5130 9848 4833 9849 5130 9849 4734 9849 4734 9850 5130 9850 4735 9850 4735 9851 5130 9851 5131 9851 4735 9852 5131 9852 5133 9852 4735 9853 5133 9853 4733 9853 4735 9854 4732 9854 4959 9854 4735 9855 4959 9855 5075 9855 4735 9856 5075 9856 4734 9856 4734 9857 5075 9857 5077 9857 5077 9858 4736 9858 4734 9858 4734 9859 4736 9859 4837 9859 4836 9860 4837 9860 4736 9860 5097 9861 5155 9861 5111 9861 5111 9862 5155 9862 5153 9862 4738 9863 4739 9863 5157 9863 4943 9864 4740 9864 5078 9864 5078 9865 4740 9865 4759 9865 5140 9866 4943 9866 5078 9866 4932 9867 5137 9867 5157 9867 5157 9868 5137 9868 4738 9868 5137 9869 4932 9869 5140 9869 5140 9870 4932 9870 4943 9870 5155 9871 5097 9871 5006 9871 5063 9872 5110 9872 5109 9872 4739 9873 4738 9873 5160 9873 5160 9874 4738 9874 5143 9874 5111 9875 5153 9875 5109 9875 5109 9876 5153 9876 5159 9876 5109 9877 5159 9877 5063 9877 5063 9878 5159 9878 5160 9878 5063 9879 5160 9879 5059 9879 5160 9880 5143 9880 5144 9880 5059 9881 5160 9881 5144 9881 5154 9882 5004 9882 4745 9882 4766 9883 4940 9883 5164 9883 5156 9884 5162 9884 4940 9884 4940 9885 5162 9885 5164 9885 4943 9886 5158 9886 4740 9886 4740 9887 5158 9887 5156 9887 4740 9888 5156 9888 4940 9888 5154 9889 5155 9889 5006 9889 5154 9890 5006 9890 5004 9890 5004 9891 5006 9891 5007 9891 5157 9892 5158 9892 4932 9892 5158 9893 4943 9893 4932 9893 4743 9894 5164 9894 5152 9894 4742 9895 4744 9895 4766 9895 4766 9896 4744 9896 4741 9896 4741 9897 4744 9897 5107 9897 5164 9898 4743 9898 4766 9898 4766 9899 4743 9899 4742 9899 5152 9900 4745 9900 4997 9900 5152 9901 4997 9901 4743 9901 4746 9902 5117 9902 5167 9902 5149 9903 5092 9903 4746 9903 4746 9904 5092 9904 5117 9904 5135 9905 5146 9905 5130 9905 5069 9906 4747 9906 5129 9906 5130 9907 5146 9907 5129 9907 4748 9908 4749 9908 5072 9908 4748 9909 5072 9909 5078 9909 4750 9910 4951 9910 4716 9910 4790 9911 4750 9911 4716 9911 5091 9912 4790 9912 4716 9912 5091 9913 4716 9913 5123 9913 5123 9914 4716 9914 5125 9914 4751 9915 4753 9915 5127 9915 4751 9916 5127 9916 4755 9916 4752 9917 5089 9917 4751 9917 4753 9918 4751 9918 5089 9918 5029 9919 5013 9919 5089 9919 5089 9920 5013 9920 4753 9920 4753 9921 5013 9921 5014 9921 5127 9922 5150 9922 4754 9922 5118 9923 4756 9923 5119 9923 5119 9924 4756 9924 5125 9924 4753 9925 5014 9925 5150 9925 4951 9926 5185 9926 5186 9926 5185 9927 4951 9927 4750 9927 4789 9928 5126 9928 5124 9928 5124 9929 5126 9929 5184 9929 5126 9930 4789 9930 4755 9930 5126 9931 4755 9931 5127 9931 5184 9932 5186 9932 5074 9932 5184 9933 5074 9933 4757 9933 5074 9934 5121 9934 5037 9934 5074 9935 5037 9935 4757 9935 4952 9936 4951 9936 5186 9936 4758 9937 4931 9937 5186 9937 4758 9938 5126 9938 4926 9938 4925 9939 4952 9939 5186 9939 4925 9940 5186 9940 4931 9940 5186 9941 5184 9941 4758 9941 4758 9942 5184 9942 5126 9942 5118 9943 5119 9943 5128 9943 5035 9944 5024 9944 5120 9944 5122 9945 5022 9945 5038 9945 5122 9946 5038 9946 5121 9946 4784 9947 5078 9947 4759 9947 4784 9948 4759 9948 4760 9948 4759 9949 4970 9949 4760 9949 4760 9950 4970 9950 4761 9950 4761 9951 4970 9951 5117 9951 4732 9952 5118 9952 4960 9952 4732 9953 4960 9953 4959 9953 5112 9954 4787 9954 4762 9954 4762 9955 4787 9955 4788 9955 5112 9956 5030 9956 5016 9956 4780 9957 5065 9957 4763 9957 5110 9958 4782 9958 5095 9958 5095 9959 4782 9959 4781 9959 4763 9960 5065 9960 5093 9960 5170 9961 5169 9961 4765 9961 4764 9962 5170 9962 4765 9962 4764 9963 4765 9963 5110 9963 5110 9964 4765 9964 4782 9964 5060 9965 5110 9965 5063 9965 5047 9966 4741 9966 5107 9966 4741 9967 4923 9967 4766 9967 4923 9968 4940 9968 4766 9968 4986 9969 5104 9969 5041 9969 4920 9970 5041 9970 5104 9970 4768 9971 5098 9971 4767 9971 5148 9972 4768 9972 4767 9972 5148 9973 4767 9973 4770 9973 5148 9974 4770 9974 5101 9974 5099 9975 4773 9975 4771 9975 4769 9976 5101 9976 4770 9976 5099 9977 4771 9977 5098 9977 4931 9978 5098 9978 4771 9978 5102 9979 4893 9979 4882 9979 4774 9980 5101 9980 4769 9980 4774 9981 4769 9981 4772 9981 4773 9982 4880 9982 4805 9982 4773 9983 4805 9983 5100 9983 5100 9984 4805 9984 5098 9984 5098 9985 4805 9985 4775 9985 5098 9986 4775 9986 5099 9986 4893 9987 5102 9987 4774 9987 4774 9988 5102 9988 5101 9988 5102 9989 4882 9989 4769 9989 4769 9990 4882 9990 4772 9990 4913 9991 4881 9991 4880 9991 4880 9992 4773 9992 5099 9992 4880 9993 5099 9993 4913 9993 4772 9994 4882 9994 4776 9994 4772 9995 4776 9995 4913 9995 4776 9996 4881 9996 4913 9996 5179 9997 4735 9997 4792 9997 5179 9998 4792 9998 5177 9998 5177 9999 4792 9999 4798 9999 5177 10000 4798 10000 4777 10000 4777 10001 4798 10001 4799 10001 4777 10002 4799 10002 5178 10002 4824 10003 4780 10003 4828 10003 4763 10004 4829 10004 4828 10004 4828 10005 4780 10005 4763 10005 4763 10006 5082 10006 4852 10006 4852 10007 5082 10007 4778 10007 4778 10008 5082 10008 4779 10008 4779 10009 5082 10009 5081 10009 4779 10010 5081 10010 4780 10010 4779 10011 4780 10011 4824 10011 4829 10012 4733 10012 4833 10012 4783 10013 5096 10013 4847 10013 5096 10014 4781 10014 4847 10014 4847 10015 4781 10015 4848 10015 4848 10016 4781 10016 4782 10016 4782 10017 4823 10017 4822 10017 4782 10018 4822 10018 4848 10018 4823 10019 4782 10019 4765 10019 4783 10020 4765 10020 5096 10020 4841 10021 4787 10021 4825 10021 4825 10022 4787 10022 4784 10022 5138 10023 5141 10023 4784 10023 5142 10024 4825 10024 4784 10024 5142 10025 4784 10025 5141 10025 4825 10026 5142 10026 4846 10026 4785 10027 4846 10027 5142 10027 4785 10028 5139 10028 4786 10028 4846 10029 4785 10029 4786 10029 4786 10030 5139 10030 5138 10030 5138 10031 4784 10031 4786 10031 4786 10032 4784 10032 4760 10032 4786 10033 4760 10033 4761 10033 4786 10034 4761 10034 4850 10034 4761 10035 4788 10035 4850 10035 4787 10036 4841 10036 4843 10036 4787 10037 4843 10037 4788 10037 4883 10038 4789 10038 5073 10038 4883 10039 5073 10039 4892 10039 4892 10040 5073 10040 4839 10040 4898 10041 5073 10041 4752 10041 4898 10042 4839 10042 5073 10042 4751 10043 4898 10043 4752 10043 4755 10044 4789 10044 4883 10044 4751 10045 4755 10045 4898 10045 4898 10046 4755 10046 4883 10046 4888 10047 5185 10047 4750 10047 4888 10048 4750 10048 5180 10048 5180 10049 4750 10049 4790 10049 5180 10050 4790 10050 4849 10050 5090 10051 4844 10051 4849 10051 4849 10052 4790 10052 5090 10052 5090 10053 4791 10053 4844 10053 4791 10054 5090 10054 5185 10054 4791 10055 5185 10055 4888 10055 4792 10056 4853 10056 4795 10056 4792 10057 4735 10057 5183 10057 4792 10058 5183 10058 4853 10058 4793 10059 4794 10059 5005 10059 5005 10060 4794 10060 4993 10060 4795 10061 4853 10061 4851 10061 4795 10062 4851 10062 4797 10062 4797 10063 4851 10063 4793 10063 4793 10064 4851 10064 4794 10064 4899 10065 4871 10065 4803 10065 4900 10066 4899 10066 4803 10066 4793 10067 5005 10067 4796 10067 4796 10068 5005 10068 4998 10068 4793 10069 4796 10069 4797 10069 4797 10070 4796 10070 4802 10070 4797 10071 4802 10071 4795 10071 4802 10072 4801 10072 4795 10072 4795 10073 4801 10073 4798 10073 4795 10074 4798 10074 4792 10074 4804 10075 4799 10075 4801 10075 4801 10076 4799 10076 4798 10076 4990 10077 4872 10077 4859 10077 4859 10078 4872 10078 4800 10078 4800 10079 4858 10079 4859 10079 4998 10080 4992 10080 4796 10080 4796 10081 4992 10081 4856 10081 4860 10082 4804 10082 4801 10082 4804 10083 4860 10083 4858 10083 4804 10084 4858 10084 4800 10084 4860 10085 4801 10085 4857 10085 4801 10086 4802 10086 4857 10086 4857 10087 4802 10087 4856 10087 4856 10088 4802 10088 4796 10088 4871 10089 4775 10089 4803 10089 4799 10090 4804 10090 4871 10090 4871 10091 4804 10091 4800 10091 4871 10092 4800 10092 4775 10092 4775 10093 4800 10093 5099 10093 4803 10094 4805 10094 4900 10094 4805 10095 4803 10095 4775 10095 4816 10096 4810 10096 4806 10096 4806 10097 4810 10097 4808 10097 4897 10098 4807 10098 4809 10098 4807 10099 4818 10099 4809 10099 4806 10100 4808 10100 4809 10100 4806 10101 4809 10101 4818 10101 4813 10102 4812 10102 4811 10102 4811 10103 4812 10103 4996 10103 4810 10104 4816 10104 4895 10104 4895 10105 4816 10105 4814 10105 4895 10106 4814 10106 4813 10106 4895 10107 4813 10107 4811 10107 4897 10108 4896 10108 4807 10108 4807 10109 4896 10109 4820 10109 4813 10110 4867 10110 4812 10110 4812 10111 4867 10111 5003 10111 4814 10112 4869 10112 4813 10112 4813 10113 4869 10113 4867 10113 4814 10114 4816 10114 4869 10114 4869 10115 4816 10115 4815 10115 4815 10116 4817 10116 4806 10116 4815 10117 4806 10117 4870 10117 4815 10118 4816 10118 4817 10118 4817 10119 4816 10119 4806 10119 4807 10120 4868 10120 4870 10120 4807 10121 4870 10121 4818 10121 4818 10122 4870 10122 4806 10122 4868 10123 4807 10123 4819 10123 4819 10124 4807 10124 4820 10124 4819 10125 4820 10125 4774 10125 4820 10126 4896 10126 4893 10126 4774 10127 4820 10127 4893 10127 4848 10128 4821 10128 4847 10128 4821 10129 4848 10129 4846 10129 5181 10130 4849 10130 4836 10130 4824 10131 4822 10131 4823 10131 4841 10132 4825 10132 4842 10132 4842 10133 4825 10133 4826 10133 4842 10134 4826 10134 4837 10134 4837 10135 4826 10135 4734 10135 4828 10136 4822 10136 4824 10136 4825 10137 4708 10137 4826 10137 4826 10138 4708 10138 4734 10138 4734 10139 4708 10139 4832 10139 4734 10140 4832 10140 4833 10140 4833 10141 4831 10141 4829 10141 4829 10142 4831 10142 4827 10142 4830 10143 4822 10143 4828 10143 4708 10144 4825 10144 4709 10144 4830 10145 4828 10145 4827 10145 4827 10146 4828 10146 4829 10146 4711 10147 4822 10147 4830 10147 4711 10148 4848 10148 4822 10148 4710 10149 4846 10149 4848 10149 4825 10150 4846 10150 4709 10150 4709 10151 4846 10151 4710 10151 4831 10152 4833 10152 4832 10152 4710 10153 4848 10153 4711 10153 4835 10154 4849 10154 4844 10154 4835 10155 4844 10155 4840 10155 4834 10156 4836 10156 4712 10156 4715 10157 4838 10157 4843 10157 4839 10158 4713 10158 4845 10158 4712 10159 4849 10159 4835 10159 4712 10160 4836 10160 4849 10160 4834 10161 4842 10161 4837 10161 4834 10162 4837 10162 4836 10162 4714 10163 4839 10163 4843 10163 4714 10164 4843 10164 4838 10164 4713 10165 4839 10165 4714 10165 4840 10166 4844 10166 4845 10166 4840 10167 4845 10167 4713 10167 4843 10168 4841 10168 4715 10168 4715 10169 4841 10169 4834 10169 4834 10170 4841 10170 4842 10170 4898 10171 4843 10171 4839 10171 4791 10172 4892 10172 4844 10172 4844 10173 4892 10173 4845 10173 4892 10174 4839 10174 4845 10174 4821 10175 4846 10175 4786 10175 4829 10176 4852 10176 4733 10176 4829 10177 4763 10177 4852 10177 4836 10178 4736 10178 4737 10178 4843 10179 4898 10179 4850 10179 4850 10180 4788 10180 4843 10180 4794 10181 4852 10181 4778 10181 4794 10182 4778 10182 4993 10182 4993 10183 4778 10183 4994 10183 4851 10184 4852 10184 4794 10184 4853 10185 4733 10185 4851 10185 4851 10186 4733 10186 4852 10186 4853 10187 5183 10187 4733 10187 4733 10188 5183 10188 4735 10188 5001 10189 4824 10189 4854 10189 4854 10190 4824 10190 4823 10190 4824 10191 5001 10191 4779 10191 4779 10192 5001 10192 4995 10192 4765 10193 4855 10193 4823 10193 4823 10194 4855 10194 4854 10194 4894 10195 4855 10195 4783 10195 4783 10196 4855 10196 4765 10196 4994 10197 4778 10197 4995 10197 4995 10198 4778 10198 4779 10198 4874 10199 5087 10199 4857 10199 4857 10200 5087 10200 4860 10200 4856 10201 4874 10201 4857 10201 4858 10202 5087 10202 4873 10202 4858 10203 4873 10203 4859 10203 4860 10204 5087 10204 4858 10204 4902 10205 4874 10205 4856 10205 4903 10206 4902 10206 4861 10206 4861 10207 4902 10207 4992 10207 4992 10208 4902 10208 4856 10208 4864 10209 4876 10209 4862 10209 4862 10210 4876 10210 4866 10210 4865 10211 4878 10211 4864 10211 4865 10212 4864 10212 5088 10212 4877 10213 4909 10213 4863 10213 4866 10214 4876 10214 5002 10214 5002 10215 4876 10215 4877 10215 5002 10216 4877 10216 4907 10216 4907 10217 4877 10217 4863 10217 4865 10218 4910 10218 4906 10218 4878 10219 4865 10219 4908 10219 4908 10220 4865 10220 4906 10220 4912 10221 4910 10221 4819 10221 4819 10222 4910 10222 4865 10222 4869 10223 4866 10223 4867 10223 4870 10224 4868 10224 5088 10224 4862 10225 4870 10225 5088 10225 5002 10226 5003 10226 4866 10226 4866 10227 5003 10227 4867 10227 4866 10228 4869 10228 4815 10228 4819 10229 4865 10229 4868 10229 4868 10230 4865 10230 5088 10230 4866 10231 4815 10231 4862 10231 4862 10232 4815 10232 4870 10232 5174 10233 4871 10233 4899 10233 4871 10234 5174 10234 5176 10234 4871 10235 5176 10235 4799 10235 4799 10236 5176 10236 5178 10236 5174 10237 4899 10237 5180 10237 4872 10238 4988 10238 4985 10238 4913 10239 5099 10239 4985 10239 4985 10240 5099 10240 4800 10240 4985 10241 4800 10241 4872 10241 4987 10242 4911 10242 4912 10242 4912 10243 4819 10243 4987 10243 4987 10244 4819 10244 4774 10244 4987 10245 4774 10245 4772 10245 4873 10246 5087 10246 4902 10246 4901 10247 4873 10247 4902 10247 4902 10248 5087 10248 4874 10248 4875 10249 4990 10249 4859 10249 4859 10250 4873 10250 4901 10250 4859 10251 4901 10251 4875 10251 4878 10252 4908 10252 4877 10252 4877 10253 4876 10253 4864 10253 4878 10254 4877 10254 4864 10254 4881 10255 4885 10255 4879 10255 4881 10256 4879 10256 4880 10256 4881 10257 4776 10257 4885 10257 4885 10258 4776 10258 4891 10258 4891 10259 4776 10259 4884 10259 4884 10260 4776 10260 4882 10260 4891 10261 4884 10261 4720 10261 4892 10262 4723 10262 4883 10262 4883 10263 4723 10263 4721 10263 4886 10264 4887 10264 4879 10264 4879 10265 4887 10265 4888 10265 4883 10266 4721 10266 4884 10266 4884 10267 4721 10267 4720 10267 4891 10268 4724 10268 4885 10268 4885 10269 4724 10269 4886 10269 4885 10270 4886 10270 4879 10270 4888 10271 4887 10271 4791 10271 4791 10272 4887 10272 4889 10272 4889 10273 4724 10273 4890 10273 4720 10274 4890 10274 4891 10274 4891 10275 4890 10275 4724 10275 4890 10276 4723 10276 4889 10276 4889 10277 4723 10277 4892 10277 4889 10278 4892 10278 4791 10278 4893 10279 4883 10279 4884 10279 4893 10280 4884 10280 4882 10280 4996 10281 4894 10281 4811 10281 4811 10282 4894 10282 4783 10282 4811 10283 4783 10283 4847 10283 4811 10284 4847 10284 4895 10284 4895 10285 4847 10285 4821 10285 4895 10286 4821 10286 4810 10286 4808 10287 4850 10287 4809 10287 4809 10288 4898 10288 4897 10288 4809 10289 4850 10289 4898 10289 4850 10290 4808 10290 4786 10290 4786 10291 4808 10291 4810 10291 4786 10292 4810 10292 4821 10292 4893 10293 4896 10293 4883 10293 4883 10294 4896 10294 4898 10294 4898 10295 4896 10295 4897 10295 4880 10296 4879 10296 4805 10296 4805 10297 4879 10297 4888 10297 5180 10298 4899 10298 4900 10298 5180 10299 4900 10299 4888 10299 4888 10300 4900 10300 4805 10300 4983 10301 4861 10301 4992 10301 4875 10302 4983 10302 4990 10302 4901 10303 4902 10303 4875 10303 4875 10304 4902 10304 4903 10304 4875 10305 4903 10305 4861 10305 4875 10306 4861 10306 4983 10306 4906 10307 4910 10307 4904 10307 4904 10308 4905 10308 4906 10308 5002 10309 4907 10309 4905 10309 4907 10310 4863 10310 4906 10310 4906 10311 4905 10311 4907 10311 4909 10312 4877 10312 4908 10312 4909 10313 4908 10313 4906 10313 4909 10314 4906 10314 4863 10314 4912 10315 4911 10315 4904 10315 4912 10316 4904 10316 4910 10316 4987 10317 4772 10317 4913 10317 4987 10318 4913 10318 4985 10318 4916 10319 4915 10319 5085 10319 4915 10320 4937 10320 5085 10320 4914 10321 4915 10321 4916 10321 4944 10322 4917 10322 4919 10322 4918 10323 4759 10323 4740 10323 4759 10324 4944 10324 4919 10324 4944 10325 4759 10325 4918 10325 4944 10326 4918 10326 4917 10326 5041 10327 5042 10327 4986 10327 4989 10328 4984 10328 4921 10328 4921 10329 4984 10329 4958 10329 4953 10330 4922 10330 5008 10330 5008 10331 4922 10331 5050 10331 4923 10332 4741 10332 5047 10332 5047 10333 4940 10333 4923 10333 4929 10334 4945 10334 4930 10334 4957 10335 4950 10335 4956 10335 4978 10336 4769 10336 4975 10336 4773 10337 4971 10337 4771 10337 4961 10338 4952 10338 4925 10338 4939 10339 4926 10339 4969 10339 4962 10340 4927 10340 4937 10340 4929 10341 4924 10341 4928 10341 4928 10342 4924 10342 4927 10342 4924 10343 4929 10343 4930 10343 4930 10344 4945 10344 4962 10344 4962 10345 4945 10345 4946 10345 4946 10346 4928 10346 4962 10346 4962 10347 4928 10347 4927 10347 4758 10348 4975 10348 4770 10348 4770 10349 4931 10349 4758 10349 4931 10350 4770 10350 4767 10350 4767 10351 5098 10351 4931 10351 4770 10352 4975 10352 4769 10352 4950 10353 4949 10353 4956 10353 4947 10354 4955 10354 4949 10354 4949 10355 4955 10355 4956 10355 4947 10356 4948 10356 4942 10356 4942 10357 4948 10357 4957 10357 4950 10358 4957 10358 4948 10358 4955 10359 4947 10359 4942 10359 5134 10360 5132 10360 4934 10360 4933 10361 5094 10361 5134 10361 4934 10362 4935 10362 4933 10362 5009 10363 5084 10363 4933 10363 4933 10364 5134 10364 4934 10364 5084 10365 5094 10365 4933 10365 4933 10366 4935 10366 5010 10366 4933 10367 5010 10367 5009 10367 5128 10368 4936 10368 4731 10368 4964 10369 4707 10369 4936 10369 5011 10370 5041 10370 4920 10370 5011 10371 4937 10371 4927 10371 4954 10372 5040 10372 5039 10372 4954 10373 5039 10373 4972 10373 4972 10374 5039 10374 4971 10374 5132 10375 4937 10375 4934 10375 4939 10376 4975 10376 4758 10376 4939 10377 4758 10377 4926 10377 4972 10378 4975 10378 4954 10378 4954 10379 4975 10379 4939 10379 4941 10380 4955 10380 4922 10380 4922 10381 4955 10381 4942 10381 4740 10382 4940 10382 4922 10382 4969 10383 4919 10383 4917 10383 4969 10384 4917 10384 4918 10384 4740 10385 4922 10385 4942 10385 4918 10386 4740 10386 4942 10386 4945 10387 4929 10387 4928 10387 4945 10388 4928 10388 4946 10388 4948 10389 4947 10389 4949 10389 4948 10390 4949 10390 4950 10390 4966 10391 4963 10391 4961 10391 4961 10392 4963 10392 4952 10392 4951 10393 4952 10393 4716 10393 4963 10394 4964 10394 4952 10394 4952 10395 4964 10395 4716 10395 4716 10396 4964 10396 4936 10396 4768 10397 5148 10397 5147 10397 5147 10398 5148 10398 4981 10398 4953 10399 4938 10399 4939 10399 4938 10400 4954 10400 4939 10400 4938 10401 5040 10401 4954 10401 4956 10402 4955 10402 4941 10402 4941 10403 4953 10403 4956 10403 4956 10404 4953 10404 4939 10404 4956 10405 4939 10405 4957 10405 4957 10406 4939 10406 4969 10406 4957 10407 4969 10407 4918 10407 4942 10408 4957 10408 4918 10408 4938 10409 4921 10409 5040 10409 5040 10410 4921 10410 4958 10410 4962 10411 4937 10411 4915 10411 4965 10412 4966 10412 4916 10412 4968 10413 4960 10413 5128 10413 4968 10414 4967 10414 4960 10414 4960 10415 4967 10415 5085 10415 4960 10416 5085 10416 4959 10416 5085 10417 4967 10417 4916 10417 4916 10418 4967 10418 4965 10418 4916 10419 4966 10419 4914 10419 4961 10420 4914 10420 4966 10420 4914 10421 4961 10421 4925 10421 4930 10422 4962 10422 4915 10422 4930 10423 4915 10423 4914 10423 4930 10424 4914 10424 4925 10424 4930 10425 4925 10425 4924 10425 4924 10426 4925 10426 5046 10426 4924 10427 5046 10427 4927 10427 4927 10428 5046 10428 5011 10428 4967 10429 4728 10429 4965 10429 4968 10430 5128 10430 4731 10430 5127 10431 4926 10431 5126 10431 5127 10432 4754 10432 4926 10432 4926 10433 4754 10433 5165 10433 4926 10434 5165 10434 4969 10434 4919 10435 5167 10435 4759 10435 4759 10436 5167 10436 4970 10436 4969 10437 5165 10437 4919 10437 4980 10438 4977 10438 4972 10438 4971 10439 4973 10439 4972 10439 4972 10440 4973 10440 4980 10440 4973 10441 4971 10441 4974 10441 4973 10442 4974 10442 4726 10442 4977 10443 4978 10443 4972 10443 4972 10444 4978 10444 4975 10444 4981 10445 4722 10445 5147 10445 5147 10446 4722 10446 4976 10446 4976 10447 4722 10447 4725 10447 4978 10448 4977 10448 4982 10448 4978 10449 4982 10449 4981 10449 4725 10450 4722 10450 4979 10450 4725 10451 4979 10451 4980 10451 4725 10452 4980 10452 4973 10452 5147 10453 4976 10453 4726 10453 5147 10454 4726 10454 4974 10454 4981 10455 4982 10455 4722 10455 5084 10456 5083 10456 5094 10456 4958 10457 4984 10457 4985 10457 4985 10458 4988 10458 4958 10458 4958 10459 4988 10459 5040 10459 5039 10460 5040 10460 4988 10460 4991 10461 5045 10461 5046 10461 4904 10462 5048 10462 4905 10462 4987 10463 4989 10463 4911 10463 4911 10464 4989 10464 4921 10464 4911 10465 4921 10465 4938 10465 5039 10466 4988 10466 4991 10466 4984 10467 4989 10467 4985 10467 4985 10468 4989 10468 4987 10468 4988 10469 4872 10469 4991 10469 4990 10470 4983 10470 4991 10470 4990 10471 4991 10471 4872 10471 4812 10472 5007 10472 4996 10472 4983 10473 4992 10473 5000 10473 4855 10474 4894 10474 4996 10474 4993 10475 4994 10475 5009 10475 5009 10476 4994 10476 4995 10476 5009 10477 4995 10477 5001 10477 4996 10478 5007 10478 4855 10478 4855 10479 5007 10479 5009 10479 4855 10480 5009 10480 4854 10480 4812 10481 4997 10481 5007 10481 5007 10482 4997 10482 5004 10482 5005 10483 4718 10483 4998 10483 4998 10484 4718 10484 4999 10484 4998 10485 4999 10485 4992 10485 4992 10486 4999 10486 5000 10486 4983 10487 5000 10487 5106 10487 5009 10488 5001 10488 4854 10488 4993 10489 5009 10489 5005 10489 4935 10490 5012 10490 4718 10490 4905 10491 5049 10491 5002 10491 5002 10492 4717 10492 5003 10492 5003 10493 4717 10493 4812 10493 4812 10494 4717 10494 4997 10494 4745 10495 5004 10495 4997 10495 5010 10496 4935 10496 5009 10496 5009 10497 4935 10497 4718 10497 5009 10498 4718 10498 5005 10498 4904 10499 4953 10499 5008 10499 5008 10500 5050 10500 5048 10500 5008 10501 5048 10501 4904 10501 4991 10502 4983 10502 5044 10502 4911 10503 4938 10503 4953 10503 4911 10504 4953 10504 4904 10504 4991 10505 5046 10505 5039 10505 4935 10506 4934 10506 4937 10506 4937 10507 5011 10507 4935 10507 4935 10508 5011 10508 5103 10508 4935 10509 5103 10509 5012 10509 5103 10510 5011 10510 5104 10510 5104 10511 5011 10511 4920 10511 5123 10512 5022 10512 5122 10512 5115 10513 5021 10513 5015 10513 5125 10514 4756 10514 5123 10514 5123 10515 4756 10515 5015 10515 5123 10516 5015 10516 5022 10516 5022 10517 5015 10517 5021 10517 5076 10518 5016 10518 5027 10518 5037 10519 5017 10519 5035 10519 5035 10520 5017 10520 5034 10520 5021 10521 5033 10521 5020 10521 5022 10522 5021 10522 5038 10522 5028 10523 5018 10523 5023 10523 5024 10524 5028 10524 5023 10524 5025 10525 5023 10525 4714 10525 5027 10526 5016 10526 5026 10526 5026 10527 5025 10527 5032 10527 5032 10528 5033 10528 5027 10528 5027 10529 5033 10529 5021 10529 5026 10530 5032 10530 5027 10530 5038 10531 5028 10531 5034 10531 5038 10532 5034 10532 5017 10532 5014 10533 5013 10533 5029 10533 5029 10534 5120 10534 5151 10534 5151 10535 5014 10535 5029 10535 5031 10536 5112 10536 5113 10536 5031 10537 5113 10537 5149 10537 5149 10538 5113 10538 5092 10538 5030 10539 5031 10539 5151 10539 5030 10540 5151 10540 5024 10540 5120 10541 5024 10541 5151 10541 5030 10542 5112 10542 5031 10542 5030 10543 5025 10543 5026 10543 5025 10544 5030 10544 5023 10544 5023 10545 5030 10545 5024 10545 5016 10546 5030 10546 5026 10546 5028 10547 5024 10547 5034 10547 5035 10548 5034 10548 5024 10548 5028 10549 5038 10549 5018 10549 5038 10550 5019 10550 5018 10550 5036 10551 5019 10551 5038 10551 5036 10552 5038 10552 5020 10552 5020 10553 5038 10553 5021 10553 5037 10554 5121 10554 5017 10554 5121 10555 5038 10555 5017 10555 5039 10556 5046 10556 4925 10556 4925 10557 4771 10557 5039 10557 4771 10558 4925 10558 4931 10558 5039 10559 4771 10559 4971 10559 5044 10560 5041 10560 5045 10560 5044 10561 5045 10561 4991 10561 5076 10562 5116 10562 5016 10562 5016 10563 5116 10563 5080 10563 5035 10564 4757 10564 5037 10564 5044 10565 4983 10565 5042 10565 5042 10566 4983 10566 5043 10566 5043 10567 4983 10567 5106 10567 5041 10568 5044 10568 5042 10568 5045 10569 5041 10569 5011 10569 5045 10570 5011 10570 5046 10570 5047 10571 5107 10571 5048 10571 5048 10572 5107 10572 5049 10572 5049 10573 4905 10573 5048 10573 5047 10574 5050 10574 4940 10574 5050 10575 5047 10575 5048 10575 4953 10576 4941 10576 4922 10576 4940 10577 5050 10577 4922 10577 4747 10578 5072 10578 4749 10578 5051 10579 5056 10579 5069 10579 5108 10580 5065 10580 5056 10580 5071 10581 5070 10581 5051 10581 5051 10582 5070 10582 5108 10582 5051 10583 5108 10583 5056 10583 5171 10584 5052 10584 5064 10584 5064 10585 5052 10585 5060 10585 5067 10586 5053 10586 5068 10586 5056 10587 5055 10587 5054 10587 5059 10588 5066 10588 4709 10588 5060 10589 5058 10589 5062 10589 5062 10590 5055 10590 5064 10590 5060 10591 5062 10591 5064 10591 5053 10592 5066 10592 5061 10592 5053 10593 5061 10593 5068 10593 5068 10594 5061 10594 4747 10594 5063 10595 5058 10595 5060 10595 5058 10596 5063 10596 5057 10596 5057 10597 5063 10597 5059 10597 5060 10598 5052 10598 5110 10598 5065 10599 5171 10599 5064 10599 5055 10600 5056 10600 5064 10600 5064 10601 5056 10601 5065 10601 5144 10602 5145 10602 5061 10602 5144 10603 5061 10603 5059 10603 5059 10604 4709 10604 5057 10604 5072 10605 4747 10605 5145 10605 5066 10606 5059 10606 5061 10606 5061 10607 5145 10607 4747 10607 5067 10608 5069 10608 5054 10608 5054 10609 5069 10609 5056 10609 4747 10610 5069 10610 5068 10610 5069 10611 5067 10611 5068 10611 5171 10612 5170 10612 5052 10612 4789 10613 5124 10613 5073 10613 5073 10614 5124 10614 5035 10614 5073 10615 5035 10615 5120 10615 5184 10616 4757 10616 5124 10616 5124 10617 4757 10617 5035 10617 5185 10618 5074 10618 5186 10618 5121 10619 5185 10619 5090 10619 5121 10620 5074 10620 5185 10620 5122 10621 5121 10621 5090 10621 5027 10622 5021 10622 5115 10622 5075 10623 4959 10623 5077 10623 5077 10624 4959 10624 5085 10624 5085 10625 4748 10625 5077 10625 5079 10626 5116 10626 5076 10626 4748 10627 5079 10627 5077 10627 5077 10628 5079 10628 5076 10628 5077 10629 5076 10629 4736 10629 4736 10630 5076 10630 5115 10630 5112 10631 4784 10631 4787 10631 5112 10632 5080 10632 4784 10632 4784 10633 5080 10633 5078 10633 4748 10634 5078 10634 5079 10634 5116 10635 5079 10635 5080 10635 5080 10636 5079 10636 5078 10636 5081 10637 5171 10637 4780 10637 4780 10638 5171 10638 5065 10638 5081 10639 5172 10639 5171 10639 5083 10640 5172 10640 5081 10640 5082 10641 5083 10641 5081 10641 5169 10642 5009 10642 5007 10642 5169 10643 5007 10643 5086 10643 5169 10644 5172 10644 5009 10644 5006 10645 5086 10645 5007 10645 5009 10646 5172 10646 5083 10646 5009 10647 5083 10647 5084 10647 4748 10648 5085 10648 4937 10648 4748 10649 4937 10649 5132 10649 5071 10650 5134 10650 5094 10650 5070 10651 5071 10651 5094 10651 5006 10652 5097 10652 5086 10652 5097 10653 5096 10653 4765 10653 4765 10654 5086 10654 5097 10654 5088 10655 4864 10655 4862 10655 5073 10656 5120 10656 4752 10656 4752 10657 5120 10657 5089 10657 5122 10658 5090 10658 5091 10658 5091 10659 5090 10659 4790 10659 4736 10660 5115 10660 5114 10660 4736 10661 5114 10661 4737 10661 5118 10662 4732 10662 4756 10662 4756 10663 4732 10663 5015 10663 5015 10664 4732 10664 5114 10664 5092 10665 5113 10665 5117 10665 5117 10666 5113 10666 4762 10666 5117 10667 4762 10667 4788 10667 5117 10668 4788 10668 4761 10668 5093 10669 5094 10669 5082 10669 5093 10670 5082 10670 4763 10670 5082 10671 5094 10671 5083 10671 5095 10672 4781 10672 5096 10672 5095 10673 5096 10673 5097 10673 4773 10674 5100 10674 4974 10674 4773 10675 4974 10675 4971 10675 5100 10676 5098 10676 4768 10676 5102 10677 5148 10677 5101 10677 5102 10678 4769 10678 4978 10678 5102 10679 4978 10679 4981 10679 5104 10680 4719 10680 5103 10680 4719 10681 5104 10681 5105 10681 5105 10682 5104 10682 4986 10682 5043 10683 5105 10683 4986 10683 5043 10684 4986 10684 5042 10684 4719 10685 4718 10685 5103 10685 5103 10686 4718 10686 5012 10686 5043 10687 5106 10687 5105 10687 5108 10688 5093 10688 5065 10688 5093 10689 5108 10689 5094 10689 5094 10690 5108 10690 5070 10690 5052 10691 4764 10691 5110 10691 5109 10692 5110 10692 5095 10692 5170 10693 4764 10693 5052 10693 5109 10694 5095 10694 5111 10694 5111 10695 5095 10695 5097 10695 5112 10696 4762 10696 5113 10696 5112 10697 5016 10697 5080 10697 5015 10698 5114 10698 5115 10698 5076 10699 5027 10699 5115 10699 4970 10700 5167 10700 5117 10700 4960 10701 5118 10701 5128 10701 5029 10702 5089 10702 5120 10702 5122 10703 5091 10703 5123 10703 5125 10704 4716 10704 5119 10704 4753 10705 5150 10705 5127 10705 5128 10706 4716 10706 4936 10706 5119 10707 4716 10707 5128 10707 5129 10708 5131 10708 5130 10708 5129 10709 4749 10709 5131 10709 5131 10710 4749 10710 4748 10710 4748 10711 5132 10711 5131 10711 5131 10712 5132 10712 5133 10712 5133 10713 5132 10713 5134 10713 5071 10714 5051 10714 5146 10714 5071 10715 5146 10715 5134 10715 5134 10716 5146 10716 5135 10716 5134 10717 5135 10717 5133 10717 4785 10718 5136 10718 5137 10718 4785 10719 5137 10719 5139 10719 5139 10720 5137 10720 5140 10720 5138 10721 5139 10721 5140 10721 5138 10722 5140 10722 5141 10722 5141 10723 5140 10723 5078 10723 5078 10724 5072 10724 5145 10724 5141 10725 5078 10725 5145 10725 5141 10726 5145 10726 5142 10726 5142 10727 5145 10727 5144 10727 4785 10728 5142 10728 5144 10728 5144 10729 5136 10729 4785 10729 5136 10730 5143 10730 5137 10730 5143 10731 5136 10731 5144 10731 4749 10732 5129 10732 4747 10732 5129 10733 5146 10733 5069 10733 5069 10734 5146 10734 5051 10734 5137 10735 5143 10735 4738 10735 4768 10736 5147 10736 5100 10736 5100 10737 5147 10737 4974 10737 5102 10738 4981 10738 5148 10738 5167 10739 5168 10739 5031 10739 5149 10740 4746 10740 5031 10740 5031 10741 4746 10741 5167 10741 5151 10742 4754 10742 5014 10742 5014 10743 4754 10743 5150 10743 5166 10744 5165 10744 5151 10744 5151 10745 5165 10745 4754 10745 5168 10746 4919 10746 5166 10746 5168 10747 5166 10747 5151 10747 5154 10748 4745 10748 5152 10748 5152 10749 5155 10749 5154 10749 5152 10750 5164 10750 5155 10750 5155 10751 5164 10751 5163 10751 5155 10752 5163 10752 5159 10752 5155 10753 5159 10753 5153 10753 5162 10754 5156 10754 5163 10754 5163 10755 5156 10755 5161 10755 5157 10756 5161 10756 5156 10756 5157 10757 5156 10757 5158 10757 5161 10758 5157 10758 4739 10758 5161 10759 4739 10759 5160 10759 5163 10760 5161 10760 5159 10760 5159 10761 5161 10761 5160 10761 5162 10762 5163 10762 5164 10762 5165 10763 5166 10763 4919 10763 4919 10764 5168 10764 5167 10764 5170 10765 5172 10765 5169 10765 5170 10766 5171 10766 5172 10766 5179 10767 5182 10767 5181 10767 4730 10768 5176 10768 5174 10768 5173 10769 5174 10769 4706 10769 4730 10770 5174 10770 5173 10770 5174 10771 5180 10771 4706 10771 5180 10772 5182 10772 4706 10772 5175 10773 5178 10773 4730 10773 4730 10774 5178 10774 5176 10774 4728 10775 4777 10775 4729 10775 4777 10776 4728 10776 5177 10776 4729 10777 5178 10777 5175 10777 4729 10778 4777 10778 5178 10778 5180 10779 5181 10779 5182 10779 5204 10780 5200 10780 5198 10780 5204 10781 5198 10781 5203 10781 5200 10782 5201 10782 5197 10782 5188 10783 5187 10783 5194 10783 5204 10784 5187 10784 5188 10784 5187 10785 5204 10785 5195 10785 5187 10786 5195 10786 5194 10786 5202 10787 5191 10787 5196 10787 5189 10788 5191 10788 5202 10788 5202 10789 5196 10789 5201 10789 5194 10790 5195 10790 5190 10790 5190 10791 5192 10791 5194 10791 5192 10792 5190 10792 5191 10792 5191 10793 5193 10793 5192 10793 5191 10794 5204 10794 5188 10794 5188 10795 5194 10795 5192 10795 5188 10796 5193 10796 5191 10796 5192 10797 5193 10797 5188 10797 5195 10798 5196 10798 5190 10798 5189 10799 5204 10799 5191 10799 5196 10800 5195 10800 5199 10800 5195 10801 5203 10801 5199 10801 5195 10802 5204 10802 5203 10802 5190 10803 5196 10803 5191 10803 5199 10804 5201 10804 5196 10804 5189 10805 5200 10805 5204 10805 5197 10806 5198 10806 5200 10806 5197 10807 5201 10807 5198 10807 5201 10808 5199 10808 5198 10808 5200 10809 5202 10809 5201 10809 5202 10810 5200 10810 5189 10810 5199 10811 5203 10811 5198 10811 5313 10812 5316 10812 5205 10812 5205 10813 5267 10813 5207 10813 5206 10814 5205 10814 5207 10814 5324 10815 5224 10815 5209 10815 5208 10816 5209 10816 5210 10816 5324 10817 5310 10817 5224 10817 5239 10818 5238 10818 5211 10818 5240 10819 5239 10819 5213 10819 5241 10820 5240 10820 5213 10820 5238 10821 5237 10821 5211 10821 5211 10822 5237 10822 5212 10822 5213 10823 5223 10823 5274 10823 5213 10824 5274 10824 5241 10824 5241 10825 5274 10825 5242 10825 5212 10826 5210 10826 5211 10826 5211 10827 5213 10827 5239 10827 5301 10828 5217 10828 5219 10828 5219 10829 5217 10829 5277 10829 5214 10830 5215 10830 5216 10830 5301 10831 5219 10831 5242 10831 5237 10832 5238 10832 5215 10832 5216 10833 5215 10833 5238 10833 5238 10834 5218 10834 5277 10834 5277 10835 5218 10835 5219 10835 5277 10836 5275 10836 5216 10836 5217 10837 5281 10837 5277 10837 5238 10838 5277 10838 5216 10838 5328 10839 5332 10839 5248 10839 5320 10840 5330 10840 5322 10840 5322 10841 5330 10841 5247 10841 5247 10842 5330 10842 5256 10842 5330 10843 5319 10843 5256 10843 5317 10844 5314 10844 5270 10844 5315 10845 5270 10845 5314 10845 5270 10846 5315 10846 5221 10846 5207 10847 5267 10847 5221 10847 5207 10848 5221 10848 5315 10848 5206 10849 5207 10849 5222 10849 5313 10850 5222 10850 5314 10850 5306 10851 5268 10851 5307 10851 5307 10852 5268 10852 5223 10852 5310 10853 5307 10853 5223 10853 5310 10854 5223 10854 5213 10854 5310 10855 5213 10855 5224 10855 5224 10856 5213 10856 5211 10856 5224 10857 5211 10857 5209 10857 5334 10858 5311 10858 5296 10858 5311 10859 5254 10859 5225 10859 5311 10860 5225 10860 5226 10860 5292 10861 5296 10861 5311 10861 5292 10862 5311 10862 5226 10862 5293 10863 5287 10863 5295 10863 5295 10864 5287 10864 5284 10864 5295 10865 5284 10865 5225 10865 5225 10866 5284 10866 5230 10866 5226 10867 5225 10867 5230 10867 5226 10868 5230 10868 5229 10868 5226 10869 5229 10869 5261 10869 5227 10870 5228 10870 5283 10870 5261 10871 5258 10871 5227 10871 5227 10872 5258 10872 5228 10872 5230 10873 5266 10873 5229 10873 5282 10874 5233 10874 5265 10874 5299 10875 5216 10875 5231 10875 5235 10876 5299 10876 5232 10876 5280 10877 5278 10877 5234 10877 5280 10878 5234 10878 5282 10878 5232 10879 5263 10879 5259 10879 5299 10880 5231 10880 5232 10880 5232 10881 5231 10881 5263 10881 5233 10882 5282 10882 5234 10882 5233 10883 5234 10883 5232 10883 5232 10884 5234 10884 5235 10884 5278 10885 5297 10885 5234 10885 5234 10886 5297 10886 5298 10886 5234 10887 5298 10887 5235 10887 5235 10888 5236 10888 5299 10888 5273 10889 5304 10889 5214 10889 5214 10890 5304 10890 5215 10890 5215 10891 5304 10891 5212 10891 5215 10892 5212 10892 5237 10892 5218 10893 5238 10893 5239 10893 5218 10894 5239 10894 5240 10894 5218 10895 5240 10895 5219 10895 5219 10896 5240 10896 5241 10896 5219 10897 5241 10897 5242 10897 5265 10898 5264 10898 5290 10898 5265 10899 5290 10899 5279 10899 5279 10900 5290 10900 5243 10900 5279 10901 5243 10901 5244 10901 5244 10902 5243 10902 5285 10902 5244 10903 5285 10903 5286 10903 5244 10904 5286 10904 5245 10904 5245 10905 5286 10905 5289 10905 5245 10906 5289 10906 5263 10906 5263 10907 5289 10907 5288 10907 5263 10908 5288 10908 5283 10908 5322 10909 5246 10909 5320 10909 5246 10910 5322 10910 5266 10910 5266 10911 5322 10911 5247 10911 5266 10912 5247 10912 5262 10912 5260 10913 5262 10913 5256 10913 5256 10914 5262 10914 5247 10914 5248 10915 5296 10915 5294 10915 5296 10916 5248 10916 5249 10916 5249 10917 5248 10917 5328 10917 5254 10918 5325 10918 5327 10918 5254 10919 5327 10919 5225 10919 5249 10920 5335 10920 5334 10920 5249 10921 5334 10921 5296 10921 5326 10922 5324 10922 5250 10922 5308 10923 5338 10923 5210 10923 5210 10924 5338 10924 5208 10924 5251 10925 5308 10925 5309 10925 5324 10926 5326 10926 5310 10926 5310 10927 5326 10927 5251 10927 5251 10928 5326 10928 5337 10928 5338 10929 5250 10929 5208 10929 5327 10930 5328 10930 5323 10930 5327 10931 5323 10931 5225 10931 5208 10932 5250 10932 5324 10932 5252 10933 5251 10933 5337 10933 5252 10934 5336 10934 5251 10934 5336 10935 5252 10935 5253 10935 5253 10936 5252 10936 5337 10936 5336 10937 5253 10937 5308 10937 5308 10938 5253 10938 5338 10938 5328 10939 5248 10939 5323 10939 5334 10940 5332 10940 5333 10940 5333 10941 5332 10941 5325 10941 5334 10942 5335 10942 5332 10942 5325 10943 5332 10943 5335 10943 5325 10944 5254 10944 5333 10944 5220 10945 5255 10945 5256 10945 5256 10946 5255 10946 5260 10946 5321 10947 5257 10947 5220 10947 5220 10948 5257 10948 5259 10948 5220 10949 5259 10949 5255 10949 5257 10950 5321 10950 5320 10950 5257 10951 5320 10951 5246 10951 5257 10952 5232 10952 5259 10952 5260 10953 5255 10953 5258 10953 5259 10954 5228 10954 5255 10954 5255 10955 5228 10955 5258 10955 5260 10956 5258 10956 5261 10956 5260 10957 5261 10957 5262 10957 5262 10958 5261 10958 5229 10958 5233 10959 5246 10959 5265 10959 5265 10960 5246 10960 5266 10960 5229 10961 5266 10961 5262 10961 5232 10962 5257 10962 5246 10962 5232 10963 5246 10963 5233 10963 5263 10964 5283 10964 5259 10964 5259 10965 5283 10965 5228 10965 5264 10966 5265 10966 5230 10966 5230 10967 5265 10967 5266 10967 5269 10968 5221 10968 5274 10968 5221 10969 5267 10969 5300 10969 5268 10970 5317 10970 5270 10970 5268 10971 5270 10971 5269 10971 5269 10972 5270 10972 5221 10972 5317 10973 5268 10973 5305 10973 5300 10974 5272 10974 5271 10974 5317 10975 5305 10975 5271 10975 5271 10976 5305 10976 5302 10976 5300 10977 5267 10977 5272 10977 5271 10978 5302 10978 5273 10978 5273 10979 5302 10979 5304 10979 5274 10980 5221 10980 5242 10980 5231 10981 5216 10981 5275 10981 5276 10982 5275 10982 5277 10982 5276 10983 5277 10983 5281 10983 5281 10984 5217 10984 5280 10984 5280 10985 5217 10985 5278 10985 5278 10986 5217 10986 5297 10986 5279 10987 5244 10987 5281 10987 5282 10988 5265 10988 5279 10988 5245 10989 5263 10989 5275 10989 5275 10990 5263 10990 5231 10990 5279 10991 5281 10991 5280 10991 5279 10992 5280 10992 5282 10992 5275 10993 5276 10993 5245 10993 5245 10994 5276 10994 5281 10994 5245 10995 5281 10995 5244 10995 5283 10996 5288 10996 5291 10996 5286 10997 5285 10997 5243 10997 5289 10998 5286 10998 5291 10998 5291 10999 5286 10999 5243 10999 5243 11000 5290 11000 5287 11000 5287 11001 5290 11001 5264 11001 5288 11002 5289 11002 5291 11002 5291 11003 5243 11003 5287 11003 5287 11004 5264 11004 5284 11004 5264 11005 5230 11005 5284 11005 5287 11006 5293 11006 5291 11006 5291 11007 5293 11007 5283 11007 5283 11008 5293 11008 5296 11008 5283 11009 5296 11009 5227 11009 5227 11010 5296 11010 5292 11010 5227 11011 5292 11011 5226 11011 5227 11012 5226 11012 5261 11012 5225 11013 5323 11013 5295 11013 5295 11014 5323 11014 5293 11014 5293 11015 5323 11015 5294 11015 5293 11016 5294 11016 5296 11016 5236 11017 5235 11017 5298 11017 5236 11018 5298 11018 5300 11018 5300 11019 5216 11019 5236 11019 5236 11020 5216 11020 5299 11020 5273 11021 5300 11021 5271 11021 5221 11022 5300 11022 5242 11022 5297 11023 5217 11023 5301 11023 5298 11024 5297 11024 5300 11024 5300 11025 5301 11025 5242 11025 5297 11026 5301 11026 5300 11026 5214 11027 5216 11027 5273 11027 5300 11028 5273 11028 5216 11028 5304 11029 5302 11029 5303 11029 5268 11030 5303 11030 5302 11030 5223 11031 5268 11031 5269 11031 5303 11032 5212 11032 5304 11032 5302 11033 5305 11033 5268 11033 5223 11034 5269 11034 5274 11034 5209 11035 5211 11035 5210 11035 5210 11036 5212 11036 5303 11036 5210 11037 5303 11037 5308 11037 5308 11038 5303 11038 5268 11038 5308 11039 5268 11039 5306 11039 5309 11040 5310 11040 5251 11040 5306 11041 5307 11041 5309 11041 5308 11042 5306 11042 5309 11042 5309 11043 5307 11043 5310 11043 5333 11044 5311 11044 5334 11044 5206 11045 5312 11045 5313 11045 5313 11046 5312 11046 5222 11046 5205 11047 5206 11047 5313 11047 5207 11048 5314 11048 5222 11048 5207 11049 5315 11049 5314 11049 5314 11050 5316 11050 5313 11050 5267 11051 5205 11051 5272 11051 5272 11052 5205 11052 5316 11052 5316 11053 5317 11053 5271 11053 5316 11054 5271 11054 5272 11054 5316 11055 5314 11055 5317 11055 5222 11056 5329 11056 5314 11056 5312 11057 5206 11057 5222 11057 5318 11058 5330 11058 5331 11058 5330 11059 5318 11059 5319 11059 5256 11060 5319 11060 5220 11060 5220 11061 5319 11061 5321 11061 5321 11062 5318 11062 5320 11062 5294 11063 5323 11063 5248 11063 5208 11064 5324 11064 5209 11064 5335 11065 5249 11065 5327 11065 5325 11066 5335 11066 5327 11066 5337 11067 5326 11067 5338 11067 5253 11068 5337 11068 5338 11068 5338 11069 5326 11069 5250 11069 5327 11070 5249 11070 5328 11070 5321 11071 5319 11071 5318 11071 5314 11072 5329 11072 5222 11072 5318 11073 5331 11073 5320 11073 5248 11074 5332 11074 5334 11074 5248 11075 5334 11075 5328 11075 5328 11076 5334 11076 5332 11076 5333 11077 5254 11077 5311 11077 5251 11078 5336 11078 5308 11078 5330 11079 5320 11079 5331 11079 5517 11080 5518 11080 5430 11080 5517 11081 5430 11081 5518 11081 5350 11082 5514 11082 5431 11082 5350 11083 5431 11083 5339 11083 5513 11084 5439 11084 5340 11084 5513 11085 5340 11085 5439 11085 5356 11086 5512 11086 5358 11086 5358 11087 5512 11087 5356 11087 5452 11088 5366 11088 5530 11088 5341 11089 5342 11089 5364 11089 5341 11090 5364 11090 5342 11090 5427 11091 5428 11091 5367 11091 5425 11092 5369 11092 5426 11092 5344 11093 5374 11093 5373 11093 5417 11094 5372 11094 5418 11094 5414 11095 5416 11095 5345 11095 5414 11096 5345 11096 5415 11096 5399 11097 5414 11097 5415 11097 5347 11098 5484 11098 5346 11098 5346 11099 5484 11099 5483 11099 5513 11100 5484 11100 5347 11100 5484 11101 5513 11101 5489 11101 5487 11102 5513 11102 5347 11102 5487 11103 5489 11103 5513 11103 5467 11104 5488 11104 5487 11104 5487 11105 5488 11105 5489 11105 5348 11106 5397 11106 5493 11106 5493 11107 5397 11107 5494 11107 5348 11108 5339 11108 5350 11108 5348 11109 5350 11109 5351 11109 5349 11110 5350 11110 5339 11110 5493 11111 5339 11111 5348 11111 5350 11112 5349 11112 5351 11112 5351 11113 5349 11113 5492 11113 5349 11114 5352 11114 5477 11114 5349 11115 5477 11115 5492 11115 5493 11116 5352 11116 5349 11116 5349 11117 5339 11117 5493 11117 5391 11118 5498 11118 5353 11118 5391 11119 5353 11119 5499 11119 5356 11120 5498 11120 5355 11120 5354 11121 5356 11121 5485 11121 5485 11122 5356 11122 5355 11122 5498 11123 5356 11123 5357 11123 5357 11124 5353 11124 5498 11124 5353 11125 5357 11125 5497 11125 5358 11126 5357 11126 5356 11126 5358 11127 5356 11127 5357 11127 5357 11128 5356 11128 5354 11128 5357 11129 5354 11129 5497 11129 5511 11130 5494 11130 5361 11130 5361 11131 5494 11131 5509 11131 5359 11132 5362 11132 5376 11132 5376 11133 5362 11133 5360 11133 5361 11134 5360 11134 5511 11134 5511 11135 5360 11135 5362 11135 5519 11136 5520 11136 5529 11136 5529 11137 5520 11137 5443 11137 5415 11138 5345 11138 5418 11138 5363 11139 5539 11139 5535 11139 5365 11140 5443 11140 5532 11140 5420 11141 5365 11141 5342 11141 5342 11142 5364 11142 5420 11142 5420 11143 5364 11143 5342 11143 5342 11144 5365 11144 5532 11144 5452 11145 5530 11145 5420 11145 5420 11146 5530 11146 5365 11146 5366 11147 5452 11147 5343 11147 5530 11148 5366 11148 5528 11148 5370 11149 5368 11149 5465 11149 5528 11150 5366 11150 5343 11150 5528 11151 5343 11151 5370 11151 5528 11152 5370 11152 5527 11152 5527 11153 5370 11153 5465 11153 5527 11154 5465 11154 5409 11154 5455 11155 5525 11155 5526 11155 5525 11156 5455 11156 5409 11156 5525 11157 5409 11157 5465 11157 5458 11158 5371 11158 5418 11158 5458 11159 5418 11159 5373 11159 5426 11160 5428 11160 5367 11160 5367 11161 5428 11161 5427 11161 5428 11162 5435 11162 5367 11162 5435 11163 5428 11163 5371 11163 5423 11164 5426 11164 5369 11164 5435 11165 5368 11165 5367 11165 5367 11166 5368 11166 5369 11166 5367 11167 5369 11167 5426 11167 5426 11168 5369 11168 5425 11168 5423 11169 5422 11169 5370 11169 5369 11170 5368 11170 5370 11170 5369 11171 5370 11171 5423 11171 5423 11172 5370 11172 5422 11172 5370 11173 5343 11173 5423 11173 5416 11174 5415 11174 5371 11174 5371 11175 5415 11175 5418 11175 5426 11176 5345 11176 5371 11176 5426 11177 5371 11177 5428 11177 5345 11178 5416 11178 5371 11178 5418 11179 5423 11179 5373 11179 5345 11180 5426 11180 5418 11180 5418 11181 5426 11181 5372 11181 5418 11182 5372 11182 5417 11182 5423 11183 5418 11183 5372 11183 5423 11184 5372 11184 5426 11184 5458 11185 5373 11185 5532 11185 5458 11186 5532 11186 5445 11186 5445 11187 5532 11187 5406 11187 5445 11188 5406 11188 5535 11188 5445 11189 5535 11189 5539 11189 5373 11190 5374 11190 5423 11190 5423 11191 5374 11191 5373 11191 5375 11192 5419 11192 5420 11192 5420 11193 5375 11193 5373 11193 5373 11194 5375 11194 5420 11194 5373 11195 5420 11195 5532 11195 5532 11196 5420 11196 5342 11196 5420 11197 5423 11197 5343 11197 5423 11198 5420 11198 5373 11198 5452 11199 5420 11199 5343 11199 5377 11200 5376 11200 5509 11200 5377 11201 5359 11201 5376 11201 5377 11202 5509 11202 5421 11202 5421 11203 5509 11203 5494 11203 5494 11204 5510 11204 5359 11204 5456 11205 5522 11205 5500 11205 5468 11206 5500 11206 5378 11206 5378 11207 5500 11207 5522 11207 5456 11208 5500 11208 5388 11208 5468 11209 5394 11209 5499 11209 5524 11210 5490 11210 5482 11210 5379 11211 5496 11211 5397 11211 5380 11212 5490 11212 5524 11212 5490 11213 5380 11213 5381 11213 5397 11214 5496 11214 5381 11214 5397 11215 5381 11215 5380 11215 5454 11216 5478 11216 5377 11216 5377 11217 5478 11217 5495 11217 5413 11218 5476 11218 5411 11218 5411 11219 5476 11219 5478 11219 5411 11220 5478 11220 5454 11220 5476 11221 5382 11221 5492 11221 5424 11222 5494 11222 5397 11222 5377 11223 5507 11223 5378 11223 5378 11224 5507 11224 5393 11224 5471 11225 5421 11225 5395 11225 5471 11226 5395 11226 5472 11226 5472 11227 5395 11227 5424 11227 5380 11228 5504 11228 5502 11228 5504 11229 5380 11229 5383 11229 5383 11230 5380 11230 5399 11230 5384 11231 5486 11231 5385 11231 5384 11232 5385 11232 5391 11232 5384 11233 5537 11233 5486 11233 5486 11234 5537 11234 5387 11234 5387 11235 5537 11235 5457 11235 5387 11236 5457 11236 5386 11236 5386 11237 5457 11237 5456 11237 5346 11238 5384 11238 5467 11238 5384 11239 5346 11239 5399 11239 5399 11240 5346 11240 5483 11240 5384 11241 5488 11241 5467 11241 5383 11242 5483 11242 5390 11242 5386 11243 5456 11243 5499 11243 5499 11244 5456 11244 5388 11244 5499 11245 5388 11245 5389 11245 5488 11246 5384 11246 5390 11246 5390 11247 5384 11247 5383 11247 5383 11248 5384 11248 5391 11248 5495 11249 5494 11249 5377 11249 5377 11250 5494 11250 5359 11250 5378 11251 5393 11251 5394 11251 5378 11252 5394 11252 5468 11252 5393 11253 5392 11253 5394 11253 5499 11254 5394 11254 5392 11254 5377 11255 5421 11255 5471 11255 5377 11256 5471 11256 5507 11256 5499 11257 5344 11257 5392 11257 5392 11258 5344 11258 5499 11258 5421 11259 5494 11259 5395 11259 5395 11260 5494 11260 5422 11260 5393 11261 5383 11261 5392 11261 5392 11262 5383 11262 5396 11262 5392 11263 5396 11263 5499 11263 5499 11264 5396 11264 5391 11264 5422 11265 5494 11265 5395 11265 5395 11266 5494 11266 5424 11266 5424 11267 5397 11267 5398 11267 5424 11268 5398 11268 5472 11268 5383 11269 5391 11269 5396 11269 5397 11270 5482 11270 5379 11270 5476 11271 5413 11271 5382 11271 5382 11272 5413 11272 5397 11272 5397 11273 5413 11273 5524 11273 5397 11274 5524 11274 5482 11274 5384 11275 5399 11275 5380 11275 5383 11276 5399 11276 5483 11276 5380 11277 5398 11277 5397 11277 5398 11278 5380 11278 5472 11278 5472 11279 5380 11279 5502 11279 5460 11280 5539 11280 5400 11280 5447 11281 5437 11281 5459 11281 5459 11282 5437 11282 5438 11282 5459 11283 5438 11283 5404 11283 5525 11284 5401 11284 5402 11284 5400 11285 5461 11285 5460 11285 5449 11286 5429 11286 5466 11286 5466 11287 5429 11287 5401 11287 5466 11288 5401 11288 5525 11288 5380 11289 5526 11289 5525 11289 5380 11290 5525 11290 5436 11290 5436 11291 5525 11291 5402 11291 5436 11292 5402 11292 5448 11292 5403 11293 5384 11293 5539 11293 5539 11294 5384 11294 5404 11294 5539 11295 5404 11295 5400 11295 5400 11296 5404 11296 5438 11296 5402 11297 5463 11297 5448 11297 5404 11298 5384 11298 5380 11298 5404 11299 5380 11299 5436 11299 5531 11300 5443 11300 5521 11300 5521 11301 5456 11301 5533 11301 5521 11302 5533 11302 5531 11302 5407 11303 5534 11303 5457 11303 5457 11304 5534 11304 5535 11304 5457 11305 5535 11305 5406 11305 5457 11306 5406 11306 5456 11306 5456 11307 5406 11307 5533 11307 5534 11308 5407 11308 5536 11308 5536 11309 5407 11309 5537 11309 5520 11310 5519 11310 5444 11310 5444 11311 5519 11311 5408 11311 5444 11312 5408 11312 5377 11312 5377 11313 5408 11313 5453 11313 5453 11314 5408 11314 5454 11314 5454 11315 5408 11315 5527 11315 5454 11316 5527 11316 5409 11316 5454 11317 5409 11317 5411 11317 5411 11318 5409 11318 5410 11318 5412 11319 5411 11319 5410 11319 5412 11320 5413 11320 5411 11320 5412 11321 5455 11321 5413 11321 5526 11322 5405 11322 5455 11322 5455 11323 5405 11323 5413 11323 5399 11324 5415 11324 5414 11324 5414 11325 5415 11325 5416 11325 5344 11326 5373 11326 5374 11326 5419 11327 5375 11327 5420 11327 5466 11328 5525 11328 5465 11328 5433 11329 5401 11329 5449 11329 5449 11330 5401 11330 5429 11330 5433 11331 5430 11331 5401 11331 5401 11332 5430 11332 5518 11332 5518 11333 5430 11333 5431 11333 5431 11334 5430 11334 5433 11334 5401 11335 5518 11335 5402 11335 5514 11336 5518 11336 5431 11336 5518 11337 5514 11337 5402 11337 5516 11338 5432 11338 5402 11338 5514 11339 5515 11339 5516 11339 5514 11340 5516 11340 5402 11340 5516 11341 5515 11341 5432 11341 5432 11342 5515 11342 5433 11342 5515 11343 5514 11343 5431 11343 5515 11344 5431 11344 5433 11344 5434 11345 5463 11345 5432 11345 5432 11346 5463 11346 5402 11346 5464 11347 5463 11347 5434 11347 5464 11348 5368 11348 5448 11348 5448 11349 5368 11349 5435 11349 5448 11350 5435 11350 5436 11350 5404 11351 5371 11351 5459 11351 5459 11352 5371 11352 5458 11352 5438 11353 5437 11353 5446 11353 5446 11354 5437 11354 5447 11354 5438 11355 5446 11355 5340 11355 5512 11356 5440 11356 5400 11356 5340 11357 5446 11357 5512 11357 5340 11358 5512 11358 5439 11358 5439 11359 5400 11359 5438 11359 5439 11360 5438 11360 5340 11360 5439 11361 5512 11361 5400 11361 5512 11362 5441 11362 5440 11362 5440 11363 5441 11363 5446 11363 5446 11364 5441 11364 5512 11364 5461 11365 5400 11365 5442 11365 5442 11366 5400 11366 5440 11366 5461 11367 5442 11367 5462 11367 5462 11368 5445 11368 5539 11368 5462 11369 5539 11369 5460 11369 5444 11370 5377 11370 5523 11370 5523 11371 5377 11371 5378 11371 5520 11372 5451 11372 5443 11372 5443 11373 5451 11373 5450 11373 5521 11374 5443 11374 5523 11374 5444 11375 5451 11375 5520 11375 5443 11376 5450 11376 5523 11376 5523 11377 5450 11377 5451 11377 5523 11378 5451 11378 5444 11378 5462 11379 5442 11379 5445 11379 5445 11380 5442 11380 5440 11380 5445 11381 5440 11381 5458 11381 5458 11382 5440 11382 5446 11382 5447 11383 5458 11383 5446 11383 5464 11384 5434 11384 5368 11384 5368 11385 5434 11385 5432 11385 5368 11386 5432 11386 5465 11386 5465 11387 5432 11387 5433 11387 5449 11388 5465 11388 5433 11388 5453 11389 5454 11389 5377 11389 5526 11390 5524 11390 5405 11390 5405 11391 5524 11391 5413 11391 5521 11392 5522 11392 5456 11392 5407 11393 5457 11393 5537 11393 5537 11394 5384 11394 5538 11394 5447 11395 5459 11395 5458 11395 5460 11396 5461 11396 5462 11396 5448 11397 5463 11397 5464 11397 5449 11398 5466 11398 5465 11398 5487 11399 5347 11399 5467 11399 5467 11400 5347 11400 5346 11400 5499 11401 5481 11401 5468 11401 5468 11402 5481 11402 5501 11402 5500 11403 5468 11403 5469 11403 5469 11404 5468 11404 5501 11404 5470 11405 5388 11405 5469 11405 5469 11406 5388 11406 5500 11406 5354 11407 5387 11407 5386 11407 5354 11408 5386 11408 5497 11408 5486 11409 5387 11409 5485 11409 5485 11410 5387 11410 5354 11410 5469 11411 5501 11411 5470 11411 5470 11412 5501 11412 5481 11412 5471 11413 5472 11413 5474 11413 5474 11414 5472 11414 5503 11414 5393 11415 5507 11415 5506 11415 5506 11416 5507 11416 5508 11416 5505 11417 5383 11417 5475 11417 5475 11418 5383 11418 5393 11418 5502 11419 5504 11419 5473 11419 5473 11420 5505 11420 5475 11420 5473 11421 5475 11421 5474 11421 5473 11422 5474 11422 5503 11422 5508 11423 5474 11423 5506 11423 5506 11424 5474 11424 5475 11424 5509 11425 5376 11425 5361 11425 5361 11426 5376 11426 5360 11426 5381 11427 5496 11427 5480 11427 5490 11428 5381 11428 5479 11428 5479 11429 5381 11429 5480 11429 5479 11430 5491 11430 5490 11430 5490 11431 5491 11431 5482 11431 5492 11432 5477 11432 5476 11432 5476 11433 5477 11433 5478 11433 5352 11434 5478 11434 5477 11434 5517 11435 5496 11435 5491 11435 5480 11436 5517 11436 5479 11436 5479 11437 5517 11437 5491 11437 5517 11438 5480 11438 5496 11438 5494 11439 5495 11439 5493 11439 5493 11440 5495 11440 5352 11440 5359 11441 5510 11441 5362 11441 5362 11442 5510 11442 5511 11442 5389 11443 5388 11443 5481 11443 5481 11444 5388 11444 5470 11444 5386 11445 5499 11445 5497 11445 5497 11446 5499 11446 5353 11446 5382 11447 5397 11447 5351 11447 5351 11448 5397 11448 5348 11448 5491 11449 5496 11449 5482 11449 5482 11450 5496 11450 5379 11450 5355 11451 5498 11451 5385 11451 5385 11452 5498 11452 5391 11452 5390 11453 5483 11453 5489 11453 5489 11454 5483 11454 5484 11454 5355 11455 5385 11455 5486 11455 5355 11456 5486 11456 5485 11456 5489 11457 5488 11457 5390 11457 5382 11458 5351 11458 5492 11458 5478 11459 5352 11459 5495 11459 5499 11460 5389 11460 5481 11460 5502 11461 5473 11461 5503 11461 5502 11462 5503 11462 5472 11462 5383 11463 5505 11463 5504 11463 5504 11464 5505 11464 5473 11464 5393 11465 5506 11465 5475 11465 5471 11466 5474 11466 5507 11466 5507 11467 5474 11467 5508 11467 5511 11468 5510 11468 5494 11468 5339 11469 5431 11469 5514 11469 5339 11470 5514 11470 5350 11470 5349 11471 5515 11471 5516 11471 5349 11472 5516 11472 5515 11472 5522 11473 5523 11473 5378 11473 5523 11474 5522 11474 5521 11474 5538 11475 5384 11475 5363 11475 5363 11476 5384 11476 5403 11476 5524 11477 5526 11477 5380 11477 5412 11478 5409 11478 5455 11478 5410 11479 5409 11479 5412 11479 5519 11480 5528 11480 5408 11480 5408 11481 5528 11481 5527 11481 5528 11482 5519 11482 5530 11482 5365 11483 5530 11483 5529 11483 5529 11484 5530 11484 5519 11484 5365 11485 5529 11485 5443 11485 5531 11486 5532 11486 5443 11486 5532 11487 5531 11487 5533 11487 5533 11488 5406 11488 5532 11488 5536 11489 5535 11489 5534 11489 5538 11490 5363 11490 5537 11490 5537 11491 5363 11491 5536 11491 5536 11492 5363 11492 5535 11492 5403 11493 5539 11493 5363 11493 5436 11494 5435 11494 5371 11494 5436 11495 5371 11495 5404 11495 5731 11496 5786 11496 5785 11496 5731 11497 5785 11497 5784 11497 5724 11498 5781 11498 5780 11498 5732 11499 5780 11499 5797 11499 5732 11500 5781 11500 5724 11500 5544 11501 5799 11501 5543 11501 5722 11502 5603 11502 5721 11502 5721 11503 5603 11503 5541 11503 5603 11504 5722 11504 5600 11504 5600 11505 5722 11505 5542 11505 5600 11506 5542 11506 5599 11506 5800 11507 5599 11507 5542 11507 5800 11508 5542 11508 5721 11508 5800 11509 5721 11509 5543 11509 5543 11510 5721 11510 5544 11510 5544 11511 5721 11511 5541 11511 5544 11512 5541 11512 5594 11512 5749 11513 5748 11513 5545 11513 5723 11514 5749 11514 5724 11514 5749 11515 5723 11515 5688 11515 5688 11516 5723 11516 5546 11516 5688 11517 5546 11517 5595 11517 5595 11518 5546 11518 5725 11518 5595 11519 5725 11519 5547 11519 5547 11520 5725 11520 5724 11520 5547 11521 5724 11521 5545 11521 5545 11522 5724 11522 5749 11522 5550 11523 5637 11523 5636 11523 5703 11524 5637 11524 5550 11524 5550 11525 5636 11525 5548 11525 5548 11526 5636 11526 5549 11526 5548 11527 5549 11527 5550 11527 5550 11528 5549 11528 5703 11528 5733 11529 5700 11529 5553 11529 5733 11530 5553 11530 5638 11530 5733 11531 5638 11531 5552 11531 5733 11532 5552 11532 5551 11532 5551 11533 5552 11533 5700 11533 5551 11534 5700 11534 5733 11534 5726 11535 5548 11535 5707 11535 5707 11536 5548 11536 5554 11536 5707 11537 5554 11537 5706 11537 5706 11538 5554 11538 5727 11538 5613 11539 5706 11539 5727 11539 5613 11540 5727 11540 5598 11540 5798 11541 5598 11541 5727 11541 5798 11542 5727 11542 5555 11542 5555 11543 5727 11543 5726 11543 5726 11544 5639 11544 5555 11544 5555 11545 5639 11545 5611 11545 5585 11546 5698 11546 5730 11546 5711 11547 5728 11547 5551 11547 5711 11548 5551 11548 5698 11548 5698 11549 5551 11549 5730 11549 5588 11550 5585 11550 5556 11550 5556 11551 5585 11551 5730 11551 5556 11552 5730 11552 5729 11552 5556 11553 5729 11553 5557 11553 5729 11554 5558 11554 5557 11554 5728 11555 5614 11555 5729 11555 5729 11556 5614 11556 5558 11556 5558 11557 5614 11557 5559 11557 5728 11558 5711 11558 5614 11558 5604 11559 5560 11559 5578 11559 5589 11560 5561 11560 5744 11560 5561 11561 5562 11561 5563 11561 5563 11562 5562 11562 5540 11562 5563 11563 5540 11563 5689 11563 5804 11564 5807 11564 5540 11564 5540 11565 5807 11565 5689 11565 5578 11566 5560 11566 5567 11566 5562 11567 5561 11567 5564 11567 5564 11568 5561 11568 5589 11568 5564 11569 5589 11569 5578 11569 5578 11570 5589 11570 5604 11570 5815 11571 5566 11571 5565 11571 5565 11572 5566 11572 5788 11572 5567 11573 5820 11573 5815 11573 5567 11574 5815 11574 5565 11574 5804 11575 5813 11575 5567 11575 5567 11576 5813 11576 5820 11576 5817 11577 5813 11577 5804 11577 5816 11578 5817 11578 5805 11578 5805 11579 5817 11579 5804 11579 5816 11580 5805 11580 5770 11580 5770 11581 5805 11581 5806 11581 5568 11582 5788 11582 5806 11582 5806 11583 5788 11583 5770 11583 5565 11584 5788 11584 5568 11584 5624 11585 5622 11585 5570 11585 5823 11586 5569 11586 5708 11586 5708 11587 5569 11587 5701 11587 5708 11588 5701 11588 5707 11588 5570 11589 5622 11589 5701 11589 5701 11590 5622 11590 5707 11590 5656 11591 5785 11591 5794 11591 5656 11592 5794 11592 5571 11592 5571 11593 5794 11593 5811 11593 5811 11594 5794 11594 5795 11594 5566 11595 5811 11595 5795 11595 5566 11596 5795 11596 5791 11596 5572 11597 5573 11597 5658 11597 5573 11598 5781 11598 5658 11598 5812 11599 5796 11599 5572 11599 5572 11600 5796 11600 5573 11600 5796 11601 5812 11601 5816 11601 5796 11602 5816 11602 5793 11602 5571 11603 5811 11603 5652 11603 5652 11604 5811 11604 5574 11604 5652 11605 5574 11605 5653 11605 5653 11606 5574 11606 5822 11606 5653 11607 5822 11607 5575 11607 5822 11608 5821 11608 5575 11608 5575 11609 5821 11609 5582 11609 5582 11610 5821 11610 5814 11610 5582 11611 5814 11611 5581 11611 5581 11612 5814 11612 5819 11612 5581 11613 5819 11613 5576 11613 5819 11614 5818 11614 5576 11614 5577 11615 5812 11615 5572 11615 5572 11616 5648 11616 5577 11616 5577 11617 5648 11617 5650 11617 5577 11618 5650 11618 5818 11618 5818 11619 5650 11619 5576 11619 5562 11620 5564 11620 5565 11620 5565 11621 5564 11621 5578 11621 5806 11622 5540 11622 5562 11622 5712 11623 5579 11623 5580 11623 5580 11624 5579 11624 5584 11624 5741 11625 5581 11625 5584 11625 5584 11626 5581 11626 5626 11626 5584 11627 5626 11627 5580 11627 5654 11628 5582 11628 5825 11628 5825 11629 5582 11629 5607 11629 5825 11630 5607 11630 5720 11630 5720 11631 5607 11631 5608 11631 5581 11632 5741 11632 5582 11632 5582 11633 5741 11633 5583 11633 5582 11634 5583 11634 5607 11634 5584 11635 5586 11635 5693 11635 5690 11636 5693 11636 5586 11636 5623 11637 5697 11637 5579 11637 5696 11638 5586 11638 5579 11638 5697 11639 5696 11639 5579 11639 5690 11640 5586 11640 5587 11640 5587 11641 5586 11641 5699 11641 5579 11642 5586 11642 5584 11642 5587 11643 5699 11643 5585 11643 5587 11644 5585 11644 5588 11644 5667 11645 5660 11645 5591 11645 5662 11646 5665 11646 5661 11646 5561 11647 5597 11647 5671 11647 5593 11648 5747 11648 5590 11648 5675 11649 5683 11649 5747 11649 5679 11650 5686 11650 5754 11650 5589 11651 5673 11651 5685 11651 5685 11652 5673 11652 5684 11652 5747 11653 5683 11653 5754 11653 5747 11654 5754 11654 5590 11654 5754 11655 5686 11655 5684 11655 5754 11656 5684 11656 5590 11656 5590 11657 5684 11657 5674 11657 5674 11658 5684 11658 5673 11658 5671 11659 5597 11659 5674 11659 5674 11660 5597 11660 5591 11660 5591 11661 5592 11661 5590 11661 5591 11662 5590 11662 5674 11662 5591 11663 5660 11663 5661 11663 5591 11664 5661 11664 5592 11664 5661 11665 5665 11665 5592 11665 5592 11666 5665 11666 5666 11666 5681 11667 5745 11667 5686 11667 5681 11668 5686 11668 5679 11668 5683 11669 5675 11669 5676 11669 5683 11670 5676 11670 5680 11670 5799 11671 5593 11671 5590 11671 5685 11672 5779 11672 5589 11672 5589 11673 5779 11673 5604 11673 5604 11674 5779 11674 5745 11674 5745 11675 5681 11675 5604 11675 5604 11676 5681 11676 5680 11676 5680 11677 5676 11677 5604 11677 5604 11678 5676 11678 5678 11678 5604 11679 5678 11679 5594 11679 5799 11680 5544 11680 5593 11680 5593 11681 5544 11681 5677 11681 5594 11682 5678 11682 5544 11682 5544 11683 5678 11683 5677 11683 5592 11684 5666 11684 5801 11684 5801 11685 5666 11685 5746 11685 5547 11686 5801 11686 5595 11686 5595 11687 5801 11687 5746 11687 5665 11688 5662 11688 5664 11688 5665 11689 5664 11689 5596 11689 5563 11690 5669 11690 5597 11690 5563 11691 5597 11691 5561 11691 5660 11692 5667 11692 5668 11692 5660 11693 5668 11693 5659 11693 5595 11694 5746 11694 5689 11694 5596 11695 5664 11695 5768 11695 5659 11696 5668 11696 5689 11696 5659 11697 5689 11697 5768 11697 5768 11698 5689 11698 5746 11698 5768 11699 5746 11699 5596 11699 5668 11700 5669 11700 5689 11700 5689 11701 5669 11701 5563 11701 5592 11702 5557 11702 5558 11702 5592 11703 5558 11703 5613 11703 5559 11704 5613 11704 5558 11704 5613 11705 5598 11705 5592 11705 5592 11706 5598 11706 5590 11706 5590 11707 5598 11707 5798 11707 5602 11708 5599 11708 5611 11708 5599 11709 5602 11709 5600 11709 5802 11710 5603 11710 5601 11710 5601 11711 5603 11711 5600 11711 5601 11712 5600 11712 5602 11712 5604 11713 5594 11713 5541 11713 5603 11714 5802 11714 5541 11714 5541 11715 5802 11715 5604 11715 5740 11716 5605 11716 5803 11716 5740 11717 5607 11717 5738 11717 5738 11718 5607 11718 5583 11718 5740 11719 5803 11719 5802 11719 5740 11720 5802 11720 5601 11720 5740 11721 5739 11721 5605 11721 5605 11722 5739 11722 5606 11722 5739 11723 5737 11723 5606 11723 5610 11724 5622 11724 5608 11724 5607 11725 5740 11725 5609 11725 5639 11726 5694 11726 5602 11726 5609 11727 5610 11727 5607 11727 5602 11728 5694 11728 5601 11728 5601 11729 5694 11729 5609 11729 5601 11730 5609 11730 5740 11730 5607 11731 5610 11731 5608 11731 5611 11732 5639 11732 5602 11732 5709 11733 5706 11733 5613 11733 5709 11734 5613 11734 5612 11734 5612 11735 5613 11735 5559 11735 5612 11736 5559 11736 5614 11736 5711 11737 5705 11737 5615 11737 5615 11738 5705 11738 5616 11738 5615 11739 5616 11739 5824 11739 5711 11740 5623 11740 5705 11740 5705 11741 5623 11741 5621 11741 5618 11742 5617 11742 5713 11742 5625 11743 5646 11743 5719 11743 5717 11744 5719 11744 5646 11744 5717 11745 5646 11745 5654 11745 5626 11746 5617 11746 5716 11746 5716 11747 5617 11747 5618 11747 5825 11748 5619 11748 5717 11748 5718 11749 5619 11749 5720 11749 5720 11750 5619 11750 5825 11750 5715 11751 5714 11751 5712 11751 5715 11752 5712 11752 5580 11752 5626 11753 5716 11753 5715 11753 5624 11754 5570 11754 5702 11754 5702 11755 5570 11755 5701 11755 5620 11756 5705 11756 5621 11756 5695 11757 5726 11757 5622 11757 5622 11758 5610 11758 5695 11758 5623 11759 5698 11759 5697 11759 5625 11760 5624 11760 5702 11760 5621 11761 5713 11761 5620 11761 5635 11762 5629 11762 5626 11762 5626 11763 5629 11763 5617 11763 5617 11764 5629 11764 5630 11764 5617 11765 5630 11765 5713 11765 5630 11766 5627 11766 5713 11766 5713 11767 5627 11767 5631 11767 5635 11768 5586 11768 5628 11768 5628 11769 5629 11769 5635 11769 5696 11770 5629 11770 5628 11770 5629 11771 5696 11771 5630 11771 5627 11772 5630 11772 5696 11772 5696 11773 5697 11773 5627 11773 5631 11774 5697 11774 5698 11774 5631 11775 5627 11775 5697 11775 5713 11776 5631 11776 5620 11776 5620 11777 5631 11777 5634 11777 5620 11778 5634 11778 5783 11778 5783 11779 5634 11779 5633 11779 5635 11780 5649 11780 5632 11780 5632 11781 5649 11781 5633 11781 5632 11782 5633 11782 5634 11782 5634 11783 5585 11783 5632 11783 5698 11784 5634 11784 5631 11784 5698 11785 5585 11785 5634 11785 5586 11786 5635 11786 5632 11786 5586 11787 5632 11787 5699 11787 5553 11788 5700 11788 5783 11788 5702 11789 5636 11789 5790 11789 5783 11790 5700 11790 5620 11790 5636 11791 5637 11791 5790 11791 5790 11792 5637 11792 5783 11792 5553 11793 5783 11793 5638 11793 5703 11794 5638 11794 5783 11794 5703 11795 5783 11795 5637 11795 5651 11796 5645 11796 5655 11796 5655 11797 5645 11797 5750 11797 5655 11798 5750 11798 5657 11798 5642 11799 5625 11799 5641 11799 5641 11800 5625 11800 5702 11800 5657 11801 5750 11801 5640 11801 5657 11802 5640 11802 5790 11802 5790 11803 5640 11803 5702 11803 5702 11804 5640 11804 5641 11804 5640 11805 5639 11805 5726 11805 5640 11806 5726 11806 5641 11806 5695 11807 5642 11807 5641 11807 5641 11808 5726 11808 5695 11808 5642 11809 5695 11809 5610 11809 5642 11810 5610 11810 5643 11810 5643 11811 5610 11811 5647 11811 5644 11812 5647 11812 5610 11812 5647 11813 5644 11813 5609 11813 5609 11814 5645 11814 5647 11814 5646 11815 5643 11815 5647 11815 5646 11816 5647 11816 5654 11816 5647 11817 5645 11817 5654 11817 5654 11818 5645 11818 5651 11818 5625 11819 5642 11819 5646 11819 5646 11820 5642 11820 5643 11820 5626 11821 5581 11821 5576 11821 5572 11822 5649 11822 5648 11822 5648 11823 5649 11823 5650 11823 5650 11824 5649 11824 5635 11824 5650 11825 5635 11825 5576 11825 5576 11826 5635 11826 5626 11826 5572 11827 5658 11827 5649 11827 5649 11828 5658 11828 5633 11828 5651 11829 5571 11829 5652 11829 5651 11830 5652 11830 5653 11830 5651 11831 5653 11831 5654 11831 5654 11832 5653 11832 5575 11832 5582 11833 5654 11833 5575 11833 5571 11834 5651 11834 5656 11834 5656 11835 5651 11835 5655 11835 5655 11836 5657 11836 5656 11836 5656 11837 5657 11837 5785 11837 5781 11838 5782 11838 5658 11838 5658 11839 5782 11839 5633 11839 5760 11840 5763 11840 5661 11840 5768 11841 5766 11841 5659 11841 5659 11842 5766 11842 5660 11842 5661 11843 5660 11843 5760 11843 5760 11844 5660 11844 5766 11844 5662 11845 5661 11845 5763 11845 5763 11846 5663 11846 5662 11846 5662 11847 5663 11847 5664 11847 5663 11848 5768 11848 5664 11848 5761 11849 5762 11849 5665 11849 5666 11850 5665 11850 5762 11850 5762 11851 5789 11851 5666 11851 5666 11852 5789 11852 5746 11852 5765 11853 5764 11853 5596 11853 5596 11854 5764 11854 5665 11854 5761 11855 5665 11855 5764 11855 5668 11856 5769 11856 5669 11856 5667 11857 5591 11857 5670 11857 5771 11858 5667 11858 5670 11858 5771 11859 5767 11859 5667 11859 5667 11860 5767 11860 5668 11860 5769 11861 5668 11861 5767 11861 5751 11862 5597 11862 5669 11862 5751 11863 5669 11863 5769 11863 5591 11864 5597 11864 5670 11864 5670 11865 5597 11865 5751 11865 5773 11866 5772 11866 5674 11866 5671 11867 5674 11867 5772 11867 5672 11868 5561 11868 5671 11868 5672 11869 5671 11869 5772 11869 5744 11870 5774 11870 5673 11870 5673 11871 5589 11871 5744 11871 5674 11872 5673 11872 5773 11872 5773 11873 5673 11873 5774 11873 5753 11874 5787 11874 5675 11874 5675 11875 5787 11875 5676 11875 5759 11876 5678 11876 5676 11876 5676 11877 5787 11877 5759 11877 5677 11878 5678 11878 5792 11878 5792 11879 5678 11879 5759 11879 5792 11880 5752 11880 5677 11880 5677 11881 5752 11881 5593 11881 5778 11882 5682 11882 5680 11882 5679 11883 5754 11883 5756 11883 5756 11884 5778 11884 5679 11884 5679 11885 5778 11885 5681 11885 5778 11886 5680 11886 5681 11886 5758 11887 5683 11887 5680 11887 5758 11888 5680 11888 5682 11888 5754 11889 5683 11889 5758 11889 5755 11890 5757 11890 5684 11890 5685 11891 5684 11891 5757 11891 5684 11892 5686 11892 5755 11892 5755 11893 5686 11893 5777 11893 5609 11894 5694 11894 5645 11894 5645 11895 5694 11895 5750 11895 5688 11896 5687 11896 5690 11896 5688 11897 5690 11897 5749 11897 5687 11898 5688 11898 5689 11898 5689 11899 5688 11899 5595 11899 5587 11900 5749 11900 5690 11900 5690 11901 5687 11901 5692 11901 5692 11902 5691 11902 5736 11902 5690 11903 5692 11903 5736 11903 5690 11904 5736 11904 5693 11904 5693 11905 5741 11905 5584 11905 5644 11906 5610 11906 5609 11906 5586 11907 5696 11907 5628 11907 5699 11908 5632 11908 5585 11908 5620 11909 5700 11909 5705 11909 5569 11910 5549 11910 5701 11910 5636 11911 5702 11911 5701 11911 5636 11912 5701 11912 5549 11912 5703 11913 5569 11913 5704 11913 5703 11914 5704 11914 5638 11914 5638 11915 5704 11915 5616 11915 5549 11916 5569 11916 5703 11916 5705 11917 5700 11917 5552 11917 5705 11918 5552 11918 5616 11918 5616 11919 5552 11919 5638 11919 5622 11920 5726 11920 5707 11920 5708 11921 5707 11921 5709 11921 5709 11922 5707 11922 5706 11922 5615 11923 5824 11923 5612 11923 5823 11924 5708 11924 5709 11924 5824 11925 5710 11925 5612 11925 5612 11926 5710 11926 5709 11926 5709 11927 5710 11927 5823 11927 5612 11928 5614 11928 5615 11928 5711 11929 5615 11929 5614 11929 5698 11930 5623 11930 5711 11930 5714 11931 5618 11931 5712 11931 5712 11932 5618 11932 5713 11932 5712 11933 5713 11933 5621 11933 5621 11934 5623 11934 5579 11934 5621 11935 5579 11935 5712 11935 5618 11936 5714 11936 5715 11936 5618 11937 5715 11937 5716 11937 5717 11938 5619 11938 5719 11938 5719 11939 5619 11939 5718 11939 5720 11940 5608 11940 5622 11940 5719 11941 5718 11941 5625 11941 5625 11942 5718 11942 5720 11942 5625 11943 5720 11943 5624 11943 5624 11944 5720 11944 5622 11944 5721 11945 5542 11945 5722 11945 5724 11946 5725 11946 5546 11946 5724 11947 5546 11947 5723 11947 5548 11948 5726 11948 5727 11948 5548 11949 5727 11949 5554 11949 5551 11950 5728 11950 5729 11950 5551 11951 5729 11951 5730 11951 5731 11952 5784 11952 5786 11952 5780 11953 5732 11953 5724 11953 5743 11954 5736 11954 5734 11954 5734 11955 5736 11955 5691 11955 5741 11956 5693 11956 5735 11956 5735 11957 5693 11957 5743 11957 5743 11958 5693 11958 5736 11958 5738 11959 5583 11959 5737 11959 5738 11960 5737 11960 5739 11960 5738 11961 5739 11961 5740 11961 5741 11962 5735 11962 5809 11962 5741 11963 5809 11963 5742 11963 5741 11964 5742 11964 5810 11964 5741 11965 5810 11965 5808 11965 5606 11966 5737 11966 5808 11966 5808 11967 5737 11967 5583 11967 5808 11968 5583 11968 5741 11968 5743 11969 5734 11969 5735 11969 5735 11970 5734 11970 5809 11970 5561 11971 5672 11971 5744 11971 5745 11972 5779 11972 5776 11972 5779 11973 5685 11973 5757 11973 5779 11974 5757 11974 5775 11974 5777 11975 5686 11975 5745 11975 5777 11976 5745 11976 5776 11976 5746 11977 5768 11977 5596 11977 5768 11978 5746 11978 5789 11978 5765 11979 5596 11979 5768 11979 5752 11980 5753 11980 5747 11980 5675 11981 5747 11981 5753 11981 5752 11982 5747 11982 5593 11982 5588 11983 5748 11983 5587 11983 5587 11984 5748 11984 5749 11984 5694 11985 5639 11985 5750 11985 5750 11986 5639 11986 5640 11986 5753 11987 5752 11987 5783 11987 5753 11988 5754 11988 5758 11988 5754 11989 5753 11989 5783 11989 5754 11990 5783 11990 5756 11990 5777 11991 5756 11991 5755 11991 5755 11992 5756 11992 5783 11992 5783 11993 5757 11993 5755 11993 5753 11994 5758 11994 5787 11994 5787 11995 5758 11995 5682 11995 5787 11996 5682 11996 5778 11996 5759 11997 5787 11997 5791 11997 5759 11998 5791 11998 5792 11998 5783 11999 5760 11999 5771 11999 5760 12000 5766 12000 5771 12000 5783 12001 5763 12001 5760 12001 5763 12002 5761 12002 5764 12002 5761 12003 5763 12003 5783 12003 5761 12004 5783 12004 5762 12004 5768 12005 5663 12005 5765 12005 5763 12006 5764 12006 5663 12006 5663 12007 5764 12007 5765 12007 5771 12008 5766 12008 5767 12008 5767 12009 5766 12009 5768 12009 5769 12010 5816 12010 5770 12010 5769 12011 5770 12011 5672 12011 5769 12012 5672 12012 5751 12012 5672 12013 5770 12013 5788 12013 5672 12014 5788 12014 5775 12014 5670 12015 5783 12015 5771 12015 5783 12016 5670 12016 5751 12016 5772 12017 5751 12017 5672 12017 5772 12018 5783 12018 5751 12018 5775 12019 5744 12019 5672 12019 5773 12020 5774 12020 5783 12020 5783 12021 5774 12021 5757 12021 5783 12022 5772 12022 5773 12022 5757 12023 5774 12023 5775 12023 5775 12024 5774 12024 5744 12024 5776 12025 5778 12025 5777 12025 5777 12026 5778 12026 5756 12026 5778 12027 5776 12027 5775 12027 5775 12028 5776 12028 5779 12028 5791 12029 5786 12029 5784 12029 5781 12030 5732 12030 5797 12030 5781 12031 5797 12031 5780 12031 5633 12032 5782 12032 5783 12032 5785 12033 5791 12033 5784 12033 5791 12034 5787 12034 5566 12034 5793 12035 5816 12035 5789 12035 5783 12036 5752 12036 5657 12036 5783 12037 5657 12037 5790 12037 5783 12038 5782 12038 5789 12038 5783 12039 5789 12039 5762 12039 5657 12040 5752 12040 5791 12040 5791 12041 5752 12041 5792 12041 5788 12042 5566 12042 5775 12042 5775 12043 5566 12043 5778 12043 5778 12044 5566 12044 5787 12044 5657 12045 5791 12045 5785 12045 5781 12046 5797 12046 5782 12046 5782 12047 5797 12047 5793 12047 5782 12048 5793 12048 5789 12048 5789 12049 5816 12049 5768 12049 5768 12050 5816 12050 5769 12050 5768 12051 5769 12051 5767 12051 5795 12052 5786 12052 5791 12052 5786 12053 5794 12053 5785 12053 5794 12054 5786 12054 5795 12054 5793 12055 5797 12055 5796 12055 5796 12056 5797 12056 5573 12056 5573 12057 5797 12057 5781 12057 5543 12058 5798 12058 5800 12058 5800 12059 5798 12059 5555 12059 5590 12060 5798 12060 5799 12060 5799 12061 5798 12061 5543 12061 5555 12062 5611 12062 5599 12062 5555 12063 5599 12063 5800 12063 5545 12064 5556 12064 5547 12064 5547 12065 5556 12065 5557 12065 5588 12066 5556 12066 5748 12066 5748 12067 5556 12067 5545 12067 5557 12068 5592 12068 5801 12068 5557 12069 5801 12069 5547 12069 5560 12070 5604 12070 5802 12070 5802 12071 5803 12071 5560 12071 5560 12072 5803 12072 5605 12072 5560 12073 5605 12073 5606 12073 5691 12074 5807 12074 5734 12074 5691 12075 5692 12075 5807 12075 5807 12076 5692 12076 5687 12076 5807 12077 5687 12077 5689 12077 5565 12078 5578 12078 5567 12078 5805 12079 5804 12079 5540 12079 5805 12080 5540 12080 5806 12080 5806 12081 5562 12081 5568 12081 5568 12082 5562 12082 5565 12082 5742 12083 5804 12083 5810 12083 5810 12084 5804 12084 5567 12084 5804 12085 5809 12085 5807 12085 5808 12086 5567 12086 5560 12086 5734 12087 5807 12087 5809 12087 5804 12088 5742 12088 5809 12088 5567 12089 5808 12089 5810 12089 5560 12090 5606 12090 5808 12090 5822 12091 5574 12091 5566 12091 5566 12092 5574 12092 5811 12092 5816 12093 5812 12093 5577 12093 5816 12094 5577 12094 5818 12094 5818 12095 5819 12095 5817 12095 5813 12096 5814 12096 5820 12096 5820 12097 5821 12097 5822 12097 5820 12098 5822 12098 5815 12098 5817 12099 5816 12099 5818 12099 5817 12100 5819 12100 5813 12100 5814 12101 5813 12101 5819 12101 5820 12102 5814 12102 5821 12102 5822 12103 5566 12103 5815 12103 5569 12104 5823 12104 5704 12104 5704 12105 5823 12105 5710 12105 5704 12106 5710 12106 5616 12106 5616 12107 5710 12107 5824 12107 5654 12108 5825 12108 5717 12108 5626 12109 5715 12109 5580 12109 5969 12110 5915 12110 5913 12110 5969 12111 5913 12111 5915 12111 5835 12112 5916 12112 5914 12112 5835 12113 5914 12113 5834 12113 5997 12114 5924 12114 5922 12114 5997 12115 5922 12115 5924 12115 5826 12116 5996 12116 5827 12116 5827 12117 5996 12117 5826 12117 5851 12118 5852 12118 5849 12118 5828 12119 5847 12119 5848 12119 5828 12120 5848 12120 5847 12120 5909 12121 5910 12121 5853 12121 5907 12122 5854 12122 5908 12122 5900 12123 5861 12123 5860 12123 5898 12124 5859 12124 5899 12124 5896 12125 5897 12125 5829 12125 5896 12126 5829 12126 5895 12126 5871 12127 5896 12127 5895 12127 5952 12128 5982 12128 5830 12128 5830 12129 5982 12129 5872 12129 5997 12130 5982 12130 5952 12130 5982 12131 5997 12131 5831 12131 5832 12132 5997 12132 5952 12132 5832 12133 5831 12133 5997 12133 5951 12134 5975 12134 5832 12134 5832 12135 5975 12135 5831 12135 5833 12136 5884 12136 5979 12136 5979 12137 5884 12137 5875 12137 5833 12138 5834 12138 5835 12138 5833 12139 5835 12139 5836 12139 5999 12140 5835 12140 5834 12140 5979 12141 5834 12141 5833 12141 5835 12142 5999 12142 5836 12142 5836 12143 5999 12143 5977 12143 5999 12144 5837 12144 5967 12144 5999 12145 5967 12145 5977 12145 5979 12146 5837 12146 5999 12146 5999 12147 5834 12147 5979 12147 5879 12148 5841 12148 5838 12148 5879 12149 5838 12149 5869 12149 5826 12150 5841 12150 5840 12150 5839 12151 5826 12151 5974 12151 5974 12152 5826 12152 5840 12152 5841 12153 5826 12153 5994 12153 5994 12154 5838 12154 5841 12154 5838 12155 5994 12155 5984 12155 5827 12156 5994 12156 5826 12156 5827 12157 5826 12157 5994 12157 5994 12158 5826 12158 5839 12158 5994 12159 5839 12159 5984 12159 5844 12160 5875 12160 5843 12160 5843 12161 5875 12161 5865 12161 5863 12162 5845 12162 5993 12162 5993 12163 5845 12163 5842 12163 5843 12164 5842 12164 5844 12164 5844 12165 5842 12165 5845 12165 6012 12166 6001 12166 5846 12166 5846 12167 6001 12167 5928 12167 5895 12168 5829 12168 5899 12168 6019 12169 6023 12169 5891 12169 6013 12170 5928 12170 6014 12170 5903 12171 6013 12171 5847 12171 5847 12172 5848 12172 5903 12172 5903 12173 5848 12173 5847 12173 5847 12174 6013 12174 6014 12174 5851 12175 5849 12175 5903 12175 5903 12176 5849 12176 6013 12176 5852 12177 5851 12177 5857 12177 5849 12178 5852 12178 5850 12178 5856 12179 5919 12179 5934 12179 5850 12180 5852 12180 5857 12180 5850 12181 5857 12181 5856 12181 5850 12182 5856 12182 6010 12182 6010 12183 5856 12183 5934 12183 6010 12184 5934 12184 6011 12184 5939 12185 5911 12185 6008 12185 5911 12186 5939 12186 6011 12186 5911 12187 6011 12187 5934 12187 5931 12188 5858 12188 5899 12188 5931 12189 5899 12189 5860 12189 5908 12190 5910 12190 5853 12190 5853 12191 5910 12191 5909 12191 5910 12192 6024 12192 5853 12192 6024 12193 5910 12193 5858 12193 5905 12194 5908 12194 5854 12194 6024 12195 5919 12195 5853 12195 5853 12196 5919 12196 5854 12196 5853 12197 5854 12197 5908 12197 5908 12198 5854 12198 5907 12198 5905 12199 5855 12199 5856 12199 5854 12200 5919 12200 5856 12200 5854 12201 5856 12201 5905 12201 5905 12202 5856 12202 5855 12202 5856 12203 5857 12203 5905 12203 5897 12204 5895 12204 5858 12204 5858 12205 5895 12205 5899 12205 5908 12206 5829 12206 5858 12206 5908 12207 5858 12207 5910 12207 5829 12208 5897 12208 5858 12208 5899 12209 5905 12209 5860 12209 5829 12210 5908 12210 5899 12210 5899 12211 5908 12211 5859 12211 5899 12212 5859 12212 5898 12212 5905 12213 5899 12213 5859 12213 5905 12214 5859 12214 5908 12214 5931 12215 5860 12215 6014 12215 5931 12216 6014 12216 5927 12216 5927 12217 6014 12217 6017 12217 5927 12218 6017 12218 5891 12218 5927 12219 5891 12219 6023 12219 5860 12220 5861 12220 5905 12220 5905 12221 5861 12221 5860 12221 5902 12222 5862 12222 5903 12222 5903 12223 5902 12223 5860 12223 5860 12224 5902 12224 5903 12224 5860 12225 5903 12225 6014 12225 6014 12226 5903 12226 5847 12226 5903 12227 5905 12227 5857 12227 5905 12228 5903 12228 5860 12228 5851 12229 5903 12229 5857 12229 5864 12230 5993 12230 5865 12230 5864 12231 5863 12231 5993 12231 5864 12232 5865 12232 5904 12232 5904 12233 5865 12233 5875 12233 5875 12234 5970 12234 5863 12234 5954 12235 5985 12235 6003 12235 6003 12236 5985 12236 6002 12236 6002 12237 5985 12237 5986 12237 5954 12238 5901 12238 5953 12238 6007 12239 5976 12239 5881 12239 5882 12240 5981 12240 5884 12240 5888 12241 5976 12241 6007 12241 5976 12242 5888 12242 5866 12242 5884 12243 5981 12243 5866 12243 5884 12244 5866 12244 5888 12244 5938 12245 5966 12245 5864 12245 5864 12246 5966 12246 5980 12246 5894 12247 5978 12247 5940 12247 5940 12248 5978 12248 5966 12248 5940 12249 5966 12249 5938 12249 5978 12250 5972 12250 5977 12250 5906 12251 5875 12251 5884 12251 5864 12252 5992 12252 6003 12252 6003 12253 5992 12253 5876 12253 5959 12254 5904 12254 5878 12254 5959 12255 5878 12255 5960 12255 5960 12256 5878 12256 5906 12256 5888 12257 5867 12257 5987 12257 5867 12258 5888 12258 5868 12258 5868 12259 5888 12259 5871 12259 5874 12260 5870 12260 5973 12260 5874 12261 5973 12261 5879 12261 5874 12262 6020 12262 5870 12262 5870 12263 6020 12263 5955 12263 5955 12264 6020 12264 5941 12264 5955 12265 5941 12265 5983 12265 5983 12266 5941 12266 6002 12266 5830 12267 5874 12267 5951 12267 5874 12268 5830 12268 5871 12268 5871 12269 5830 12269 5872 12269 5874 12270 5975 12270 5951 12270 5868 12271 5872 12271 5873 12271 5983 12272 6002 12272 5869 12272 5869 12273 6002 12273 5953 12273 5953 12274 6002 12274 5986 12274 5975 12275 5874 12275 5873 12275 5873 12276 5874 12276 5868 12276 5868 12277 5874 12277 5879 12277 5980 12278 5875 12278 5864 12278 5864 12279 5875 12279 5863 12279 6003 12280 5876 12280 5901 12280 6003 12281 5901 12281 5954 12281 5876 12282 5877 12282 5901 12282 5953 12283 5901 12283 5877 12283 5864 12284 5904 12284 5959 12284 5864 12285 5959 12285 5992 12285 5869 12286 5900 12286 5877 12286 5877 12287 5900 12287 5953 12287 5953 12288 5900 12288 5869 12288 5904 12289 5875 12289 5878 12289 5876 12290 5868 12290 5877 12290 5877 12291 5868 12291 5880 12291 5877 12292 5880 12292 5869 12292 5869 12293 5880 12293 5879 12293 5878 12294 5875 12294 5906 12294 5906 12295 5884 12295 5883 12295 5906 12296 5883 12296 5960 12296 5868 12297 5879 12297 5880 12297 5884 12298 5881 12298 5882 12298 5978 12299 5894 12299 5972 12299 5972 12300 5894 12300 5884 12300 5884 12301 5894 12301 6007 12301 5884 12302 6007 12302 5881 12302 5874 12303 5871 12303 5888 12303 5868 12304 5871 12304 5872 12304 5888 12305 5883 12305 5884 12305 5883 12306 5888 12306 5960 12306 5960 12307 5888 12307 5987 12307 5943 12308 6023 12308 5923 12308 5932 12309 5920 12309 5885 12309 5885 12310 5920 12310 5889 12310 5885 12311 5889 12311 6025 12311 5911 12312 5887 12312 5918 12312 5923 12313 5945 12313 5943 12313 5935 12314 5949 12314 5950 12314 5950 12315 5949 12315 5887 12315 5950 12316 5887 12316 5911 12316 5888 12317 6008 12317 5911 12317 5888 12318 5911 12318 5886 12318 5886 12319 5911 12319 5918 12319 5886 12320 5918 12320 5946 12320 6006 12321 5874 12321 6023 12321 6023 12322 5874 12322 6025 12322 6023 12323 6025 12323 5923 12323 5923 12324 6025 12324 5889 12324 5918 12325 5947 12325 5946 12325 6025 12326 5874 12326 5888 12326 6025 12327 5888 12327 5886 12327 6015 12328 5928 12328 6004 12328 6004 12329 6018 12329 6015 12329 5942 12330 6016 12330 5941 12330 5941 12331 6016 12331 5891 12331 5941 12332 5891 12332 6017 12332 5941 12333 6017 12333 6018 12333 6016 12334 5942 12334 6021 12334 6021 12335 5942 12335 6020 12335 6001 12336 6012 12336 5930 12336 5930 12337 6012 12337 5892 12337 5930 12338 5892 12338 5864 12338 5864 12339 5892 12339 5937 12339 5937 12340 5892 12340 5938 12340 5938 12341 5892 12341 6010 12341 5938 12342 6010 12342 6011 12342 5938 12343 6011 12343 5940 12343 5940 12344 6011 12344 6009 12344 5893 12345 5940 12345 6009 12345 5893 12346 5894 12346 5940 12346 5893 12347 5939 12347 5894 12347 6008 12348 5890 12348 5939 12348 5939 12349 5890 12349 5894 12349 5871 12350 5895 12350 5896 12350 5896 12351 5895 12351 5897 12351 5900 12352 5860 12352 5861 12352 5862 12353 5902 12353 5903 12353 5950 12354 5911 12354 5934 12354 5912 12355 5887 12355 5935 12355 5935 12356 5887 12356 5949 12356 5912 12357 5913 12357 5887 12357 5887 12358 5913 12358 5915 12358 5915 12359 5913 12359 5914 12359 5914 12360 5913 12360 5912 12360 5887 12361 5915 12361 5918 12361 5916 12362 5915 12362 5914 12362 5915 12363 5916 12363 5918 12363 6000 12364 5917 12364 5918 12364 5916 12365 5998 12365 6000 12365 5916 12366 6000 12366 5918 12366 6000 12367 5998 12367 5917 12367 5917 12368 5998 12368 5912 12368 5998 12369 5916 12369 5914 12369 5998 12370 5914 12370 5912 12370 5933 12371 5947 12371 5917 12371 5917 12372 5947 12372 5918 12372 5948 12373 5947 12373 5933 12373 5948 12374 5919 12374 5946 12374 5946 12375 5919 12375 6024 12375 5946 12376 6024 12376 5886 12376 6025 12377 5858 12377 5885 12377 5885 12378 5858 12378 5931 12378 5889 12379 5920 12379 5921 12379 5921 12380 5920 12380 5932 12380 5889 12381 5921 12381 5922 12381 5996 12382 5925 12382 5923 12382 5922 12383 5921 12383 5996 12383 5922 12384 5996 12384 5924 12384 5924 12385 5923 12385 5889 12385 5924 12386 5889 12386 5922 12386 5924 12387 5996 12387 5923 12387 5996 12388 5995 12388 5925 12388 5925 12389 5995 12389 5921 12389 5921 12390 5995 12390 5996 12390 5945 12391 5923 12391 5926 12391 5926 12392 5923 12392 5925 12392 5945 12393 5926 12393 5944 12393 5944 12394 5927 12394 6023 12394 5944 12395 6023 12395 5943 12395 5930 12396 5864 12396 6005 12396 6005 12397 5864 12397 6003 12397 6001 12398 5936 12398 5928 12398 5928 12399 5936 12399 5929 12399 6004 12400 5928 12400 6005 12400 5930 12401 5936 12401 6001 12401 5928 12402 5929 12402 6005 12402 6005 12403 5929 12403 5936 12403 6005 12404 5936 12404 5930 12404 5944 12405 5926 12405 5927 12405 5927 12406 5926 12406 5925 12406 5927 12407 5925 12407 5931 12407 5931 12408 5925 12408 5921 12408 5932 12409 5931 12409 5921 12409 5948 12410 5933 12410 5919 12410 5919 12411 5933 12411 5917 12411 5919 12412 5917 12412 5934 12412 5934 12413 5917 12413 5912 12413 5935 12414 5934 12414 5912 12414 5937 12415 5938 12415 5864 12415 6008 12416 6007 12416 5890 12416 5890 12417 6007 12417 5894 12417 6004 12418 6002 12418 6018 12418 6018 12419 6002 12419 5941 12419 5942 12420 5941 12420 6020 12420 6020 12421 5874 12421 6022 12421 5932 12422 5885 12422 5931 12422 5943 12423 5945 12423 5944 12423 5946 12424 5947 12424 5948 12424 5935 12425 5950 12425 5934 12425 5832 12426 5952 12426 5951 12426 5951 12427 5952 12427 5830 12427 5953 12428 5971 12428 5954 12428 5954 12429 5971 12429 5957 12429 5985 12430 5954 12430 5958 12430 5958 12431 5954 12431 5957 12431 5956 12432 5986 12432 5958 12432 5958 12433 5986 12433 5985 12433 5839 12434 5955 12434 5983 12434 5839 12435 5983 12435 5984 12435 5870 12436 5955 12436 5974 12436 5974 12437 5955 12437 5839 12437 5958 12438 5957 12438 5956 12438 5956 12439 5957 12439 5971 12439 5959 12440 5960 12440 5962 12440 5962 12441 5960 12441 5988 12441 5876 12442 5992 12442 5990 12442 5990 12443 5992 12443 5991 12443 5989 12444 5868 12444 5963 12444 5963 12445 5868 12445 5876 12445 5987 12446 5867 12446 5961 12446 5961 12447 5989 12447 5963 12447 5961 12448 5963 12448 5962 12448 5961 12449 5962 12449 5988 12449 5991 12450 5962 12450 5990 12450 5990 12451 5962 12451 5963 12451 5865 12452 5993 12452 5843 12452 5843 12453 5993 12453 5842 12453 5866 12454 5981 12454 5964 12454 5976 12455 5866 12455 5968 12455 5968 12456 5866 12456 5964 12456 5968 12457 5965 12457 5976 12457 5976 12458 5965 12458 5881 12458 5977 12459 5967 12459 5978 12459 5978 12460 5967 12460 5966 12460 5837 12461 5966 12461 5967 12461 5969 12462 5981 12462 5965 12462 5964 12463 5969 12463 5968 12463 5968 12464 5969 12464 5965 12464 5969 12465 5964 12465 5981 12465 5875 12466 5980 12466 5979 12466 5979 12467 5980 12467 5837 12467 5863 12468 5970 12468 5845 12468 5845 12469 5970 12469 5844 12469 5953 12470 5986 12470 5971 12470 5971 12471 5986 12471 5956 12471 5983 12472 5869 12472 5984 12472 5984 12473 5869 12473 5838 12473 5972 12474 5884 12474 5836 12474 5836 12475 5884 12475 5833 12475 5965 12476 5981 12476 5881 12476 5881 12477 5981 12477 5882 12477 5840 12478 5841 12478 5973 12478 5973 12479 5841 12479 5879 12479 5873 12480 5872 12480 5831 12480 5831 12481 5872 12481 5982 12481 5840 12482 5973 12482 5870 12482 5840 12483 5870 12483 5974 12483 5831 12484 5975 12484 5873 12484 5972 12485 5836 12485 5977 12485 5966 12486 5837 12486 5980 12486 5987 12487 5961 12487 5988 12487 5987 12488 5988 12488 5960 12488 5868 12489 5989 12489 5867 12489 5867 12490 5989 12490 5961 12490 5876 12491 5990 12491 5963 12491 5959 12492 5962 12492 5992 12492 5992 12493 5962 12493 5991 12493 5844 12494 5970 12494 5875 12494 5834 12495 5914 12495 5916 12495 5834 12496 5916 12496 5835 12496 5999 12497 5998 12497 6000 12497 5999 12498 6000 12498 5998 12498 6002 12499 6005 12499 6003 12499 6005 12500 6002 12500 6004 12500 6022 12501 5874 12501 6019 12501 6019 12502 5874 12502 6006 12502 6007 12503 6008 12503 5888 12503 5893 12504 6011 12504 5939 12504 6009 12505 6011 12505 5893 12505 6012 12506 5850 12506 5892 12506 5892 12507 5850 12507 6010 12507 5850 12508 6012 12508 5849 12508 6013 12509 5849 12509 5846 12509 5846 12510 5849 12510 6012 12510 6013 12511 5846 12511 5928 12511 6015 12512 6014 12512 5928 12512 6014 12513 6015 12513 6018 12513 6018 12514 6017 12514 6014 12514 6021 12515 5891 12515 6016 12515 6022 12516 6019 12516 6020 12516 6020 12517 6019 12517 6021 12517 6021 12518 6019 12518 5891 12518 6006 12519 6023 12519 6019 12519 5886 12520 6024 12520 5858 12520 5886 12521 5858 12521 6025 12521 6026 12522 6033 12522 6061 12522 6033 12523 6027 12523 6061 12523 6034 12524 6027 12524 6033 12524 6034 12525 6028 12525 6027 12525 6032 12526 6028 12526 6034 12526 6031 12527 6037 12527 6048 12527 6035 12528 6028 12528 6032 12528 6036 12529 6060 12529 6035 12529 6035 12530 6060 12530 6028 12530 6060 12531 6036 12531 6062 12531 6036 12532 6030 12532 6062 12532 6030 12533 6037 12533 6062 12533 6031 12534 6029 12534 6037 12534 6038 12535 6029 12535 6031 12535 6038 12536 6059 12536 6029 12536 6026 12537 6059 12537 6038 12537 6059 12538 6026 12538 6061 12538 6053 12539 6030 12539 6041 12539 6041 12540 6030 12540 6036 12540 6041 12541 6036 12541 6035 12541 6035 12542 6032 12542 6050 12542 6050 12543 6032 12543 6034 12543 6050 12544 6034 12544 6051 12544 6051 12545 6034 12545 6033 12545 6051 12546 6033 12546 6039 12546 6039 12547 6033 12547 6026 12547 6039 12548 6026 12548 6045 12548 6045 12549 6026 12549 6038 12549 6038 12550 6031 12550 6048 12550 6040 12551 6048 12551 6037 12551 6040 12552 6037 12552 6030 12552 6040 12553 6030 12553 6053 12553 6035 12554 6050 12554 6056 12554 6039 12555 6045 12555 6057 12555 6048 12556 6049 12556 6038 12556 6054 12557 6043 12557 6053 12557 6042 12558 6044 12558 6045 12558 6054 12559 6046 12559 6043 12559 6043 12560 6040 12560 6053 12560 6038 12561 6042 12561 6045 12561 6047 12562 6043 12562 6046 12562 6040 12563 6043 12563 6047 12563 6046 12564 6044 12564 6049 12564 6049 12565 6044 12565 6042 12565 6047 12566 6046 12566 6049 12566 6049 12567 6042 12567 6038 12567 6040 12568 6047 12568 6048 12568 6048 12569 6047 12569 6049 12569 6055 12570 6056 12570 6050 12570 6055 12571 6050 12571 6051 12571 6052 12572 6055 12572 6051 12572 6052 12573 6051 12573 6039 12573 6058 12574 6055 12574 6052 12574 6058 12575 6052 12575 6044 12575 6057 12576 6052 12576 6039 12576 6054 12577 6053 12577 6041 12577 6056 12578 6041 12578 6035 12578 6054 12579 6041 12579 6056 12579 6058 12580 6054 12580 6056 12580 6058 12581 6056 12581 6055 12581 6044 12582 6052 12582 6057 12582 6044 12583 6054 12583 6058 12583 6062 12584 6037 12584 6029 12584 6029 12585 6059 12585 6061 12585 6029 12586 6061 12586 6062 12586 6061 12587 6027 12587 6062 12587 6062 12588 6027 12588 6028 12588 6028 12589 6060 12589 6062 12589 6076 12590 6067 12590 6065 12590 6064 12591 6063 12591 6072 12591 6063 12592 6065 12592 6067 12592 6070 12593 6071 12593 6073 12593 6073 12594 6076 12594 6070 12594 6066 12595 6071 12595 6064 12595 6064 12596 6071 12596 6070 12596 6063 12597 6064 12597 6070 12597 6063 12598 6070 12598 6065 12598 6065 12599 6070 12599 6076 12599 6072 12600 6075 12600 6069 12600 6069 12601 6066 12601 6072 12601 6068 12602 6067 12602 6076 12602 6072 12603 6063 12603 6067 12603 6076 12604 6073 12604 6074 12604 6076 12605 6074 12605 6068 12605 6068 12606 6074 12606 6069 12606 6066 12607 6069 12607 6074 12607 6067 12608 6075 12608 6072 12608 6073 12609 6066 12609 6074 12609 6073 12610 6071 12610 6066 12610 6068 12611 6069 12611 6075 12611 6066 12612 6064 12612 6072 12612 6068 12613 6075 12613 6067 12613 6169 12614 6168 12614 6098 12614 6085 12615 6104 12615 6099 12615 6085 12616 6099 12616 6120 12616 6095 12617 6092 12617 6091 12617 6095 12618 6091 12618 6097 12618 6077 12619 6080 12619 6148 12619 6114 12620 6079 12620 6080 12620 6080 12621 6079 12621 6148 12621 6079 12622 6114 12622 6118 12622 6079 12623 6118 12623 6129 12623 6077 12624 6078 12624 6080 12624 6097 12625 6122 12625 6078 12625 6140 12626 6081 12626 6117 12626 6136 12627 6141 12627 6140 12627 6136 12628 6140 12628 6135 12628 6135 12629 6140 12629 6117 12629 6098 12630 6141 12630 6122 12630 6122 12631 6141 12631 6136 12631 6078 12632 6077 12632 6095 12632 6122 12633 6097 12633 6098 12633 6078 12634 6095 12634 6097 12634 6150 12635 6177 12635 6082 12635 6150 12636 6176 12636 6177 12636 6176 12637 6150 12637 6149 12637 6151 12638 6084 12638 6176 12638 6084 12639 6092 12639 6173 12639 6173 12640 6083 12640 6175 12640 6170 12641 6175 12641 6083 12641 6170 12642 6174 12642 6175 12642 6174 12643 6170 12643 6171 12643 6171 12644 6172 12644 6174 12644 6092 12645 6083 12645 6173 12645 6092 12646 6091 12646 6083 12646 6083 12647 6091 12647 6169 12647 6106 12648 6092 12648 6151 12648 6092 12649 6084 12649 6151 12649 6149 12650 6151 12650 6176 12650 6096 12651 6173 12651 6175 12651 6096 12652 6175 12652 6144 12652 6144 12653 6175 12653 6174 12653 6144 12654 6174 12654 6145 12654 6145 12655 6174 12655 6109 12655 6078 12656 6160 12656 6080 12656 6080 12657 6160 12657 6159 12657 6080 12658 6159 12658 6114 12658 6114 12659 6159 12659 6158 12659 6158 12660 6113 12660 6114 12660 6114 12661 6113 12661 6123 12661 6164 12662 6124 12662 6081 12662 6157 12663 6154 12663 6155 12663 6157 12664 6155 12664 6156 12664 6125 12665 6082 12665 6104 12665 6104 12666 6082 12666 6177 12666 6155 12667 6103 12667 6100 12667 6127 12668 6103 12668 6155 12668 6089 12669 6085 12669 6120 12669 6089 12670 6125 12670 6085 12670 6156 12671 6155 12671 6100 12671 6089 12672 6082 12672 6125 12672 6154 12673 6079 12673 6155 12673 6155 12674 6079 12674 6127 12674 6163 12675 6165 12675 6166 12675 6172 12676 6171 12676 6126 12676 6086 12677 6088 12677 6102 12677 6088 12678 6165 12678 6102 12678 6121 12679 6101 12679 6126 12679 6087 12680 6121 12680 6126 12680 6088 12681 6166 12681 6165 12681 6126 12682 6138 12682 6087 12682 6081 12683 6140 12683 6088 12683 6130 12684 6081 12684 6088 12684 6130 12685 6088 12685 6086 12685 6129 12686 6127 12686 6079 12686 6094 12687 6146 12687 6089 12687 6099 12688 6094 12688 6089 12688 6099 12689 6089 12689 6120 12689 6169 12690 6091 12690 6168 12690 6107 12691 6161 12691 6162 12691 6107 12692 6162 12692 6166 12692 6163 12693 6166 12693 6162 12693 6107 12694 6108 12694 6161 12694 6108 12695 6107 12695 6167 12695 6167 12696 6090 12696 6108 12696 6168 12697 6090 12697 6167 12697 6090 12698 6160 12698 6122 12698 6160 12699 6152 12699 6159 12699 6153 12700 6159 12700 6152 12700 6159 12701 6153 12701 6158 12701 6158 12702 6153 12702 6154 12702 6154 12703 6157 12703 6158 12703 6160 12704 6106 12704 6152 12704 6168 12705 6091 12705 6090 12705 6090 12706 6091 12706 6160 12706 6092 12707 6106 12707 6091 12707 6091 12708 6106 12708 6160 12708 6134 12709 6132 12709 6138 12709 6132 12710 6121 12710 6087 12710 6132 12711 6087 12711 6138 12711 6098 12712 6097 12712 6139 12712 6139 12713 6097 12713 6096 12713 6139 12714 6096 12714 6137 12714 6137 12715 6096 12715 6144 12715 6145 12716 6138 12716 6144 12716 6144 12717 6138 12717 6137 12717 6138 12718 6145 12718 6093 12718 6138 12719 6093 12719 6134 12719 6095 12720 6142 12720 6096 12720 6146 12721 6116 12721 6115 12721 6146 12722 6094 12722 6116 12722 6143 12723 6105 12723 6115 12723 6115 12724 6105 12724 6146 12724 6143 12725 6147 12725 6105 12725 6142 12726 6147 12726 6143 12726 6095 12727 6077 12727 6147 12727 6142 12728 6095 12728 6147 12728 6096 12729 6097 12729 6095 12729 6078 12730 6122 12730 6160 12730 6096 12731 6142 12731 6173 12731 6151 12732 6147 12732 6077 12732 6169 12733 6098 12733 6139 12733 6104 12734 6085 12734 6125 12734 6103 12735 6127 12735 6128 12735 6156 12736 6103 12736 6128 12736 6100 12737 6103 12737 6156 12737 6172 12738 6121 12738 6132 12738 6101 12739 6121 12739 6172 12739 6172 12740 6126 12740 6101 12740 6130 12741 6086 12741 6102 12741 6130 12742 6102 12742 6164 12742 6164 12743 6102 12743 6165 12743 6097 12744 6091 12744 6092 12744 6097 12745 6092 12745 6095 12745 6147 12746 6151 12746 6149 12746 6149 12747 6105 12747 6147 12747 6105 12748 6149 12748 6150 12748 6105 12749 6150 12749 6146 12749 6146 12750 6150 12750 6082 12750 6146 12751 6082 12751 6089 12751 6176 12752 6143 12752 6115 12752 6176 12753 6115 12753 6110 12753 6084 12754 6142 12754 6143 12754 6084 12755 6143 12755 6176 12755 6131 12756 6094 12756 6104 12756 6104 12757 6094 12757 6099 12757 6079 12758 6154 12758 6153 12758 6079 12759 6153 12759 6148 12759 6148 12760 6152 12760 6106 12760 6148 12761 6106 12761 6077 12761 6113 12762 6157 12762 6111 12762 6111 12763 6157 12763 6129 12763 6157 12764 6128 12764 6129 12764 6156 12765 6128 12765 6157 12765 6098 12766 6168 12766 6167 12766 6167 12767 6141 12767 6098 12767 6141 12768 6167 12768 6107 12768 6141 12769 6107 12769 6140 12769 6140 12770 6107 12770 6166 12770 6140 12771 6166 12771 6088 12771 6112 12772 6136 12772 6135 12772 6108 12773 6136 12773 6161 12773 6161 12774 6136 12774 6112 12774 6090 12775 6122 12775 6108 12775 6108 12776 6122 12776 6136 12776 6164 12777 6081 12777 6130 12777 6172 12778 6132 12778 6133 12778 6133 12779 6132 12779 6134 12779 6138 12780 6126 12780 6171 12780 6138 12781 6171 12781 6170 12781 6138 12782 6170 12782 6137 12782 6137 12783 6170 12783 6083 12783 6137 12784 6083 12784 6139 12784 6094 12785 6131 12785 6134 12785 6133 12786 6134 12786 6131 12786 6115 12787 6145 12787 6110 12787 6110 12788 6145 12788 6109 12788 6174 12789 6133 12789 6109 12789 6109 12790 6133 12790 6110 12790 6110 12791 6133 12791 6131 12791 6093 12792 6145 12792 6116 12792 6081 12793 6124 12793 6129 12793 6111 12794 6129 12794 6124 12794 6119 12795 6114 12795 6112 12795 6112 12796 6114 12796 6123 12796 6113 12797 6124 12797 6162 12797 6113 12798 6111 12798 6124 12798 6117 12799 6118 12799 6135 12799 6114 12800 6135 12800 6118 12800 6145 12801 6115 12801 6116 12801 6093 12802 6116 12802 6094 12802 6094 12803 6134 12803 6093 12803 6118 12804 6117 12804 6081 12804 6081 12805 6129 12805 6118 12805 6114 12806 6119 12806 6135 12806 6119 12807 6112 12807 6135 12807 6123 12808 6113 12808 6112 12808 6162 12809 6112 12809 6113 12809 6129 12810 6128 12810 6127 12810 6077 12811 6106 12811 6151 12811 6152 12812 6148 12812 6153 12812 6113 12813 6158 12813 6157 12813 6162 12814 6161 12814 6112 12814 6124 12815 6164 12815 6163 12815 6124 12816 6163 12816 6162 12816 6165 12817 6163 12817 6164 12817 6169 12818 6139 12818 6083 12818 6174 12819 6172 12819 6133 12819 6173 12820 6142 12820 6084 12820 6110 12821 6177 12821 6176 12821 6131 12822 6177 12822 6110 12822 6131 12823 6104 12823 6177 12823 6264 12824 6263 12824 6238 12824 6218 12825 6199 12825 6185 12825 6203 12826 6255 12826 6219 12826 6202 12827 6190 12827 6200 12827 6202 12828 6200 12828 6201 12828 6251 12829 6246 12829 6181 12829 6181 12830 6235 12830 6247 12830 6234 12831 6204 12831 6235 12831 6235 12832 6204 12832 6247 12832 6204 12833 6234 12833 6216 12833 6204 12834 6216 12834 6178 12834 6207 12835 6213 12835 6180 12835 6179 12836 6206 12836 6180 12836 6180 12837 6206 12837 6207 12837 6233 12838 6206 12838 6179 12838 6233 12839 6238 12839 6206 12839 6201 12840 6195 12840 6238 12840 6181 12841 6201 12841 6238 12841 6181 12842 6202 12842 6201 12842 6246 12843 6202 12843 6181 12843 6250 12844 6274 12844 6248 12844 6275 12845 6248 12845 6274 12845 6250 12846 6249 12846 6273 12846 6249 12847 6272 12847 6273 12847 6222 12848 6272 12848 6270 12848 6270 12849 6266 12849 6182 12849 6271 12850 6182 12850 6266 12850 6184 12851 6269 12851 6271 12851 6270 12852 6265 12852 6266 12852 6270 12853 6264 12853 6265 12853 6251 12854 6190 12854 6249 12854 6190 12855 6272 12855 6249 12855 6190 12856 6270 12856 6272 12856 6200 12857 6264 12857 6190 12857 6190 12858 6264 12858 6270 12858 6241 12859 6270 12859 6182 12859 6241 12860 6182 12860 6240 12860 6240 12861 6182 12861 6183 12861 6183 12862 6182 12862 6225 12862 6183 12863 6225 12863 6242 12863 6181 12864 6258 12864 6235 12864 6235 12865 6258 12865 6256 12865 6235 12866 6256 12866 6257 12866 6235 12867 6257 12867 6234 12867 6234 12868 6257 12868 6217 12868 6260 12869 6226 12869 6213 12869 6213 12870 6226 12870 6227 12870 6255 12871 6252 12871 6254 12871 6229 12872 6248 12872 6196 12872 6196 12873 6248 12873 6275 12873 6254 12874 6203 12874 6219 12874 6188 12875 6203 12875 6254 12875 6243 12876 6229 12876 6197 12876 6197 12877 6229 12877 6220 12877 6254 12878 6219 12878 6255 12878 6243 12879 6248 12879 6229 12879 6252 12880 6204 12880 6254 12880 6254 12881 6204 12881 6188 12881 6260 12882 6261 12882 6186 12882 6260 12883 6186 12883 6189 12883 6269 12884 6184 12884 6267 12884 6269 12885 6267 12885 6268 12885 6218 12886 6187 12886 6185 12886 6187 12887 6186 12887 6185 12887 6185 12888 6199 12888 6218 12888 6191 12889 6198 12889 6236 12889 6236 12890 6198 12890 6267 12890 6186 12891 6261 12891 6185 12891 6185 12892 6261 12892 6199 12892 6207 12893 6189 12893 6187 12893 6187 12894 6189 12894 6186 12894 6184 12895 6194 12895 6267 12895 6267 12896 6194 12896 6236 12896 6213 12897 6207 12897 6187 12897 6230 12898 6213 12898 6187 12898 6230 12899 6187 12899 6218 12899 6178 12900 6188 12900 6204 12900 6231 12901 6209 12901 6243 12901 6231 12902 6243 12902 6197 12902 6263 12903 6264 12903 6221 12903 6262 12904 6259 12904 6260 12904 6262 12905 6260 12905 6189 12905 6262 12906 6208 12906 6259 12906 6263 12907 6221 12907 6208 12907 6258 12908 6251 12908 6256 12908 6253 12909 6256 12909 6251 12909 6253 12910 6257 12910 6256 12910 6257 12911 6253 12911 6252 12911 6264 12912 6200 12912 6221 12912 6200 12913 6258 12913 6221 12913 6190 12914 6251 12914 6200 12914 6200 12915 6251 12915 6258 12915 6215 12916 6232 12916 6194 12916 6232 12917 6191 12917 6236 12917 6232 12918 6236 12918 6194 12918 6195 12919 6201 12919 6192 12919 6192 12920 6201 12920 6202 12920 6192 12921 6241 12921 6240 12921 6192 12922 6240 12922 6237 12922 6237 12923 6240 12923 6183 12923 6237 12924 6242 12924 6194 12924 6194 12925 6242 12925 6193 12925 6194 12926 6193 12926 6215 12926 6183 12927 6242 12927 6237 12927 6202 12928 6241 12928 6192 12928 6202 12929 6222 12929 6241 12929 6244 12930 6212 12930 6239 12930 6244 12931 6209 12931 6212 12931 6239 12932 6245 12932 6244 12932 6246 12933 6245 12933 6239 12933 6222 12934 6246 12934 6239 12934 6222 12935 6202 12935 6246 12935 6181 12936 6238 12936 6258 12936 6221 12937 6258 12937 6238 12937 6249 12938 6246 12938 6251 12938 6264 12939 6238 12939 6195 12939 6264 12940 6195 12940 6192 12940 6196 12941 6220 12941 6229 12941 6197 12942 6220 12942 6196 12942 6197 12943 6196 12943 6231 12943 6203 12944 6188 12944 6205 12944 6205 12945 6255 12945 6219 12945 6205 12946 6219 12946 6203 12946 6268 12947 6198 12947 6232 12947 6232 12948 6198 12948 6191 12948 6268 12949 6267 12949 6198 12949 6218 12950 6199 12950 6230 12950 6230 12951 6199 12951 6261 12951 6201 12952 6200 12952 6190 12952 6201 12953 6190 12953 6202 12953 6203 12954 6219 12954 6255 12954 6185 12955 6199 12955 6218 12955 6249 12956 6245 12956 6246 12956 6245 12957 6249 12957 6250 12957 6245 12958 6250 12958 6244 12958 6244 12959 6250 12959 6248 12959 6244 12960 6248 12960 6243 12960 6211 12961 6274 12961 6223 12961 6273 12962 6239 12962 6274 12962 6274 12963 6239 12963 6223 12963 6272 12964 6222 12964 6273 12964 6273 12965 6222 12965 6239 12965 6224 12966 6209 12966 6196 12966 6196 12967 6209 12967 6231 12967 6204 12968 6252 12968 6253 12968 6204 12969 6253 12969 6247 12969 6247 12970 6253 12970 6251 12970 6247 12971 6251 12971 6181 12971 6217 12972 6255 12972 6214 12972 6214 12973 6255 12973 6178 12973 6255 12974 6205 12974 6178 12974 6263 12975 6206 12975 6238 12975 6206 12976 6263 12976 6262 12976 6206 12977 6262 12977 6189 12977 6206 12978 6189 12978 6207 12978 6208 12979 6233 12979 6179 12979 6208 12980 6179 12980 6259 12980 6259 12981 6179 12981 6226 12981 6226 12982 6179 12982 6228 12982 6221 12983 6233 12983 6208 12983 6221 12984 6238 12984 6233 12984 6260 12985 6213 12985 6261 12985 6261 12986 6213 12986 6230 12986 6210 12987 6232 12987 6215 12987 6268 12988 6232 12988 6210 12988 6194 12989 6184 12989 6237 12989 6237 12990 6184 12990 6271 12990 6237 12991 6271 12991 6266 12991 6237 12992 6266 12992 6192 12992 6192 12993 6266 12993 6265 12993 6210 12994 6215 12994 6209 12994 6210 12995 6209 12995 6224 12995 6211 12996 6223 12996 6225 12996 6211 12997 6224 12997 6274 12997 6225 12998 6210 12998 6211 12998 6211 12999 6210 12999 6224 12999 6193 13000 6242 13000 6212 13000 6214 13001 6178 13001 6213 13001 6214 13002 6213 13002 6227 13002 6226 13003 6228 13003 6217 13003 6217 13004 6214 13004 6226 13004 6226 13005 6214 13005 6227 13005 6234 13006 6180 13006 6216 13006 6242 13007 6225 13007 6223 13007 6242 13008 6223 13008 6212 13008 6193 13009 6212 13009 6209 13009 6209 13010 6215 13010 6193 13010 6216 13011 6180 13011 6213 13011 6213 13012 6178 13012 6216 13012 6234 13013 6217 13013 6228 13013 6234 13014 6228 13014 6180 13014 6178 13015 6205 13015 6188 13015 6180 13016 6228 13016 6179 13016 6239 13017 6212 13017 6223 13017 6243 13018 6209 13018 6244 13018 6252 13019 6255 13019 6217 13019 6217 13020 6257 13020 6252 13020 6260 13021 6259 13021 6226 13021 6263 13022 6208 13022 6262 13022 6264 13023 6192 13023 6265 13023 6268 13024 6210 13024 6269 13024 6210 13025 6225 13025 6269 13025 6225 13026 6271 13026 6269 13026 6182 13027 6271 13027 6225 13027 6222 13028 6270 13028 6241 13028 6250 13029 6273 13029 6274 13029 6224 13030 6275 13030 6274 13030 6224 13031 6196 13031 6275 13031 6285 13032 6287 13032 6284 13032 6286 13033 6277 13033 6287 13033 6286 13034 6276 13034 6277 13034 6292 13035 6276 13035 6286 13035 6305 13036 6310 13036 6292 13036 6305 13037 6278 13037 6310 13037 6282 13038 6278 13038 6305 13038 6282 13039 6280 13039 6278 13039 6278 13040 6280 13040 6279 13040 6289 13041 6279 13041 6280 13041 6289 13042 6283 13042 6279 13042 6281 13043 6283 13043 6289 13043 6281 13044 6284 13044 6283 13044 6288 13045 6284 13045 6281 13045 6285 13046 6284 13046 6288 13046 6291 13047 6280 13047 6282 13047 6291 13048 6282 13048 6305 13048 6292 13049 6286 13049 6302 13049 6302 13050 6286 13050 6287 13050 6302 13051 6287 13051 6290 13051 6290 13052 6287 13052 6285 13052 6290 13053 6285 13053 6288 13053 6281 13054 6289 13054 6299 13054 6299 13055 6289 13055 6280 13055 6299 13056 6280 13056 6291 13056 6281 13057 6299 13057 6298 13057 6291 13058 6297 13058 6299 13058 6309 13059 6295 13059 6294 13059 6294 13060 6297 13060 6291 13060 6296 13061 6308 13061 6293 13061 6298 13062 6295 13062 6308 13062 6288 13063 6296 13063 6293 13063 6293 13064 6290 13064 6288 13064 6297 13065 6294 13065 6295 13065 6298 13066 6308 13066 6296 13066 6298 13067 6296 13067 6288 13067 6299 13068 6297 13068 6298 13068 6298 13069 6297 13069 6295 13069 6298 13070 6288 13070 6281 13070 6309 13071 6306 13071 6300 13071 6301 13072 6292 13072 6302 13072 6301 13073 6300 13073 6292 13073 6292 13074 6300 13074 6305 13074 6300 13075 6301 13075 6303 13075 6309 13076 6300 13076 6303 13076 6303 13077 6301 13077 6307 13077 6307 13078 6301 13078 6302 13078 6307 13079 6302 13079 6290 13079 6304 13080 6291 13080 6305 13080 6306 13081 6304 13081 6305 13081 6305 13082 6300 13082 6306 13082 6304 13083 6306 13083 6309 13083 6308 13084 6303 13084 6307 13084 6303 13085 6308 13085 6309 13085 6310 13086 6276 13086 6292 13086 6277 13087 6284 13087 6287 13087 6283 13088 6284 13088 6279 13088 6284 13089 6277 13089 6279 13089 6279 13090 6277 13090 6276 13090 6276 13091 6310 13091 6279 13091 6279 13092 6310 13092 6278 13092 6323 13093 6315 13093 6321 13093 6319 13094 6316 13094 6311 13094 6319 13095 6311 13095 6322 13095 6314 13096 6320 13096 6322 13096 6312 13097 6314 13097 6323 13097 6323 13098 6314 13098 6322 13098 6323 13099 6322 13099 6315 13099 6315 13100 6322 13100 6311 13100 6312 13101 6313 13101 6317 13101 6313 13102 6312 13102 6321 13102 6317 13103 6314 13103 6312 13103 6321 13104 6316 13104 6313 13104 6316 13105 6318 13105 6313 13105 6313 13106 6318 13106 6317 13106 6317 13107 6318 13107 6320 13107 6318 13108 6316 13108 6319 13108 6319 13109 6322 13109 6320 13109 6314 13110 6317 13110 6320 13110 6321 13111 6312 13111 6323 13111 6318 13112 6319 13112 6320 13112 6316 13113 6315 13113 6311 13113 6321 13114 6315 13114 6316 13114 6366 13115 6365 13115 6509 13115 6365 13116 6510 13116 6509 13116 6324 13117 6514 13117 6365 13117 6365 13118 6514 13118 6510 13118 6325 13119 6514 13119 6324 13119 6325 13120 6513 13120 6514 13120 6367 13121 6512 13121 6325 13121 6325 13122 6512 13122 6513 13122 6366 13123 6511 13123 6367 13123 6367 13124 6511 13124 6512 13124 6366 13125 6509 13125 6511 13125 6735 13126 6332 13126 6326 13126 6328 13127 6725 13127 6327 13127 6373 13128 6725 13128 6328 13128 6330 13129 6373 13129 6328 13129 6330 13130 6329 13130 6373 13130 6375 13131 6329 13131 6330 13131 6479 13132 6375 13132 6330 13132 6479 13133 6733 13133 6375 13133 6331 13134 6733 13134 6479 13134 6374 13135 6733 13135 6331 13135 6326 13136 6374 13136 6331 13136 6333 13137 6735 13137 6326 13137 6372 13138 6735 13138 6484 13138 6484 13139 6735 13139 6333 13139 6327 13140 6725 13140 6372 13140 6327 13141 6372 13141 6484 13141 6337 13142 6715 13142 6485 13142 6335 13143 6720 13143 6334 13143 6334 13144 6720 13144 6340 13144 6335 13145 6376 13145 6720 13145 6488 13146 6716 13146 6335 13146 6335 13147 6716 13147 6376 13147 6716 13148 6488 13148 6336 13148 6336 13149 6488 13149 6485 13149 6485 13150 6715 13150 6336 13150 6487 13151 6337 13151 6485 13151 6487 13152 6338 13152 6337 13152 6486 13153 6338 13153 6487 13153 6486 13154 6711 13154 6338 13154 6339 13155 6719 13155 6711 13155 6339 13156 6711 13156 6486 13156 6340 13157 6719 13157 6334 13157 6334 13158 6719 13158 6339 13158 6745 13159 6342 13159 6343 13159 6345 13160 6681 13160 6344 13160 6345 13161 6344 13161 6387 13161 6345 13162 6388 13162 6744 13162 6681 13163 6345 13163 6744 13163 6554 13164 6544 13164 6389 13164 6389 13165 6544 13165 6391 13165 6554 13166 6389 13166 6390 13166 6554 13167 6390 13167 6628 13167 6554 13168 6628 13168 6346 13168 6628 13169 6627 13169 6346 13169 6346 13170 6627 13170 6347 13170 6347 13171 6627 13171 6626 13171 6347 13172 6626 13172 6629 13172 6347 13173 6629 13173 6393 13173 6347 13174 6393 13174 6543 13174 6543 13175 6393 13175 6392 13175 6543 13176 6392 13176 6623 13176 6543 13177 6623 13177 6687 13177 6543 13178 6687 13178 6545 13178 6545 13179 6687 13179 6348 13179 6545 13180 6348 13180 6548 13180 6548 13181 6348 13181 6690 13181 6548 13182 6690 13182 6553 13182 6553 13183 6690 13183 6349 13183 6553 13184 6349 13184 6544 13184 6544 13185 6349 13185 6391 13185 6546 13186 6684 13186 6683 13186 6546 13187 6683 13187 6688 13187 6546 13188 6688 13188 6555 13188 6555 13189 6688 13189 6542 13189 6542 13190 6688 13190 6552 13190 6552 13191 6688 13191 6678 13191 6552 13192 6678 13192 6684 13192 6552 13193 6684 13193 6546 13193 6350 13194 6686 13194 6351 13194 6350 13195 6351 13195 6540 13195 6540 13196 6351 13196 6682 13196 6540 13197 6682 13197 6551 13197 6551 13198 6682 13198 6677 13198 6551 13199 6677 13199 6549 13199 6549 13200 6677 13200 6686 13200 6549 13201 6686 13201 6350 13201 6675 13202 6676 13202 6449 13202 6673 13203 6674 13203 6637 13203 6653 13204 6632 13204 6678 13204 6678 13205 6437 13205 6394 13205 6419 13206 6395 13206 6415 13206 6747 13207 6417 13207 6635 13207 6635 13208 6417 13208 6415 13208 6596 13209 6352 13209 6500 13209 6476 13210 6469 13210 6473 13210 6476 13211 6473 13211 6574 13211 6412 13212 6411 13212 6586 13212 6636 13213 6637 13213 6674 13213 6637 13214 6636 13214 6403 13214 6353 13215 6358 13215 6797 13215 6637 13216 6403 13216 6638 13216 6638 13217 6403 13217 6353 13217 6353 13218 6403 13218 6358 13218 6403 13219 6636 13219 6404 13219 6354 13220 6780 13220 6695 13220 6695 13221 6780 13221 6423 13221 6798 13222 6361 13222 6354 13222 6354 13223 6361 13223 6780 13223 6802 13224 6456 13224 6441 13224 6638 13225 6355 13225 6637 13225 6637 13226 6355 13226 6801 13226 6357 13227 6432 13227 6356 13227 6356 13228 6432 13228 6456 13228 6356 13229 6456 13229 6802 13229 6637 13230 6801 13230 6441 13230 6441 13231 6801 13231 6802 13231 6356 13232 6354 13232 6695 13232 6356 13233 6695 13233 6357 13233 6797 13234 6358 13234 6799 13234 6799 13235 6358 13235 6786 13235 6727 13236 6782 13236 6359 13236 6361 13237 6798 13237 6359 13237 6359 13238 6798 13238 6360 13238 6359 13239 6360 13239 6727 13239 6787 13240 6726 13240 6799 13240 6787 13241 6799 13241 6786 13241 6727 13242 6360 13242 6726 13242 6726 13243 6360 13243 6799 13243 6751 13244 6759 13244 6794 13244 6794 13245 6759 13245 6795 13245 6750 13246 6751 13246 6408 13246 6408 13247 6751 13247 6794 13247 6607 13248 6730 13248 6783 13248 6783 13249 6608 13249 6607 13249 6397 13250 6363 13250 6783 13250 6783 13251 6363 13251 6608 13251 6363 13252 6397 13252 6396 13252 6434 13253 6605 13253 6396 13253 6396 13254 6605 13254 6363 13254 6453 13255 6676 13255 6774 13255 6453 13256 6774 13256 6667 13256 6325 13257 6774 13257 6773 13257 6410 13258 6364 13258 6771 13258 6666 13259 6667 13259 6365 13259 6778 13260 6779 13260 6771 13260 6666 13261 6365 13261 6366 13261 6666 13262 6366 13262 6631 13262 6749 13263 6773 13263 6364 13263 6774 13264 6325 13264 6324 13264 6774 13265 6324 13265 6667 13265 6667 13266 6324 13266 6365 13266 6364 13267 6773 13267 6771 13267 6749 13268 6366 13268 6367 13268 6749 13269 6367 13269 6773 13269 6773 13270 6367 13270 6325 13270 6747 13271 6631 13271 6749 13271 6749 13272 6631 13272 6366 13272 6371 13273 6581 13273 6778 13273 6466 13274 6778 13274 6581 13274 6368 13275 6778 13275 6466 13275 6369 13276 6772 13276 6466 13276 6772 13277 6368 13277 6466 13277 6369 13278 6768 13278 6772 13278 6368 13279 6772 13279 6370 13279 6411 13280 6771 13280 6779 13280 6411 13281 6779 13281 6675 13281 6675 13282 6779 13282 6370 13282 6370 13283 6676 13283 6675 13283 6772 13284 6676 13284 6370 13284 6778 13285 6771 13285 6371 13285 6771 13286 6769 13286 6776 13286 6776 13287 6769 13287 6777 13287 6777 13288 6769 13288 6770 13288 6377 13289 6636 13289 6597 13289 6636 13290 6378 13290 6597 13290 6377 13291 6404 13291 6636 13291 6597 13292 6752 13292 6379 13292 6379 13293 6752 13293 6598 13293 6598 13294 6752 13294 6753 13294 6381 13295 6585 13295 6380 13295 6585 13296 6592 13296 6380 13296 6380 13297 6592 13297 6754 13297 6587 13298 6381 13298 6364 13298 6587 13299 6364 13299 6410 13299 6587 13300 6410 13300 6382 13300 6382 13301 6410 13301 6411 13301 6753 13302 6707 13302 6405 13302 6750 13303 6643 13303 6395 13303 6749 13304 6364 13304 6748 13304 6383 13305 6745 13305 6567 13305 6387 13306 6570 13306 6345 13306 6345 13307 6570 13307 6569 13307 6745 13308 6343 13308 6385 13308 6584 13309 6342 13309 6383 13309 6584 13310 6383 13310 6567 13310 6385 13311 6343 13311 6575 13311 6575 13312 6343 13312 6342 13312 6384 13313 6743 13313 6386 13313 6386 13314 6743 13314 6388 13314 6342 13315 6584 13315 6578 13315 6342 13316 6578 13316 6575 13316 6743 13317 6384 13317 6387 13317 6387 13318 6384 13318 6570 13318 6385 13319 6565 13319 6567 13319 6569 13320 6568 13320 6386 13320 6567 13321 6745 13321 6385 13321 6345 13322 6569 13322 6388 13322 6388 13323 6569 13323 6386 13323 6386 13324 6568 13324 6385 13324 6385 13325 6568 13325 6565 13325 6342 13326 6669 13326 6624 13326 6388 13327 6630 13327 6670 13327 6670 13328 6630 13328 6665 13328 6342 13329 6745 13329 6669 13329 6390 13330 6389 13330 6746 13330 6342 13331 6625 13331 6746 13331 6746 13332 6625 13332 6390 13332 6630 13333 6344 13333 6393 13333 6392 13334 6393 13334 6344 13334 6670 13335 6744 13335 6388 13335 6390 13336 6624 13336 6628 13336 6633 13337 6394 13337 6437 13337 6415 13338 6395 13338 6635 13338 6399 13339 6449 13339 6447 13339 6399 13340 6447 13340 6398 13340 6434 13341 6396 13341 6639 13341 6639 13342 6396 13342 6640 13342 6640 13343 6396 13343 6397 13343 6675 13344 6449 13344 6411 13344 6449 13345 6399 13345 6411 13345 6640 13346 6788 13346 6398 13346 6640 13347 6398 13347 6447 13347 6723 13348 6788 13348 6397 13348 6397 13349 6788 13349 6640 13349 6398 13350 6788 13350 6589 13350 6589 13351 6399 13351 6398 13351 6589 13352 6588 13352 6399 13352 6399 13353 6588 13353 6586 13353 6399 13354 6586 13354 6411 13354 6589 13355 6401 13355 6400 13355 6591 13356 6400 13356 6401 13356 6591 13357 6401 13357 6790 13357 6741 13358 6412 13358 6790 13358 6790 13359 6412 13359 6586 13359 6790 13360 6586 13360 6591 13360 6358 13361 6403 13361 6599 13361 6358 13362 6599 13362 6402 13362 6599 13363 6604 13363 6402 13363 6402 13364 6604 13364 6787 13364 6601 13365 6599 13365 6403 13365 6601 13366 6403 13366 6404 13366 6601 13367 6404 13367 6602 13367 6404 13368 6785 13368 6602 13368 6602 13369 6785 13369 6787 13369 6602 13370 6787 13370 6604 13370 6377 13371 6405 13371 6766 13371 6405 13372 6377 13372 6753 13372 6753 13373 6377 13373 6598 13373 6404 13374 6377 13374 6766 13374 6785 13375 6404 13375 6741 13375 6741 13376 6404 13376 6412 13376 6414 13377 6721 13377 6413 13377 6766 13378 6406 13378 6414 13378 6414 13379 6406 13379 6721 13379 6766 13380 6414 13380 6404 13380 6404 13381 6414 13381 6412 13381 6443 13382 6409 13382 6636 13382 6407 13383 6643 13383 6750 13383 6407 13384 6750 13384 6664 13384 6664 13385 6750 13385 6804 13385 6750 13386 6408 13386 6804 13386 6664 13387 6804 13387 6443 13387 6443 13388 6804 13388 6409 13388 6378 13389 6409 13389 6796 13389 6409 13390 6378 13390 6636 13390 6748 13391 6364 13391 6762 13391 6762 13392 6364 13392 6701 13392 6413 13393 6710 13393 6754 13393 6412 13394 6382 13394 6411 13394 6382 13395 6413 13395 6754 13395 6382 13396 6754 13396 6592 13396 6414 13397 6413 13397 6382 13397 6414 13398 6382 13398 6412 13398 6415 13399 6417 13399 6761 13399 6722 13400 6378 13400 6796 13400 6748 13401 6416 13401 6749 13401 6594 13402 6749 13402 6416 13402 6749 13403 6594 13403 6747 13403 6747 13404 6594 13404 6417 13404 6417 13405 6594 13405 6595 13405 6764 13406 6593 13406 6416 13406 6764 13407 6418 13407 6593 13407 6418 13408 6764 13408 6765 13408 6761 13409 6417 13409 6717 13409 6717 13410 6417 13410 6595 13410 6717 13411 6595 13411 6765 13411 6765 13412 6595 13412 6418 13412 6758 13413 6751 13413 6750 13413 6760 13414 6758 13414 6420 13414 6421 13415 6341 13415 6760 13415 6421 13416 6760 13416 6420 13416 6758 13417 6750 13417 6615 13417 6615 13418 6750 13418 6419 13418 6341 13419 6421 13419 6615 13419 6615 13420 6419 13420 6341 13420 6341 13421 6419 13421 6415 13421 6341 13422 6718 13422 6708 13422 6610 13423 6792 13423 6433 13423 6424 13424 6782 13424 6734 13424 6424 13425 6734 13425 6610 13425 6610 13426 6734 13426 6792 13426 6781 13427 6613 13427 6422 13427 6780 13428 6422 13428 6423 13428 6423 13429 6422 13429 6610 13429 6423 13430 6610 13430 6433 13430 6424 13431 6613 13431 6781 13431 6424 13432 6781 13432 6782 13432 6606 13433 6505 13433 6434 13433 6425 13434 6426 13434 6522 13434 6470 13435 6695 13435 6427 13435 6428 13436 6639 13436 6425 13436 6428 13437 6434 13437 6639 13437 6426 13438 6429 13438 6522 13438 6522 13439 6429 13439 6430 13439 6434 13440 6428 13440 6606 13440 6692 13441 6446 13441 6438 13441 6438 13442 6439 13442 6530 13442 6530 13443 6439 13443 6470 13443 6470 13444 6439 13444 6440 13444 6429 13445 6451 13445 6430 13445 6430 13446 6451 13446 6698 13446 6698 13447 6451 13447 6452 13447 6695 13448 6433 13448 6427 13448 6427 13449 6433 13449 6611 13449 6611 13450 6433 13450 6609 13450 6609 13451 6433 13451 6502 13451 6695 13452 6470 13452 6357 13452 6357 13453 6470 13453 6440 13453 6357 13454 6440 13454 6432 13454 6426 13455 6425 13455 6431 13455 6431 13456 6425 13456 6639 13456 6431 13457 6639 13457 6696 13457 6434 13458 6505 13458 6433 13458 6433 13459 6505 13459 6502 13459 6697 13460 6696 13460 6639 13460 6695 13461 6423 13461 6433 13461 6792 13462 6791 13462 6433 13462 6433 13463 6791 13463 6434 13463 6605 13464 6434 13464 6791 13464 6791 13465 6732 13465 6605 13465 6605 13466 6732 13466 6784 13466 6605 13467 6784 13467 6607 13467 6607 13468 6784 13468 6730 13468 6519 13469 6698 13469 6694 13469 6519 13470 6694 13470 6699 13470 6692 13471 6559 13471 6693 13471 6693 13472 6559 13472 6532 13472 6693 13473 6532 13473 6700 13473 6435 13474 6756 13474 6755 13474 6386 13475 6385 13475 6436 13475 6436 13476 6385 13476 6756 13476 6436 13477 6756 13477 6435 13477 6437 13478 6436 13478 6633 13478 6633 13479 6436 13479 6435 13479 6648 13480 6436 13480 6437 13480 6648 13481 6437 13481 6632 13481 6678 13482 6632 13482 6437 13482 6700 13483 6532 13483 6436 13483 6436 13484 6532 13484 6386 13484 6386 13485 6532 13485 6384 13485 6385 13486 6575 13486 6756 13486 6756 13487 6575 13487 6576 13487 6756 13488 6576 13488 6699 13488 6445 13489 6461 13489 6446 13489 6446 13490 6461 13490 6438 13490 6438 13491 6461 13491 6439 13491 6461 13492 6462 13492 6439 13492 6439 13493 6462 13493 6440 13493 6463 13494 6440 13494 6462 13494 6691 13495 6650 13495 6445 13495 6445 13496 6446 13496 6692 13496 6445 13497 6692 13497 6691 13497 6441 13498 6456 13498 6463 13498 6441 13499 6463 13499 6462 13499 6445 13500 6641 13500 6461 13500 6461 13501 6641 13501 6462 13501 6445 13502 6650 13502 6641 13502 6641 13503 6650 13503 6651 13503 6444 13504 6659 13504 6442 13504 6442 13505 6659 13505 6462 13505 6637 13506 6671 13506 6443 13506 6444 13507 6442 13507 6671 13507 6671 13508 6664 13508 6443 13508 6456 13509 6432 13509 6463 13509 6463 13510 6432 13510 6440 13510 6431 13511 6696 13511 6459 13511 6459 13512 6696 13512 6447 13512 6459 13513 6447 13513 6450 13513 6450 13514 6447 13514 6449 13514 6459 13515 6450 13515 6457 13515 6460 13516 6458 13516 6455 13516 6455 13517 6458 13517 6450 13517 6450 13518 6458 13518 6457 13518 6452 13519 6460 13519 6698 13519 6742 13520 6647 13520 6460 13520 6698 13521 6460 13521 6647 13521 6646 13522 6455 13522 6448 13522 6450 13523 6449 13523 6454 13523 6458 13524 6452 13524 6451 13524 6458 13525 6451 13525 6429 13525 6457 13526 6429 13526 6426 13526 6460 13527 6452 13527 6458 13527 6457 13528 6426 13528 6459 13528 6459 13529 6426 13529 6431 13529 6453 13530 6667 13530 6668 13530 6449 13531 6453 13531 6657 13531 6657 13532 6453 13532 6668 13532 6657 13533 6668 13533 6672 13533 6672 13534 6668 13534 6644 13534 6672 13535 6644 13535 6454 13535 6454 13536 6644 13536 6448 13536 6454 13537 6448 13537 6450 13537 6450 13538 6448 13538 6455 13538 6742 13539 6460 13539 6455 13539 6742 13540 6455 13540 6646 13540 6457 13541 6458 13541 6429 13541 6651 13542 6650 13542 6691 13542 6651 13543 6691 13543 6652 13543 6464 13544 6652 13544 6649 13544 6465 13545 6649 13545 6442 13545 6645 13546 6647 13546 6742 13546 6645 13547 6742 13547 6646 13547 6645 13548 6646 13548 6644 13548 6466 13549 6526 13549 6369 13549 6583 13550 6466 13550 6581 13550 6466 13551 6583 13551 6467 13551 6467 13552 6583 13552 6580 13552 6467 13553 6580 13553 6468 13553 6580 13554 6428 13554 6468 13554 6468 13555 6428 13555 6425 13555 6468 13556 6425 13556 6525 13556 6525 13557 6425 13557 6522 13557 6526 13558 6466 13558 6467 13558 6526 13559 6467 13559 6525 13559 6525 13560 6467 13560 6468 13560 6531 13561 6472 13561 6471 13561 6531 13562 6471 13562 6534 13562 6534 13563 6471 13563 6474 13563 6474 13564 6473 13564 6534 13564 6534 13565 6473 13565 6538 13565 6538 13566 6473 13566 6537 13566 6473 13567 6469 13567 6537 13567 6472 13568 6531 13568 6470 13568 6470 13569 6531 13569 6530 13569 6573 13570 6472 13570 6427 13570 6427 13571 6472 13571 6470 13571 6475 13572 6474 13572 6471 13572 6475 13573 6471 13573 6571 13573 6571 13574 6471 13574 6573 13574 6472 13575 6573 13575 6471 13575 6473 13576 6474 13576 6574 13576 6574 13577 6474 13577 6475 13577 6469 13578 6476 13578 6477 13578 6477 13579 6476 13579 6478 13579 6533 13580 6537 13580 6469 13580 6477 13581 6533 13581 6469 13581 6384 13582 6533 13582 6477 13582 6532 13583 6533 13583 6384 13583 6477 13584 6478 13584 6570 13584 6477 13585 6570 13585 6384 13585 6479 13586 6480 13586 6331 13586 6479 13587 6503 13587 6480 13587 6330 13588 6504 13588 6479 13588 6504 13589 6503 13589 6479 13589 6330 13590 6482 13590 6504 13590 6328 13591 6481 13591 6330 13591 6495 13592 6481 13592 6328 13592 6495 13593 6328 13593 6327 13593 6495 13594 6327 13594 6493 13594 6330 13595 6481 13595 6482 13595 6326 13596 6590 13596 6333 13596 6331 13597 6480 13597 6483 13597 6331 13598 6483 13598 6326 13598 6326 13599 6483 13599 6590 13599 6590 13600 6498 13600 6333 13600 6333 13601 6498 13601 6484 13601 6498 13602 6496 13602 6484 13602 6484 13603 6496 13603 6327 13603 6327 13604 6496 13604 6493 13604 6492 13605 6485 13605 6494 13605 6334 13606 6506 13606 6335 13606 6486 13607 6352 13607 6339 13607 6487 13608 6499 13608 6486 13608 6485 13609 6492 13609 6497 13609 6335 13610 6506 13610 6489 13610 6506 13611 6334 13611 6507 13611 6499 13612 6501 13612 6486 13612 6486 13613 6501 13613 6352 13613 6499 13614 6487 13614 6497 13614 6494 13615 6485 13615 6491 13615 6491 13616 6485 13616 6488 13616 6335 13617 6489 13617 6491 13617 6335 13618 6491 13618 6488 13618 6352 13619 6507 13619 6339 13619 6339 13620 6507 13620 6334 13620 6485 13621 6497 13621 6487 13621 6352 13622 6501 13622 6500 13622 6493 13623 6496 13623 6492 13623 6492 13624 6496 13624 6497 13624 6490 13625 6590 13625 6483 13625 6612 13626 6482 13626 6481 13626 6481 13627 6600 13627 6612 13627 6489 13628 6616 13628 6491 13628 6505 13629 6503 13629 6502 13629 6614 13630 6506 13630 6508 13630 6508 13631 6506 13631 6507 13631 6494 13632 6495 13632 6493 13632 6494 13633 6493 13633 6492 13633 6494 13634 6603 13634 6495 13634 6497 13635 6496 13635 6498 13635 6499 13636 6585 13636 6587 13636 6587 13637 6500 13637 6499 13637 6499 13638 6500 13638 6501 13638 6590 13639 6490 13639 6582 13639 6490 13640 6483 13640 6480 13640 6572 13641 6491 13641 6616 13641 6599 13642 6600 13642 6481 13642 6599 13643 6481 13643 6495 13643 6502 13644 6503 13644 6609 13644 6609 13645 6503 13645 6504 13645 6503 13646 6505 13646 6480 13646 6516 13647 6511 13647 6509 13647 6767 13648 6512 13648 6511 13648 6512 13649 6767 13649 6513 13649 6369 13650 6775 13650 6768 13650 6775 13651 6514 13651 6513 13651 6775 13652 6369 13652 6514 13652 6514 13653 6369 13653 6510 13653 6510 13654 6369 13654 6579 13654 6579 13655 6509 13655 6510 13655 6515 13656 6516 13656 6509 13656 6515 13657 6509 13657 6579 13657 6563 13658 6518 13658 6517 13658 6563 13659 6620 13659 6518 13659 6518 13660 6620 13660 6521 13660 6518 13661 6521 13661 6520 13661 6523 13662 6622 13662 6519 13662 6521 13663 6620 13663 6523 13663 6620 13664 6622 13664 6523 13664 6527 13665 6520 13665 6521 13665 6527 13666 6521 13666 6523 13666 6518 13667 6520 13667 6528 13667 6528 13668 6520 13668 6527 13668 6528 13669 6517 13669 6518 13669 6524 13670 6517 13670 6528 13670 6527 13671 6523 13671 6576 13671 6525 13672 6522 13672 6430 13672 6519 13673 6699 13673 6523 13673 6523 13674 6699 13674 6576 13674 6527 13675 6576 13675 6577 13675 6430 13676 6524 13676 6525 13676 6525 13677 6524 13677 6526 13677 6528 13678 6369 13678 6526 13678 6528 13679 6526 13679 6524 13679 6527 13680 6577 13680 6369 13680 6527 13681 6369 13681 6528 13681 6557 13682 6558 13682 6561 13682 6557 13683 6561 13683 6536 13683 6561 13684 6560 13684 6536 13684 6536 13685 6560 13685 6529 13685 6560 13686 6556 13686 6529 13686 6529 13687 6556 13687 6535 13687 6438 13688 6530 13688 6535 13688 6535 13689 6530 13689 6531 13689 6535 13690 6531 13690 6534 13690 6557 13691 6532 13691 6559 13691 6532 13692 6557 13692 6533 13692 6533 13693 6557 13693 6536 13693 6538 13694 6529 13694 6534 13694 6534 13695 6529 13695 6535 13695 6533 13696 6536 13696 6529 13696 6533 13697 6529 13697 6537 13697 6537 13698 6529 13698 6538 13698 6551 13699 6539 13699 6540 13699 6540 13700 6539 13700 6541 13700 6553 13701 6544 13701 6542 13701 6542 13702 6544 13702 6555 13702 6555 13703 6544 13703 6554 13703 6543 13704 6545 13704 6350 13704 6350 13705 6545 13705 6549 13705 6550 13706 6548 13706 6553 13706 6546 13707 6547 13707 6566 13707 6546 13708 6566 13708 6552 13708 6545 13709 6548 13709 6549 13709 6549 13710 6548 13710 6550 13710 6549 13711 6550 13711 6551 13711 6551 13712 6550 13712 6539 13712 6552 13713 6566 13713 6550 13713 6552 13714 6550 13714 6553 13714 6552 13715 6553 13715 6542 13715 6547 13716 6546 13716 6508 13716 6508 13717 6546 13717 6555 13717 6347 13718 6541 13718 6614 13718 6541 13719 6347 13719 6540 13719 6540 13720 6347 13720 6543 13720 6540 13721 6543 13721 6350 13721 6508 13722 6346 13722 6614 13722 6614 13723 6346 13723 6347 13723 6555 13724 6554 13724 6346 13724 6555 13725 6346 13725 6508 13725 6618 13726 6438 13726 6535 13726 6535 13727 6556 13727 6619 13727 6535 13728 6619 13728 6618 13728 6557 13729 6617 13729 6562 13729 6562 13730 6558 13730 6557 13730 6557 13731 6559 13731 6617 13731 6619 13732 6556 13732 6562 13732 6561 13733 6558 13733 6562 13733 6562 13734 6556 13734 6560 13734 6562 13735 6560 13735 6561 13735 6563 13736 6517 13736 6524 13736 6621 13737 6563 13737 6564 13737 6564 13738 6563 13738 6430 13738 6430 13739 6563 13739 6524 13739 6565 13740 6550 13740 6566 13740 6566 13741 6567 13741 6565 13741 6568 13742 6550 13742 6565 13742 6569 13743 6539 13743 6568 13743 6568 13744 6539 13744 6550 13744 6573 13745 6427 13745 6611 13745 6570 13746 6478 13746 6541 13746 6539 13747 6569 13747 6541 13747 6541 13748 6569 13748 6570 13748 6571 13749 6573 13749 6612 13749 6600 13750 6571 13750 6612 13750 6476 13751 6574 13751 6572 13751 6611 13752 6612 13752 6573 13752 6541 13753 6478 13753 6616 13753 6616 13754 6478 13754 6476 13754 6475 13755 6572 13755 6574 13755 6571 13756 6600 13756 6475 13756 6475 13757 6600 13757 6572 13757 6476 13758 6572 13758 6616 13758 6577 13759 6579 13759 6369 13759 6576 13760 6575 13760 6578 13760 6576 13761 6578 13761 6577 13761 6577 13762 6578 13762 6579 13762 6579 13763 6578 13763 6584 13763 6584 13764 6515 13764 6579 13764 6583 13765 6490 13765 6580 13765 6606 13766 6428 13766 6490 13766 6490 13767 6428 13767 6580 13767 6767 13768 6500 13768 6587 13768 6767 13769 6587 13769 6777 13769 6583 13770 6582 13770 6490 13770 6776 13771 6777 13771 6371 13771 6371 13772 6777 13772 6587 13772 6371 13773 6587 13773 6582 13773 6371 13774 6582 13774 6581 13774 6581 13775 6582 13775 6583 13775 6567 13776 6566 13776 6584 13776 6584 13777 6566 13777 6547 13777 6584 13778 6547 13778 6515 13778 6767 13779 6596 13779 6500 13779 6511 13780 6516 13780 6596 13780 6596 13781 6516 13781 6515 13781 6596 13782 6515 13782 6547 13782 6596 13783 6767 13783 6511 13783 6587 13784 6382 13784 6586 13784 6585 13785 6381 13785 6587 13785 6587 13786 6586 13786 6588 13786 6588 13787 6589 13787 6587 13787 6587 13788 6589 13788 6582 13788 6400 13789 6582 13789 6589 13789 6582 13790 6400 13790 6590 13790 6590 13791 6400 13791 6591 13791 6590 13792 6591 13792 6498 13792 6498 13793 6591 13793 6497 13793 6382 13794 6592 13794 6497 13794 6586 13795 6382 13795 6497 13795 6586 13796 6497 13796 6591 13796 6497 13797 6592 13797 6499 13797 6499 13798 6592 13798 6585 13798 6594 13799 6596 13799 6547 13799 6596 13800 6593 13800 6352 13800 6547 13801 6595 13801 6594 13801 6418 13802 6508 13802 6507 13802 6508 13803 6595 13803 6547 13803 6594 13804 6416 13804 6596 13804 6593 13805 6418 13805 6352 13805 6508 13806 6418 13806 6595 13806 6596 13807 6416 13807 6593 13807 6352 13808 6418 13808 6507 13808 6377 13809 6597 13809 6572 13809 6572 13810 6597 13810 6379 13810 6572 13811 6379 13811 6491 13811 6491 13812 6379 13812 6598 13812 6598 13813 6494 13813 6491 13813 6494 13814 6598 13814 6603 13814 6603 13815 6598 13815 6377 13815 6603 13816 6377 13816 6572 13816 6600 13817 6599 13817 6601 13817 6600 13818 6601 13818 6572 13818 6601 13819 6602 13819 6572 13819 6572 13820 6602 13820 6603 13820 6604 13821 6495 13821 6603 13821 6604 13822 6603 13822 6602 13822 6604 13823 6599 13823 6495 13823 6490 13824 6363 13824 6606 13824 6363 13825 6605 13825 6606 13825 6606 13826 6605 13826 6505 13826 6505 13827 6605 13827 6607 13827 6505 13828 6607 13828 6480 13828 6480 13829 6607 13829 6608 13829 6480 13830 6608 13830 6490 13830 6490 13831 6608 13831 6363 13831 6504 13832 6424 13832 6609 13832 6609 13833 6424 13833 6610 13833 6609 13834 6610 13834 6611 13834 6611 13835 6610 13835 6422 13835 6611 13836 6422 13836 6612 13836 6612 13837 6422 13837 6613 13837 6612 13838 6613 13838 6482 13838 6482 13839 6613 13839 6424 13839 6424 13840 6504 13840 6482 13840 6614 13841 6421 13841 6506 13841 6420 13842 6616 13842 6489 13842 6541 13843 6615 13843 6614 13843 6614 13844 6615 13844 6421 13844 6616 13845 6758 13845 6541 13845 6758 13846 6615 13846 6541 13846 6506 13847 6421 13847 6489 13847 6489 13848 6421 13848 6420 13848 6616 13849 6420 13849 6758 13849 6617 13850 6559 13850 6692 13850 6618 13851 6692 13851 6438 13851 6692 13852 6618 13852 6617 13852 6619 13853 6562 13853 6618 13853 6618 13854 6562 13854 6617 13854 6620 13855 6563 13855 6621 13855 6620 13856 6621 13856 6622 13856 6698 13857 6564 13857 6430 13857 6622 13858 6621 13858 6564 13858 6622 13859 6564 13859 6698 13859 6622 13860 6698 13860 6519 13860 6664 13861 6671 13861 6665 13861 6392 13862 6344 13862 6623 13862 6623 13863 6344 13863 6681 13863 6391 13864 6685 13864 6389 13864 6389 13865 6685 13865 6746 13865 6342 13866 6624 13866 6625 13866 6625 13867 6624 13867 6390 13867 6407 13868 6665 13868 6629 13868 6668 13869 6666 13869 6624 13869 6407 13870 6629 13870 6395 13870 6395 13871 6629 13871 6626 13871 6395 13872 6626 13872 6627 13872 6627 13873 6635 13873 6395 13873 6627 13874 6628 13874 6635 13874 6635 13875 6628 13875 6666 13875 6666 13876 6628 13876 6624 13876 6630 13877 6393 13877 6629 13877 6629 13878 6665 13878 6630 13878 6668 13879 6624 13879 6669 13879 6668 13880 6669 13880 6679 13880 6454 13881 6449 13881 6662 13881 6632 13882 6653 13882 6648 13882 6648 13883 6653 13883 6634 13883 6631 13884 6747 13884 6635 13884 6407 13885 6395 13885 6643 13885 6635 13886 6666 13886 6631 13886 6462 13887 6659 13887 6441 13887 6441 13888 6659 13888 6637 13888 6355 13889 6638 13889 6353 13889 6755 13890 6394 13890 6633 13890 6465 13891 6442 13891 6462 13891 6465 13892 6462 13892 6641 13892 6642 13893 6436 13893 6648 13893 6435 13894 6755 13894 6633 13894 6670 13895 6665 13895 6634 13895 6665 13896 6671 13896 6634 13896 6634 13897 6671 13897 6649 13897 6649 13898 6671 13898 6442 13898 6648 13899 6634 13899 6649 13899 6394 13900 6755 13900 6679 13900 6644 13901 6668 13901 6679 13901 6644 13902 6679 13902 6755 13902 6448 13903 6644 13903 6646 13903 6694 13904 6645 13904 6644 13904 6648 13905 6649 13905 6642 13905 6641 13906 6652 13906 6464 13906 6641 13907 6649 13907 6465 13907 6641 13908 6651 13908 6652 13908 6641 13909 6464 13909 6649 13909 6689 13910 6634 13910 6653 13910 6394 13911 6679 13911 6678 13911 6689 13912 6653 13912 6678 13912 6662 13913 6654 13913 6655 13913 6655 13914 6654 13914 6656 13914 6672 13915 6656 13915 6657 13915 6656 13916 6654 13916 6657 13916 6657 13917 6654 13917 6449 13917 6449 13918 6654 13918 6662 13918 6659 13919 6663 13919 6637 13919 6661 13920 6660 13920 6658 13920 6658 13921 6660 13921 6663 13921 6637 13922 6663 13922 6660 13922 6637 13923 6660 13923 6671 13923 6660 13924 6661 13924 6444 13924 6661 13925 6658 13925 6444 13925 6444 13926 6658 13926 6659 13926 6659 13927 6658 13927 6663 13927 6665 13928 6407 13928 6664 13928 6668 13929 6667 13929 6666 13929 6411 13930 6410 13930 6771 13930 6669 13931 6745 13931 6680 13931 6671 13932 6660 13932 6444 13932 6655 13933 6656 13933 6672 13933 6674 13934 6673 13934 6443 13934 6636 13935 6674 13935 6443 13935 6673 13936 6637 13936 6443 13936 6449 13937 6676 13937 6453 13937 6683 13938 6685 13938 6688 13938 6688 13939 6685 13939 6391 13939 6681 13940 6682 13940 6351 13940 6681 13941 6351 13941 6623 13941 6679 13942 6669 13942 6680 13942 6686 13943 6677 13943 6689 13943 6689 13944 6677 13944 6634 13944 6634 13945 6677 13945 6682 13945 6682 13946 6744 13946 6634 13946 6634 13947 6744 13947 6670 13947 6391 13948 6349 13948 6688 13948 6678 13949 6679 13949 6684 13949 6684 13950 6679 13950 6680 13950 6680 13951 6685 13951 6683 13951 6680 13952 6683 13952 6684 13952 6682 13953 6681 13953 6744 13953 6686 13954 6348 13954 6687 13954 6686 13955 6687 13955 6351 13955 6351 13956 6687 13956 6623 13956 6678 13957 6688 13957 6349 13957 6678 13958 6349 13958 6689 13958 6689 13959 6349 13959 6690 13959 6689 13960 6690 13960 6348 13960 6689 13961 6348 13961 6686 13961 6750 13962 6395 13962 6419 13962 6693 13963 6649 13963 6652 13963 6697 13964 6640 13964 6696 13964 6640 13965 6447 13965 6696 13965 6694 13966 6644 13966 6755 13966 6694 13967 6755 13967 6756 13967 6694 13968 6756 13968 6699 13968 6700 13969 6436 13969 6693 13969 6693 13970 6436 13970 6642 13970 6693 13971 6642 13971 6649 13971 6693 13972 6652 13972 6691 13972 6693 13973 6691 13973 6692 13973 6645 13974 6694 13974 6647 13974 6647 13975 6694 13975 6698 13975 6697 13976 6639 13976 6640 13976 6415 13977 6761 13977 6717 13977 6707 13978 6753 13978 6703 13978 6795 13979 6759 13979 6702 13979 6702 13980 6759 13980 6704 13980 6703 13981 6722 13981 6806 13981 6806 13982 6722 13982 6796 13982 6703 13983 6806 13983 6707 13983 6707 13984 6806 13984 6708 13984 6708 13985 6806 13985 6702 13985 6704 13986 6341 13986 6702 13986 6708 13987 6702 13987 6341 13987 6413 13988 6405 13988 6705 13988 6413 13989 6705 13989 6714 13989 6340 13990 6709 13990 6719 13990 6706 13991 6707 13991 6708 13991 6706 13992 6708 13992 6718 13992 6709 13993 6711 13993 6719 13993 6765 13994 6713 13994 6709 13994 6710 13995 6338 13995 6709 13995 6710 13996 6709 13996 6713 13996 6705 13997 6716 13997 6336 13997 6705 13998 6336 13998 6715 13998 6715 13999 6337 13999 6714 13999 6714 14000 6705 14000 6715 14000 6709 14001 6340 14001 6718 14001 6718 14002 6340 14002 6720 14002 6763 14003 6713 14003 6765 14003 6754 14004 6710 14004 6712 14004 6762 14005 6701 14005 6763 14005 6763 14006 6701 14006 6712 14006 6763 14007 6712 14007 6713 14007 6713 14008 6712 14008 6710 14008 6337 14009 6338 14009 6710 14009 6338 14010 6711 14010 6709 14010 6714 14011 6337 14011 6710 14011 6710 14012 6413 14012 6714 14012 6716 14013 6705 14013 6707 14013 6376 14014 6716 14014 6707 14014 6707 14015 6705 14015 6405 14015 6765 14016 6709 14016 6718 14016 6765 14017 6718 14017 6717 14017 6717 14018 6718 14018 6757 14018 6706 14019 6720 14019 6376 14019 6376 14020 6707 14020 6706 14020 6341 14021 6757 14021 6718 14021 6720 14022 6706 14022 6718 14022 6406 14023 6405 14023 6413 14023 6406 14024 6413 14024 6721 14024 6757 14025 6415 14025 6717 14025 6740 14026 6726 14026 6787 14026 6731 14027 6736 14027 6730 14027 6792 14028 6734 14028 6732 14028 6732 14029 6734 14029 6731 14029 6785 14030 6724 14030 6740 14030 6372 14031 6737 14031 6735 14031 6375 14032 6727 14032 6329 14032 6727 14033 6373 14033 6329 14033 6739 14034 6727 14034 6726 14034 6782 14035 6727 14035 6362 14035 6736 14036 6738 14036 6728 14036 6326 14037 6332 14037 6374 14037 6736 14038 6731 14038 6374 14038 6374 14039 6731 14039 6733 14039 6362 14040 6727 14040 6375 14040 6362 14041 6375 14041 6733 14041 6734 14042 6362 14042 6731 14042 6731 14043 6362 14043 6733 14043 6740 14044 6724 14044 6737 14044 6740 14045 6737 14045 6739 14045 6789 14046 6728 14046 6790 14046 6790 14047 6728 14047 6738 14047 6788 14048 6723 14048 6789 14048 6789 14049 6723 14049 6729 14049 6789 14050 6729 14050 6728 14050 6728 14051 6729 14051 6730 14051 6728 14052 6730 14052 6736 14052 6374 14053 6332 14053 6736 14053 6731 14054 6730 14054 6732 14054 6782 14055 6362 14055 6734 14055 6790 14056 6738 14056 6737 14056 6332 14057 6735 14057 6738 14057 6735 14058 6737 14058 6738 14058 6332 14059 6738 14059 6736 14059 6737 14060 6724 14060 6790 14060 6737 14061 6372 14061 6739 14061 6739 14062 6372 14062 6725 14062 6739 14063 6726 14063 6740 14063 6373 14064 6727 14064 6739 14064 6739 14065 6725 14065 6373 14065 6785 14066 6741 14066 6724 14066 6724 14067 6741 14067 6790 14067 6743 14068 6630 14068 6388 14068 6630 14069 6743 14069 6344 14069 6344 14070 6743 14070 6387 14070 6383 14071 6680 14071 6745 14071 6746 14072 6383 14072 6342 14072 6680 14073 6383 14073 6746 14073 6680 14074 6746 14074 6685 14074 6752 14075 6597 14075 6378 14075 6703 14076 6752 14076 6722 14076 6722 14077 6752 14077 6378 14077 6753 14078 6752 14078 6703 14078 6712 14079 6701 14079 6380 14079 6380 14080 6701 14080 6364 14080 6380 14081 6364 14081 6381 14081 6712 14082 6380 14082 6754 14082 6415 14083 6757 14083 6341 14083 6760 14084 6704 14084 6759 14084 6751 14085 6758 14085 6760 14085 6760 14086 6759 14086 6751 14086 6704 14087 6760 14087 6341 14087 6764 14088 6416 14088 6748 14088 6748 14089 6762 14089 6763 14089 6748 14090 6763 14090 6764 14090 6765 14091 6764 14091 6763 14091 6766 14092 6405 14092 6406 14092 6774 14093 6775 14093 6513 14093 6777 14094 6773 14094 6774 14094 6774 14095 6513 14095 6777 14095 6777 14096 6513 14096 6767 14096 6676 14097 6772 14097 6768 14097 6775 14098 6774 14098 6768 14098 6768 14099 6774 14099 6676 14099 6771 14100 6773 14100 6769 14100 6769 14101 6773 14101 6770 14101 6770 14102 6773 14102 6777 14102 6371 14103 6771 14103 6776 14103 6368 14104 6370 14104 6779 14104 6368 14105 6779 14105 6778 14105 6781 14106 6422 14106 6780 14106 6359 14107 6781 14107 6361 14107 6361 14108 6781 14108 6780 14108 6359 14109 6782 14109 6781 14109 6397 14110 6729 14110 6723 14110 6397 14111 6783 14111 6729 14111 6730 14112 6784 14112 6732 14112 6729 14113 6783 14113 6730 14113 6740 14114 6787 14114 6785 14114 6786 14115 6358 14115 6402 14115 6786 14116 6402 14116 6787 14116 6789 14117 6589 14117 6788 14117 6789 14118 6401 14118 6589 14118 6790 14119 6401 14119 6789 14119 6792 14120 6732 14120 6791 14120 6804 14121 6408 14121 6794 14121 6804 14122 6794 14122 6793 14122 6702 14123 6793 14123 6795 14123 6795 14124 6793 14124 6794 14124 6409 14125 6804 14125 6805 14125 6805 14126 6804 14126 6793 14126 6805 14127 6796 14127 6409 14127 6805 14128 6806 14128 6796 14128 6805 14129 6793 14129 6806 14129 6806 14130 6793 14130 6702 14130 6797 14131 6799 14131 6800 14131 6355 14132 6800 14132 6801 14132 6353 14133 6797 14133 6800 14133 6353 14134 6800 14134 6355 14134 6354 14135 6803 14135 6360 14135 6354 14136 6360 14136 6798 14136 6803 14137 6354 14137 6802 14137 6802 14138 6354 14138 6356 14138 6802 14139 6801 14139 6803 14139 6803 14140 6801 14140 6800 14140 6803 14141 6800 14141 6360 14141 6360 14142 6800 14142 6799 14142 6823 14143 6883 14143 6827 14143 6813 14144 6811 14144 6829 14144 6807 14145 6814 14145 6815 14145 7132 14146 6883 14146 6920 14146 6808 14147 6825 14147 7131 14147 7106 14148 7104 14148 7103 14148 7104 14149 7106 14149 6832 14149 7103 14150 7104 14150 6836 14150 7103 14151 6836 14151 6835 14151 7099 14152 6809 14152 7098 14152 7099 14153 7098 14153 6810 14153 7092 14154 7090 14154 7095 14154 7092 14155 7095 14155 6843 14155 6843 14156 7095 14156 7093 14156 6843 14157 7093 14157 6845 14157 7080 14158 7079 14158 6972 14158 6972 14159 7079 14159 6973 14159 6973 14160 7079 14160 7080 14160 6973 14161 7080 14161 6971 14161 7076 14162 7075 14162 6984 14162 6984 14163 7075 14163 7078 14163 6984 14164 7078 14164 7077 14164 6812 14165 6829 14165 6811 14165 6812 14166 6811 14166 7079 14166 7074 14167 7133 14167 6829 14167 6829 14168 7133 14168 6813 14168 7094 14169 6815 14169 7109 14169 7109 14170 6815 14170 6814 14170 6846 14171 7109 14171 6814 14171 6846 14172 6814 14172 6848 14172 6838 14173 6815 14173 7107 14173 7107 14174 6815 14174 7094 14174 7068 14175 7134 14175 6816 14175 7068 14176 6816 14176 7057 14176 7067 14177 6850 14177 7064 14177 7064 14178 6850 14178 6882 14178 7064 14179 6882 14179 7065 14179 7061 14180 7048 14180 6818 14180 6818 14181 7048 14181 6819 14181 6827 14182 6913 14182 6921 14182 6959 14183 6961 14183 6820 14183 6821 14184 6826 14184 6892 14184 6892 14185 6826 14185 6918 14185 6892 14186 6918 14186 6925 14186 6822 14187 6825 14187 6912 14187 6918 14188 6826 14188 6919 14188 6959 14189 6820 14189 6822 14189 6822 14190 6820 14190 6914 14190 6822 14191 6914 14191 6916 14191 6822 14192 6916 14192 6825 14192 6823 14193 6921 14193 6925 14193 6823 14194 6925 14194 6918 14194 6823 14195 6918 14195 6883 14195 6912 14196 6825 14196 6826 14196 6824 14197 6826 14197 6821 14197 6826 14198 6825 14198 6919 14198 6921 14199 6823 14199 6827 14199 6904 14200 6962 14200 6908 14200 6946 14201 6828 14201 7122 14201 7122 14202 6904 14202 6946 14202 6946 14203 6904 14203 6908 14203 6864 14204 6831 14204 6933 14204 6933 14205 6831 14205 6833 14205 6933 14206 6833 14206 6889 14206 6833 14207 7074 14207 6889 14207 6889 14208 7074 14208 6829 14208 6889 14209 6829 14209 7081 14209 7074 14210 6833 14210 7118 14210 7118 14211 6830 14211 7074 14211 6832 14212 6831 14212 7100 14212 6833 14213 6831 14213 6832 14213 6833 14214 6832 14214 7105 14214 6833 14215 7105 14215 7118 14215 7118 14216 7105 14216 7102 14216 7017 14217 6834 14217 7015 14217 6812 14218 7073 14218 6849 14218 6849 14219 7073 14219 6835 14219 6849 14220 6835 14220 6834 14220 6834 14221 6835 14221 7015 14221 6812 14222 6849 14222 6888 14222 7072 14223 7117 14223 6835 14223 7072 14224 6835 14224 7073 14224 6835 14225 6836 14225 7015 14225 7015 14226 6836 14226 7016 14226 6841 14227 7020 14227 7019 14227 6837 14228 6839 14228 6901 14228 6901 14229 6839 14229 7019 14229 7019 14230 6839 14230 6841 14230 6901 14231 7070 14231 6838 14231 6901 14232 6838 14232 6837 14232 6901 14233 7086 14233 7070 14233 7107 14234 7108 14234 6837 14234 7107 14235 6837 14235 6838 14235 6844 14236 7022 14236 7059 14236 6837 14237 7108 14237 7096 14237 7096 14238 7098 14238 6837 14238 6837 14239 7098 14239 6840 14239 6837 14240 6840 14240 6839 14240 6839 14241 6840 14241 6842 14241 6839 14242 6842 14242 6841 14242 6841 14243 6842 14243 7110 14243 6841 14244 7110 14244 7020 14244 7024 14245 7023 14245 6893 14245 7092 14246 6843 14246 6847 14246 7022 14247 6844 14247 7091 14247 6893 14248 7023 14248 6834 14248 6834 14249 7023 14249 6885 14249 6834 14250 6885 14250 6886 14250 7022 14251 7091 14251 7092 14251 7022 14252 7092 14252 6847 14252 6848 14253 7069 14253 6847 14253 6845 14254 6846 14254 6843 14254 6843 14255 6846 14255 6848 14255 6843 14256 6848 14256 6847 14256 7069 14257 7084 14257 6847 14257 6834 14258 6886 14258 6849 14258 6894 14259 6895 14259 6893 14259 6893 14260 6895 14260 7024 14260 6885 14261 7023 14261 6847 14261 6847 14262 7023 14262 7022 14262 6829 14263 6888 14263 6942 14263 6851 14264 6819 14264 7039 14264 7039 14265 6819 14265 7042 14265 7042 14266 6819 14266 7048 14266 6851 14267 7039 14267 7113 14267 7113 14268 7039 14268 7046 14268 7039 14269 7038 14269 7046 14269 7046 14270 7038 14270 6852 14270 6852 14271 7038 14271 7044 14271 7047 14272 7042 14272 7048 14272 6852 14273 7044 14273 7047 14273 7047 14274 7044 14274 7042 14274 7009 14275 6862 14275 7005 14275 6858 14276 6941 14276 7002 14276 6858 14277 7002 14277 6976 14277 6976 14278 7002 14278 6998 14278 6853 14279 6941 14279 6857 14279 6997 14280 7003 14280 7005 14280 7006 14281 6974 14281 7005 14281 7005 14282 6974 14282 6997 14282 7003 14283 6854 14283 7006 14283 7006 14284 6854 14284 6974 14284 7011 14285 6938 14285 7007 14285 7007 14286 6938 14286 6855 14286 7007 14287 6855 14287 6860 14287 6856 14288 7011 14288 7008 14288 7007 14289 6860 14289 7008 14289 7008 14290 6860 14290 6856 14290 6999 14291 7001 14291 6975 14291 7004 14292 6859 14292 7001 14292 6859 14293 7004 14293 7000 14293 6859 14294 7000 14294 6975 14294 6999 14295 6975 14295 7000 14295 6853 14296 6857 14296 6998 14296 6998 14297 6857 14297 6976 14297 7010 14298 7017 14298 7015 14298 7005 14299 7017 14299 7006 14299 7006 14300 7017 14300 7010 14300 6854 14301 7003 14301 6997 14301 7011 14302 6861 14302 6938 14302 6861 14303 7011 14303 6856 14303 6862 14304 7009 14304 6929 14304 7009 14305 7012 14305 6929 14305 6864 14306 7014 14306 7115 14306 7014 14307 6863 14307 7115 14307 7062 14308 7014 14308 6864 14308 6864 14309 6933 14309 7062 14309 7062 14310 6933 14310 7066 14310 6943 14311 6866 14311 6954 14311 6943 14312 6954 14312 6996 14312 6891 14313 6909 14313 6865 14313 6950 14314 6985 14314 6943 14314 6943 14315 6985 14315 6866 14315 6910 14316 6907 14316 6909 14316 6909 14317 6907 14317 6865 14317 6891 14318 6897 14318 6996 14318 6996 14319 6897 14319 6867 14319 6996 14320 6867 14320 6934 14320 6995 14321 6978 14321 6868 14321 6995 14322 6868 14322 6952 14322 6952 14323 6868 14323 6987 14323 6935 14324 6936 14324 6869 14324 6869 14325 6936 14325 6937 14325 6935 14326 6869 14326 6871 14326 6935 14327 6871 14327 6870 14327 6870 14328 6871 14328 6872 14328 7066 14329 6872 14329 6871 14329 6850 14330 6879 14330 6882 14330 6873 14331 6879 14331 6850 14331 6850 14332 7067 14332 6873 14332 7067 14333 6817 14333 6873 14333 6873 14334 6817 14334 6874 14334 6817 14335 6875 14335 6874 14335 6878 14336 6874 14336 6875 14336 6873 14337 6874 14337 6877 14337 6873 14338 6880 14338 6879 14338 6873 14339 6877 14339 6880 14339 6877 14340 6874 14340 6878 14340 6926 14341 6940 14341 6882 14341 6882 14342 6940 14342 7065 14342 6928 14343 6875 14343 7065 14343 6928 14344 7065 14344 6940 14344 6875 14345 6928 14345 6878 14345 6878 14346 6928 14346 6876 14346 6877 14347 6876 14347 6924 14347 6877 14348 6878 14348 6876 14348 6877 14349 6924 14349 6880 14349 6880 14350 6924 14350 6922 14350 6923 14351 6879 14351 6880 14351 6923 14352 6880 14352 6922 14352 6881 14353 6879 14353 6923 14353 6926 14354 6882 14354 6881 14354 6881 14355 6882 14355 6879 14355 6919 14356 6825 14356 6916 14356 6827 14357 6883 14357 6918 14357 6885 14358 7121 14358 6884 14358 6847 14359 7122 14359 7121 14359 6847 14360 7121 14360 6885 14360 6885 14361 6884 14361 6887 14361 6904 14362 7122 14362 6847 14362 6888 14363 6886 14363 6944 14363 6944 14364 6886 14364 6885 14364 6944 14365 6885 14365 6887 14365 6886 14366 6888 14366 6849 14366 7081 14367 6829 14367 6942 14367 6889 14368 7081 14368 6942 14368 6996 14369 6934 14369 6889 14369 6996 14370 6889 14370 6943 14370 6943 14371 6889 14371 6942 14371 6934 14372 6867 14372 6890 14372 6906 14373 6903 14373 6905 14373 6905 14374 6897 14374 6891 14374 6891 14375 6865 14375 6907 14375 6891 14376 6907 14376 6906 14376 6891 14377 6906 14377 6905 14377 6925 14378 6928 14378 6892 14378 6928 14379 6977 14379 6892 14379 6892 14380 6977 14380 6821 14380 6834 14381 7017 14381 6893 14381 7017 14382 6862 14382 6893 14382 6893 14383 6862 14383 6929 14383 6900 14384 6894 14384 6929 14384 6929 14385 6894 14385 6893 14385 6890 14386 6867 14386 6931 14386 6931 14387 6867 14387 6897 14387 6931 14388 6897 14388 6932 14388 6902 14389 7018 14389 6905 14389 6905 14390 7018 14390 6896 14390 6905 14391 6896 14391 6897 14391 6897 14392 6896 14392 6898 14392 6897 14393 6898 14393 6932 14393 6932 14394 6898 14394 6899 14394 6932 14395 6899 14395 6900 14395 6895 14396 6894 14396 6899 14396 6899 14397 6894 14397 6900 14397 7018 14398 6902 14398 7019 14398 6901 14399 7019 14399 6902 14399 7085 14400 7086 14400 6901 14400 6903 14401 6847 14401 7084 14401 6903 14402 6904 14402 6847 14402 7085 14403 6901 14403 6902 14403 7084 14404 7082 14404 6903 14404 6903 14405 7082 14405 7085 14405 6903 14406 7085 14406 6905 14406 6905 14407 7085 14407 6902 14407 6962 14408 6904 14408 6903 14408 6962 14409 6903 14409 6911 14409 6911 14410 6903 14410 6906 14410 6911 14411 6906 14411 6910 14411 6910 14412 6906 14412 6907 14412 7130 14413 6948 14413 6908 14413 6908 14414 6948 14414 6946 14414 6960 14415 7130 14415 6908 14415 6960 14416 6908 14416 6962 14416 6915 14417 6914 14417 6909 14417 6909 14418 6914 14418 6820 14418 6910 14419 6909 14419 6820 14419 6910 14420 6820 14420 6911 14420 6911 14421 6820 14421 6962 14421 6912 14422 7136 14422 6822 14422 7136 14423 6912 14423 7031 14423 7031 14424 6912 14424 6826 14424 6927 14425 6913 14425 6917 14425 6927 14426 6917 14426 6954 14426 6914 14427 6915 14427 6916 14427 6916 14428 6915 14428 6917 14428 6916 14429 6917 14429 6919 14429 6917 14430 6918 14430 6919 14430 6913 14431 6827 14431 6917 14431 6917 14432 6827 14432 6918 14432 6917 14433 6915 14433 6891 14433 6891 14434 6915 14434 6909 14434 6996 14435 6808 14435 6891 14435 6808 14436 7131 14436 6891 14436 6891 14437 7131 14437 6917 14437 6920 14438 7131 14438 7132 14438 7132 14439 7131 14439 6808 14439 7132 14440 6808 14440 6996 14440 6917 14441 6920 14441 7132 14441 7132 14442 6996 14442 6917 14442 6917 14443 6996 14443 6954 14443 6917 14444 7131 14444 6920 14444 6921 14445 6923 14445 6922 14445 6923 14446 6927 14446 6939 14446 6940 14447 6926 14447 6939 14447 6939 14448 6926 14448 6881 14448 6881 14449 6923 14449 6939 14449 6921 14450 6922 14450 6925 14450 6925 14451 6922 14451 6924 14451 6925 14452 6924 14452 6876 14452 6925 14453 6876 14453 6928 14453 6921 14454 6913 14454 6927 14454 6921 14455 6927 14455 6923 14455 6997 14456 6928 14456 6854 14456 6854 14457 6928 14457 6940 14457 6997 14458 6977 14458 6928 14458 6930 14459 6931 14459 6932 14459 6930 14460 6932 14460 7012 14460 7012 14461 6932 14461 6929 14461 6929 14462 6932 14462 6900 14462 6889 14463 7126 14463 6933 14463 6933 14464 7126 14464 7128 14464 7128 14465 6890 14465 6931 14465 6931 14466 6930 14466 6936 14466 6934 14467 6890 14467 6889 14467 6889 14468 6890 14468 7126 14468 7128 14469 6870 14469 6872 14469 7066 14470 6933 14470 6872 14470 6872 14471 6933 14471 7128 14471 6936 14472 6935 14472 6931 14472 6931 14473 6935 14473 7128 14473 7128 14474 6935 14474 6870 14474 6930 14475 6937 14475 6936 14475 6937 14476 6930 14476 7063 14476 7063 14477 6930 14477 7012 14477 6972 14478 6855 14478 6938 14478 6971 14479 6972 14479 6953 14479 6953 14480 6972 14480 6938 14480 6953 14481 6938 14481 6939 14481 6939 14482 6938 14482 6861 14482 6939 14483 6861 14483 6940 14483 6941 14484 6861 14484 6856 14484 6861 14485 6941 14485 6940 14485 6941 14486 6858 14486 6940 14486 6858 14487 7001 14487 6940 14487 7001 14488 6859 14488 6940 14488 6859 14489 6854 14489 6940 14489 6854 14490 6859 14490 6974 14490 7001 14491 6858 14491 6976 14491 6941 14492 6856 14492 6857 14492 6943 14493 6942 14493 6950 14493 6944 14494 6951 14494 6888 14494 6888 14495 6951 14495 6950 14495 6888 14496 6950 14496 6942 14496 6966 14497 6965 14497 6979 14497 6979 14498 6965 14498 7130 14498 6979 14499 7130 14499 6960 14499 6945 14500 7119 14500 7120 14500 6945 14501 7120 14501 6993 14501 6993 14502 7120 14502 6828 14502 7129 14503 6991 14503 6947 14503 7129 14504 6947 14504 7119 14504 6946 14505 6948 14505 6828 14505 6995 14506 7129 14506 6945 14506 6945 14507 7129 14507 7119 14507 6948 14508 7130 14508 6993 14508 6948 14509 6993 14509 6828 14509 6949 14510 6990 14510 6969 14510 6969 14511 6990 14511 6964 14511 6887 14512 6952 14512 6944 14512 6884 14513 7119 14513 6887 14513 6887 14514 7119 14514 6947 14514 6887 14515 6947 14515 6952 14515 6952 14516 6947 14516 6991 14516 6985 14517 6950 14517 6951 14517 6985 14518 6951 14518 6986 14518 6986 14519 6951 14519 6944 14519 6986 14520 6944 14520 6952 14520 6971 14521 6953 14521 6989 14521 6927 14522 6954 14522 6989 14522 6927 14523 6989 14523 6939 14523 6939 14524 6989 14524 6953 14524 7031 14525 6826 14525 7027 14525 6955 14526 6956 14526 7028 14526 6955 14527 7027 14527 6826 14527 7028 14528 7027 14528 6955 14528 6957 14529 6958 14529 7134 14529 7134 14530 7028 14530 6956 14530 7134 14531 6956 14531 6957 14531 6958 14532 6957 14532 7026 14532 7026 14533 6957 14533 6983 14533 7026 14534 6983 14534 6959 14534 7026 14535 6959 14535 7136 14535 7136 14536 6959 14536 6822 14536 6959 14537 6983 14537 6963 14537 6963 14538 6961 14538 6959 14538 6963 14539 6979 14539 6960 14539 6963 14540 6960 14540 6962 14540 6962 14541 6820 14541 6961 14541 6962 14542 6961 14542 6963 14542 6968 14543 6966 14543 6979 14543 6964 14544 6965 14544 6969 14544 6969 14545 6965 14545 6966 14545 6969 14546 6966 14546 6967 14546 6967 14547 6966 14547 6968 14547 6969 14548 6967 14548 6949 14548 6949 14549 6967 14549 6982 14549 6971 14550 6989 14550 6970 14550 6981 14551 6973 14551 6970 14551 6970 14552 6973 14552 6971 14552 6981 14553 6997 14553 6974 14553 6974 14554 6975 14554 6981 14554 6972 14555 6860 14555 6855 14555 6856 14556 6860 14556 6981 14556 6981 14557 6860 14557 6973 14557 6973 14558 6860 14558 6972 14558 6975 14559 6976 14559 6981 14559 6976 14560 6857 14560 6981 14560 6981 14561 6857 14561 6856 14561 6974 14562 6859 14562 6975 14562 7001 14563 6976 14563 6975 14563 6980 14564 6997 14564 6981 14564 6977 14565 6997 14565 6980 14565 6977 14566 6980 14566 6824 14566 6977 14567 6824 14567 6821 14567 6955 14568 6826 14568 6824 14568 6978 14569 6994 14569 6868 14569 6868 14570 6994 14570 6982 14570 6983 14571 7077 14571 6963 14571 6984 14572 7077 14572 6979 14572 6967 14573 6980 14573 6981 14573 7077 14574 7076 14574 6963 14574 6967 14575 6981 14575 6970 14575 6967 14576 6970 14576 6982 14576 6982 14577 6970 14577 6868 14577 7077 14578 6967 14578 6968 14578 7077 14579 6968 14579 6979 14579 7077 14580 6983 14580 6957 14580 7077 14581 6957 14581 6967 14581 6967 14582 6957 14582 6956 14582 6967 14583 6956 14583 6980 14583 6963 14584 7076 14584 6984 14584 6963 14585 6984 14585 6979 14585 6955 14586 6824 14586 6956 14586 6956 14587 6824 14587 6980 14587 6954 14588 6866 14588 6989 14588 6989 14589 6866 14589 6985 14589 6985 14590 6988 14590 6989 14590 6988 14591 6985 14591 6986 14591 6988 14592 6986 14592 6987 14592 6986 14593 6952 14593 6987 14593 6987 14594 6868 14594 6988 14594 6988 14595 6868 14595 6970 14595 6988 14596 6970 14596 6989 14596 6982 14597 6994 14597 6949 14597 6949 14598 6994 14598 6990 14598 6990 14599 6994 14599 6992 14599 6991 14600 6995 14600 6952 14600 6990 14601 6992 14601 6995 14601 6993 14602 7130 14602 6965 14602 6965 14603 6964 14603 6993 14603 6993 14604 6964 14604 6990 14604 6993 14605 6990 14605 6945 14605 6945 14606 6990 14606 6995 14606 6992 14607 6994 14607 6995 14607 6995 14608 6994 14608 6978 14608 7012 14609 7013 14609 7063 14609 7010 14610 6853 14610 6998 14610 6999 14611 6998 14611 7002 14611 6941 14612 6853 14612 7011 14612 7002 14613 6941 14613 7011 14613 6998 14614 6999 14614 7010 14614 7010 14615 6999 14615 7006 14615 7006 14616 6999 14616 7000 14616 7002 14617 7001 14617 6999 14617 7002 14618 7004 14618 7001 14618 7009 14619 7005 14619 7003 14619 7004 14620 7003 14620 7006 14620 7004 14621 7006 14621 7000 14621 7010 14622 7007 14622 7008 14622 7010 14623 7008 14623 6853 14623 6853 14624 7008 14624 7011 14624 7003 14625 7013 14625 7012 14625 7003 14626 7012 14626 7009 14626 7014 14627 7011 14627 7007 14627 7011 14628 7014 14628 7062 14628 7007 14629 7010 14629 7014 14629 7003 14630 7004 14630 7065 14630 7065 14631 7004 14631 7002 14631 7065 14632 7002 14632 7064 14632 7064 14633 7002 14633 7011 14633 7003 14634 7065 14634 7013 14634 7064 14635 7011 14635 7062 14635 6863 14636 7014 14636 7016 14636 7016 14637 7014 14637 7010 14637 7010 14638 7015 14638 7016 14638 7005 14639 6862 14639 7017 14639 7052 14640 6899 14640 6898 14640 6899 14641 7052 14641 7049 14641 6898 14642 6896 14642 7052 14642 7052 14643 6896 14643 7053 14643 6896 14644 7018 14644 7053 14644 7053 14645 7018 14645 7056 14645 7019 14646 7056 14646 7018 14646 7020 14647 7056 14647 7019 14647 7022 14648 7021 14648 7059 14648 7022 14649 7023 14649 7021 14649 7024 14650 7021 14650 7023 14650 7021 14651 7024 14651 6895 14651 7021 14652 6895 14652 7025 14652 7025 14653 6895 14653 7049 14653 6895 14654 6899 14654 7049 14654 7137 14655 7030 14655 7033 14655 7137 14656 7033 14656 7135 14656 7033 14657 7032 14657 7135 14657 7138 14658 7028 14658 7034 14658 7139 14659 7027 14659 7028 14659 7139 14660 7028 14660 7138 14660 7026 14661 7135 14661 6958 14661 7135 14662 7032 14662 6958 14662 6958 14663 7032 14663 7034 14663 7028 14664 6816 14664 7034 14664 7028 14665 7134 14665 6816 14665 7034 14666 6816 14666 6958 14666 6958 14667 6816 14667 7134 14667 7140 14668 7036 14668 7029 14668 7137 14669 7029 14669 7030 14669 7137 14670 7136 14670 7029 14670 7135 14671 7026 14671 7136 14671 7031 14672 7027 14672 7139 14672 7139 14673 7029 14673 7031 14673 7136 14674 7031 14674 7029 14674 7032 14675 7033 14675 7034 14675 7034 14676 7033 14676 7138 14676 7138 14677 7033 14677 7035 14677 7036 14678 7140 14678 7035 14678 7035 14679 7140 14679 7139 14679 7035 14680 7139 14680 7138 14680 7029 14681 7036 14681 7030 14681 7043 14682 7030 14682 7041 14682 7041 14683 7030 14683 7036 14683 7037 14684 7033 14684 7043 14684 7043 14685 7033 14685 7030 14685 7033 14686 7037 14686 7035 14686 7037 14687 7040 14687 7035 14687 7035 14688 7040 14688 7036 14688 7036 14689 7040 14689 7041 14689 7043 14690 7038 14690 7037 14690 7037 14691 7038 14691 7039 14691 7037 14692 7039 14692 7040 14692 7040 14693 7039 14693 7042 14693 7040 14694 7042 14694 7041 14694 7041 14695 7042 14695 7044 14695 7041 14696 7044 14696 7043 14696 7043 14697 7044 14697 7038 14697 7047 14698 7060 14698 7045 14698 7049 14699 6852 14699 7045 14699 7045 14700 6852 14700 7047 14700 7051 14701 6852 14701 7049 14701 7046 14702 6852 14702 7050 14702 7050 14703 6852 14703 7051 14703 7046 14704 7050 14704 7055 14704 7111 14705 7097 14705 7054 14705 7113 14706 7046 14706 7097 14706 7097 14707 7046 14707 7055 14707 7097 14708 7055 14708 7054 14708 7058 14709 6851 14709 7112 14709 7112 14710 6851 14710 7113 14710 6851 14711 7058 14711 6819 14711 6819 14712 7058 14712 7057 14712 7060 14713 7047 14713 7048 14713 7060 14714 7048 14714 7061 14714 7045 14715 7025 14715 7049 14715 7051 14716 7049 14716 7052 14716 7051 14717 7052 14717 7050 14717 7050 14718 7052 14718 7053 14718 7056 14719 7054 14719 7055 14719 7056 14720 7055 14720 7053 14720 7053 14721 7055 14721 7050 14721 7020 14722 7111 14722 7056 14722 7111 14723 7054 14723 7056 14723 7021 14724 7068 14724 7057 14724 7021 14725 7057 14725 7059 14725 7057 14726 7058 14726 7059 14726 7112 14727 6844 14727 7059 14727 7112 14728 7059 14728 7058 14728 7021 14729 7060 14729 7061 14729 6818 14730 7068 14730 7061 14730 7061 14731 7068 14731 7021 14731 7021 14732 7025 14732 7060 14732 7060 14733 7025 14733 7045 14733 6817 14734 6937 14734 7063 14734 7013 14735 7065 14735 7063 14735 7064 14736 7062 14736 7066 14736 7064 14737 7066 14737 7067 14737 7067 14738 7066 14738 6871 14738 7067 14739 6871 14739 6869 14739 7067 14740 6869 14740 6817 14740 6817 14741 6869 14741 6937 14741 7063 14742 7065 14742 6875 14742 7063 14743 6875 14743 6817 14743 6818 14744 6816 14744 7134 14744 6818 14745 7134 14745 7068 14745 6848 14746 6814 14746 7069 14746 7069 14747 6814 14747 7083 14747 7070 14748 7086 14748 7087 14748 7084 14749 7069 14749 7083 14749 7087 14750 7083 14750 6807 14750 7087 14751 6807 14751 7070 14751 6807 14752 6815 14752 6838 14752 6838 14753 7070 14753 6807 14753 7073 14754 6812 14754 7079 14754 7133 14755 7071 14755 7079 14755 7079 14756 7071 14756 7116 14756 7079 14757 7116 14757 7072 14757 7079 14758 7072 14758 7073 14758 6830 14759 7071 14759 7133 14759 6830 14760 7133 14760 7074 14760 7079 14761 6813 14761 7133 14761 7079 14762 6811 14762 6813 14762 7078 14763 7075 14763 7076 14763 7078 14764 7076 14764 7077 14764 6971 14765 7080 14765 6972 14765 6812 14766 6888 14766 6829 14766 7087 14767 7085 14767 7083 14767 7083 14768 7085 14768 7082 14768 7083 14769 7082 14769 7084 14769 7086 14770 7085 14770 7087 14770 7088 14771 6810 14771 7114 14771 7114 14772 7089 14772 7088 14772 7114 14773 6809 14773 7089 14773 7089 14774 6809 14774 7099 14774 7091 14775 6844 14775 7114 14775 7114 14776 7090 14776 7091 14776 7091 14777 7090 14777 7092 14777 7096 14778 7094 14778 7093 14778 7093 14779 7094 14779 7109 14779 7093 14780 7095 14780 7090 14780 7093 14781 7090 14781 7096 14781 7113 14782 7097 14782 7114 14782 7114 14783 7097 14783 7110 14783 7114 14784 7110 14784 6842 14784 6842 14785 6840 14785 6809 14785 6809 14786 6840 14786 7098 14786 7098 14787 7096 14787 6810 14787 6810 14788 7096 14788 7090 14788 6842 14789 6809 14789 7114 14789 7090 14790 7114 14790 6810 14790 7099 14791 7088 14791 7089 14791 6810 14792 7088 14792 7099 14792 7101 14793 7106 14793 7103 14793 7105 14794 7106 14794 7101 14794 7117 14795 7101 14795 6835 14795 6835 14796 7101 14796 7103 14796 7100 14797 7104 14797 6832 14797 7104 14798 7115 14798 6863 14798 7116 14799 7071 14799 7101 14799 7101 14800 7071 14800 7102 14800 7104 14801 7100 14801 7115 14801 7105 14802 7101 14802 7102 14802 7106 14803 7105 14803 6832 14803 7094 14804 7096 14804 7107 14804 7107 14805 7096 14805 7108 14805 6845 14806 7093 14806 6846 14806 6846 14807 7093 14807 7109 14807 7020 14808 7110 14808 7111 14808 7111 14809 7110 14809 7097 14809 7112 14810 7113 14810 6844 14810 6844 14811 7113 14811 7114 14811 7100 14812 6831 14812 7115 14812 7115 14813 6831 14813 6864 14813 6836 14814 7104 14814 7016 14814 7016 14815 7104 14815 6863 14815 7116 14816 7101 14816 7072 14816 7072 14817 7101 14817 7117 14817 7118 14818 7102 14818 7071 14818 7118 14819 7071 14819 6830 14819 7119 14820 6884 14820 7121 14820 7119 14821 7121 14821 7120 14821 7120 14822 7121 14822 6828 14822 6828 14823 7121 14823 7122 14823 7123 14824 7125 14824 7128 14824 7124 14825 6890 14825 7125 14825 7126 14826 6890 14826 7127 14826 7127 14827 6890 14827 7124 14827 7123 14828 7126 14828 7127 14828 7124 14829 7125 14829 7127 14829 7127 14830 7125 14830 7123 14830 7126 14831 7123 14831 7128 14831 7128 14832 7125 14832 6890 14832 6991 14833 7129 14833 6995 14833 7131 14834 6825 14834 6808 14834 6920 14835 6883 14835 7132 14835 6807 14836 7083 14836 6814 14836 6818 14837 6819 14837 6816 14837 6819 14838 7057 14838 6816 14838 7136 14839 7137 14839 7135 14839 7140 14840 7029 14840 7139 14840 7409 14841 7403 14841 7406 14841 7405 14842 7414 14842 7415 14842 7141 14843 7216 14843 7168 14843 7221 14844 7222 14844 7249 14844 7221 14845 7249 14845 7248 14845 7228 14846 7142 14846 7250 14846 7223 14847 7379 14847 7228 14847 7207 14848 7203 14848 7232 14848 7348 14849 7309 14849 7143 14849 7143 14850 7309 14850 7233 14850 7143 14851 7233 14851 7387 14851 7387 14852 7233 14852 7389 14852 7144 14853 7311 14853 7194 14853 7386 14854 7194 14854 7311 14854 7328 14855 7379 14855 7330 14855 7402 14856 7147 14856 7150 14856 7402 14857 7417 14857 7147 14857 7404 14858 7417 14858 7402 14858 7404 14859 7408 14859 7157 14859 7158 14860 7417 14860 7404 14860 7158 14861 7404 14861 7166 14861 7166 14862 7404 14862 7157 14862 7409 14863 7406 14863 7413 14863 7410 14864 7411 14864 7145 14864 7145 14865 7411 14865 7413 14865 7146 14866 7185 14866 7416 14866 7210 14867 7414 14867 7213 14867 7210 14868 7146 14868 7414 14868 7414 14869 7146 14869 7416 14869 7198 14870 7197 14870 7147 14870 7153 14871 7409 14871 7197 14871 7197 14872 7409 14872 7147 14872 7147 14873 7409 14873 7412 14873 7409 14874 7413 14874 7412 14874 7152 14875 7271 14875 7199 14875 7358 14876 7149 14876 7199 14876 7375 14877 7352 14877 7373 14877 7373 14878 7352 14878 7148 14878 7373 14879 7148 14879 7271 14879 7271 14880 7148 14880 7339 14880 7363 14881 7178 14881 7149 14881 7149 14882 7178 14882 7172 14882 7149 14883 7172 14883 7199 14883 7199 14884 7172 14884 7152 14884 7151 14885 7150 14885 7406 14885 7151 14886 7406 14886 7403 14886 7414 14887 7405 14887 7421 14887 7421 14888 7405 14888 7422 14888 7402 14889 7150 14889 7152 14889 7152 14890 7150 14890 7151 14890 7152 14891 7151 14891 7271 14891 7271 14892 7151 14892 7373 14892 7198 14893 7147 14893 7397 14893 7197 14894 7196 14894 7153 14894 7418 14895 7399 14895 7154 14895 7154 14896 7401 14896 7411 14896 7418 14897 7156 14897 7155 14897 7418 14898 7155 14898 7153 14898 7409 14899 7153 14899 7155 14899 7411 14900 7410 14900 7154 14900 7154 14901 7410 14901 7156 14901 7156 14902 7418 14902 7154 14902 7150 14903 7147 14903 7407 14903 7407 14904 7147 14904 7412 14904 7407 14905 7412 14905 7408 14905 7157 14906 7408 14906 7412 14906 7165 14907 7315 14907 7166 14907 7158 14908 7278 14908 7169 14908 7169 14909 7278 14909 7160 14909 7171 14910 7316 14910 7159 14910 7316 14911 7171 14911 7277 14911 7277 14912 7171 14912 7276 14912 7276 14913 7171 14913 7355 14913 7355 14914 7287 14914 7283 14914 7355 14915 7283 14915 7276 14915 7283 14916 7281 14916 7276 14916 7281 14917 7283 14917 7285 14917 7281 14918 7285 14918 7160 14918 7160 14919 7285 14919 7169 14919 7284 14920 7287 14920 7169 14920 7285 14921 7284 14921 7169 14921 7399 14922 7300 14922 7301 14922 7301 14923 7293 14923 7399 14923 7399 14924 7293 14924 7162 14924 7171 14925 7302 14925 7306 14925 7161 14926 7171 14926 7296 14926 7296 14927 7171 14927 7306 14927 7293 14928 7301 14928 7302 14928 7293 14929 7302 14929 7291 14929 7296 14930 7306 14930 7300 14930 7296 14931 7300 14931 7164 14931 7401 14932 7154 14932 7162 14932 7295 14933 7291 14933 7171 14933 7171 14934 7291 14934 7302 14934 7162 14935 7211 14935 7401 14935 7401 14936 7211 14936 7166 14936 7321 14937 7295 14937 7171 14937 7295 14938 7321 14938 7162 14938 7162 14939 7321 14939 7211 14939 7163 14940 7208 14940 7170 14940 7163 14941 7170 14941 7399 14941 7399 14942 7170 14942 7164 14942 7399 14943 7164 14943 7300 14943 7171 14944 7320 14944 7321 14944 7211 14945 7209 14945 7166 14945 7316 14946 7277 14946 7278 14946 7316 14947 7278 14947 7315 14947 7315 14948 7278 14948 7158 14948 7315 14949 7158 14949 7166 14949 7159 14950 7209 14950 7171 14950 7171 14951 7209 14951 7320 14951 7209 14952 7165 14952 7166 14952 7209 14953 7159 14953 7165 14953 7167 14954 7208 14954 7207 14954 7208 14955 7167 14955 7203 14955 7162 14956 7154 14956 7399 14956 7216 14957 7220 14957 7168 14957 7168 14958 7220 14958 7204 14958 7252 14959 7216 14959 7215 14959 7252 14960 7215 14960 7357 14960 7357 14961 7215 14961 7168 14961 7168 14962 7215 14962 7214 14962 7355 14963 7357 14963 7168 14963 7355 14964 7168 14964 7287 14964 7287 14965 7168 14965 7204 14965 7287 14966 7204 14966 7169 14966 7163 14967 7207 14967 7208 14967 7170 14968 7208 14968 7336 14968 7170 14969 7336 14969 7171 14969 7171 14970 7336 14970 7247 14970 7274 14971 7396 14971 7172 14971 7172 14972 7396 14972 7152 14972 7173 14973 7393 14973 7236 14973 7373 14974 7151 14974 7236 14974 7236 14975 7151 14975 7173 14975 7174 14976 7377 14976 7143 14976 7174 14977 7143 14977 7387 14977 7390 14978 7190 14978 7324 14978 7324 14979 7190 14979 7383 14979 7383 14980 7384 14980 7329 14980 7329 14981 7175 14981 7383 14981 7383 14982 7175 14982 7324 14982 7172 14983 7381 14983 7367 14983 7176 14984 7381 14984 7172 14984 7367 14985 7381 14985 7371 14985 7371 14986 7381 14986 7179 14986 7179 14987 7381 14987 7382 14987 7365 14988 7362 14988 7178 14988 7178 14989 7362 14989 7176 14989 7179 14990 7382 14990 7177 14990 7177 14991 7382 14991 7331 14991 7178 14992 7176 14992 7172 14992 7180 14993 7279 14993 7212 14993 7212 14994 7279 14994 7317 14994 7317 14995 7279 14995 7184 14995 7181 14996 7282 14996 7182 14996 7318 14997 7319 14997 7213 14997 7213 14998 7319 14998 7210 14998 7183 14999 7288 14999 7383 14999 7181 15000 7183 15000 7282 15000 7182 15001 7282 15001 7280 15001 7386 15002 7383 15002 7194 15002 7194 15003 7383 15003 7288 15003 7194 15004 7288 15004 7286 15004 7318 15005 7383 15005 7319 15005 7183 15006 7383 15006 7184 15006 7383 15007 7318 15007 7317 15007 7383 15008 7317 15008 7184 15008 7180 15009 7314 15009 7194 15009 7383 15010 7187 15010 7319 15010 7185 15011 7294 15011 7186 15011 7190 15012 7298 15012 7189 15012 7294 15013 7185 15013 7146 15013 7294 15014 7146 15014 7188 15014 7349 15015 7298 15015 7307 15015 7307 15016 7298 15016 7190 15016 7188 15017 7289 15017 7294 15017 7290 15018 7303 15018 7292 15018 7292 15019 7303 15019 7193 15019 7289 15020 7383 15020 7290 15020 7290 15021 7383 15021 7190 15021 7186 15022 7294 15022 7322 15022 7322 15023 7294 15023 7191 15023 7305 15024 7299 15024 7192 15024 7192 15025 7299 15025 7297 15025 7304 15026 7296 15026 7305 15026 7187 15027 7383 15027 7289 15027 7187 15028 7289 15028 7188 15028 7290 15029 7304 15029 7303 15029 7304 15030 7290 15030 7190 15030 7304 15031 7190 15031 7296 15031 7296 15032 7190 15032 7189 15032 7305 15033 7296 15033 7299 15033 7297 15034 7298 15034 7349 15034 7322 15035 7191 15035 7292 15035 7192 15036 7297 15036 7322 15036 7192 15037 7322 15037 7193 15037 7193 15038 7322 15038 7292 15038 7297 15039 7349 15039 7322 15039 7194 15040 7286 15040 7180 15040 7180 15041 7286 15041 7182 15041 7182 15042 7280 15042 7278 15042 7182 15043 7278 15043 7180 15043 7180 15044 7278 15044 7279 15044 7202 15045 7400 15045 7266 15045 7195 15046 7268 15046 7267 15046 7266 15047 7400 15047 7267 15047 7267 15048 7400 15048 7195 15048 7268 15049 7195 15049 7196 15049 7268 15050 7196 15050 7270 15050 7270 15051 7196 15051 7271 15051 7196 15052 7197 15052 7271 15052 7271 15053 7197 15053 7199 15053 7199 15054 7197 15054 7198 15054 7198 15055 7397 15055 7199 15055 7200 15056 7264 15056 7397 15056 7397 15057 7264 15057 7201 15057 7397 15058 7201 15058 7199 15058 7397 15059 7398 15059 7200 15059 7200 15060 7398 15060 7205 15060 7200 15061 7205 15061 7206 15061 7218 15062 7208 15062 7203 15062 7218 15063 7203 15063 7266 15063 7266 15064 7203 15064 7234 15064 7266 15065 7234 15065 7202 15065 7234 15066 7163 15066 7202 15066 7202 15067 7163 15067 7399 15067 7204 15068 7219 15068 7205 15068 7169 15069 7204 15069 7205 15069 7205 15070 7219 15070 7206 15070 7219 15071 7252 15071 7251 15071 7206 15072 7219 15072 7251 15072 7210 15073 7209 15073 7211 15073 7210 15074 7211 15074 7146 15074 7213 15075 7315 15075 7165 15075 7315 15076 7213 15076 7212 15076 7141 15077 7168 15077 7214 15077 7215 15078 7216 15078 7214 15078 7214 15079 7216 15079 7141 15079 7313 15080 7217 15080 7311 15080 7218 15081 7335 15081 7336 15081 7218 15082 7336 15082 7208 15082 7335 15083 7218 15083 7269 15083 7269 15084 7218 15084 7266 15084 7216 15085 7252 15085 7219 15085 7219 15086 7220 15086 7216 15086 7204 15087 7220 15087 7219 15087 7238 15088 7240 15088 7351 15088 7248 15089 7222 15089 7221 15089 7222 15090 7248 15090 7227 15090 7222 15091 7227 15091 7224 15091 7222 15092 7224 15092 7249 15092 7226 15093 7223 15093 7250 15093 7250 15094 7223 15094 7228 15094 7248 15095 7240 15095 7258 15095 7227 15096 7248 15096 7258 15096 7250 15097 7224 15097 7226 15097 7226 15098 7224 15098 7227 15098 7225 15099 7260 15099 7226 15099 7225 15100 7226 15100 7258 15100 7258 15101 7226 15101 7227 15101 7223 15102 7226 15102 7260 15102 7223 15103 7260 15103 7228 15103 7228 15104 7260 15104 7142 15104 7228 15105 7379 15105 7223 15105 7330 15106 7259 15106 7328 15106 7328 15107 7259 15107 7327 15107 7259 15108 7230 15108 7327 15108 7327 15109 7230 15109 7229 15109 7230 15110 7325 15110 7326 15110 7230 15111 7326 15111 7229 15111 7343 15112 7243 15112 7341 15112 7337 15113 7343 15113 7341 15113 7232 15114 7203 15114 7167 15114 7232 15115 7167 15115 7207 15115 7232 15116 7207 15116 7231 15116 7232 15117 7231 15117 7207 15117 7233 15118 7309 15118 7308 15118 7272 15119 7242 15119 7339 15119 7339 15120 7242 15120 7338 15120 7394 15121 7396 15121 7274 15121 7273 15122 7394 15122 7274 15122 7393 15123 7237 15123 7236 15123 7207 15124 7234 15124 7203 15124 7163 15125 7234 15125 7207 15125 7343 15126 7334 15126 7378 15126 7378 15127 7334 15127 7342 15127 7343 15128 7337 15128 7334 15128 7344 15129 7325 15129 7354 15129 7344 15130 7235 15130 7325 15130 7350 15131 7237 15131 7391 15131 7391 15132 7237 15132 7393 15132 7376 15133 7373 15133 7236 15133 7376 15134 7236 15134 7237 15134 7376 15135 7237 15135 7350 15135 7240 15136 7238 15136 7239 15136 7240 15137 7239 15137 7258 15137 7272 15138 7261 15138 7242 15138 7242 15139 7261 15139 7241 15139 7351 15140 7338 15140 7242 15140 7354 15141 7325 15141 7353 15141 7374 15142 7338 15142 7341 15142 7374 15143 7341 15143 7243 15143 7244 15144 7340 15144 7338 15144 7244 15145 7338 15145 7374 15145 7245 15146 7340 15146 7244 15146 7260 15147 7246 15147 7355 15147 7142 15148 7260 15148 7355 15148 7240 15149 7248 15149 7247 15149 7247 15150 7248 15150 7249 15150 7249 15151 7224 15151 7250 15151 7247 15152 7249 15152 7171 15152 7355 15153 7171 15153 7250 15153 7249 15154 7250 15154 7171 15154 7355 15155 7250 15155 7142 15155 7357 15156 7251 15156 7252 15156 7357 15157 7265 15157 7251 15157 7251 15158 7265 15158 7206 15158 7359 15159 7263 15159 7358 15159 7366 15160 7364 15160 7246 15160 7331 15161 7332 15161 7362 15161 7254 15162 7362 15162 7332 15162 7253 15163 7381 15163 7360 15163 7176 15164 7360 15164 7381 15164 7360 15165 7176 15165 7254 15165 7254 15166 7176 15166 7362 15166 7359 15167 7262 15167 7255 15167 7359 15168 7255 15168 7263 15168 7238 15169 7353 15169 7239 15169 7353 15170 7258 15170 7239 15170 7330 15171 7256 15171 7225 15171 7225 15172 7256 15172 7257 15172 7257 15173 7256 15173 7365 15173 7257 15174 7365 15174 7366 15174 7353 15175 7325 15175 7258 15175 7258 15176 7325 15176 7230 15176 7258 15177 7230 15177 7225 15177 7225 15178 7230 15178 7259 15178 7225 15179 7259 15179 7330 15179 7366 15180 7246 15180 7257 15180 7260 15181 7225 15181 7257 15181 7257 15182 7246 15182 7260 15182 7241 15183 7261 15183 7352 15183 7352 15184 7261 15184 7148 15184 7255 15185 7262 15185 7149 15185 7149 15186 7262 15186 7363 15186 7263 15187 7255 15187 7358 15187 7358 15188 7255 15188 7149 15188 7206 15189 7265 15189 7200 15189 7200 15190 7265 15190 7264 15190 7264 15191 7265 15191 7201 15191 7201 15192 7265 15192 7358 15192 7201 15193 7358 15193 7199 15193 7269 15194 7266 15194 7267 15194 7269 15195 7267 15195 7268 15195 7268 15196 7270 15196 7269 15196 7269 15197 7270 15197 7271 15197 7269 15198 7271 15198 7339 15198 7261 15199 7272 15199 7148 15199 7148 15200 7272 15200 7339 15200 7367 15201 7273 15201 7274 15201 7367 15202 7274 15202 7172 15202 7273 15203 7367 15203 7394 15203 7394 15204 7367 15204 7275 15204 7276 15205 7183 15205 7277 15205 7277 15206 7183 15206 7184 15206 7279 15207 7278 15207 7184 15207 7184 15208 7278 15208 7277 15208 7160 15209 7278 15209 7280 15209 7160 15210 7280 15210 7282 15210 7160 15211 7282 15211 7281 15211 7281 15212 7282 15212 7276 15212 7276 15213 7282 15213 7183 15213 7287 15214 7183 15214 7283 15214 7181 15215 7283 15215 7183 15215 7181 15216 7285 15216 7283 15216 7182 15217 7284 15217 7285 15217 7182 15218 7285 15218 7181 15218 7284 15219 7182 15219 7286 15219 7284 15220 7286 15220 7287 15220 7287 15221 7286 15221 7288 15221 7287 15222 7288 15222 7183 15222 7295 15223 7289 15223 7291 15223 7291 15224 7289 15224 7290 15224 7292 15225 7293 15225 7290 15225 7290 15226 7293 15226 7291 15226 7293 15227 7292 15227 7162 15227 7162 15228 7292 15228 7191 15228 7162 15229 7191 15229 7294 15229 7294 15230 7295 15230 7162 15230 7295 15231 7294 15231 7289 15231 7161 15232 7296 15232 7189 15232 7170 15233 7171 15233 7298 15233 7298 15234 7171 15234 7189 15234 7189 15235 7171 15235 7161 15235 7170 15236 7298 15236 7297 15236 7170 15237 7297 15237 7164 15237 7164 15238 7297 15238 7296 15238 7296 15239 7297 15239 7299 15239 7300 15240 7192 15240 7301 15240 7301 15241 7192 15241 7193 15241 7301 15242 7193 15242 7302 15242 7302 15243 7193 15243 7303 15243 7302 15244 7303 15244 7304 15244 7302 15245 7304 15245 7306 15245 7305 15246 7306 15246 7304 15246 7192 15247 7300 15247 7305 15247 7305 15248 7300 15248 7306 15248 7308 15249 7346 15249 7349 15249 7308 15250 7349 15250 7233 15250 7349 15251 7307 15251 7233 15251 7233 15252 7307 15252 7388 15252 7233 15253 7388 15253 7389 15253 7348 15254 7346 15254 7308 15254 7348 15255 7308 15255 7309 15255 7313 15256 7369 15256 7217 15256 7217 15257 7369 15257 7310 15257 7369 15258 7313 15258 7370 15258 7217 15259 7310 15259 7372 15259 7217 15260 7372 15260 7312 15260 7217 15261 7312 15261 7311 15261 7311 15262 7312 15262 7386 15262 7370 15263 7313 15263 7144 15263 7144 15264 7313 15264 7311 15264 7212 15265 7213 15265 7414 15265 7212 15266 7414 15266 7421 15266 7395 15267 7314 15267 7180 15267 7395 15268 7180 15268 7422 15268 7422 15269 7180 15269 7212 15269 7422 15270 7212 15270 7421 15270 7315 15271 7212 15271 7317 15271 7315 15272 7317 15272 7316 15272 7316 15273 7317 15273 7159 15273 7159 15274 7317 15274 7318 15274 7213 15275 7165 15275 7318 15275 7318 15276 7165 15276 7159 15276 7210 15277 7319 15277 7209 15277 7209 15278 7319 15278 7320 15278 7320 15279 7319 15279 7187 15279 7188 15280 7321 15280 7320 15280 7188 15281 7320 15281 7187 15281 7211 15282 7321 15282 7146 15282 7146 15283 7321 15283 7188 15283 7420 15284 7186 15284 7419 15284 7419 15285 7186 15285 7322 15285 7323 15286 7416 15286 7185 15286 7323 15287 7185 15287 7186 15287 7323 15288 7186 15288 7420 15288 7235 15289 7326 15289 7325 15289 7390 15290 7324 15290 7235 15290 7235 15291 7324 15291 7175 15291 7235 15292 7175 15292 7326 15292 7229 15293 7326 15293 7175 15293 7229 15294 7175 15294 7327 15294 7327 15295 7175 15295 7329 15295 7327 15296 7329 15296 7328 15296 7379 15297 7328 15297 7380 15297 7385 15298 7380 15298 7384 15298 7384 15299 7380 15299 7328 15299 7328 15300 7329 15300 7384 15300 7331 15301 7362 15301 7256 15301 7333 15302 7332 15302 7331 15302 7333 15303 7331 15303 7356 15303 7356 15304 7331 15304 7382 15304 7253 15305 7361 15305 7381 15305 7247 15306 7334 15306 7240 15306 7240 15307 7334 15307 7337 15307 7269 15308 7245 15308 7335 15308 7335 15309 7245 15309 7342 15309 7335 15310 7342 15310 7336 15310 7336 15311 7342 15311 7247 15311 7247 15312 7342 15312 7334 15312 7240 15313 7337 15313 7351 15313 7351 15314 7337 15314 7341 15314 7338 15315 7340 15315 7339 15315 7339 15316 7340 15316 7269 15316 7340 15317 7245 15317 7269 15317 7351 15318 7341 15318 7338 15318 7378 15319 7245 15319 7244 15319 7245 15320 7378 15320 7342 15320 7344 15321 7343 15321 7345 15321 7344 15322 7345 15322 7235 15322 7235 15323 7345 15323 7390 15323 7344 15324 7354 15324 7343 15324 7343 15325 7354 15325 7243 15325 7392 15326 7346 15326 7347 15326 7347 15327 7346 15327 7348 15327 7347 15328 7348 15328 7377 15328 7377 15329 7348 15329 7143 15329 7346 15330 7392 15330 7349 15330 7349 15331 7392 15331 7322 15331 7391 15332 7392 15332 7350 15332 7350 15333 7392 15333 7347 15333 7350 15334 7347 15334 7376 15334 7352 15335 7375 15335 7353 15335 7242 15336 7241 15336 7351 15336 7351 15337 7241 15337 7352 15337 7351 15338 7352 15338 7238 15338 7238 15339 7352 15339 7353 15339 7243 15340 7354 15340 7353 15340 7246 15341 7332 15341 7333 15341 7246 15342 7333 15342 7355 15342 7361 15343 7265 15343 7356 15343 7356 15344 7265 15344 7357 15344 7364 15345 7332 15345 7246 15345 7355 15346 7333 15346 7356 15346 7355 15347 7356 15347 7357 15347 7265 15348 7361 15348 7253 15348 7265 15349 7253 15349 7358 15349 7253 15350 7360 15350 7358 15350 7358 15351 7360 15351 7359 15351 7359 15352 7360 15352 7364 15352 7360 15353 7254 15353 7364 15353 7364 15354 7254 15354 7332 15354 7381 15355 7361 15355 7382 15355 7382 15356 7361 15356 7356 15356 7256 15357 7362 15357 7365 15357 7262 15358 7359 15358 7363 15358 7363 15359 7359 15359 7364 15359 7363 15360 7364 15360 7366 15360 7366 15361 7365 15361 7178 15361 7366 15362 7178 15362 7363 15362 7368 15363 7275 15363 7371 15363 7371 15364 7275 15364 7367 15364 7144 15365 7194 15365 7314 15365 7370 15366 7368 15366 7371 15366 7370 15367 7371 15367 7369 15367 7310 15368 7369 15368 7371 15368 7368 15369 7370 15369 7144 15369 7368 15370 7144 15370 7314 15370 7179 15371 7310 15371 7371 15371 7310 15372 7179 15372 7177 15372 7310 15373 7177 15373 7372 15373 7353 15374 7375 15374 7243 15374 7243 15375 7375 15375 7374 15375 7347 15376 7244 15376 7376 15376 7373 15377 7376 15377 7244 15377 7373 15378 7244 15378 7375 15378 7375 15379 7244 15379 7374 15379 7174 15380 7343 15380 7378 15380 7174 15381 7378 15381 7377 15381 7377 15382 7378 15382 7347 15382 7347 15383 7378 15383 7244 15383 7330 15384 7379 15384 7256 15384 7379 15385 7380 15385 7256 15385 7331 15386 7256 15386 7380 15386 7385 15387 7331 15387 7380 15387 7383 15388 7386 15388 7384 15388 7331 15389 7385 15389 7177 15389 7177 15390 7385 15390 7312 15390 7177 15391 7312 15391 7372 15391 7312 15392 7385 15392 7386 15392 7386 15393 7385 15393 7384 15393 7387 15394 7389 15394 7174 15394 7174 15395 7389 15395 7345 15395 7174 15396 7345 15396 7343 15396 7190 15397 7390 15397 7388 15397 7190 15398 7388 15398 7307 15398 7388 15399 7390 15399 7389 15399 7389 15400 7390 15400 7345 15400 7391 15401 7419 15401 7392 15401 7392 15402 7419 15402 7322 15402 7391 15403 7393 15403 7419 15403 7314 15404 7395 15404 7368 15404 7368 15405 7395 15405 7275 15405 7395 15406 7394 15406 7275 15406 7402 15407 7152 15407 7395 15407 7395 15408 7152 15408 7396 15408 7151 15409 7403 15409 7173 15409 7403 15410 7419 15410 7393 15410 7403 15411 7393 15411 7173 15411 7395 15412 7396 15412 7394 15412 7397 15413 7147 15413 7417 15413 7417 15414 7158 15414 7169 15414 7169 15415 7205 15415 7417 15415 7417 15416 7205 15416 7398 15416 7417 15417 7398 15417 7397 15417 7202 15418 7399 15418 7418 15418 7202 15419 7418 15419 7400 15419 7400 15420 7418 15420 7195 15420 7411 15421 7401 15421 7157 15421 7157 15422 7401 15422 7166 15422 7419 15423 7403 15423 7155 15423 7402 15424 7422 15424 7404 15424 7404 15425 7422 15425 7405 15425 7404 15426 7405 15426 7408 15426 7415 15427 7413 15427 7406 15427 7413 15428 7415 15428 7145 15428 7405 15429 7415 15429 7408 15429 7408 15430 7415 15430 7407 15430 7403 15431 7409 15431 7155 15431 7155 15432 7156 15432 7420 15432 7420 15433 7156 15433 7323 15433 7323 15434 7156 15434 7410 15434 7323 15435 7410 15435 7145 15435 7407 15436 7415 15436 7406 15436 7407 15437 7406 15437 7150 15437 7145 15438 7415 15438 7416 15438 7145 15439 7416 15439 7323 15439 7412 15440 7413 15440 7157 15440 7157 15441 7413 15441 7411 15441 7414 15442 7416 15442 7415 15442 7418 15443 7153 15443 7196 15443 7418 15444 7196 15444 7195 15444 7419 15445 7155 15445 7420 15445 7422 15446 7402 15446 7395 15446 7423 15447 7426 15447 7439 15447 7426 15448 7424 15448 7425 15448 7424 15449 7426 15449 7425 15449 7426 15450 7423 15450 7424 15450 7424 15451 7439 15451 7426 15451 7465 15452 7428 15452 7483 15452 7483 15453 7428 15453 7427 15453 7484 15454 7479 15454 7481 15454 7483 15455 7427 15455 7484 15455 7484 15456 7427 15456 7479 15456 7438 15457 7473 15457 7434 15457 7434 15458 7473 15458 7472 15458 7478 15459 7437 15459 7432 15459 7432 15460 7431 15460 7478 15460 7478 15461 7431 15461 7433 15461 7478 15462 7433 15462 7472 15462 7472 15463 7433 15463 7434 15463 7458 15464 7462 15464 7461 15464 7462 15465 7458 15465 7437 15465 7432 15466 7437 15466 7458 15466 7459 15467 7431 15467 7432 15467 7459 15468 7463 15468 7431 15468 7431 15469 7463 15469 7433 15469 7433 15470 7463 15470 7434 15470 7460 15471 7434 15471 7455 15471 7438 15472 7434 15472 7460 15472 7448 15473 7438 15473 7460 15473 7461 15474 7441 15474 7464 15474 7464 15475 7441 15475 7448 15475 7461 15476 7462 15476 7441 15476 7435 15477 7446 15477 7476 15477 7435 15478 7476 15478 7442 15478 7476 15479 7436 15479 7442 15479 7445 15480 7435 15480 7443 15480 7443 15481 7435 15481 7442 15481 7445 15482 7447 15482 7435 15482 7485 15483 7470 15483 7445 15483 7485 15484 7443 15484 7477 15484 7443 15485 7485 15485 7445 15485 7435 15486 7473 15486 7448 15486 7471 15487 7440 15487 7447 15487 7447 15488 7440 15488 7472 15488 7447 15489 7472 15489 7435 15489 7435 15490 7472 15490 7473 15490 7445 15491 7470 15491 7471 15491 7462 15492 7437 15492 7477 15492 7473 15493 7438 15493 7448 15493 7423 15494 7439 15494 7440 15494 7423 15495 7440 15495 7471 15495 7444 15496 7474 15496 7441 15496 7462 15497 7476 15497 7475 15497 7441 15498 7474 15498 7448 15498 7462 15499 7475 15499 7441 15499 7441 15500 7475 15500 7444 15500 7474 15501 7444 15501 7446 15501 7442 15502 7436 15502 7462 15502 7475 15503 7476 15503 7444 15503 7462 15504 7477 15504 7442 15504 7442 15505 7477 15505 7443 15505 7446 15506 7444 15506 7476 15506 7445 15507 7471 15507 7447 15507 7448 15508 7446 15508 7435 15508 7464 15509 7448 15509 7460 15509 7430 15510 7449 15510 7467 15510 7449 15511 7482 15511 7467 15511 7481 15512 7450 15512 7469 15512 7429 15513 7481 15513 7451 15513 7481 15514 7469 15514 7451 15514 7468 15515 7453 15515 7469 15515 7469 15516 7453 15516 7451 15516 7429 15517 7451 15517 7453 15517 7483 15518 7484 15518 7465 15518 7484 15519 7429 15519 7453 15519 7484 15520 7453 15520 7452 15520 7484 15521 7452 15521 7465 15521 7428 15522 7465 15522 7482 15522 7482 15523 7465 15523 7452 15523 7482 15524 7452 15524 7466 15524 7482 15525 7466 15525 7467 15525 7469 15526 7450 15526 7480 15526 7468 15527 7469 15527 7480 15527 7468 15528 7480 15528 7466 15528 7480 15529 7430 15529 7466 15529 7466 15530 7430 15530 7467 15530 7452 15531 7455 15531 7466 15531 7466 15532 7455 15532 7454 15532 7453 15533 7457 15533 7452 15533 7452 15534 7457 15534 7455 15534 7468 15535 7456 15535 7453 15535 7453 15536 7456 15536 7457 15536 7466 15537 7454 15537 7468 15537 7468 15538 7454 15538 7456 15538 7461 15539 7456 15539 7458 15539 7458 15540 7456 15540 7454 15540 7459 15541 7454 15541 7463 15541 7463 15542 7454 15542 7455 15542 7460 15543 7455 15543 7464 15543 7464 15544 7455 15544 7457 15544 7456 15545 7461 15545 7457 15545 7457 15546 7461 15546 7464 15546 7458 15547 7454 15547 7459 15547 7434 15548 7463 15548 7455 15548 7432 15549 7458 15549 7459 15549 7485 15550 7440 15550 7439 15550 7485 15551 7439 15551 7470 15551 7472 15552 7440 15552 7485 15552 7423 15553 7471 15553 7424 15553 7424 15554 7471 15554 7470 15554 7470 15555 7439 15555 7424 15555 7474 15556 7446 15556 7448 15556 7476 15557 7462 15557 7436 15557 7478 15558 7485 15558 7477 15558 7477 15559 7437 15559 7478 15559 7481 15560 7479 15560 7450 15560 7450 15561 7479 15561 7480 15561 7480 15562 7479 15562 7430 15562 7430 15563 7479 15563 7449 15563 7449 15564 7479 15564 7482 15564 7428 15565 7482 15565 7479 15565 7428 15566 7479 15566 7427 15566 7429 15567 7484 15567 7481 15567 7472 15568 7485 15568 7478 15568 7729 15569 7746 15569 7728 15569 7632 15570 7689 15570 7690 15570 7691 15571 7690 15571 7633 15571 7633 15572 7690 15572 7689 15572 7689 15573 7632 15573 7633 15573 7685 15574 7667 15574 7686 15574 7685 15575 7660 15575 7667 15575 7660 15576 7685 15576 7688 15576 7690 15577 7684 15577 7689 15577 7631 15578 7664 15578 7593 15578 7593 15579 7664 15579 7486 15579 7593 15580 7486 15580 7487 15580 7593 15581 7487 15581 7594 15581 7552 15582 7553 15582 7488 15582 7546 15583 7547 15583 7488 15583 7488 15584 7547 15584 7681 15584 7488 15585 7681 15585 7552 15585 7552 15586 7681 15586 7550 15586 7697 15587 7489 15587 7655 15587 7653 15588 7550 15588 7681 15588 7653 15589 7681 15589 7490 15589 7653 15590 7490 15590 7655 15590 7655 15591 7490 15591 7697 15591 7697 15592 7490 15592 7584 15592 7600 15593 7702 15593 7641 15593 7682 15594 7600 15594 7641 15594 7682 15595 7641 15595 7646 15595 7600 15596 7682 15596 7491 15596 7491 15597 7682 15597 7684 15597 7694 15598 7576 15598 7684 15598 7491 15599 7684 15599 7576 15599 7570 15600 7588 15600 7574 15600 7493 15601 7492 15601 7589 15601 7493 15602 7749 15602 7591 15602 7591 15603 7749 15603 7494 15603 7624 15604 7628 15604 7748 15604 7749 15605 7493 15605 7589 15605 7495 15606 7747 15606 7748 15606 7495 15607 7748 15607 7630 15607 7630 15608 7748 15608 7628 15608 7591 15609 7494 15609 7569 15609 7624 15610 7748 15610 7574 15610 7574 15611 7748 15611 7570 15611 7747 15612 7495 15612 7591 15612 7747 15613 7591 15613 7569 15613 7511 15614 7516 15614 7517 15614 7511 15615 7517 15615 7510 15615 7503 15616 7521 15616 7520 15616 7522 15617 7503 15617 7505 15617 7519 15618 7743 15618 7496 15618 7519 15619 7496 15619 7497 15619 7501 15620 7505 15620 7497 15620 7497 15621 7496 15621 7501 15621 7501 15622 7496 15622 7563 15622 7520 15623 7497 15623 7503 15623 7503 15624 7497 15624 7505 15624 7527 15625 7526 15625 7741 15625 7741 15626 7526 15626 7498 15626 7542 15627 7543 15627 7721 15627 7721 15628 7543 15628 7499 15628 7504 15629 7501 15629 7500 15629 7500 15630 7501 15630 7563 15630 7521 15631 7503 15631 7502 15631 7744 15632 7519 15632 7497 15632 7501 15633 7504 15633 7505 15633 7505 15634 7504 15634 7745 15634 7505 15635 7745 15635 7522 15635 7506 15636 7615 15636 7611 15636 7509 15637 7709 15637 7507 15637 7562 15638 7710 15638 7509 15638 7709 15639 7706 15639 7507 15639 7507 15640 7706 15640 7561 15640 7507 15641 7561 15641 7640 15641 7507 15642 7514 15642 7509 15642 7509 15643 7514 15643 7508 15643 7509 15644 7508 15644 7562 15644 7565 15645 7513 15645 7512 15645 7565 15646 7582 15646 7511 15646 7565 15647 7511 15647 7513 15647 7513 15648 7511 15648 7510 15648 7515 15649 7514 15649 7507 15649 7514 15650 7515 15650 7512 15650 7512 15651 7515 15651 7605 15651 7512 15652 7605 15652 7565 15652 7506 15653 7692 15653 7615 15653 7615 15654 7692 15654 7580 15654 7563 15655 7581 15655 7579 15655 7563 15656 7579 15656 7500 15656 7578 15657 7585 15657 7743 15657 7743 15658 7585 15658 7496 15658 7516 15659 7518 15659 7517 15659 7517 15660 7518 15660 7736 15660 7744 15661 7497 15661 7520 15661 7502 15662 7503 15662 7522 15662 7717 15663 7524 15663 7610 15663 7610 15664 7524 15664 7523 15664 7720 15665 7609 15665 7523 15665 7523 15666 7609 15666 7610 15666 7523 15667 7524 15667 7719 15667 7719 15668 7524 15668 7525 15668 7527 15669 7528 15669 7526 15669 7528 15670 7527 15670 7529 15670 7530 15671 7531 15671 7533 15671 7531 15672 7530 15672 7716 15672 7531 15673 7716 15673 7532 15673 7609 15674 7720 15674 7533 15674 7533 15675 7720 15675 7530 15675 7555 15676 7715 15676 7724 15676 7555 15677 7724 15677 7617 15677 7528 15678 7529 15678 7724 15678 7724 15679 7529 15679 7617 15679 7536 15680 7700 15680 7534 15680 7534 15681 7700 15681 7535 15681 7534 15682 7535 15682 7718 15682 7718 15683 7535 15683 7701 15683 7544 15684 7537 15684 7716 15684 7536 15685 7545 15685 7700 15685 7700 15686 7545 15686 7646 15686 7537 15687 7545 15687 7536 15687 7541 15688 7538 15688 7539 15688 7539 15689 7538 15689 7540 15689 7712 15690 7541 15690 7645 15690 7645 15691 7541 15691 7539 15691 7722 15692 7714 15692 7542 15692 7542 15693 7714 15693 7543 15693 7540 15694 7538 15694 7657 15694 7657 15695 7538 15695 7656 15695 7652 15696 7714 15696 7723 15696 7723 15697 7714 15697 7722 15697 7554 15698 7694 15698 7651 15698 7651 15699 7694 15699 7683 15699 7651 15700 7683 15700 7544 15700 7544 15701 7683 15701 7545 15701 7544 15702 7545 15702 7537 15702 7682 15703 7646 15703 7683 15703 7683 15704 7646 15704 7545 15704 7584 15705 7490 15705 7575 15705 7560 15706 7706 15706 7707 15706 7710 15707 7548 15707 7708 15707 7708 15708 7548 15708 7575 15708 7708 15709 7575 15709 7547 15709 7708 15710 7547 15710 7707 15710 7707 15711 7547 15711 7560 15711 7560 15712 7547 15712 7546 15712 7560 15713 7546 15713 7559 15713 7548 15714 7710 15714 7562 15714 7699 15715 7548 15715 7562 15715 7617 15716 7549 15716 7555 15716 7564 15717 7693 15717 7549 15717 7617 15718 7529 15718 7527 15718 7527 15719 7741 15719 7617 15719 7550 15720 7551 15720 7558 15720 7550 15721 7558 15721 7552 15721 7552 15722 7558 15722 7557 15722 7552 15723 7557 15723 7553 15723 7715 15724 7554 15724 7651 15724 7554 15725 7715 15725 7549 15725 7549 15726 7715 15726 7555 15726 7549 15727 7693 15727 7554 15727 7703 15728 7602 15728 7647 15728 7647 15729 7602 15729 7648 15729 7717 15730 7610 15730 7532 15730 7602 15731 7703 15731 7601 15731 7703 15732 7702 15732 7601 15732 7556 15733 7557 15733 7644 15733 7644 15734 7557 15734 7558 15734 7559 15735 7606 15735 7560 15735 7560 15736 7606 15736 7561 15736 7560 15737 7561 15737 7706 15737 7699 15738 7562 15738 7698 15738 7698 15739 7562 15739 7508 15739 7516 15740 7511 15740 7518 15740 7713 15741 7608 15741 7737 15741 7737 15742 7608 15742 7696 15742 7581 15743 7563 15743 7585 15743 7585 15744 7563 15744 7496 15744 7693 15745 7564 15745 7739 15745 7693 15746 7739 15746 7742 15746 7491 15747 7613 15747 7711 15747 7605 15748 7573 15748 7565 15748 7565 15749 7573 15749 7566 15749 7676 15750 7603 15750 7567 15750 7565 15751 7566 15751 7582 15751 7612 15752 7636 15752 7567 15752 7678 15753 7670 15753 7671 15753 7678 15754 7671 15754 7568 15754 7568 15755 7671 15755 7673 15755 7531 15756 7532 15756 7610 15756 7569 15757 7725 15757 7589 15757 7570 15758 7746 15758 7747 15758 7493 15759 7591 15759 7597 15759 7597 15760 7591 15760 7593 15760 7590 15761 7493 15761 7635 15761 7635 15762 7493 15762 7597 15762 7635 15763 7597 15763 7637 15763 7731 15764 7730 15764 7643 15764 7730 15765 7571 15765 7640 15765 7734 15766 7572 15766 7730 15766 7730 15767 7572 15767 7571 15767 7730 15768 7731 15768 7734 15768 7734 15769 7731 15769 7733 15769 7588 15770 7587 15770 7574 15770 7574 15771 7587 15771 7582 15771 7582 15772 7566 15772 7574 15772 7574 15773 7566 15773 7573 15773 7573 15774 7604 15774 7574 15774 7574 15775 7604 15775 7571 15775 7571 15776 7604 15776 7640 15776 7518 15777 7511 15777 7582 15777 7692 15778 7680 15778 7735 15778 7584 15779 7575 15779 7583 15779 7512 15780 7513 15780 7583 15780 7583 15781 7513 15781 7736 15781 7576 15782 7694 15782 7577 15782 7590 15783 7636 15783 7612 15783 7692 15784 7576 15784 7577 15784 7692 15785 7577 15785 7579 15785 7579 15786 7577 15786 7695 15786 7579 15787 7695 15787 7578 15787 7692 15788 7579 15788 7580 15788 7580 15789 7579 15789 7581 15789 7580 15790 7581 15790 7612 15790 7612 15791 7581 15791 7586 15791 7612 15792 7586 15792 7590 15792 7582 15793 7587 15793 7518 15793 7518 15794 7587 15794 7729 15794 7729 15795 7728 15795 7518 15795 7518 15796 7728 15796 7585 15796 7518 15797 7585 15797 7736 15797 7736 15798 7585 15798 7578 15798 7736 15799 7578 15799 7583 15799 7583 15800 7578 15800 7695 15800 7583 15801 7695 15801 7584 15801 7581 15802 7585 15802 7727 15802 7727 15803 7726 15803 7581 15803 7581 15804 7726 15804 7586 15804 7586 15805 7726 15805 7727 15805 7586 15806 7727 15806 7587 15806 7727 15807 7585 15807 7728 15807 7727 15808 7728 15808 7729 15808 7587 15809 7727 15809 7729 15809 7590 15810 7586 15810 7492 15810 7588 15811 7570 15811 7587 15811 7570 15812 7747 15812 7587 15812 7587 15813 7747 15813 7569 15813 7587 15814 7569 15814 7589 15814 7587 15815 7589 15815 7586 15815 7586 15816 7589 15816 7492 15816 7492 15817 7493 15817 7590 15817 7630 15818 7631 15818 7495 15818 7495 15819 7631 15819 7593 15819 7495 15820 7593 15820 7591 15820 7593 15821 7592 15821 7597 15821 7592 15822 7593 15822 7595 15822 7595 15823 7593 15823 7594 15823 7632 15824 7595 15824 7594 15824 7595 15825 7632 15825 7596 15825 7595 15826 7596 15826 7592 15826 7632 15827 7691 15827 7596 15827 7592 15828 7596 15828 7597 15828 7597 15829 7596 15829 7637 15829 7602 15830 7598 15830 7638 15830 7638 15831 7648 15831 7602 15831 7599 15832 7697 15832 7607 15832 7705 15833 7489 15833 7599 15833 7599 15834 7489 15834 7697 15834 7601 15835 7600 15835 7598 15835 7601 15836 7598 15836 7602 15836 7601 15837 7702 15837 7600 15837 7612 15838 7567 15838 7680 15838 7680 15839 7567 15839 7603 15839 7680 15840 7603 15840 7614 15840 7614 15841 7603 15841 7638 15841 7614 15842 7638 15842 7598 15842 7640 15843 7604 15843 7507 15843 7507 15844 7604 15844 7515 15844 7515 15845 7604 15845 7573 15845 7515 15846 7573 15846 7605 15846 7561 15847 7606 15847 7640 15847 7640 15848 7606 15848 7642 15848 7599 15849 7607 15849 7713 15849 7713 15850 7607 15850 7608 15850 7533 15851 7610 15851 7609 15851 7610 15852 7533 15852 7531 15852 7611 15853 7615 15853 7612 15853 7711 15854 7613 15854 7735 15854 7614 15855 7711 15855 7735 15855 7614 15856 7735 15856 7680 15856 7612 15857 7680 15857 7611 15857 7580 15858 7612 15858 7615 15858 7564 15859 7549 15859 7739 15859 7739 15860 7549 15860 7616 15860 7616 15861 7549 15861 7617 15861 7616 15862 7617 15862 7741 15862 7734 15863 7625 15863 7572 15863 7734 15864 7623 15864 7625 15864 7731 15865 7643 15865 7618 15865 7618 15866 7643 15866 7639 15866 7732 15867 7618 15867 7639 15867 7731 15868 7618 15868 7733 15868 7732 15869 7639 15869 7619 15869 7679 15870 7732 15870 7671 15870 7671 15871 7732 15871 7619 15871 7620 15872 7621 15872 7677 15872 7677 15873 7621 15873 7622 15873 7661 15874 7662 15874 7621 15874 7621 15875 7662 15875 7622 15875 7662 15876 7658 15876 7622 15876 7622 15877 7658 15877 7623 15877 7622 15878 7623 15878 7677 15878 7623 15879 7658 15879 7625 15879 7629 15880 7624 15880 7571 15880 7571 15881 7624 15881 7574 15881 7572 15882 7625 15882 7626 15882 7572 15883 7626 15883 7571 15883 7571 15884 7626 15884 7629 15884 7626 15885 7665 15885 7629 15885 7665 15886 7627 15886 7629 15886 7629 15887 7627 15887 7628 15887 7629 15888 7628 15888 7624 15888 7665 15889 7664 15889 7631 15889 7631 15890 7630 15890 7628 15890 7628 15891 7627 15891 7631 15891 7631 15892 7627 15892 7665 15892 7634 15893 7672 15893 7691 15893 7633 15894 7487 15894 7634 15894 7633 15895 7634 15895 7691 15895 7487 15896 7633 15896 7594 15896 7594 15897 7633 15897 7632 15897 7636 15898 7590 15898 7635 15898 7672 15899 7636 15899 7635 15899 7672 15900 7635 15900 7637 15900 7672 15901 7637 15901 7596 15901 7691 15902 7672 15902 7596 15902 7673 15903 7648 15903 7638 15903 7673 15904 7638 15904 7674 15904 7674 15905 7638 15905 7676 15905 7676 15906 7638 15906 7603 15906 7546 15907 7488 15907 7556 15907 7718 15908 7701 15908 7639 15908 7643 15909 7640 15909 7642 15909 7640 15910 7643 15910 7730 15910 7738 15911 7740 15911 7723 15911 7723 15912 7740 15912 7724 15912 7646 15913 7641 15913 7647 15913 7642 15914 7546 15914 7556 15914 7642 15915 7556 15915 7643 15915 7643 15916 7556 15916 7644 15916 7645 15917 7643 15917 7712 15917 7712 15918 7643 15918 7644 15918 7712 15919 7644 15919 7656 15919 7657 15920 7530 15920 7645 15920 7645 15921 7530 15921 7719 15921 7645 15922 7719 15922 7643 15922 7643 15923 7719 15923 7525 15923 7701 15924 7646 15924 7647 15924 7701 15925 7647 15925 7639 15925 7639 15926 7647 15926 7648 15926 7639 15927 7648 15927 7673 15927 7639 15928 7673 15928 7619 15928 7649 15929 7650 15929 7654 15929 7654 15930 7650 15930 7652 15930 7544 15931 7716 15931 7651 15931 7651 15932 7716 15932 7715 15932 7639 15933 7643 15933 7718 15933 7718 15934 7643 15934 7525 15934 7718 15935 7525 15935 7716 15935 7704 15936 7653 15936 7652 15936 7652 15937 7653 15937 7654 15937 7654 15938 7653 15938 7655 15938 7644 15939 7704 15939 7656 15939 7656 15940 7704 15940 7652 15940 7656 15941 7652 15941 7657 15941 7657 15942 7652 15942 7723 15942 7657 15943 7723 15943 7530 15943 7530 15944 7723 15944 7724 15944 7530 15945 7724 15945 7716 15945 7716 15946 7724 15946 7715 15946 7661 15947 7669 15947 7670 15947 7670 15948 7678 15948 7661 15948 7661 15949 7678 15949 7659 15949 7487 15950 7486 15950 7666 15950 7487 15951 7661 15951 7634 15951 7634 15952 7661 15952 7659 15952 7626 15953 7660 15953 7666 15953 7626 15954 7666 15954 7665 15954 7661 15955 7487 15955 7666 15955 7661 15956 7666 15956 7662 15956 7662 15957 7666 15957 7663 15957 7662 15958 7663 15958 7658 15958 7658 15959 7663 15959 7667 15959 7658 15960 7667 15960 7625 15960 7486 15961 7664 15961 7666 15961 7666 15962 7664 15962 7665 15962 7625 15963 7667 15963 7626 15963 7626 15964 7667 15964 7660 15964 7620 15965 7668 15965 7621 15965 7621 15966 7668 15966 7669 15966 7621 15967 7669 15967 7661 15967 7673 15968 7671 15968 7619 15968 7676 15969 7567 15969 7636 15969 7636 15970 7672 15970 7676 15970 7674 15971 7568 15971 7673 15971 7568 15972 7674 15972 7675 15972 7675 15973 7674 15973 7676 15973 7675 15974 7676 15974 7672 15974 7677 15975 7623 15975 7734 15975 7618 15976 7679 15976 7668 15976 7668 15977 7620 15977 7618 15977 7618 15978 7620 15978 7677 15978 7618 15979 7677 15979 7733 15979 7733 15980 7677 15980 7734 15980 7659 15981 7678 15981 7568 15981 7659 15982 7568 15982 7675 15982 7659 15983 7675 15983 7634 15983 7634 15984 7675 15984 7672 15984 7669 15985 7668 15985 7670 15985 7670 15986 7668 15986 7679 15986 7670 15987 7679 15987 7671 15987 7575 15988 7490 15988 7681 15988 7575 15989 7681 15989 7547 15989 7684 15990 7682 15990 7683 15990 7684 15991 7683 15991 7694 15991 7689 15992 7684 15992 7690 15992 7686 15993 7687 15993 7688 15993 7686 15994 7688 15994 7685 15994 7660 15995 7688 15995 7666 15995 7688 15996 7687 15996 7663 15996 7663 15997 7687 15997 7686 15997 7663 15998 7686 15998 7667 15998 7632 15999 7690 15999 7691 15999 7692 16000 7613 16000 7576 16000 7576 16001 7613 16001 7491 16001 7742 16002 7577 16002 7693 16002 7693 16003 7577 16003 7694 16003 7693 16004 7694 16004 7554 16004 7695 16005 7696 16005 7584 16005 7584 16006 7696 16006 7608 16006 7608 16007 7607 16007 7584 16007 7584 16008 7607 16008 7697 16008 7575 16009 7548 16009 7699 16009 7698 16010 7583 16010 7699 16010 7699 16011 7583 16011 7575 16011 7546 16012 7642 16012 7559 16012 7559 16013 7642 16013 7606 16013 7557 16014 7556 16014 7553 16014 7553 16015 7556 16015 7488 16015 7700 16016 7646 16016 7701 16016 7700 16017 7701 16017 7535 16017 7641 16018 7702 16018 7647 16018 7647 16019 7702 16019 7703 16019 7551 16020 7550 16020 7704 16020 7704 16021 7550 16021 7653 16021 7655 16022 7489 16022 7654 16022 7654 16023 7489 16023 7705 16023 7707 16024 7706 16024 7709 16024 7707 16025 7709 16025 7708 16025 7708 16026 7709 16026 7509 16026 7509 16027 7710 16027 7708 16027 7491 16028 7711 16028 7600 16028 7600 16029 7711 16029 7598 16029 7598 16030 7711 16030 7614 16030 7551 16031 7704 16031 7558 16031 7558 16032 7704 16032 7644 16032 7712 16033 7656 16033 7541 16033 7541 16034 7656 16034 7538 16034 7705 16035 7599 16035 7654 16035 7654 16036 7599 16036 7713 16036 7737 16037 7649 16037 7713 16037 7713 16038 7649 16038 7654 16038 7714 16039 7652 16039 7543 16039 7650 16040 7499 16040 7652 16040 7652 16041 7499 16041 7543 16041 7532 16042 7716 16042 7717 16042 7717 16043 7716 16043 7525 16043 7717 16044 7525 16044 7524 16044 7716 16045 7537 16045 7718 16045 7718 16046 7537 16046 7536 16046 7718 16047 7536 16047 7534 16047 7540 16048 7657 16048 7539 16048 7539 16049 7657 16049 7645 16049 7719 16050 7530 16050 7523 16050 7523 16051 7530 16051 7720 16051 7721 16052 7738 16052 7542 16052 7542 16053 7738 16053 7723 16053 7723 16054 7722 16054 7542 16054 7528 16055 7724 16055 7526 16055 7740 16056 7498 16056 7724 16056 7724 16057 7498 16057 7526 16057 7727 16058 7725 16058 7726 16058 7726 16059 7725 16059 7727 16059 7728 16060 7746 16060 7729 16060 7688 16061 7663 16061 7666 16061 7732 16062 7679 16062 7618 16062 7735 16063 7613 16063 7692 16063 7692 16064 7506 16064 7680 16064 7680 16065 7506 16065 7611 16065 7510 16066 7517 16066 7736 16066 7510 16067 7736 16067 7513 16067 7698 16068 7508 16068 7583 16068 7583 16069 7508 16069 7514 16069 7583 16070 7514 16070 7512 16070 7737 16071 7696 16071 7649 16071 7649 16072 7696 16072 7695 16072 7649 16073 7695 16073 7650 16073 7650 16074 7695 16074 7738 16074 7650 16075 7738 16075 7499 16075 7499 16076 7738 16076 7721 16076 7739 16077 7616 16077 7740 16077 7741 16078 7498 16078 7740 16078 7741 16079 7740 16079 7616 16079 7740 16080 7738 16080 7739 16080 7739 16081 7738 16081 7695 16081 7739 16082 7695 16082 7577 16082 7739 16083 7577 16083 7742 16083 7578 16084 7743 16084 7519 16084 7578 16085 7519 16085 7744 16085 7578 16086 7744 16086 7579 16086 7520 16087 7521 16087 7744 16087 7502 16088 7522 16088 7745 16088 7500 16089 7579 16089 7504 16089 7504 16090 7579 16090 7744 16090 7504 16091 7744 16091 7745 16091 7745 16092 7744 16092 7521 16092 7745 16093 7521 16093 7502 16093 7746 16094 7748 16094 7747 16094 7746 16095 7570 16095 7748 16095 7749 16096 7725 16096 7494 16096 7494 16097 7725 16097 7569 16097 7725 16098 7749 16098 7589 16098 7761 16099 7850 16099 7858 16099 7858 16100 7846 16100 7810 16100 7858 16101 7810 16101 7761 16101 7846 16102 7847 16102 7810 16102 7811 16103 7844 16103 7786 16103 7815 16104 7814 16104 7785 16104 7815 16105 7785 16105 7816 16105 7816 16106 7785 16106 7864 16106 7843 16107 7840 16107 7864 16107 7844 16108 7788 16108 7786 16108 7814 16109 7787 16109 7785 16109 7752 16110 7813 16110 7751 16110 7756 16111 7750 16111 7768 16111 7756 16112 7755 16112 7752 16112 7750 16113 7756 16113 7751 16113 7751 16114 7756 16114 7752 16114 7752 16115 7839 16115 7813 16115 7754 16116 7750 16116 7753 16116 7837 16117 7754 16117 7757 16117 7867 16118 7875 16118 7803 16118 7865 16119 7845 16119 7805 16119 7850 16120 7857 16120 7874 16120 7852 16121 7854 16121 7853 16121 7808 16122 7855 16122 7852 16122 7758 16123 7851 16123 7808 16123 7761 16124 7812 16124 7760 16124 7761 16125 7811 16125 7812 16125 7761 16126 7810 16126 7811 16126 7846 16127 7858 16127 7849 16127 7846 16128 7856 16128 7760 16128 7771 16129 7800 16129 7774 16129 7800 16130 7807 16130 7762 16130 7796 16131 7773 16131 7774 16131 7762 16132 7770 16132 7763 16132 7817 16133 7832 16133 7833 16133 7764 16134 7763 16134 7770 16134 7764 16135 7770 16135 7817 16135 7817 16136 7833 16136 7834 16136 7827 16137 7823 16137 7806 16137 7775 16138 7827 16138 7771 16138 7771 16139 7827 16139 7806 16139 7828 16140 7779 16140 7765 16140 7823 16141 7765 16141 7806 16141 7831 16142 7828 16142 7765 16142 7824 16143 7831 16143 7765 16143 7824 16144 7765 16144 7767 16144 7767 16145 7765 16145 7823 16145 7766 16146 7821 16146 7754 16146 7754 16147 7821 16147 7830 16147 7754 16148 7830 16148 7750 16148 7750 16149 7830 16149 7820 16149 7768 16150 7750 16150 7820 16150 7768 16151 7820 16151 7769 16151 7768 16152 7769 16152 7756 16152 7756 16153 7769 16153 7755 16153 7755 16154 7769 16154 7831 16154 7755 16155 7831 16155 7826 16155 7778 16156 7770 16156 7809 16156 7809 16157 7770 16157 7807 16157 7807 16158 7770 16158 7762 16158 7807 16159 7771 16159 7806 16159 7807 16160 7800 16160 7771 16160 7765 16161 7779 16161 7806 16161 7772 16162 7773 16162 7783 16162 7772 16163 7783 16163 7830 16163 7773 16164 7772 16164 7827 16164 7773 16165 7827 16165 7774 16165 7774 16166 7827 16166 7775 16166 7774 16167 7775 16167 7771 16167 7754 16168 7864 16168 7840 16168 7836 16169 7776 16169 7812 16169 7812 16170 7776 16170 7848 16170 7848 16171 7776 16171 7838 16171 7842 16172 7847 16172 7838 16172 7838 16173 7847 16173 7848 16173 7792 16174 7847 16174 7841 16174 7841 16175 7847 16175 7842 16175 7777 16176 7847 16176 7792 16176 7847 16177 7777 16177 7810 16177 7810 16178 7777 16178 7844 16178 7843 16179 7842 16179 7837 16179 7843 16180 7837 16180 7840 16180 7840 16181 7837 16181 7757 16181 7840 16182 7757 16182 7754 16182 7809 16183 7759 16183 7778 16183 7759 16184 7832 16184 7778 16184 7759 16185 7779 16185 7832 16185 7758 16186 7779 16186 7759 16186 7861 16187 7802 16187 7834 16187 7802 16188 7861 16188 7865 16188 7833 16189 7861 16189 7834 16189 7861 16190 7833 16190 7780 16190 7781 16191 7780 16191 7819 16191 7781 16192 7819 16192 7835 16192 7781 16193 7835 16193 7860 16193 7860 16194 7835 16194 7783 16194 7860 16195 7783 16195 7782 16195 7782 16196 7783 16196 7773 16196 7866 16197 7865 16197 7859 16197 7866 16198 7859 16198 7796 16198 7796 16199 7859 16199 7773 16199 7773 16200 7859 16200 7782 16200 7843 16201 7863 16201 7794 16201 7794 16202 7863 16202 7867 16202 7843 16203 7864 16203 7863 16203 7784 16204 7864 16204 7785 16204 7784 16205 7785 16205 7787 16205 7786 16206 7862 16206 7787 16206 7787 16207 7814 16207 7786 16207 7791 16208 7867 16208 7862 16208 7791 16209 7862 16209 7788 16209 7788 16210 7862 16210 7786 16210 7790 16211 7871 16211 7870 16211 7790 16212 7870 16212 7789 16212 7790 16213 7789 16213 7791 16213 7790 16214 7791 16214 7844 16214 7844 16215 7791 16215 7788 16215 7870 16216 7803 16216 7789 16216 7792 16217 7872 16217 7871 16217 7792 16218 7871 16218 7777 16218 7777 16219 7871 16219 7790 16219 7804 16220 7872 16220 7792 16220 7804 16221 7792 16221 7793 16221 7804 16222 7793 16222 7795 16222 7804 16223 7795 16223 7794 16223 7794 16224 7795 16224 7843 16224 7866 16225 7796 16225 7774 16225 7866 16226 7774 16226 7797 16226 7800 16227 7799 16227 7869 16227 7800 16228 7869 16228 7797 16228 7800 16229 7797 16229 7774 16229 7869 16230 7798 16230 7797 16230 7763 16231 7799 16231 7762 16231 7762 16232 7799 16232 7800 16232 7763 16233 7801 16233 7799 16233 7801 16234 7763 16234 7764 16234 7801 16235 7764 16235 7802 16235 7764 16236 7817 16236 7802 16236 7802 16237 7817 16237 7834 16237 7862 16238 7867 16238 7863 16238 7875 16239 7873 16239 7803 16239 7875 16240 7804 16240 7873 16240 7859 16241 7865 16241 7861 16241 7798 16242 7845 16242 7805 16242 7798 16243 7805 16243 7868 16243 7805 16244 7801 16244 7868 16244 7798 16245 7869 16245 7845 16245 7779 16246 7758 16246 7806 16246 7808 16247 7806 16247 7758 16247 7808 16248 7807 16248 7806 16248 7808 16249 7759 16249 7809 16249 7808 16250 7809 16250 7807 16250 7839 16251 7812 16251 7811 16251 7810 16252 7844 16252 7811 16252 7836 16253 7812 16253 7839 16253 7864 16254 7754 16254 7753 16254 7839 16255 7811 16255 7813 16255 7813 16256 7811 16256 7786 16256 7813 16257 7786 16257 7814 16257 7813 16258 7814 16258 7751 16258 7751 16259 7814 16259 7815 16259 7751 16260 7815 16260 7750 16260 7750 16261 7815 16261 7816 16261 7750 16262 7816 16262 7753 16262 7753 16263 7816 16263 7864 16263 7828 16264 7832 16264 7779 16264 7817 16265 7770 16265 7778 16265 7778 16266 7832 16266 7817 16266 7830 16267 7783 16267 7835 16267 7832 16268 7828 16268 7833 16268 7833 16269 7828 16269 7829 16269 7833 16270 7829 16270 7780 16270 7780 16271 7829 16271 7818 16271 7780 16272 7818 16272 7819 16272 7819 16273 7818 16273 7835 16273 7835 16274 7818 16274 7820 16274 7835 16275 7820 16275 7830 16275 7803 16276 7871 16276 7875 16276 7875 16277 7871 16277 7872 16277 7766 16278 7822 16278 7827 16278 7827 16279 7822 16279 7838 16279 7827 16280 7838 16280 7823 16280 7823 16281 7838 16281 7776 16281 7767 16282 7823 16282 7776 16282 7767 16283 7776 16283 7825 16283 7767 16284 7825 16284 7824 16284 7824 16285 7825 16285 7831 16285 7831 16286 7825 16286 7826 16286 7766 16287 7827 16287 7821 16287 7821 16288 7827 16288 7830 16288 7818 16289 7829 16289 7831 16289 7769 16290 7818 16290 7831 16290 7827 16291 7772 16291 7830 16291 7769 16292 7820 16292 7818 16292 7829 16293 7828 16293 7831 16293 7776 16294 7836 16294 7752 16294 7842 16295 7838 16295 7837 16295 7826 16296 7752 16296 7755 16296 7752 16297 7826 16297 7825 16297 7776 16298 7752 16298 7825 16298 7766 16299 7754 16299 7822 16299 7822 16300 7754 16300 7837 16300 7822 16301 7837 16301 7838 16301 7752 16302 7836 16302 7839 16302 7843 16303 7841 16303 7842 16303 7793 16304 7792 16304 7841 16304 7793 16305 7841 16305 7795 16305 7795 16306 7841 16306 7843 16306 7790 16307 7844 16307 7777 16307 7845 16308 7799 16308 7805 16308 7805 16309 7799 16309 7801 16309 7856 16310 7849 16310 7857 16310 7857 16311 7849 16311 7874 16311 7856 16312 7850 16312 7760 16312 7850 16313 7761 16313 7760 16313 7847 16314 7846 16314 7848 16314 7848 16315 7846 16315 7760 16315 7848 16316 7760 16316 7812 16316 7849 16317 7858 16317 7874 16317 7858 16318 7850 16318 7874 16318 7852 16319 7855 16319 7854 16319 7854 16320 7855 16320 7851 16320 7854 16321 7851 16321 7758 16321 7758 16322 7759 16322 7854 16322 7854 16323 7759 16323 7852 16323 7808 16324 7852 16324 7759 16324 7852 16325 7853 16325 7854 16325 7851 16326 7855 16326 7808 16326 7856 16327 7846 16327 7849 16327 7856 16328 7857 16328 7850 16328 7859 16329 7861 16329 7782 16329 7781 16330 7860 16330 7861 16330 7780 16331 7781 16331 7861 16331 7782 16332 7861 16332 7860 16332 7784 16333 7787 16333 7863 16333 7864 16334 7784 16334 7863 16334 7862 16335 7863 16335 7787 16335 7866 16336 7797 16336 7802 16336 7802 16337 7797 16337 7798 16337 7801 16338 7802 16338 7868 16338 7868 16339 7802 16339 7798 16339 7804 16340 7794 16340 7873 16340 7873 16341 7794 16341 7791 16341 7803 16342 7873 16342 7789 16342 7789 16343 7873 16343 7791 16343 7866 16344 7802 16344 7865 16344 7791 16345 7794 16345 7867 16345 7799 16346 7845 16346 7869 16346 7870 16347 7871 16347 7803 16347 7872 16348 7804 16348 7875 16348 7865 16349 7805 16349 7845 16349 7867 16350 7803 16350 7875 16350 7942 16351 8060 16351 7878 16351 8059 16352 8028 16352 8040 16352 8059 16353 8040 16353 7940 16353 7940 16354 8040 16354 7918 16354 7982 16355 7897 16355 8063 16355 8025 16356 7915 16356 8030 16356 8044 16357 8188 16357 7876 16357 7882 16358 8017 16358 8051 16358 7949 16359 7986 16359 7988 16359 7992 16360 7994 16360 7883 16360 7881 16361 7991 16361 7986 16361 7881 16362 7986 16362 7949 16362 7953 16363 7948 16363 7950 16363 7992 16364 7883 16364 7986 16364 7971 16365 7959 16365 7958 16365 7971 16366 7958 16366 7976 16366 7976 16367 7958 16367 7965 16367 7976 16368 7965 16368 7886 16368 7886 16369 7965 16369 7888 16369 7888 16370 7965 16370 7957 16370 7888 16371 7957 16371 7887 16371 7888 16372 7887 16372 7975 16372 7975 16373 7887 16373 7964 16373 7975 16374 7964 16374 7963 16374 7975 16375 7963 16375 7974 16375 7959 16376 8011 16376 7958 16376 8011 16377 7947 16377 7881 16377 7938 16378 7985 16378 7932 16378 7932 16379 7985 16379 8016 16379 7932 16380 8016 16380 7934 16380 7943 16381 7880 16381 7889 16381 7943 16382 7889 16382 7941 16382 7941 16383 7889 16383 7890 16383 7890 16384 7889 16384 7987 16384 7890 16385 7987 16385 7937 16385 7937 16386 7987 16386 7891 16386 7937 16387 7891 16387 7935 16387 7935 16388 7891 16388 7990 16388 7935 16389 7990 16389 7892 16389 7892 16390 7990 16390 8053 16390 8053 16391 7990 16391 7989 16391 8053 16392 7989 16392 7985 16392 8053 16393 7985 16393 7938 16393 7879 16394 8029 16394 8000 16394 7922 16395 8022 16395 7894 16395 7884 16396 8044 16396 8043 16396 7884 16397 8043 16397 7998 16397 8027 16398 7998 16398 7977 16398 7926 16399 7999 16399 7895 16399 7926 16400 7895 16400 8042 16400 8005 16401 8006 16401 7893 16401 8037 16402 7924 16402 7896 16402 8037 16403 7896 16403 8035 16403 8027 16404 7977 16404 8045 16404 8045 16405 7977 16405 7999 16405 8045 16406 7999 16406 7894 16406 8042 16407 7895 16407 8006 16407 8042 16408 8006 16408 8041 16408 8005 16409 7893 16409 8040 16409 8040 16410 7893 16410 7924 16410 8040 16411 7924 16411 8039 16411 8035 16412 7896 16412 7929 16412 7910 16413 8051 16413 8017 16413 8017 16414 7909 16414 7910 16414 8051 16415 7909 16415 8017 16415 7909 16416 8051 16416 8068 16416 7909 16417 8068 16417 8018 16417 7944 16418 8179 16418 8023 16418 7944 16419 8023 16419 7910 16419 8050 16420 7910 16420 8023 16420 8050 16421 8023 16421 8068 16421 8068 16422 8023 16422 7917 16422 8068 16423 7917 16423 8018 16423 7913 16424 8018 16424 7917 16424 7913 16425 7917 16425 8025 16425 8025 16426 8064 16426 7913 16426 8064 16427 8025 16427 8030 16427 8064 16428 8030 16428 7897 16428 7898 16429 8063 16429 7897 16429 7898 16430 7911 16430 8063 16430 7911 16431 7898 16431 7912 16431 7912 16432 7898 16432 8047 16432 8047 16433 7899 16433 8062 16433 7901 16434 8015 16434 8019 16434 7899 16435 8019 16435 8062 16435 7900 16436 8020 16436 7899 16436 8020 16437 7901 16437 7899 16437 7899 16438 7901 16438 8019 16438 7902 16439 7876 16439 8188 16439 7902 16440 8188 16440 7931 16440 7903 16441 8052 16441 7931 16441 7903 16442 7904 16442 7877 16442 7877 16443 7904 16443 8054 16443 8058 16444 7921 16444 7905 16444 7918 16445 7906 16445 7940 16445 7920 16446 8179 16446 8065 16446 8065 16447 8179 16447 7944 16447 7940 16448 7906 16448 7907 16448 7907 16449 7906 16449 7919 16449 7907 16450 7919 16450 7920 16450 7907 16451 7920 16451 8066 16451 7905 16452 8026 16452 7908 16452 7908 16453 8026 16453 8067 16453 7908 16454 8067 16454 7933 16454 8054 16455 7904 16455 7939 16455 7939 16456 7904 16456 8022 16456 7939 16457 8022 16457 7921 16457 7939 16458 7921 16458 8058 16458 7903 16459 7931 16459 8188 16459 7897 16460 7915 16460 8030 16460 7897 16461 8030 16461 8064 16461 8064 16462 8030 16462 7915 16462 8003 16463 7929 16463 7973 16463 8003 16464 7973 16464 7930 16464 8033 16465 8002 16465 7972 16465 8033 16466 7972 16466 7915 16466 8036 16467 7914 16467 7928 16467 7879 16468 7927 16468 7978 16468 7879 16469 7978 16469 8029 16469 8029 16470 7978 16470 8021 16470 7930 16471 7973 16471 8031 16471 8031 16472 7973 16472 8002 16472 8031 16473 8002 16473 8032 16473 7915 16474 7972 16474 7914 16474 7915 16475 7914 16475 8036 16475 7928 16476 7914 16476 8048 16476 8048 16477 7914 16477 7979 16477 8048 16478 7979 16478 7927 16478 8048 16479 7927 16479 8000 16479 8021 16480 7978 16480 7998 16480 8021 16481 7998 16481 8043 16481 7916 16482 8047 16482 7898 16482 7898 16483 7897 16483 8030 16483 8068 16484 7917 16484 8023 16484 8068 16485 8023 16485 8031 16485 7920 16486 8060 16486 8179 16486 8067 16487 8028 16487 7918 16487 7906 16488 7918 16488 7919 16488 7921 16489 8042 16489 8057 16489 8057 16490 7905 16490 7921 16490 7903 16491 8055 16491 7904 16491 7904 16492 8055 16492 8045 16492 8021 16493 7876 16493 7900 16493 8044 16494 7884 16494 8027 16494 8022 16495 7922 16495 7926 16495 7894 16496 7999 16496 7922 16496 8024 16497 7923 16497 7928 16497 7923 16498 8024 16498 8036 16498 8032 16499 8002 16499 8001 16499 8001 16500 8033 16500 8032 16500 8034 16501 8003 16501 7930 16501 8003 16502 8034 16502 7929 16502 7929 16503 8034 16503 8035 16503 7924 16504 8004 16504 8038 16504 7924 16505 8038 16505 8039 16505 8026 16506 7925 16506 8005 16506 8041 16507 8006 16507 7925 16507 7925 16508 8026 16508 8041 16508 7946 16509 7945 16509 7910 16509 7909 16510 7946 16510 7910 16510 7909 16511 8018 16511 8012 16511 7902 16512 7931 16512 8061 16512 7905 16513 7908 16513 8056 16513 8052 16514 8061 16514 7931 16514 7932 16515 7934 16515 8020 16515 8061 16516 8052 16516 7938 16516 8061 16517 7938 16517 7932 16517 8056 16518 7935 16518 7936 16518 7936 16519 7935 16519 7892 16519 8056 16520 7937 16520 7935 16520 8054 16521 7936 16521 7892 16521 8054 16522 7892 16522 8053 16522 8052 16523 8053 16523 7938 16523 7936 16524 8054 16524 7939 16524 7936 16525 7939 16525 8058 16525 8056 16526 7908 16526 7933 16526 8056 16527 7933 16527 8059 16527 8066 16528 7940 16528 7907 16528 8056 16529 8059 16529 7937 16529 7937 16530 8059 16530 7890 16530 7890 16531 8059 16531 7940 16531 7890 16532 7940 16532 7941 16532 8066 16533 7942 16533 7940 16533 7940 16534 7942 16534 7941 16534 7941 16535 7942 16535 7943 16535 7943 16536 7942 16536 7878 16536 7945 16537 7943 16537 7944 16537 7944 16538 7943 16538 7878 16538 7944 16539 7878 16539 8065 16539 7910 16540 7945 16540 7944 16540 7945 16541 7946 16541 7943 16541 7943 16542 7946 16542 7880 16542 7947 16543 7992 16543 7881 16543 7881 16544 7992 16544 7991 16544 7949 16545 7948 16545 7953 16545 7953 16546 7950 16546 7952 16546 7952 16547 7950 16547 7951 16547 7952 16548 7951 16548 7954 16548 7882 16549 7953 16549 7952 16549 7952 16550 7954 16550 8010 16550 8010 16551 7954 16551 7955 16551 7955 16552 7956 16552 8010 16552 7956 16553 7947 16553 8011 16553 8017 16554 7882 16554 7952 16554 8017 16555 7952 16555 8010 16555 7970 16556 8010 16556 7956 16556 7956 16557 8011 16557 7959 16557 7882 16558 7964 16558 7953 16558 7953 16559 7964 16559 7957 16559 7953 16560 7957 16560 7949 16560 7949 16561 7957 16561 7881 16561 7881 16562 7957 16562 7965 16562 7881 16563 7965 16563 7958 16563 7881 16564 7958 16564 8011 16564 7966 16565 8017 16565 8010 16565 7966 16566 8010 16566 7970 16566 7970 16567 7967 16567 7966 16567 7956 16568 7959 16568 7960 16568 7956 16569 7960 16569 7961 16569 7956 16570 7961 16570 7962 16570 7956 16571 7962 16571 7970 16571 7882 16572 7963 16572 7964 16572 7964 16573 7887 16573 7957 16573 8017 16574 8007 16574 7974 16574 7974 16575 7963 16575 7882 16575 7974 16576 7882 16576 8017 16576 8007 16577 8017 16577 7966 16577 7967 16578 7968 16578 7966 16578 7966 16579 7968 16579 8007 16579 7970 16580 7969 16580 7967 16580 7967 16581 7969 16581 7968 16581 7962 16582 8008 16582 7970 16582 7970 16583 8008 16583 7969 16583 7961 16584 8008 16584 7962 16584 7959 16585 7971 16585 7960 16585 7961 16586 7960 16586 8008 16586 7969 16587 7914 16587 7968 16587 7968 16588 7914 16588 7972 16588 7968 16589 7972 16589 8007 16589 8007 16590 7972 16590 8002 16590 8007 16591 8002 16591 7974 16591 7974 16592 8002 16592 7973 16592 7974 16593 7973 16593 7929 16593 7974 16594 7929 16594 7975 16594 7975 16595 7929 16595 7896 16595 7975 16596 7896 16596 7924 16596 7975 16597 7924 16597 7888 16597 7888 16598 7924 16598 7893 16598 7888 16599 7893 16599 8006 16599 7888 16600 8006 16600 7886 16600 7886 16601 8006 16601 7895 16601 7886 16602 7895 16602 7976 16602 7976 16603 7895 16603 7999 16603 7976 16604 7999 16604 7971 16604 7971 16605 7999 16605 7977 16605 7971 16606 7977 16606 7998 16606 7971 16607 7998 16607 7960 16607 7960 16608 7998 16608 7978 16608 7960 16609 7978 16609 8008 16609 8008 16610 7978 16610 7927 16610 8008 16611 7927 16611 7979 16611 8008 16612 7979 16612 7969 16612 7969 16613 7979 16613 7914 16613 8049 16614 7911 16614 7912 16614 7911 16615 8049 16615 8063 16615 7983 16616 8046 16616 7982 16616 7983 16617 7982 16617 7981 16617 7980 16618 7981 16618 8049 16618 8049 16619 7981 16619 7982 16619 8049 16620 7982 16620 8063 16620 7996 16621 7980 16621 8019 16621 8019 16622 7980 16622 8062 16622 8064 16623 8046 16623 7913 16623 7997 16624 7913 16624 7983 16624 7983 16625 7913 16625 8046 16625 7996 16626 8015 16626 7980 16626 7980 16627 8015 16627 8014 16627 7980 16628 8014 16628 7981 16628 7981 16629 8014 16629 8013 16629 7981 16630 8013 16630 7983 16630 7983 16631 8013 16631 8012 16631 7983 16632 8012 16632 7997 16632 8012 16633 7984 16633 7885 16633 7885 16634 7946 16634 8012 16634 8012 16635 7946 16635 7909 16635 8016 16636 7994 16636 8015 16636 7994 16637 8009 16637 8015 16637 8015 16638 8009 16638 8014 16638 8014 16639 8009 16639 8013 16639 8013 16640 8009 16640 7984 16640 8013 16641 7984 16641 8012 16641 7986 16642 7987 16642 7988 16642 7988 16643 7987 16643 7889 16643 7988 16644 7889 16644 7880 16644 7988 16645 7880 16645 7885 16645 7885 16646 7880 16646 7946 16646 7994 16647 8016 16647 7985 16647 7994 16648 7985 16648 7883 16648 7883 16649 7985 16649 7989 16649 7883 16650 7989 16650 7990 16650 7883 16651 7990 16651 7986 16651 7986 16652 7990 16652 7891 16652 7986 16653 7891 16653 7987 16653 7984 16654 8009 16654 7995 16654 7984 16655 7995 16655 7954 16655 7984 16656 7954 16656 7951 16656 7885 16657 7951 16657 7950 16657 7885 16658 7950 16658 7988 16658 7988 16659 7950 16659 7948 16659 7988 16660 7948 16660 7949 16660 7986 16661 7991 16661 7992 16661 7994 16662 7992 16662 7947 16662 7994 16663 7947 16663 7993 16663 7994 16664 7993 16664 8009 16664 7954 16665 7995 16665 7955 16665 7955 16666 7995 16666 8009 16666 7955 16667 8009 16667 7993 16667 7955 16668 7993 16668 7956 16668 7956 16669 7993 16669 7947 16669 8016 16670 8020 16670 7934 16670 8015 16671 7996 16671 8019 16671 8018 16672 7913 16672 8012 16672 8012 16673 7913 16673 7997 16673 7884 16674 7998 16674 8027 16674 7922 16675 7999 16675 7926 16675 7879 16676 8000 16676 7927 16676 7928 16677 7923 16677 8036 16677 8033 16678 8001 16678 8002 16678 7924 16679 8037 16679 8004 16679 7925 16680 8006 16680 8005 16680 7984 16681 7951 16681 7885 16681 8016 16682 8015 16682 7901 16682 8016 16683 7901 16683 8020 16683 8017 16684 7882 16684 8051 16684 8055 16685 7903 16685 8044 16685 8044 16686 7903 16686 8188 16686 8042 16687 7921 16687 8022 16687 8057 16688 8026 16688 7905 16688 8038 16689 7920 16689 7919 16689 8038 16690 7919 16690 7918 16690 8030 16691 7915 16691 7898 16691 8024 16692 7898 16692 8036 16692 7926 16693 8042 16693 8022 16693 7917 16694 8032 16694 8033 16694 7917 16695 8033 16695 8025 16695 8025 16696 8033 16696 7915 16696 8041 16697 8057 16697 8042 16697 8179 16698 8034 16698 8023 16698 8057 16699 8041 16699 8026 16699 8055 16700 8044 16700 8027 16700 7915 16701 8036 16701 7898 16701 7876 16702 8021 16702 8043 16702 8179 16703 8035 16703 8034 16703 8060 16704 8035 16704 8179 16704 8044 16705 7876 16705 8043 16705 8055 16706 8027 16706 8045 16706 8038 16707 7918 16707 8040 16707 8040 16708 8039 16708 8038 16708 8048 16709 8000 16709 8047 16709 8045 16710 7894 16710 7904 16710 7920 16711 8004 16711 8060 16711 8060 16712 8004 16712 8037 16712 8032 16713 8068 16713 8031 16713 8023 16714 8034 16714 8031 16714 8031 16715 8034 16715 7930 16715 8000 16716 7899 16716 8047 16716 8022 16717 7904 16717 7894 16717 7917 16718 8068 16718 8032 16718 8029 16719 8021 16719 7900 16719 8040 16720 8028 16720 8005 16720 8035 16721 8060 16721 8037 16721 8038 16722 8004 16722 7920 16722 7898 16723 8024 16723 7916 16723 7916 16724 8024 16724 7928 16724 8067 16725 8026 16725 8005 16725 8067 16726 8005 16726 8028 16726 7928 16727 8048 16727 7916 16727 7899 16728 8000 16728 8029 16728 7899 16729 8029 16729 7900 16729 8046 16730 8064 16730 7915 16730 8046 16731 7915 16731 7982 16731 7982 16732 7915 16732 7897 16732 7916 16733 7912 16733 8047 16733 8049 16734 7912 16734 7916 16734 8049 16735 7916 16735 7980 16735 7980 16736 7916 16736 8048 16736 7980 16737 8048 16737 8062 16737 8062 16738 8048 16738 8047 16738 8068 16739 8051 16739 8031 16739 8031 16740 7910 16740 8050 16740 8031 16741 8051 16741 7910 16741 8052 16742 7903 16742 8055 16742 8052 16743 8055 16743 8053 16743 8053 16744 8055 16744 8045 16744 8053 16745 8045 16745 8054 16745 8054 16746 8045 16746 7877 16746 7903 16747 7877 16747 8055 16747 8055 16748 7877 16748 8045 16748 7936 16749 8058 16749 8042 16749 7936 16750 8042 16750 8056 16750 8056 16751 8042 16751 8057 16751 8056 16752 8057 16752 7905 16752 8042 16753 8058 16753 8057 16753 8057 16754 8058 16754 7905 16754 8059 16755 8067 16755 8028 16755 8028 16756 8067 16756 7918 16756 7942 16757 7920 16757 8060 16757 8060 16758 7920 16758 8065 16758 8060 16759 8065 16759 7878 16759 7932 16760 7900 16760 8021 16760 7932 16761 8021 16761 8061 16761 8061 16762 8021 16762 7902 16762 7902 16763 8021 16763 7876 16763 7876 16764 8021 16764 7900 16764 7920 16765 7942 16765 8066 16765 8067 16766 8059 16766 7933 16766 7900 16767 7932 16767 8020 16767 7900 16768 8021 16768 7876 16768 7900 16769 7876 16769 8021 16769 8031 16770 8050 16770 8068 16770 8437 16771 8171 16771 8181 16771 8188 16772 8069 16772 8236 16772 8081 16773 8082 16773 8069 16773 8069 16774 8082 16774 8083 16774 8083 16775 8080 16775 8079 16775 8084 16776 8085 16776 8245 16776 8390 16777 8299 16777 8073 16777 8282 16778 8291 16778 8290 16778 8282 16779 8290 16779 8291 16779 8336 16780 8286 16780 8302 16780 8133 16781 8341 16781 8292 16781 8133 16782 8292 16782 8341 16782 8251 16783 8274 16783 8090 16783 8102 16784 8098 16784 8165 16784 8084 16785 8272 16785 8243 16785 8243 16786 8272 16786 8084 16786 8234 16787 8187 16787 8239 16787 8078 16788 8094 16788 8095 16788 8210 16789 8099 16789 8215 16789 8259 16790 8098 16790 8099 16790 8257 16791 8163 16791 8164 16791 8257 16792 8164 16792 8169 16792 8255 16793 8159 16793 8434 16793 8254 16794 8161 16794 8253 16794 8179 16795 8430 16795 8185 16795 8079 16796 8080 16796 8183 16796 8183 16797 8080 16797 8182 16797 8079 16798 8429 16798 8084 16798 8272 16799 8429 16799 8183 16799 8183 16800 8429 16800 8079 16800 8171 16801 8081 16801 8069 16801 8171 16802 8069 16802 8188 16802 8081 16803 8171 16803 8082 16803 8082 16804 8171 16804 8182 16804 8083 16805 8082 16805 8182 16805 8083 16806 8182 16806 8080 16806 8084 16807 8429 16807 8272 16807 8272 16808 8085 16808 8084 16808 8085 16809 8272 16809 8184 16809 8085 16810 8184 16810 8245 16810 8185 16811 8245 16811 8184 16811 8245 16812 8185 16812 8248 16812 8248 16813 8185 16813 8430 16813 8087 16814 8086 16814 8228 16814 8226 16815 8088 16815 8219 16815 8092 16816 8088 16816 8226 16816 8092 16817 8226 16817 8086 16817 8092 16818 8086 16818 8089 16818 8089 16819 8086 16819 8087 16819 8087 16820 8228 16820 8215 16820 8092 16821 8211 16821 8088 16821 8089 16822 8090 16822 8092 16822 8215 16823 8210 16823 8087 16823 8087 16824 8210 16824 8091 16824 8090 16825 8089 16825 8091 16825 8091 16826 8089 16826 8087 16826 8092 16827 8090 16827 8274 16827 8092 16828 8274 16828 8211 16828 8209 16829 8196 16829 8197 16829 8197 16830 8198 16830 8093 16830 8200 16831 8202 16831 8078 16831 8078 16832 8202 16832 8201 16832 8078 16833 8201 16833 8203 16833 8078 16834 8203 16834 8094 16834 8094 16835 8097 16835 8095 16835 8095 16836 8097 16836 8189 16836 8209 16837 8172 16837 8196 16837 8196 16838 8172 16838 8180 16838 8196 16839 8180 16839 8173 16839 8196 16840 8173 16840 8197 16840 8197 16841 8173 16841 8096 16841 8197 16842 8096 16842 8198 16842 8198 16843 8096 16843 8093 16843 8093 16844 8096 16844 8175 16844 8093 16845 8175 16845 8199 16845 8199 16846 8175 16846 8174 16846 8199 16847 8174 16847 8200 16847 8200 16848 8174 16848 8186 16848 8200 16849 8186 16849 8202 16849 8202 16850 8186 16850 8201 16850 8201 16851 8186 16851 8076 16851 8201 16852 8076 16852 8176 16852 8201 16853 8176 16853 8203 16853 8203 16854 8176 16854 8094 16854 8094 16855 8176 16855 8178 16855 8094 16856 8178 16856 8097 16856 8097 16857 8178 16857 8189 16857 8189 16858 8178 16858 8077 16858 8260 16859 8102 16859 8165 16859 8260 16860 8159 16860 8100 16860 8260 16861 8100 16861 8102 16861 8102 16862 8103 16862 8098 16862 8098 16863 8103 16863 8099 16863 8099 16864 8103 16864 8101 16864 8156 16865 8101 16865 8103 16865 8100 16866 8155 16866 8148 16866 8100 16867 8148 16867 8102 16867 8102 16868 8148 16868 8152 16868 8102 16869 8152 16869 8103 16869 8151 16870 8103 16870 8152 16870 8153 16871 8156 16871 8151 16871 8151 16872 8156 16872 8103 16872 8149 16873 8147 16873 8074 16873 8105 16874 8104 16874 8074 16874 8074 16875 8147 16875 8105 16875 8105 16876 8146 16876 8104 16876 8262 16877 8145 16877 8227 16877 8147 16878 8225 16878 8105 16878 8289 16879 8144 16879 8385 16879 8289 16880 8385 16880 8106 16880 8106 16881 8385 16881 8407 16881 8106 16882 8407 16882 8073 16882 8073 16883 8407 16883 8390 16883 8299 16884 8390 16884 8388 16884 8299 16885 8388 16885 8107 16885 8107 16886 8388 16886 8393 16886 8107 16887 8393 16887 8072 16887 8072 16888 8393 16888 8394 16888 8072 16889 8394 16889 8108 16889 8455 16890 8241 16890 8237 16890 8455 16891 8237 16891 8444 16891 8444 16892 8237 16892 8452 16892 8237 16893 8242 16893 8452 16893 8452 16894 8242 16894 8453 16894 8453 16895 8242 16895 8109 16895 8109 16896 8243 16896 8453 16896 8453 16897 8243 16897 8450 16897 8450 16898 8243 16898 8110 16898 8450 16899 8110 16899 8439 16899 8439 16900 8110 16900 8244 16900 8439 16901 8244 16901 8246 16901 8439 16902 8246 16902 8438 16902 8382 16903 8345 16903 8348 16903 8382 16904 8348 16904 8377 16904 8377 16905 8348 16905 8111 16905 8377 16906 8111 16906 8384 16906 8384 16907 8111 16907 8112 16907 8112 16908 8111 16908 8450 16908 8112 16909 8450 16909 8353 16909 8112 16910 8353 16910 8381 16910 8381 16911 8353 16911 8354 16911 8128 16912 8358 16912 8367 16912 8128 16913 8367 16913 8406 16913 8406 16914 8367 16914 8366 16914 8406 16915 8366 16915 8403 16915 8403 16916 8366 16916 8113 16916 8113 16917 8366 16917 8418 16917 8113 16918 8418 16918 8370 16918 8113 16919 8370 16919 8402 16919 8402 16920 8370 16920 8114 16920 8386 16921 8397 16921 8409 16921 8386 16922 8409 16922 8423 16922 8359 16923 8122 16923 8374 16923 8359 16924 8374 16924 8414 16924 8433 16925 8298 16925 8287 16925 8434 16926 8287 16926 8288 16926 8435 16927 8301 16927 8436 16927 8312 16928 8436 16928 8286 16928 8355 16929 8120 16929 8441 16929 8355 16930 8441 16930 8352 16930 8349 16931 8119 16931 8115 16931 8349 16932 8115 16932 8116 16932 8116 16933 8115 16933 8449 16933 8346 16934 8117 16934 8347 16934 8347 16935 8117 16935 8454 16935 8347 16936 8454 16936 8344 16936 8344 16937 8454 16937 8443 16937 8343 16938 8447 16938 8346 16938 8346 16939 8447 16939 8117 16939 8118 16940 8451 16940 8355 16940 8344 16941 8443 16941 8442 16941 8348 16942 8442 16942 8452 16942 8348 16943 8452 16943 8349 16943 8349 16944 8452 16944 8119 16944 8355 16945 8451 16945 8120 16945 8352 16946 8441 16946 8121 16946 8352 16947 8121 16947 8351 16947 8350 16948 8351 16948 8446 16948 8350 16949 8446 16949 8343 16949 8343 16950 8446 16950 8447 16950 8116 16951 8449 16951 8450 16951 8450 16952 8451 16952 8118 16952 8312 16953 8286 16953 8301 16953 8312 16954 8301 16954 8435 16954 8434 16955 8288 16955 8298 16955 8368 16956 8379 16956 8365 16956 8365 16957 8379 16957 8376 16957 8365 16958 8376 16958 8364 16958 8361 16959 8419 16959 8362 16959 8362 16960 8419 16960 8383 16960 8362 16961 8383 16961 8356 16961 8356 16962 8383 16962 8380 16962 8357 16963 8417 16963 8361 16963 8361 16964 8417 16964 8419 16964 8369 16965 8371 16965 8416 16965 8413 16966 8420 16966 8381 16966 8071 16967 8404 16967 8391 16967 8391 16968 8404 16968 8123 16968 8391 16969 8123 16969 8421 16969 8387 16970 8399 16970 8124 16970 8124 16971 8399 16971 8405 16971 8124 16972 8405 16972 8070 16972 8070 16973 8405 16973 8400 16973 8412 16974 8401 16974 8387 16974 8387 16975 8401 16975 8399 16975 8423 16976 8411 16976 8422 16976 8408 16977 8125 16977 8402 16977 8402 16978 8114 16978 8127 16978 8127 16979 8114 16979 8126 16979 8127 16980 8126 16980 8369 16980 8127 16981 8369 16981 8410 16981 8410 16982 8369 16982 8357 16982 8410 16983 8357 16983 8396 16983 8396 16984 8357 16984 8360 16984 8396 16985 8360 16985 8395 16985 8395 16986 8360 16986 8363 16986 8395 16987 8363 16987 8128 16987 8128 16988 8363 16988 8358 16988 8381 16989 8354 16989 8373 16989 8373 16990 8354 16990 8129 16990 8373 16991 8129 16991 8350 16991 8373 16992 8350 16992 8415 16992 8415 16993 8350 16993 8372 16993 8372 16994 8350 16994 8130 16994 8372 16995 8130 16995 8378 16995 8378 16996 8130 16996 8131 16996 8378 16997 8131 16997 8382 16997 8382 16998 8131 16998 8345 16998 8438 16999 8246 16999 8238 16999 8438 17000 8238 17000 8440 17000 8440 17001 8238 17001 8132 17001 8440 17002 8132 17002 8121 17002 8121 17003 8132 17003 8247 17003 8121 17004 8247 17004 8446 17004 8446 17005 8247 17005 8239 17005 8446 17006 8239 17006 8448 17006 8448 17007 8239 17007 8445 17007 8445 17008 8239 17008 8240 17008 8445 17009 8240 17009 8455 17009 8455 17010 8240 17010 8241 17010 8277 17011 8303 17011 8336 17011 8284 17012 8133 17012 8308 17012 8308 17013 8133 17013 8315 17013 8315 17014 8133 17014 8309 17014 8309 17015 8133 17015 8281 17015 8309 17016 8281 17016 8282 17016 8282 17017 8283 17017 8309 17017 8283 17018 8330 17018 8309 17018 8309 17019 8330 17019 8306 17019 8342 17020 8307 17020 8280 17020 8280 17021 8307 17021 8306 17021 8280 17022 8306 17022 8330 17022 8138 17023 8139 17023 8137 17023 8307 17024 8332 17024 8141 17024 8134 17025 8135 17025 8136 17025 8135 17026 8134 17026 8321 17026 8307 17027 8141 17027 8319 17027 8336 17028 8135 17028 8321 17028 8275 17029 8140 17029 8141 17029 8141 17030 8278 17030 8275 17030 8342 17031 8279 17031 8307 17031 8307 17032 8279 17032 8332 17032 8280 17033 8279 17033 8342 17033 8136 17034 8284 17034 8308 17034 8284 17035 8136 17035 8135 17035 8338 17036 8277 17036 8336 17036 8338 17037 8336 17037 8137 17037 8137 17038 8336 17038 8321 17038 8321 17039 8134 17039 8136 17039 8321 17040 8136 17040 8308 17040 8139 17041 8138 17041 8277 17041 8338 17042 8137 17042 8139 17042 8338 17043 8139 17043 8277 17043 8277 17044 8140 17044 8275 17044 8138 17045 8140 17045 8277 17045 8138 17046 8319 17046 8140 17046 8140 17047 8319 17047 8141 17047 8278 17048 8141 17048 8279 17048 8279 17049 8141 17049 8332 17049 8108 17050 8394 17050 8142 17050 8108 17051 8142 17051 8341 17051 8389 17052 8412 17052 8340 17052 8340 17053 8412 17053 8143 17053 8143 17054 8412 17054 8392 17054 8392 17055 8144 17055 8289 17055 8146 17056 8105 17056 8145 17056 8262 17057 8227 17057 8225 17057 8147 17058 8262 17058 8225 17058 8104 17059 8146 17059 8145 17059 8149 17060 8145 17060 8262 17060 8149 17061 8262 17061 8147 17061 8104 17062 8145 17062 8149 17062 8148 17063 8155 17063 8074 17063 8151 17064 8074 17064 8153 17064 8150 17065 8104 17065 8149 17065 8153 17066 8074 17066 8150 17066 8074 17067 8104 17067 8150 17067 8152 17068 8074 17068 8151 17068 8152 17069 8148 17069 8074 17069 8149 17070 8074 17070 8155 17070 8149 17071 8155 17071 8150 17071 8155 17072 8154 17072 8150 17072 8153 17073 8157 17073 8156 17073 8150 17074 8157 17074 8153 17074 8154 17075 8158 17075 8150 17075 8150 17076 8158 17076 8157 17076 8158 17077 8154 17077 8155 17077 8158 17078 8155 17078 8100 17078 8254 17079 8101 17079 8156 17079 8254 17080 8156 17080 8157 17080 8254 17081 8157 17081 8273 17081 8273 17082 8157 17082 8168 17082 8157 17083 8158 17083 8168 17083 8100 17084 8159 17084 8158 17084 8162 17085 8168 17085 8158 17085 8162 17086 8158 17086 8159 17086 8162 17087 8159 17087 8256 17087 8160 17088 8250 17088 8162 17088 8162 17089 8250 17089 8168 17089 8250 17090 8160 17090 8311 17090 8250 17091 8311 17091 8252 17091 8254 17092 8273 17092 8161 17092 8161 17093 8273 17093 8252 17093 8161 17094 8252 17094 8311 17094 8311 17095 8435 17095 8161 17095 8101 17096 8254 17096 8316 17096 8316 17097 8254 17097 8253 17097 8434 17098 8160 17098 8162 17098 8434 17099 8162 17099 8256 17099 8434 17100 8159 17100 8163 17100 8163 17101 8159 17101 8164 17101 8159 17102 8260 17102 8164 17102 8260 17103 8165 17103 8169 17103 8098 17104 8314 17104 8258 17104 8098 17105 8258 17105 8165 17105 8314 17106 8318 17106 8258 17106 8318 17107 8170 17107 8166 17107 8316 17108 8167 17108 8101 17108 8098 17109 8167 17109 8314 17109 8434 17110 8163 17110 8433 17110 8166 17111 8170 17111 8169 17111 8161 17112 8316 17112 8253 17112 8273 17113 8168 17113 8252 17113 8169 17114 8165 17114 8166 17114 8169 17115 8170 17115 8257 17115 8257 17116 8170 17116 8163 17116 8265 17117 8272 17117 8183 17117 8265 17118 8183 17118 8266 17118 8265 17119 8264 17119 8272 17119 8272 17120 8264 17120 8263 17120 8272 17121 8263 17121 8184 17121 8184 17122 8263 17122 8191 17122 8182 17123 8267 17123 8266 17123 8267 17124 8182 17124 8268 17124 8268 17125 8182 17125 8171 17125 8268 17126 8171 17126 8269 17126 8269 17127 8171 17127 8181 17127 8269 17128 8181 17128 8192 17128 8192 17129 8181 17129 8180 17129 8192 17130 8180 17130 8172 17130 8235 17131 8173 17131 8180 17131 8174 17132 8175 17132 8187 17132 8187 17133 8175 17133 8096 17133 8187 17134 8096 17134 8235 17134 8235 17135 8096 17135 8173 17135 8076 17136 8186 17136 8232 17136 8076 17137 8232 17137 8176 17137 8176 17138 8232 17138 8233 17138 8176 17139 8233 17139 8178 17139 8190 17140 8189 17140 8077 17140 8190 17141 8077 17141 8177 17141 8177 17142 8077 17142 8178 17142 8177 17143 8178 17143 8233 17143 8190 17144 8177 17144 8179 17144 8188 17145 8180 17145 8181 17145 8181 17146 8171 17146 8188 17146 8183 17147 8182 17147 8266 17147 8190 17148 8185 17148 8184 17148 8190 17149 8184 17149 8191 17149 8179 17150 8185 17150 8190 17150 8229 17151 8270 17151 8232 17151 8229 17152 8232 17152 8186 17152 8186 17153 8174 17153 8229 17153 8229 17154 8174 17154 8187 17154 8075 17155 8235 17155 8180 17155 8075 17156 8180 17156 8230 17156 8230 17157 8180 17157 8188 17157 8205 17158 8189 17158 8190 17158 8205 17159 8190 17159 8191 17159 8205 17160 8191 17160 8206 17160 8206 17161 8191 17161 8263 17161 8206 17162 8263 17162 8204 17162 8204 17163 8263 17163 8264 17163 8204 17164 8264 17164 8193 17164 8193 17165 8264 17165 8265 17165 8193 17166 8265 17166 8249 17166 8249 17167 8265 17167 8194 17167 8194 17168 8265 17168 8266 17168 8194 17169 8266 17169 8207 17169 8207 17170 8266 17170 8267 17170 8207 17171 8267 17171 8268 17171 8207 17172 8268 17172 8195 17172 8195 17173 8268 17173 8208 17173 8208 17174 8268 17174 8269 17174 8208 17175 8269 17175 8209 17175 8209 17176 8269 17176 8192 17176 8209 17177 8192 17177 8172 17177 8095 17178 8189 17178 8205 17178 8206 17179 8204 17179 8193 17179 8249 17180 8194 17180 8207 17180 8207 17181 8195 17181 8261 17181 8261 17182 8195 17182 8208 17182 8261 17183 8208 17183 8209 17183 8193 17184 8249 17184 8090 17184 8091 17185 8206 17185 8090 17185 8206 17186 8091 17186 8095 17186 8095 17187 8091 17187 8210 17187 8274 17188 8249 17188 8207 17188 8274 17189 8207 17189 8261 17189 8090 17190 8206 17190 8193 17190 8212 17191 8200 17191 8078 17191 8212 17192 8078 17192 8210 17192 8210 17193 8078 17193 8095 17193 8261 17194 8211 17194 8274 17194 8214 17195 8197 17195 8093 17195 8200 17196 8212 17196 8213 17196 8200 17197 8213 17197 8199 17197 8214 17198 8093 17198 8213 17198 8213 17199 8093 17199 8199 17199 8197 17200 8214 17200 8211 17200 8211 17201 8261 17201 8197 17201 8215 17202 8212 17202 8210 17202 8217 17203 8213 17203 8216 17203 8088 17204 8211 17204 8218 17204 8218 17205 8211 17205 8214 17205 8213 17206 8217 17206 8214 17206 8214 17207 8217 17207 8218 17207 8216 17208 8213 17208 8212 17208 8216 17209 8212 17209 8215 17209 8215 17210 8228 17210 8223 17210 8215 17211 8223 17211 8216 17211 8216 17212 8223 17212 8221 17212 8216 17213 8221 17213 8217 17213 8217 17214 8221 17214 8220 17214 8217 17215 8220 17215 8218 17215 8218 17216 8220 17216 8219 17216 8218 17217 8219 17217 8088 17217 8224 17218 8219 17218 8220 17218 8224 17219 8220 17219 8221 17219 8221 17220 8223 17220 8222 17220 8222 17221 8223 17221 8228 17221 8227 17222 8224 17222 8225 17222 8224 17223 8227 17223 8226 17223 8224 17224 8226 17224 8219 17224 8222 17225 8105 17225 8221 17225 8225 17226 8224 17226 8105 17226 8221 17227 8105 17227 8224 17227 8222 17228 8145 17228 8105 17228 8226 17229 8227 17229 8145 17229 8226 17230 8145 17230 8086 17230 8145 17231 8222 17231 8228 17231 8228 17232 8086 17232 8145 17232 8177 17233 8231 17233 8179 17233 8427 17234 8431 17234 8234 17234 8431 17235 8229 17235 8187 17235 8427 17236 8426 17236 8229 17236 8427 17237 8229 17237 8431 17237 8229 17238 8426 17238 8270 17238 8236 17239 8230 17239 8188 17239 8075 17240 8230 17240 8236 17240 8231 17241 8430 17241 8179 17241 8424 17242 8231 17242 8177 17242 8424 17243 8177 17243 8233 17243 8424 17244 8233 17244 8232 17244 8232 17245 8270 17245 8425 17245 8425 17246 8270 17246 8426 17246 8234 17247 8431 17247 8187 17247 8187 17248 8432 17248 8234 17248 8432 17249 8187 17249 8235 17249 8432 17250 8235 17250 8428 17250 8428 17251 8235 17251 8075 17251 8428 17252 8075 17252 8271 17252 8271 17253 8075 17253 8236 17253 8428 17254 8240 17254 8234 17254 8245 17255 8110 17255 8084 17255 8238 17256 8424 17256 8132 17256 8247 17257 8427 17257 8239 17257 8239 17258 8234 17258 8240 17258 8240 17259 8271 17259 8241 17259 8069 17260 8237 17260 8236 17260 8236 17261 8237 17261 8241 17261 8237 17262 8069 17262 8242 17262 8242 17263 8069 17263 8083 17263 8242 17264 8083 17264 8109 17264 8109 17265 8083 17265 8079 17265 8243 17266 8109 17266 8084 17266 8079 17267 8084 17267 8109 17267 8110 17268 8243 17268 8084 17268 8110 17269 8245 17269 8244 17269 8244 17270 8248 17270 8246 17270 8424 17271 8238 17271 8430 17271 8430 17272 8238 17272 8246 17272 8248 17273 8244 17273 8245 17273 8246 17274 8248 17274 8430 17274 8425 17275 8427 17275 8247 17275 8424 17276 8425 17276 8132 17276 8132 17277 8425 17277 8247 17277 8239 17278 8427 17278 8234 17278 8271 17279 8236 17279 8241 17279 8428 17280 8271 17280 8240 17280 8251 17281 8168 17281 8250 17281 8251 17282 8252 17282 8168 17282 8249 17283 8250 17283 8252 17283 8251 17284 8250 17284 8249 17284 8251 17285 8249 17285 8252 17285 8255 17286 8434 17286 8256 17286 8159 17287 8255 17287 8256 17287 8169 17288 8164 17288 8260 17288 8258 17289 8166 17289 8165 17289 8258 17290 8318 17290 8166 17290 8099 17291 8101 17291 8259 17291 8259 17292 8101 17292 8167 17292 8259 17293 8167 17293 8098 17293 8099 17294 8210 17294 8215 17294 8095 17295 8205 17295 8206 17295 8261 17296 8209 17296 8197 17296 8239 17297 8187 17297 8234 17297 8274 17298 8251 17298 8249 17298 8251 17299 8090 17299 8249 17299 8293 17300 8135 17300 8336 17300 8293 17301 8336 17301 8302 17301 8275 17302 8276 17302 8277 17302 8300 17303 8277 17303 8276 17303 8304 17304 8278 17304 8296 17304 8296 17305 8278 17305 8279 17305 8280 17306 8295 17306 8296 17306 8280 17307 8296 17307 8279 17307 8284 17308 8294 17308 8292 17308 8284 17309 8292 17309 8133 17309 8133 17310 8292 17310 8281 17310 8281 17311 8292 17311 8290 17311 8281 17312 8290 17312 8282 17312 8282 17313 8290 17313 8283 17313 8283 17314 8290 17314 8331 17314 8283 17315 8331 17315 8330 17315 8330 17316 8331 17316 8295 17316 8330 17317 8295 17317 8280 17317 8284 17318 8285 17318 8294 17318 8285 17319 8284 17319 8135 17319 8285 17320 8135 17320 8293 17320 8299 17321 8436 17321 8301 17321 8436 17322 8107 17322 8072 17322 8301 17323 8286 17323 8339 17323 8287 17324 8298 17324 8106 17324 8287 17325 8106 17325 8073 17325 8287 17326 8073 17326 8288 17326 8299 17327 8297 17327 8288 17327 8297 17328 8298 17328 8288 17328 8340 17329 8292 17329 8341 17329 8294 17330 8341 17330 8292 17330 8295 17331 8331 17331 8289 17331 8289 17332 8331 17332 8143 17332 8291 17333 8290 17333 8292 17333 8143 17334 8331 17334 8290 17334 8143 17335 8290 17335 8291 17335 8143 17336 8291 17336 8340 17336 8291 17337 8292 17337 8340 17337 8293 17338 8334 17338 8285 17338 8341 17339 8294 17339 8285 17339 8341 17340 8285 17340 8108 17340 8107 17341 8436 17341 8299 17341 8299 17342 8301 17342 8337 17342 8073 17343 8299 17343 8288 17343 8108 17344 8285 17344 8334 17344 8108 17345 8334 17345 8072 17345 8333 17346 8295 17346 8289 17346 8333 17347 8296 17347 8295 17347 8335 17348 8276 17348 8304 17348 8302 17349 8300 17349 8339 17349 8335 17350 8304 17350 8333 17350 8333 17351 8304 17351 8296 17351 8335 17352 8333 17352 8298 17352 8335 17353 8297 17353 8276 17353 8289 17354 8106 17354 8333 17354 8333 17355 8106 17355 8298 17355 8335 17356 8298 17356 8297 17356 8276 17357 8297 17357 8299 17357 8276 17358 8299 17358 8337 17358 8301 17359 8276 17359 8337 17359 8276 17360 8339 17360 8300 17360 8276 17361 8301 17361 8339 17361 8286 17362 8302 17362 8339 17362 8072 17363 8334 17363 8293 17363 8072 17364 8293 17364 8436 17364 8436 17365 8293 17365 8286 17365 8286 17366 8293 17366 8302 17366 8302 17367 8336 17367 8303 17367 8302 17368 8303 17368 8300 17368 8300 17369 8303 17369 8277 17369 8278 17370 8304 17370 8275 17370 8275 17371 8304 17371 8276 17371 8305 17372 8325 17372 8329 17372 8305 17373 8329 17373 8310 17373 8310 17374 8329 17374 8313 17374 8313 17375 8329 17375 8328 17375 8313 17376 8328 17376 8320 17376 8319 17377 8329 17377 8307 17377 8307 17378 8329 17378 8325 17378 8307 17379 8325 17379 8322 17379 8329 17380 8138 17380 8328 17380 8328 17381 8138 17381 8137 17381 8321 17382 8323 17382 8320 17382 8309 17383 8306 17383 8317 17383 8322 17384 8306 17384 8307 17384 8308 17385 8323 17385 8321 17385 8309 17386 8326 17386 8315 17386 8326 17387 8309 17387 8327 17387 8327 17388 8309 17388 8317 17388 8310 17389 8298 17389 8433 17389 8310 17390 8433 17390 8305 17390 8160 17391 8298 17391 8310 17391 8312 17392 8311 17392 8313 17392 8313 17393 8311 17393 8310 17393 8310 17394 8311 17394 8160 17394 8316 17395 8312 17395 8313 17395 8316 17396 8313 17396 8324 17396 8326 17397 8314 17397 8315 17397 8314 17398 8167 17398 8315 17398 8315 17399 8167 17399 8324 17399 8324 17400 8167 17400 8316 17400 8325 17401 8163 17401 8322 17401 8163 17402 8170 17402 8322 17402 8322 17403 8170 17403 8317 17403 8317 17404 8170 17404 8327 17404 8318 17405 8327 17405 8170 17405 8314 17406 8326 17406 8318 17406 8318 17407 8326 17407 8327 17407 8305 17408 8433 17408 8163 17408 8325 17409 8305 17409 8163 17409 8329 17410 8319 17410 8138 17410 8328 17411 8137 17411 8320 17411 8320 17412 8137 17412 8321 17412 8317 17413 8306 17413 8322 17413 8308 17414 8315 17414 8324 17414 8308 17415 8324 17415 8323 17415 8323 17416 8313 17416 8320 17416 8323 17417 8324 17417 8313 17417 8336 17418 8302 17418 8286 17418 8143 17419 8392 17419 8289 17419 8389 17420 8340 17420 8142 17420 8142 17421 8340 17421 8341 17421 8344 17422 8348 17422 8345 17422 8354 17423 8355 17423 8129 17423 8129 17424 8355 17424 8352 17424 8131 17425 8344 17425 8345 17425 8130 17426 8346 17426 8131 17426 8346 17427 8347 17427 8131 17427 8131 17428 8347 17428 8344 17428 8353 17429 8450 17429 8118 17429 8129 17430 8352 17430 8350 17430 8352 17431 8351 17431 8350 17431 8116 17432 8450 17432 8111 17432 8349 17433 8116 17433 8111 17433 8344 17434 8442 17434 8348 17434 8111 17435 8348 17435 8349 17435 8346 17436 8130 17436 8343 17436 8343 17437 8130 17437 8350 17437 8353 17438 8118 17438 8355 17438 8353 17439 8355 17439 8354 17439 8356 17440 8367 17440 8358 17440 8413 17441 8359 17441 8114 17441 8114 17442 8359 17442 8126 17442 8126 17443 8359 17443 8414 17443 8363 17444 8356 17444 8358 17444 8360 17445 8361 17445 8363 17445 8356 17446 8375 17446 8367 17446 8361 17447 8362 17447 8363 17447 8363 17448 8362 17448 8356 17448 8370 17449 8418 17449 8420 17449 8126 17450 8414 17450 8369 17450 8364 17451 8418 17451 8366 17451 8368 17452 8365 17452 8366 17452 8366 17453 8365 17453 8364 17453 8366 17454 8367 17454 8368 17454 8361 17455 8360 17455 8357 17455 8416 17456 8357 17456 8369 17456 8420 17457 8413 17457 8370 17457 8370 17458 8413 17458 8114 17458 8375 17459 8382 17459 8377 17459 8378 17460 8419 17460 8372 17460 8419 17461 8417 17461 8372 17461 8373 17462 8415 17462 8374 17462 8373 17463 8374 17463 8381 17463 8381 17464 8374 17464 8122 17464 8375 17465 8380 17465 8382 17465 8376 17466 8384 17466 8112 17466 8420 17467 8112 17467 8381 17467 8377 17468 8384 17468 8379 17468 8371 17469 8415 17469 8372 17469 8384 17470 8376 17470 8379 17470 8380 17471 8383 17471 8382 17471 8382 17472 8383 17472 8378 17472 8378 17473 8383 17473 8419 17473 8356 17474 8380 17474 8375 17474 8070 17475 8407 17475 8385 17475 8408 17476 8386 17476 8394 17476 8070 17477 8385 17477 8144 17477 8394 17478 8386 17478 8142 17478 8142 17479 8386 17479 8423 17479 8070 17480 8398 17480 8407 17480 8387 17481 8124 17481 8392 17481 8392 17482 8124 17482 8144 17482 8144 17483 8124 17483 8070 17483 8393 17484 8388 17484 8125 17484 8142 17485 8423 17485 8389 17485 8423 17486 8422 17486 8389 17486 8421 17487 8388 17487 8390 17487 8071 17488 8391 17488 8390 17488 8390 17489 8391 17489 8421 17489 8390 17490 8407 17490 8071 17490 8387 17491 8392 17491 8412 17491 8422 17492 8412 17492 8389 17492 8125 17493 8408 17493 8393 17493 8393 17494 8408 17494 8394 17494 8398 17495 8128 17495 8406 17495 8395 17496 8399 17496 8396 17496 8399 17497 8401 17497 8396 17497 8127 17498 8410 17498 8409 17498 8127 17499 8409 17499 8402 17499 8402 17500 8409 17500 8397 17500 8398 17501 8400 17501 8128 17501 8123 17502 8403 17502 8113 17502 8125 17503 8113 17503 8402 17503 8406 17504 8403 17504 8404 17504 8411 17505 8410 17505 8396 17505 8403 17506 8123 17506 8404 17506 8400 17507 8405 17507 8128 17507 8128 17508 8405 17508 8395 17508 8395 17509 8405 17509 8399 17509 8070 17510 8400 17510 8398 17510 8407 17511 8398 17511 8406 17511 8407 17512 8406 17512 8071 17512 8071 17513 8406 17513 8404 17513 8408 17514 8402 17514 8386 17514 8386 17515 8402 17515 8397 17515 8423 17516 8409 17516 8410 17516 8422 17517 8411 17517 8412 17517 8412 17518 8411 17518 8396 17518 8412 17519 8396 17519 8401 17519 8421 17520 8123 17520 8388 17520 8388 17521 8123 17521 8113 17521 8388 17522 8113 17522 8125 17522 8367 17523 8375 17523 8377 17523 8367 17524 8377 17524 8368 17524 8368 17525 8377 17525 8379 17525 8413 17526 8381 17526 8359 17526 8359 17527 8381 17527 8122 17527 8414 17528 8374 17528 8369 17528 8369 17529 8374 17529 8415 17529 8416 17530 8371 17530 8357 17530 8357 17531 8371 17531 8372 17531 8357 17532 8372 17532 8417 17532 8364 17533 8376 17533 8418 17533 8418 17534 8376 17534 8112 17534 8418 17535 8112 17535 8420 17535 8371 17536 8369 17536 8415 17536 8411 17537 8423 17537 8410 17537 8231 17538 8424 17538 8430 17538 8425 17539 8424 17539 8232 17539 8425 17540 8426 17540 8427 17540 8234 17541 8432 17541 8428 17541 8287 17542 8434 17542 8433 17542 8298 17543 8160 17543 8434 17543 8436 17544 8161 17544 8435 17544 8435 17545 8311 17545 8312 17545 8436 17546 8312 17546 8316 17546 8436 17547 8316 17547 8161 17547 8437 17548 8181 17548 8171 17548 8120 17549 8439 17549 8438 17549 8439 17550 8120 17550 8451 17550 8440 17551 8121 17551 8441 17551 8440 17552 8441 17552 8120 17552 8440 17553 8120 17553 8438 17553 8452 17554 8442 17554 8444 17554 8117 17555 8448 17555 8445 17555 8117 17556 8447 17556 8448 17556 8442 17557 8443 17557 8444 17557 8351 17558 8121 17558 8446 17558 8447 17559 8446 17559 8448 17559 8449 17560 8453 17560 8450 17560 8450 17561 8439 17561 8451 17561 8452 17562 8453 17562 8119 17562 8444 17563 8443 17563 8455 17563 8443 17564 8454 17564 8455 17564 8455 17565 8454 17565 8445 17565 8453 17566 8115 17566 8119 17566 8449 17567 8115 17567 8453 17567 8445 17568 8454 17568 8117 17568 8831 17569 8561 17569 8832 17569 8570 17570 8624 17570 8619 17570 8468 17571 8825 17571 8624 17571 8624 17572 8825 17572 8469 17572 8469 17573 8456 17573 8623 17573 8470 17574 8471 17574 8630 17574 8779 17575 8462 17575 8463 17575 8535 17576 8689 17576 8687 17576 8535 17577 8687 17577 8689 17577 8731 17578 8732 17578 8690 17578 8731 17579 8690 17579 8732 17579 8670 17580 8652 17580 8554 17580 8554 17581 8652 17581 8670 17581 8470 17582 8668 17582 8627 17582 8627 17583 8668 17583 8470 17583 8618 17584 8666 17584 8622 17584 8586 17585 8483 17585 8602 17585 8582 17586 8584 17586 8586 17586 8602 17587 8465 17587 8589 17587 8589 17588 8480 17588 8481 17588 8604 17589 8649 17589 8608 17589 8466 17590 8716 17590 8467 17590 8466 17591 8467 17591 8646 17591 8569 17592 8822 17592 8573 17592 8623 17593 8456 17593 8572 17593 8572 17594 8456 17594 8571 17594 8623 17595 8820 17595 8470 17595 8668 17596 8820 17596 8572 17596 8572 17597 8820 17597 8623 17597 8570 17598 8619 17598 8987 17598 8561 17599 8468 17599 8624 17599 8561 17600 8624 17600 8570 17600 8468 17601 8561 17601 8825 17601 8825 17602 8561 17602 8571 17602 8469 17603 8825 17603 8571 17603 8469 17604 8571 17604 8456 17604 8470 17605 8820 17605 8668 17605 8668 17606 8471 17606 8470 17606 8471 17607 8668 17607 8560 17607 8471 17608 8560 17608 8630 17608 8573 17609 8630 17609 8560 17609 8630 17610 8573 17610 8634 17610 8634 17611 8573 17611 8822 17611 8473 17612 8613 17612 8474 17612 8474 17613 8613 17613 8475 17613 8613 17614 8473 17614 8472 17614 8613 17615 8472 17615 8636 17615 8479 17616 8472 17616 8473 17616 8479 17617 8473 17617 8474 17617 8479 17618 8474 17618 8478 17618 8478 17619 8474 17619 8475 17619 8478 17620 8475 17620 8477 17620 8477 17621 8475 17621 8612 17621 8477 17622 8612 17622 8606 17622 8479 17623 8476 17623 8472 17623 8478 17624 8601 17624 8479 17624 8477 17625 8600 17625 8598 17625 8606 17626 8600 17626 8477 17626 8598 17627 8601 17627 8478 17627 8598 17628 8478 17628 8477 17628 8479 17629 8601 17629 8476 17629 8603 17630 8472 17630 8476 17630 8582 17631 8583 17631 8584 17631 8584 17632 8585 17632 8586 17632 8483 17633 8587 17633 8602 17633 8602 17634 8587 17634 8588 17634 8602 17635 8588 17635 8465 17635 8589 17636 8485 17636 8480 17636 8480 17637 8486 17637 8481 17637 8582 17638 8562 17638 8583 17638 8583 17639 8562 17639 8578 17639 8583 17640 8578 17640 8563 17640 8583 17641 8563 17641 8584 17641 8584 17642 8563 17642 8482 17642 8584 17643 8482 17643 8585 17643 8585 17644 8482 17644 8586 17644 8586 17645 8482 17645 8484 17645 8586 17646 8484 17646 8483 17646 8483 17647 8484 17647 8575 17647 8483 17648 8575 17648 8587 17648 8587 17649 8575 17649 8574 17649 8587 17650 8574 17650 8588 17650 8588 17651 8574 17651 8465 17651 8465 17652 8574 17652 8564 17652 8465 17653 8564 17653 8566 17653 8465 17654 8566 17654 8589 17654 8589 17655 8566 17655 8485 17655 8485 17656 8566 17656 8567 17656 8485 17657 8567 17657 8480 17657 8480 17658 8567 17658 8486 17658 8486 17659 8567 17659 8487 17659 8467 17660 8555 17660 8488 17660 8467 17661 8488 17661 8489 17661 8488 17662 8555 17662 8491 17662 8488 17663 8491 17663 8489 17663 8489 17664 8491 17664 8558 17664 8491 17665 8493 17665 8558 17665 8558 17666 8493 17666 8649 17666 8649 17667 8493 17667 8490 17667 8551 17668 8490 17668 8493 17668 8555 17669 8550 17669 8492 17669 8555 17670 8492 17670 8491 17670 8491 17671 8492 17671 8494 17671 8491 17672 8494 17672 8493 17672 8546 17673 8493 17673 8494 17673 8546 17674 8551 17674 8493 17674 8672 17675 8543 17675 8545 17675 8545 17676 8543 17676 8655 17676 8545 17677 8655 17677 8541 17677 8545 17678 8541 17678 8671 17678 8738 17679 8773 17679 8796 17679 8738 17680 8796 17680 8463 17680 8463 17681 8796 17681 8779 17681 8462 17682 8779 17682 8802 17682 8462 17683 8802 17683 8684 17683 8684 17684 8802 17684 8495 17684 8684 17685 8495 17685 8461 17685 8461 17686 8495 17686 8496 17686 8461 17687 8496 17687 8741 17687 8847 17688 8533 17688 8497 17688 8847 17689 8497 17689 8840 17689 8840 17690 8497 17690 8746 17690 8497 17691 8625 17691 8746 17691 8746 17692 8625 17692 8849 17692 8849 17693 8625 17693 8626 17693 8626 17694 8627 17694 8849 17694 8849 17695 8627 17695 8498 17695 8498 17696 8627 17696 8628 17696 8498 17697 8628 17697 8499 17697 8499 17698 8628 17698 8629 17698 8499 17699 8629 17699 8631 17699 8499 17700 8631 17700 8833 17700 8771 17701 8508 17701 8500 17701 8771 17702 8500 17702 8769 17702 8769 17703 8500 17703 8803 17703 8803 17704 8500 17704 8746 17704 8803 17705 8746 17705 8747 17705 8803 17706 8747 17706 8765 17706 8765 17707 8747 17707 8501 17707 8765 17708 8501 17708 8766 17708 8766 17709 8501 17709 8498 17709 8766 17710 8498 17710 8764 17710 8764 17711 8498 17711 8751 17711 8764 17712 8751 17712 8503 17712 8503 17713 8751 17713 8502 17713 8793 17714 8754 17714 8753 17714 8793 17715 8753 17715 8789 17715 8789 17716 8753 17716 8804 17716 8789 17717 8804 17717 8795 17717 8795 17718 8804 17718 8759 17718 8795 17719 8759 17719 8788 17719 8788 17720 8759 17720 8787 17720 8787 17721 8759 17721 8811 17721 8787 17722 8811 17722 8504 17722 8504 17723 8811 17723 8762 17723 8504 17724 8762 17724 8786 17724 8786 17725 8762 17725 8505 17725 8506 17726 8797 17726 8785 17726 8506 17727 8785 17727 8815 17727 8755 17728 8770 17728 8805 17728 8755 17729 8805 17729 8814 17729 8828 17730 8695 17730 8827 17730 8827 17731 8695 17731 8463 17731 8827 17732 8463 17732 8691 17732 8829 17733 8699 17733 8507 17733 8508 17734 8839 17734 8509 17734 8843 17735 8848 17735 8748 17735 8752 17736 8834 17736 8510 17736 8752 17737 8510 17737 8517 17737 8747 17738 8515 17738 8511 17738 8511 17739 8515 17739 8512 17739 8511 17740 8512 17740 8745 17740 8745 17741 8512 17741 8844 17741 8748 17742 8848 17742 8743 17742 8743 17743 8848 17743 8846 17743 8743 17744 8846 17744 8513 17744 8513 17745 8846 17745 8839 17745 8517 17746 8838 17746 8750 17746 8750 17747 8838 17747 8842 17747 8514 17748 8845 17748 8752 17748 8509 17749 8839 17749 8516 17749 8509 17750 8516 17750 8746 17750 8747 17751 8746 17751 8515 17751 8752 17752 8845 17752 8834 17752 8517 17753 8510 17753 8835 17753 8517 17754 8835 17754 8838 17754 8750 17755 8842 17755 8843 17755 8513 17756 8839 17756 8508 17756 8745 17757 8844 17757 8498 17757 8498 17758 8845 17758 8514 17758 8518 17759 8699 17759 8829 17759 8827 17760 8691 17760 8826 17760 8826 17761 8691 17761 8695 17761 8826 17762 8695 17762 8828 17762 8760 17763 8768 17763 8519 17763 8519 17764 8768 17764 8520 17764 8519 17765 8520 17765 8810 17765 8810 17766 8520 17766 8766 17766 8521 17767 8767 17767 8757 17767 8757 17768 8767 17768 8522 17768 8757 17769 8522 17769 8457 17769 8457 17770 8522 17770 8458 17770 8809 17771 8812 17771 8521 17771 8521 17772 8812 17772 8767 17772 8814 17773 8807 17773 8813 17773 8763 17774 8523 17774 8770 17774 8780 17775 8791 17775 8778 17775 8778 17776 8791 17776 8524 17776 8778 17777 8524 17777 8801 17777 8801 17778 8524 17778 8787 17778 8782 17779 8794 17779 8776 17779 8776 17780 8794 17780 8525 17780 8776 17781 8525 17781 8459 17781 8459 17782 8525 17782 8784 17782 8781 17783 8792 17783 8782 17783 8782 17784 8792 17784 8794 17784 8815 17785 8799 17785 8800 17785 8774 17786 8816 17786 8797 17786 8786 17787 8505 17787 8526 17787 8786 17788 8526 17788 8798 17788 8798 17789 8526 17789 8761 17789 8798 17790 8761 17790 8527 17790 8527 17791 8761 17791 8808 17791 8527 17792 8808 17792 8756 17792 8527 17793 8756 17793 8528 17793 8528 17794 8756 17794 8758 17794 8528 17795 8758 17795 8754 17795 8528 17796 8754 17796 8793 17796 8503 17797 8502 17797 8744 17797 8503 17798 8744 17798 8806 17798 8806 17799 8744 17799 8749 17799 8806 17800 8749 17800 8808 17800 8808 17801 8749 17801 8748 17801 8808 17802 8748 17802 8529 17802 8529 17803 8748 17803 8530 17803 8530 17804 8748 17804 8531 17804 8530 17805 8531 17805 8508 17805 8530 17806 8508 17806 8771 17806 8833 17807 8631 17807 8620 17807 8833 17808 8620 17808 8836 17808 8836 17809 8620 17809 8632 17809 8836 17810 8632 17810 8835 17810 8835 17811 8632 17811 8621 17811 8835 17812 8621 17812 8842 17812 8842 17813 8621 17813 8622 17813 8842 17814 8622 17814 8841 17814 8841 17815 8622 17815 8837 17815 8837 17816 8622 17816 8532 17816 8837 17817 8532 17817 8847 17817 8847 17818 8532 17818 8533 17818 8675 17819 8701 17819 8735 17819 8681 17820 8731 17820 8709 17820 8709 17821 8731 17821 8713 17821 8713 17822 8731 17822 8710 17822 8710 17823 8731 17823 8534 17823 8710 17824 8534 17824 8535 17824 8535 17825 8679 17825 8710 17825 8679 17826 8730 17826 8710 17826 8710 17827 8730 17827 8721 17827 8742 17828 8708 17828 8680 17828 8680 17829 8708 17829 8721 17829 8680 17830 8721 17830 8730 17830 8538 17831 8539 17831 8718 17831 8734 17832 8682 17832 8460 17832 8682 17833 8734 17833 8719 17833 8536 17834 8708 17834 8540 17834 8708 17835 8536 17835 8717 17835 8735 17836 8682 17836 8719 17836 8674 17837 8737 17837 8536 17837 8536 17838 8676 17838 8674 17838 8742 17839 8678 17839 8708 17839 8708 17840 8678 17840 8540 17840 8678 17841 8742 17841 8680 17841 8460 17842 8681 17842 8709 17842 8681 17843 8460 17843 8682 17843 8537 17844 8675 17844 8735 17844 8537 17845 8735 17845 8718 17845 8718 17846 8735 17846 8719 17846 8719 17847 8734 17847 8460 17847 8719 17848 8460 17848 8709 17848 8539 17849 8538 17849 8675 17849 8537 17850 8718 17850 8539 17850 8537 17851 8539 17851 8675 17851 8675 17852 8737 17852 8674 17852 8538 17853 8737 17853 8675 17853 8538 17854 8717 17854 8737 17854 8737 17855 8717 17855 8536 17855 8676 17856 8536 17856 8540 17856 8676 17857 8540 17857 8678 17857 8741 17858 8496 17858 8775 17858 8777 17859 8781 17859 8740 17859 8740 17860 8781 17860 8783 17860 8740 17861 8783 17861 8739 17861 8739 17862 8783 17862 8693 17862 8693 17863 8783 17863 8773 17863 8693 17864 8773 17864 8738 17864 8672 17865 8671 17865 8542 17865 8672 17866 8542 17866 8464 17866 8672 17867 8464 17867 8543 17867 8672 17868 8545 17868 8671 17868 8492 17869 8550 17869 8545 17869 8547 17870 8545 17870 8672 17870 8547 17871 8672 17871 8544 17871 8546 17872 8545 17872 8547 17872 8494 17873 8545 17873 8546 17873 8494 17874 8492 17874 8545 17874 8672 17875 8545 17875 8550 17875 8672 17876 8549 17876 8544 17876 8672 17877 8550 17877 8549 17877 8551 17878 8546 17878 8547 17878 8547 17879 8548 17879 8551 17879 8544 17880 8548 17880 8547 17880 8549 17881 8548 17881 8544 17881 8549 17882 8552 17882 8548 17882 8552 17883 8549 17883 8550 17883 8552 17884 8550 17884 8555 17884 8639 17885 8490 17885 8551 17885 8639 17886 8551 17886 8548 17886 8639 17887 8548 17887 8669 17887 8669 17888 8548 17888 8554 17888 8548 17889 8552 17889 8554 17889 8554 17890 8552 17890 8553 17890 8553 17891 8552 17891 8555 17891 8637 17892 8711 17892 8830 17892 8637 17893 8830 17893 8638 17893 8639 17894 8669 17894 8641 17894 8641 17895 8669 17895 8638 17895 8829 17896 8638 17896 8830 17896 8638 17897 8829 17897 8641 17897 8726 17898 8639 17898 8712 17898 8637 17899 8827 17899 8711 17899 8643 17900 8827 17900 8637 17900 8467 17901 8644 17901 8553 17901 8716 17902 8644 17902 8467 17902 8467 17903 8489 17903 8559 17903 8713 17904 8556 17904 8558 17904 8558 17905 8556 17905 8489 17905 8556 17906 8714 17906 8557 17906 8726 17907 8490 17907 8639 17907 8726 17908 8713 17908 8648 17908 8648 17909 8713 17909 8558 17909 8637 17910 8554 17910 8553 17910 8644 17911 8716 17911 8643 17911 8643 17912 8716 17912 8827 17912 8827 17913 8716 17913 8828 17913 8557 17914 8714 17914 8559 17914 8641 17915 8829 17915 8712 17915 8641 17916 8712 17916 8639 17916 8669 17917 8554 17917 8638 17917 8559 17918 8489 17918 8557 17918 8559 17919 8714 17919 8466 17919 8466 17920 8714 17920 8716 17920 8660 17921 8668 17921 8572 17921 8660 17922 8572 17922 8661 17922 8660 17923 8659 17923 8668 17923 8668 17924 8659 17924 8658 17924 8668 17925 8658 17925 8560 17925 8560 17926 8658 17926 8657 17926 8571 17927 8579 17927 8661 17927 8579 17928 8571 17928 8662 17928 8662 17929 8571 17929 8561 17929 8662 17930 8561 17930 8663 17930 8663 17931 8561 17931 8832 17931 8663 17932 8832 17932 8664 17932 8664 17933 8832 17933 8578 17933 8664 17934 8578 17934 8562 17934 8577 17935 8563 17935 8578 17935 8575 17936 8484 17936 8666 17936 8666 17937 8484 17937 8482 17937 8666 17938 8482 17938 8577 17938 8577 17939 8482 17939 8563 17939 8564 17940 8574 17940 8617 17940 8564 17941 8617 17941 8566 17941 8566 17942 8617 17942 8565 17942 8566 17943 8565 17943 8567 17943 8656 17944 8486 17944 8487 17944 8656 17945 8487 17945 8568 17945 8568 17946 8487 17946 8567 17946 8568 17947 8567 17947 8565 17947 8656 17948 8568 17948 8569 17948 8570 17949 8578 17949 8832 17949 8832 17950 8561 17950 8570 17950 8572 17951 8571 17951 8661 17951 8656 17952 8573 17952 8560 17952 8656 17953 8560 17953 8657 17953 8569 17954 8573 17954 8656 17954 8615 17955 8665 17955 8617 17955 8615 17956 8617 17956 8574 17956 8574 17957 8575 17957 8615 17957 8615 17958 8575 17958 8666 17958 8576 17959 8577 17959 8578 17959 8570 17960 8987 17960 8578 17960 8576 17961 8578 17961 8616 17961 8616 17962 8578 17962 8987 17962 8591 17963 8486 17963 8656 17963 8591 17964 8656 17964 8592 17964 8592 17965 8656 17965 8657 17965 8592 17966 8657 17966 8593 17966 8593 17967 8657 17967 8658 17967 8593 17968 8658 17968 8590 17968 8590 17969 8658 17969 8651 17969 8651 17970 8658 17970 8659 17970 8651 17971 8659 17971 8580 17971 8580 17972 8659 17972 8654 17972 8654 17973 8659 17973 8660 17973 8654 17974 8660 17974 8594 17974 8594 17975 8660 17975 8595 17975 8595 17976 8660 17976 8661 17976 8595 17977 8661 17977 8596 17977 8596 17978 8661 17978 8579 17978 8596 17979 8579 17979 8662 17979 8596 17980 8662 17980 8597 17980 8597 17981 8662 17981 8663 17981 8597 17982 8663 17982 8581 17982 8581 17983 8663 17983 8582 17983 8582 17984 8663 17984 8664 17984 8582 17985 8664 17985 8562 17985 8481 17986 8486 17986 8591 17986 8481 17987 8591 17987 8593 17987 8593 17988 8591 17988 8592 17988 8593 17989 8590 17989 8651 17989 8651 17990 8580 17990 8654 17990 8652 17991 8654 17991 8594 17991 8652 17992 8594 17992 8595 17992 8652 17993 8595 17993 8653 17993 8653 17994 8595 17994 8596 17994 8653 17995 8596 17995 8597 17995 8653 17996 8597 17996 8599 17996 8599 17997 8597 17997 8581 17997 8599 17998 8581 17998 8582 17998 8652 17999 8593 17999 8654 17999 8598 18000 8600 18000 8593 18000 8598 18001 8593 18001 8652 18001 8598 18002 8652 18002 8601 18002 8653 18003 8599 18003 8652 18003 8650 18004 8589 18004 8604 18004 8604 18005 8589 18005 8481 18005 8604 18006 8481 18006 8600 18006 8600 18007 8481 18007 8593 18007 8599 18008 8476 18008 8601 18008 8650 18009 8602 18009 8589 18009 8603 18010 8586 18010 8605 18010 8652 18011 8599 18011 8601 18011 8602 18012 8650 18012 8605 18012 8586 18013 8602 18013 8605 18013 8586 18014 8603 18014 8582 18014 8476 18015 8599 18015 8582 18015 8476 18016 8582 18016 8603 18016 8608 18017 8604 18017 8606 18017 8608 18018 8650 18018 8604 18018 8609 18019 8650 18019 8608 18019 8611 18020 8603 18020 8605 18020 8472 18021 8603 18021 8611 18021 8605 18022 8609 18022 8611 18022 8605 18023 8650 18023 8609 18023 8600 18024 8606 18024 8604 18024 8606 18025 8612 18025 8607 18025 8606 18026 8607 18026 8608 18026 8608 18027 8607 18027 8635 18027 8608 18028 8635 18028 8609 18028 8609 18029 8635 18029 8610 18029 8609 18030 8610 18030 8611 18030 8611 18031 8610 18031 8636 18031 8611 18032 8636 18032 8472 18032 8636 18033 8610 18033 8635 18033 8635 18034 8607 18034 8612 18034 8636 18035 8464 18035 8613 18035 8464 18036 8636 18036 8543 18036 8543 18037 8636 18037 8635 18037 8635 18038 8612 18038 8655 18038 8635 18039 8655 18039 8543 18039 8613 18040 8464 18040 8542 18040 8613 18041 8542 18041 8475 18041 8655 18042 8612 18042 8475 18042 8655 18043 8475 18043 8671 18043 8655 18044 8671 18044 8541 18044 8542 18045 8671 18045 8475 18045 8568 18046 8821 18046 8569 18046 8633 18047 8823 18047 8618 18047 8823 18048 8615 18048 8666 18048 8633 18049 8614 18049 8615 18049 8633 18050 8615 18050 8823 18050 8615 18051 8614 18051 8665 18051 8619 18052 8616 18052 8987 18052 8576 18053 8616 18053 8619 18053 8821 18054 8822 18054 8569 18054 8817 18055 8821 18055 8568 18055 8817 18056 8568 18056 8565 18056 8817 18057 8565 18057 8617 18057 8617 18058 8665 18058 8818 18058 8818 18059 8665 18059 8614 18059 8618 18060 8823 18060 8666 18060 8666 18061 8824 18061 8618 18061 8824 18062 8666 18062 8577 18062 8824 18063 8577 18063 8819 18063 8819 18064 8577 18064 8576 18064 8819 18065 8576 18065 8667 18065 8667 18066 8576 18066 8619 18066 8819 18067 8532 18067 8618 18067 8630 18068 8628 18068 8470 18068 8620 18069 8817 18069 8632 18069 8621 18070 8633 18070 8622 18070 8622 18071 8618 18071 8532 18071 8532 18072 8667 18072 8533 18072 8624 18073 8497 18073 8619 18073 8619 18074 8497 18074 8533 18074 8497 18075 8624 18075 8625 18075 8625 18076 8624 18076 8469 18076 8625 18077 8469 18077 8626 18077 8626 18078 8469 18078 8623 18078 8627 18079 8626 18079 8470 18079 8623 18080 8470 18080 8626 18080 8628 18081 8627 18081 8470 18081 8628 18082 8630 18082 8629 18082 8629 18083 8634 18083 8631 18083 8817 18084 8620 18084 8822 18084 8822 18085 8620 18085 8631 18085 8634 18086 8629 18086 8630 18086 8631 18087 8634 18087 8822 18087 8818 18088 8633 18088 8621 18088 8817 18089 8818 18089 8632 18089 8632 18090 8818 18090 8621 18090 8622 18091 8633 18091 8618 18091 8667 18092 8619 18092 8533 18092 8819 18093 8667 18093 8532 18093 8554 18094 8637 18094 8670 18094 8670 18095 8637 18095 8638 18095 8670 18096 8638 18096 8554 18096 8640 18097 8639 18097 8641 18097 8640 18098 8641 18098 8639 18098 8642 18099 8553 18099 8644 18099 8643 18100 8637 18100 8553 18100 8643 18101 8553 18101 8642 18101 8642 18102 8644 18102 8643 18102 8646 18103 8467 18103 8559 18103 8646 18104 8559 18104 8645 18104 8645 18105 8559 18105 8466 18105 8466 18106 8646 18106 8645 18106 8647 18107 8489 18107 8556 18107 8647 18108 8557 18108 8489 18108 8647 18109 8556 18109 8557 18109 8649 18110 8490 18110 8648 18110 8648 18111 8490 18111 8726 18111 8649 18112 8648 18112 8558 18112 8649 18113 8604 18113 8608 18113 8654 18114 8593 18114 8651 18114 8622 18115 8666 18115 8618 18115 8555 18116 8467 18116 8553 18116 8673 18117 8682 18117 8735 18117 8673 18118 8735 18118 8700 18118 8674 18119 8685 18119 8675 18119 8697 18120 8675 18120 8685 18120 8702 18121 8676 18121 8694 18121 8694 18122 8676 18122 8678 18122 8680 18123 8677 18123 8694 18123 8680 18124 8694 18124 8678 18124 8681 18125 8692 18125 8690 18125 8681 18126 8690 18126 8731 18126 8731 18127 8690 18127 8534 18127 8534 18128 8690 18128 8687 18128 8534 18129 8687 18129 8535 18129 8535 18130 8687 18130 8679 18130 8679 18131 8687 18131 8688 18131 8679 18132 8688 18132 8730 18132 8730 18133 8688 18133 8677 18133 8730 18134 8677 18134 8680 18134 8681 18135 8683 18135 8692 18135 8683 18136 8681 18136 8682 18136 8683 18137 8682 18137 8673 18137 8463 18138 8695 18138 8738 18138 8462 18139 8507 18139 8699 18139 8507 18140 8684 18140 8461 18140 8699 18141 8518 18141 8698 18141 8698 18142 8518 18142 8700 18142 8700 18143 8518 18143 8507 18143 8696 18144 8695 18144 8691 18144 8692 18145 8741 18145 8732 18145 8740 18146 8690 18146 8732 18146 8740 18147 8732 18147 8741 18147 8692 18148 8732 18148 8690 18148 8693 18149 8738 18149 8686 18149 8677 18150 8688 18150 8693 18150 8693 18151 8688 18151 8739 18151 8689 18152 8687 18152 8690 18152 8739 18153 8688 18153 8687 18153 8739 18154 8687 18154 8740 18154 8740 18155 8687 18155 8689 18155 8689 18156 8690 18156 8740 18156 8673 18157 8733 18157 8683 18157 8741 18158 8692 18158 8683 18158 8684 18159 8507 18159 8462 18159 8462 18160 8699 18160 8736 18160 8463 18161 8462 18161 8691 18161 8741 18162 8683 18162 8733 18162 8741 18163 8733 18163 8461 18163 8686 18164 8677 18164 8693 18164 8686 18165 8694 18165 8677 18165 8695 18166 8685 18166 8702 18166 8700 18167 8697 18167 8698 18167 8695 18168 8702 18168 8686 18168 8686 18169 8702 18169 8694 18169 8686 18170 8738 18170 8695 18170 8685 18171 8695 18171 8696 18171 8696 18172 8691 18172 8685 18172 8685 18173 8691 18173 8462 18173 8685 18174 8462 18174 8736 18174 8699 18175 8685 18175 8736 18175 8685 18176 8698 18176 8697 18176 8685 18177 8699 18177 8698 18177 8461 18178 8733 18178 8673 18178 8461 18179 8673 18179 8507 18179 8507 18180 8673 18180 8700 18180 8700 18181 8735 18181 8701 18181 8700 18182 8701 18182 8697 18182 8697 18183 8701 18183 8675 18183 8676 18184 8702 18184 8674 18184 8674 18185 8702 18185 8685 18185 8724 18186 8703 18186 8706 18186 8724 18187 8706 18187 8826 18187 8826 18188 8706 18188 8707 18188 8826 18189 8707 18189 8704 18189 8704 18190 8707 18190 8705 18190 8705 18191 8707 18191 8729 18191 8705 18192 8729 18192 8728 18192 8717 18193 8706 18193 8708 18193 8708 18194 8706 18194 8703 18194 8708 18195 8703 18195 8722 18195 8707 18196 8538 18196 8729 18196 8729 18197 8538 18197 8718 18197 8719 18198 8725 18198 8728 18198 8710 18199 8721 18199 8720 18199 8722 18200 8721 18200 8708 18200 8709 18201 8725 18201 8719 18201 8710 18202 8723 18202 8713 18202 8710 18203 8715 18203 8723 18203 8715 18204 8710 18204 8727 18204 8727 18205 8710 18205 8720 18205 8711 18206 8826 18206 8704 18206 8518 18207 8830 18207 8705 18207 8705 18208 8830 18208 8704 18208 8704 18209 8830 18209 8711 18209 8507 18210 8518 18210 8712 18210 8712 18211 8518 18211 8705 18211 8712 18212 8705 18212 8726 18212 8723 18213 8556 18213 8713 18213 8703 18214 8716 18214 8722 18214 8716 18215 8714 18215 8722 18215 8722 18216 8714 18216 8720 18216 8720 18217 8714 18217 8727 18217 8556 18218 8727 18218 8714 18218 8556 18219 8723 18219 8715 18219 8556 18220 8715 18220 8727 18220 8724 18221 8826 18221 8828 18221 8724 18222 8828 18222 8716 18222 8703 18223 8724 18223 8716 18223 8706 18224 8717 18224 8707 18224 8707 18225 8717 18225 8538 18225 8729 18226 8718 18226 8728 18226 8728 18227 8718 18227 8719 18227 8720 18228 8721 18228 8722 18228 8709 18229 8713 18229 8726 18229 8709 18230 8726 18230 8725 18230 8725 18231 8705 18231 8728 18231 8725 18232 8726 18232 8705 18232 8777 18233 8740 18233 8775 18233 8775 18234 8740 18234 8741 18234 8509 18235 8500 18235 8508 18235 8502 18236 8752 18236 8744 18236 8744 18237 8752 18237 8517 18237 8531 18238 8513 18238 8508 18238 8748 18239 8743 18239 8531 18239 8531 18240 8743 18240 8513 18240 8751 18241 8498 18241 8514 18241 8744 18242 8517 18242 8749 18242 8517 18243 8750 18243 8749 18243 8745 18244 8498 18244 8501 18244 8747 18245 8511 18245 8501 18245 8501 18246 8511 18246 8745 18246 8500 18247 8509 18247 8746 18247 8843 18248 8748 18248 8750 18248 8750 18249 8748 18249 8749 18249 8751 18250 8514 18250 8752 18250 8751 18251 8752 18251 8502 18251 8804 18252 8753 18252 8457 18252 8457 18253 8753 18253 8754 18253 8763 18254 8755 18254 8505 18254 8505 18255 8755 18255 8526 18255 8526 18256 8755 18256 8814 18256 8758 18257 8457 18257 8754 18257 8756 18258 8521 18258 8758 18258 8457 18259 8772 18259 8804 18259 8521 18260 8757 18260 8758 18260 8758 18261 8757 18261 8457 18261 8762 18262 8811 18262 8523 18262 8526 18263 8814 18263 8761 18263 8814 18264 8813 18264 8761 18264 8810 18265 8811 18265 8759 18265 8760 18266 8519 18266 8759 18266 8759 18267 8519 18267 8810 18267 8759 18268 8804 18268 8760 18268 8521 18269 8756 18269 8809 18269 8809 18270 8756 18270 8808 18270 8808 18271 8761 18271 8813 18271 8523 18272 8763 18272 8762 18272 8762 18273 8763 18273 8505 18273 8770 18274 8764 18274 8503 18274 8772 18275 8769 18275 8803 18275 8530 18276 8767 18276 8529 18276 8767 18277 8812 18277 8529 18277 8806 18278 8805 18278 8503 18278 8503 18279 8805 18279 8770 18279 8772 18280 8458 18280 8769 18280 8766 18281 8764 18281 8523 18281 8523 18282 8764 18282 8770 18282 8803 18283 8765 18283 8768 18283 8769 18284 8458 18284 8771 18284 8807 18285 8806 18285 8808 18285 8808 18286 8529 18286 8812 18286 8766 18287 8520 18287 8765 18287 8765 18288 8520 18288 8768 18288 8771 18289 8458 18289 8530 18289 8458 18290 8522 18290 8530 18290 8530 18291 8522 18291 8767 18291 8457 18292 8458 18292 8772 18292 8459 18293 8796 18293 8773 18293 8774 18294 8506 18294 8496 18294 8496 18295 8506 18295 8775 18295 8775 18296 8506 18296 8815 18296 8459 18297 8790 18297 8796 18297 8782 18298 8776 18298 8783 18298 8783 18299 8776 18299 8773 18299 8773 18300 8776 18300 8459 18300 8495 18301 8802 18301 8816 18301 8775 18302 8815 18302 8777 18302 8815 18303 8800 18303 8777 18303 8801 18304 8802 18304 8779 18304 8780 18305 8778 18305 8779 18305 8779 18306 8778 18306 8801 18306 8779 18307 8796 18307 8780 18307 8782 18308 8783 18308 8781 18308 8800 18309 8781 18309 8777 18309 8816 18310 8774 18310 8495 18310 8495 18311 8774 18311 8496 18311 8797 18312 8504 18312 8786 18312 8790 18313 8789 18313 8795 18313 8528 18314 8794 18314 8527 18314 8794 18315 8792 18315 8527 18315 8798 18316 8785 18316 8786 18316 8786 18317 8785 18317 8797 18317 8790 18318 8784 18318 8789 18318 8787 18319 8504 18319 8816 18319 8816 18320 8504 18320 8797 18320 8795 18321 8788 18321 8791 18321 8789 18322 8784 18322 8793 18322 8799 18323 8798 18323 8527 18323 8787 18324 8524 18324 8788 18324 8788 18325 8524 18325 8791 18325 8793 18326 8784 18326 8528 18326 8784 18327 8525 18327 8528 18327 8528 18328 8525 18328 8794 18328 8459 18329 8784 18329 8790 18329 8796 18330 8790 18330 8795 18330 8796 18331 8795 18331 8780 18331 8780 18332 8795 18332 8791 18332 8774 18333 8797 18333 8506 18333 8815 18334 8785 18334 8798 18334 8800 18335 8799 18335 8781 18335 8781 18336 8799 18336 8527 18336 8781 18337 8527 18337 8792 18337 8801 18338 8787 18338 8802 18338 8802 18339 8787 18339 8816 18339 8804 18340 8772 18340 8803 18340 8804 18341 8803 18341 8760 18341 8760 18342 8803 18342 8768 18342 8763 18343 8770 18343 8755 18343 8814 18344 8805 18344 8806 18344 8813 18345 8807 18345 8808 18345 8809 18346 8808 18346 8812 18346 8810 18347 8766 18347 8811 18347 8811 18348 8766 18348 8523 18348 8807 18349 8814 18349 8806 18349 8799 18350 8815 18350 8798 18350 8821 18351 8817 18351 8822 18351 8818 18352 8817 18352 8617 18352 8818 18353 8614 18353 8633 18353 8618 18354 8824 18354 8819 18354 8826 18355 8711 18355 8827 18355 8829 18356 8830 18356 8518 18356 8507 18357 8712 18357 8829 18357 8831 18358 8832 18358 8561 18358 8834 18359 8499 18359 8833 18359 8499 18360 8834 18360 8845 18360 8836 18361 8835 18361 8510 18361 8836 18362 8510 18362 8834 18362 8836 18363 8834 18363 8833 18363 8746 18364 8516 18364 8840 18364 8848 18365 8841 18365 8837 18365 8848 18366 8843 18366 8841 18366 8516 18367 8839 18367 8840 18367 8838 18368 8835 18368 8842 18368 8843 18369 8842 18369 8841 18369 8844 18370 8849 18370 8498 18370 8498 18371 8499 18371 8845 18371 8746 18372 8849 18372 8515 18372 8840 18373 8839 18373 8847 18373 8839 18374 8846 18374 8847 18374 8847 18375 8846 18375 8837 18375 8849 18376 8512 18376 8515 18376 8844 18377 8512 18377 8849 18377 8837 18378 8846 18378 8848 18378 9038 18379 8979 18379 9010 18379 8996 18380 9035 18380 8903 18380 9034 18381 9033 18381 9023 18381 9034 18382 9023 18382 8885 18382 8878 18383 8979 18383 9010 18383 8878 18384 9010 18384 8907 18384 8886 18385 9032 18385 9010 18385 9010 18386 9032 18386 8907 18386 9006 18387 8990 18387 8850 18387 9031 18388 8850 18388 8977 18388 8936 18389 8900 18389 8947 18389 8860 18390 8856 18390 8914 18390 8914 18391 8856 18391 8855 18391 8914 18392 8855 18392 8867 18392 8867 18393 8855 18393 8944 18393 8867 18394 8944 18394 8861 18394 8862 18395 8851 18395 8858 18395 8959 18396 8918 18396 8915 18396 8959 18397 8915 18397 8924 18397 8924 18398 8915 18398 8864 18398 8864 18399 8915 18399 8863 18399 8864 18400 8863 18400 8865 18400 8864 18401 8865 18401 8857 18401 8857 18402 8865 18402 8917 18402 8857 18403 8917 18403 8866 18403 8857 18404 8866 18404 8862 18404 8862 18405 8866 18405 8851 18405 8921 18406 8858 18406 8851 18406 8915 18407 8914 18407 8863 18407 8916 18408 8921 18408 8967 18408 8916 18409 8967 18409 8920 18409 8923 18410 8913 18410 8919 18410 8919 18411 8913 18411 8915 18411 8913 18412 8911 18412 8915 18412 8915 18413 8911 18413 8914 18413 8909 18414 8936 18414 8853 18414 8909 18415 8853 18415 8894 18415 8894 18416 8853 18416 8896 18416 8896 18417 8853 18417 8939 18417 8896 18418 8939 18418 8898 18418 8898 18419 8939 18419 8941 18419 8898 18420 8941 18420 8899 18420 8899 18421 8941 18421 8904 18421 8904 18422 8941 18422 8852 18422 8904 18423 8852 18423 8868 18423 8868 18424 8852 18424 8906 18424 8906 18425 8852 18425 8940 18425 8906 18426 8940 18426 8869 18426 8869 18427 8940 18427 8974 18427 8869 18428 8974 18428 8907 18428 9005 18429 8890 18429 8948 18429 8859 18430 8569 18430 9004 18430 8859 18431 9004 18431 8891 18431 9001 18432 8891 18432 8925 18432 8997 18433 8949 18433 8871 18433 8997 18434 8871 18434 8995 18434 8870 18435 8950 18435 8872 18435 8951 18436 8953 18436 8929 18436 8951 18437 8929 18437 8979 18437 9001 18438 8925 18438 9002 18438 9002 18439 8925 18439 8949 18439 9002 18440 8949 18440 8998 18440 8995 18441 8871 18441 8950 18441 8995 18442 8950 18442 8993 18442 8870 18443 8872 18443 8990 18443 8990 18444 8872 18444 8953 18444 8990 18445 8953 18445 8988 18445 8979 18446 8929 18446 8954 18446 8979 18447 8954 18447 8980 18447 8907 18448 8851 18448 8878 18448 9015 18449 8983 18449 9017 18449 9021 18450 8981 18450 8996 18450 9007 18451 8985 18451 8995 18451 9034 18452 8875 18452 9033 18452 9019 18453 8875 18453 8981 18453 9019 18454 8981 18454 9020 18454 9017 18455 9018 18455 8905 18455 9014 18456 8883 18456 9013 18456 8873 18457 9013 18457 8569 18457 8873 18458 8569 18458 8892 18458 8905 18459 9018 18459 8883 18459 8905 18460 8883 18460 8874 18460 8874 18461 8883 18461 9014 18461 8874 18462 9014 18462 9011 18462 9035 18463 9020 18463 8982 18463 9035 18464 8982 18464 8893 18464 8893 18465 8982 18465 8884 18465 8893 18466 8884 18466 8897 18466 8897 18467 8884 18467 9018 18467 9033 18468 8875 18468 8876 18468 8876 18469 8875 18469 9019 18469 9024 18470 9022 18470 8987 18470 8987 18471 9022 18471 8908 18471 8892 18472 8569 18472 9025 18472 8901 18473 8892 18473 9025 18473 9026 18474 8877 18474 8895 18474 8971 18475 8975 18475 8877 18475 8877 18476 8975 18476 8895 18476 8879 18477 8971 18477 8877 18477 8879 18478 8877 18478 9027 18478 9027 18479 8877 18479 9007 18479 8984 18480 8930 18480 8978 18480 8978 18481 8930 18481 9028 18481 8930 18482 8984 18482 9029 18482 9029 18483 8984 18483 9030 18483 8976 18484 8933 18484 9031 18484 8976 18485 9031 18485 8977 18485 8933 18486 8976 18486 9038 18486 8972 18487 8973 18487 8933 18487 8933 18488 9038 18488 8972 18488 8972 18489 9038 18489 8886 18489 9032 18490 8886 18490 8908 18490 8908 18491 8886 18491 8987 18491 8850 18492 8990 18492 8977 18492 9020 18493 8981 18493 9021 18493 9017 18494 8983 18494 9015 18494 8851 18495 8907 18495 8878 18495 8958 18496 8954 18496 8928 18496 8958 18497 8928 18497 8989 18497 8994 18498 8956 18498 8881 18498 8994 18499 8881 18499 8996 18499 9005 18500 8926 18500 8882 18500 9005 18501 8882 18501 8890 18501 8890 18502 8882 18502 9037 18502 8989 18503 8928 18503 8991 18503 8991 18504 8928 18504 8956 18504 8996 18505 8881 18505 8957 18505 8996 18506 8957 18506 9000 18506 8880 18507 8957 18507 9003 18507 9003 18508 8957 18508 8926 18508 9003 18509 8926 18509 8948 18509 9037 18510 8882 18510 8891 18510 9037 18511 8891 18511 9004 18511 9025 18512 9002 18512 9026 18512 9037 18513 9013 18513 8883 18513 8983 18514 9018 18514 8884 18514 8885 18515 9034 18515 9024 18515 9010 18516 8886 18516 9038 18516 9030 18517 8990 18517 8977 18517 9007 18518 8995 18518 8985 18518 8985 18519 8978 18519 9007 18519 8859 18520 9001 18520 8569 18520 8887 18521 8998 18521 8949 18521 8887 18522 8997 18522 8998 18522 8888 18523 8993 18523 8950 18523 8870 18524 8984 18524 8888 18524 8888 18525 8984 18525 8993 18525 8986 18526 8988 18526 8953 18526 8958 18527 8989 18527 8987 18527 8958 18528 8987 18528 8954 18528 8954 18529 8987 18529 8980 18529 8955 18530 8991 18530 8956 18530 8955 18531 8994 18531 8992 18531 8955 18532 8992 18532 8991 18532 8880 18533 8999 18533 8889 18533 8889 18534 8999 18534 8957 18534 8957 18535 8999 18535 9000 18535 8973 18536 8972 18536 8970 18536 8972 18537 8878 18537 8970 18537 8908 18538 8907 18538 9032 18538 8873 18539 8892 18539 9012 18539 8892 18540 8901 18540 9012 18540 8893 18541 8897 18541 9035 18541 8896 18542 9011 18542 8894 18542 8894 18543 9011 18543 9012 18543 9036 18544 8895 18544 8900 18544 8899 18545 8903 18545 8897 18545 8902 18546 9033 18546 8876 18546 8902 18547 8876 18547 9019 18547 9033 18548 8902 18548 9023 18548 9035 18549 8897 18549 8903 18549 9016 18550 9011 18550 8896 18550 9016 18551 8896 18551 8898 18551 9016 18552 8898 18552 8897 18552 8897 18553 8898 18553 8899 18553 8874 18554 9011 18554 9016 18554 8874 18555 9016 18555 8905 18555 9036 18556 8900 18556 8909 18556 9036 18557 8909 18557 8901 18557 8901 18558 8909 18558 9012 18558 9012 18559 8909 18559 8894 18559 8903 18560 8899 18560 8904 18560 8903 18561 8904 18561 8902 18561 8902 18562 8904 18562 8868 18562 8902 18563 8868 18563 9023 18563 8869 18564 9022 18564 8906 18564 8906 18565 9022 18565 9023 18565 8906 18566 9023 18566 8868 18566 8869 18567 8907 18567 8908 18567 8869 18568 8908 18568 9022 18568 8900 18569 8936 18569 8909 18569 8867 18570 8861 18570 8910 18570 8910 18571 8945 18571 8967 18571 8967 18572 8945 18572 8946 18572 8967 18573 8946 18573 8912 18573 8911 18574 8860 18574 8914 18574 8942 18575 8913 18575 8912 18575 8851 18576 8917 18576 8910 18576 8910 18577 8917 18577 8867 18577 8867 18578 8917 18578 8865 18578 8867 18579 8865 18579 8914 18579 8914 18580 8865 18580 8863 18580 8921 18581 8910 18581 8967 18581 8920 18582 8967 18582 8912 18582 8923 18583 8912 18583 8913 18583 8866 18584 8917 18584 8851 18584 8915 18585 8918 18585 8919 18585 8912 18586 8923 18586 8922 18586 8912 18587 8922 18587 8920 18587 8858 18588 8921 18588 8964 18588 8964 18589 8921 18589 8963 18589 8963 18590 8921 18590 8916 18590 8963 18591 8916 18591 8962 18591 8962 18592 8916 18592 8920 18592 8962 18593 8920 18593 8927 18593 8927 18594 8920 18594 8922 18594 8927 18595 8922 18595 8961 18595 8961 18596 8922 18596 8923 18596 8961 18597 8923 18597 8960 18597 8960 18598 8923 18598 8919 18598 8960 18599 8919 18599 8959 18599 8959 18600 8919 18600 8918 18600 8857 18601 8950 18601 8864 18601 8864 18602 8950 18602 8871 18602 8864 18603 8871 18603 8949 18603 8864 18604 8949 18604 8924 18604 8924 18605 8949 18605 8959 18605 8959 18606 8949 18606 8925 18606 8959 18607 8925 18607 8891 18607 8959 18608 8891 18608 8960 18608 8960 18609 8891 18609 8882 18609 8960 18610 8882 18610 8926 18610 8960 18611 8926 18611 8961 18611 8961 18612 8926 18612 8927 18612 8927 18613 8926 18613 8957 18613 8927 18614 8957 18614 8962 18614 8962 18615 8957 18615 8881 18615 8962 18616 8881 18616 8963 18616 8963 18617 8881 18617 8956 18617 8963 18618 8956 18618 8964 18618 8964 18619 8956 18619 8928 18619 8964 18620 8928 18620 8858 18620 8858 18621 8928 18621 8954 18621 8858 18622 8954 18622 8929 18622 8858 18623 8929 18623 8862 18623 8862 18624 8929 18624 8953 18624 8862 18625 8953 18625 8857 18625 8857 18626 8953 18626 8872 18626 8857 18627 8872 18627 8950 18627 8930 18628 9029 18628 9009 18628 8930 18629 9009 18629 9028 18629 9009 18630 8935 18630 9008 18630 9008 18631 8931 18631 9027 18631 8879 18632 9027 18632 8931 18632 8850 18633 8932 18633 9006 18633 9006 18634 8932 18634 8935 18634 9006 18635 8935 18635 9009 18635 9006 18636 9009 18636 9029 18636 8932 18637 8850 18637 8933 18637 8932 18638 8933 18638 8934 18638 8933 18639 8850 18639 9031 18639 8934 18640 8970 18640 8932 18640 8932 18641 8970 18641 8969 18641 8932 18642 8969 18642 8935 18642 8935 18643 8969 18643 8968 18643 8935 18644 8968 18644 9008 18644 9008 18645 8968 18645 8937 18645 9008 18646 8937 18646 8931 18646 8936 18647 8937 18647 8856 18647 8878 18648 8974 18648 8970 18648 8970 18649 8974 18649 8966 18649 8970 18650 8966 18650 8854 18650 8947 18651 8937 18651 8936 18651 8856 18652 8937 18652 8855 18652 8855 18653 8937 18653 8968 18653 8855 18654 8968 18654 8944 18654 8944 18655 8968 18655 8969 18655 8944 18656 8969 18656 8970 18656 8944 18657 8970 18657 8854 18657 8856 18658 8860 18658 8936 18658 8936 18659 8860 18659 8938 18659 8936 18660 8938 18660 8853 18660 8853 18661 8938 18661 8939 18661 8939 18662 8938 18662 8965 18662 8939 18663 8965 18663 8941 18663 8941 18664 8965 18664 8943 18664 8974 18665 8940 18665 8966 18665 8966 18666 8940 18666 8943 18666 8943 18667 8940 18667 8852 18667 8943 18668 8852 18668 8941 18668 8966 18669 8943 18669 8945 18669 8938 18670 8860 18670 8911 18670 8911 18671 8942 18671 8965 18671 8854 18672 8966 18672 8910 18672 8854 18673 8910 18673 8861 18673 8854 18674 8861 18674 8944 18674 8910 18675 8966 18675 8945 18675 8946 18676 8945 18676 8943 18676 8946 18677 8943 18677 8912 18677 8912 18678 8943 18678 8965 18678 8912 18679 8965 18679 8942 18679 8913 18680 8942 18680 8911 18680 8947 18681 8900 18681 8975 18681 8975 18682 8900 18682 8895 18682 8971 18683 8879 18683 8931 18683 8971 18684 8931 18684 8937 18684 8970 18685 8934 18685 8973 18685 8973 18686 8934 18686 8933 18686 8859 18687 8891 18687 9001 18687 9005 18688 8948 18688 8926 18688 8887 18689 8949 18689 8997 18689 8870 18690 8888 18690 8950 18690 8986 18691 8953 18691 8951 18691 8986 18692 8951 18692 8952 18692 8955 18693 8956 18693 8994 18693 8889 18694 8957 18694 8880 18694 8911 18695 8965 18695 8938 18695 8937 18696 8975 18696 8971 18696 8937 18697 8947 18697 8975 18697 8910 18698 8921 18698 8851 18698 8878 18699 8907 18699 8974 18699 8982 18700 8983 18700 8884 18700 8981 18701 8875 18701 9034 18701 8885 18702 9024 18702 8987 18702 8984 18703 8978 18703 8985 18703 9038 18704 8976 18704 8952 18704 8999 18705 8982 18705 9020 18705 8999 18706 9020 18706 9000 18706 8991 18707 8885 18707 8989 18707 8979 18708 8980 18708 9010 18708 8885 18709 8987 18709 8989 18709 8988 18710 8986 18710 8976 18710 8976 18711 8986 18711 8952 18711 8976 18712 8977 18712 8990 18712 8990 18713 8988 18713 8976 18713 8886 18714 8980 18714 8987 18714 9010 18715 8980 18715 8886 18715 8981 18716 8994 18716 8996 18716 8994 18717 8981 18717 8992 18717 9038 18718 8952 18718 8979 18718 8979 18719 8952 18719 8951 18719 8948 18720 9018 18720 9003 18720 9003 18721 9018 18721 8983 18721 8991 18722 9034 18722 8885 18722 8992 18723 8981 18723 9034 18723 8992 18724 9034 18724 8991 18724 9018 18725 8948 18725 8883 18725 9003 18726 8983 18726 8880 18726 8982 18727 8999 18727 8983 18727 8983 18728 8999 18728 8880 18728 9025 18729 8569 18729 9001 18729 9025 18730 9001 18730 9002 18730 9007 18731 8997 18731 8995 18731 8996 18732 9000 18732 9020 18732 9013 18733 9037 18733 9004 18733 8995 18734 8993 18734 8985 18734 8997 18735 9007 18735 8877 18735 8997 18736 8877 18736 8998 18736 9030 18737 8984 18737 8870 18737 9030 18738 8870 18738 8990 18738 8569 18739 9013 18739 9004 18739 8985 18740 8993 18740 8984 18740 9002 18741 8998 18741 9026 18741 8890 18742 9037 18742 8883 18742 8998 18743 8877 18743 9026 18743 8883 18744 8948 18744 8890 18744 8990 18745 9030 18745 8977 18745 9029 18746 9030 18746 9006 18746 9006 18747 9030 18747 8990 18747 9007 18748 8978 18748 8985 18748 9027 18749 9007 18749 8995 18749 9027 18750 8995 18750 9008 18750 9008 18751 8995 18751 8985 18751 9008 18752 8985 18752 9009 18752 9009 18753 8985 18753 9028 18753 9028 18754 8985 18754 8978 18754 8979 18755 8972 18755 9010 18755 9010 18756 8972 18756 8886 18756 8972 18757 8979 18757 8878 18757 9011 18758 9014 18758 9037 18758 9011 18759 9037 18759 9012 18759 9012 18760 9037 18760 8873 18760 8873 18761 9037 18761 9013 18761 9013 18762 9037 18762 9014 18762 8897 18763 9018 18763 9015 18763 8897 18764 9015 18764 9016 18764 9016 18765 9015 18765 9017 18765 9016 18766 9017 18766 8905 18766 9015 18767 9018 18767 9017 18767 8902 18768 9021 18768 8903 18768 8903 18769 9021 18769 8996 18769 9021 18770 9019 18770 9020 18770 9022 18771 9024 18771 8885 18771 9022 18772 8885 18772 9023 18772 9024 18773 9034 18773 8885 18773 8901 18774 9025 18774 9036 18774 9036 18775 9025 18775 9002 18775 9036 18776 9002 18776 9026 18776 9026 18777 9002 18777 9025 18777 8902 18778 9019 18778 9021 18778 9020 18779 9035 18779 8996 18779 9026 18780 8895 18780 9036 18780 9217 18781 9218 18781 9105 18781 9102 18782 9216 18782 9039 18782 9039 18783 9216 18783 9073 18783 9039 18784 9073 18784 9227 18784 9207 18785 9189 18785 9224 18785 9204 18786 9390 18786 9220 18786 9116 18787 9106 18787 9040 18787 9116 18788 9040 18788 9106 18788 9153 18789 9110 18789 9146 18789 9043 18790 9110 18790 9153 18790 9043 18791 9153 18791 9152 18791 9152 18792 9144 18792 9112 18792 9115 18793 9112 18793 9151 18793 9115 18794 9151 18794 9155 18794 9152 18795 9153 18795 9144 18795 9174 18796 9044 18796 9045 18796 9174 18797 9045 18797 9041 18797 9041 18798 9045 18798 9133 18798 9133 18799 9045 18799 9122 18799 9133 18800 9122 18800 9132 18800 9132 18801 9122 18801 9121 18801 9132 18802 9121 18802 9119 18802 9132 18803 9119 18803 9130 18803 9130 18804 9119 18804 9123 18804 9130 18805 9123 18805 9046 18805 9044 18806 9118 18806 9045 18806 9045 18807 9118 18807 9109 18807 9045 18808 9109 18808 9122 18808 9123 18809 9119 18809 9115 18809 9111 18810 9152 18810 9120 18810 9094 18811 9183 18811 9091 18811 9091 18812 9183 18812 9186 18812 9091 18813 9186 18813 9042 18813 9108 18814 9047 18814 9049 18814 9108 18815 9049 18815 9048 18815 9048 18816 9049 18816 9103 18816 9103 18817 9049 18817 9145 18817 9103 18818 9145 18818 9095 18818 9095 18819 9145 18819 9148 18819 9095 18820 9148 18820 9096 18820 9096 18821 9148 18821 9147 18821 9096 18822 9147 18822 9098 18822 9098 18823 9147 18823 9210 18823 9210 18824 9147 18824 9050 18824 9210 18825 9050 18825 9183 18825 9210 18826 9183 18826 9094 18826 9164 18827 9051 18827 9084 18827 9161 18828 9203 18828 9206 18828 9160 18829 9204 18829 9202 18829 9160 18830 9202 18830 9083 18830 9160 18831 9083 18831 9136 18831 9160 18832 9136 18832 9205 18832 9082 18833 9162 18833 9135 18833 9082 18834 9135 18834 9215 18834 9168 18835 9134 18835 9053 18835 9198 18836 9166 18836 9131 18836 9198 18837 9131 18837 9196 18837 9205 18838 9136 18838 9052 18838 9052 18839 9136 18839 9162 18839 9052 18840 9162 18840 9206 18840 9215 18841 9135 18841 9134 18841 9215 18842 9134 18842 9201 18842 9168 18843 9053 18843 9054 18843 9054 18844 9053 18844 9166 18844 9054 18845 9166 18845 9087 18845 9196 18846 9131 18846 9086 18846 9106 18847 9069 18847 9040 18847 9073 18848 9074 18848 9216 18848 9222 18849 9199 18849 9208 18849 9104 18850 9194 18850 9107 18850 9209 18851 9107 18851 9194 18851 9184 18852 9157 18852 9209 18852 9184 18853 9209 18853 9070 18853 9055 18854 9225 18854 9184 18854 9055 18855 9184 18855 9070 18855 9207 18856 9224 18856 9067 18856 9225 18857 9055 18857 9224 18857 9224 18858 9055 18858 9067 18858 9190 18859 9064 18859 9067 18859 9067 18860 9064 18860 9207 18860 9064 18861 9190 18861 9208 18861 9222 18862 9208 18862 9056 18862 9057 18863 9141 18863 9185 18863 9056 18864 9185 18864 9222 18864 9058 18865 9186 18865 9057 18865 9058 18866 9057 18866 9056 18866 9056 18867 9057 18867 9185 18867 9059 18868 9220 18868 9390 18868 9059 18869 9390 18869 9090 18869 9212 18870 9099 18870 9090 18870 9212 18871 9076 18871 9078 18871 9078 18872 9076 18872 9211 18872 9228 18873 9063 18873 9188 18873 9073 18874 9072 18874 9061 18874 9073 18875 9061 18875 9227 18875 9226 18876 9060 18876 9071 18876 9226 18877 9071 18877 9105 18877 9105 18878 9071 18878 9194 18878 9105 18879 9194 18879 9104 18879 9227 18880 9061 18880 9101 18880 9101 18881 9061 18881 9060 18881 9101 18882 9060 18882 9226 18882 9097 18883 9188 18883 9187 18883 9097 18884 9187 18884 9093 18884 9093 18885 9187 18885 9062 18885 9093 18886 9062 18886 9092 18886 9092 18887 9062 18887 9072 18887 9211 18888 9076 18888 9100 18888 9100 18889 9076 18889 9077 18889 9100 18890 9077 18890 9063 18890 9100 18891 9063 18891 9228 18891 9212 18892 9090 18892 9390 18892 9224 18893 9189 18893 9068 18893 9216 18894 9074 18894 9073 18894 9088 18895 9086 18895 9066 18895 9195 18896 9089 18896 9129 18896 9195 18897 9129 18897 9068 18897 9051 18898 9163 18898 9137 18898 9051 18899 9137 18899 9221 18899 9088 18900 9066 18900 9192 18900 9192 18901 9066 18901 9089 18901 9192 18902 9089 18902 9193 18902 9068 18903 9129 18903 9065 18903 9068 18904 9065 18904 9197 18904 9085 18905 9065 18905 9199 18905 9199 18906 9065 18906 9138 18906 9199 18907 9138 18907 9163 18907 9199 18908 9163 18908 9084 18908 9221 18909 9137 18909 9083 18909 9221 18910 9083 18910 9202 18910 9189 18911 9067 18911 9055 18911 9055 18912 9068 18912 9189 18912 9060 18913 9191 18913 9071 18913 9072 18914 9074 18914 9073 18914 9074 18915 9072 18915 9073 18915 9074 18916 9072 18916 9062 18916 9215 18917 9188 18917 9063 18917 9212 18918 9075 18918 9076 18918 9076 18919 9075 18919 9078 18919 9075 18920 9212 18920 9052 18920 9075 18921 9052 18921 9078 18921 9058 18922 9056 18922 9079 18922 9079 18923 9056 18923 9080 18923 9221 18924 9220 18924 9080 18924 9080 18925 9220 18925 9079 18925 9204 18926 9160 18926 9205 18926 9206 18927 9162 18927 9161 18927 9161 18928 9082 18928 9203 18928 9084 18929 9163 18929 9164 18929 9190 18930 9165 18930 9065 18930 9197 18931 9065 18931 9165 18931 9165 18932 9190 18932 9197 18932 9193 18933 9089 18933 9081 18933 9081 18934 9195 18934 9193 18934 9194 18935 9170 18935 9088 18935 9170 18936 9194 18936 9086 18936 9086 18937 9194 18937 9196 18937 9061 18938 9167 18938 9198 18938 9087 18939 9166 18939 9167 18939 9167 18940 9061 18940 9087 18940 9200 18941 9169 18941 9168 18941 9169 18942 9200 18942 9134 18942 9134 18943 9200 18943 9201 18943 9190 18944 9065 18944 9085 18944 9040 18945 9157 18945 9180 18945 9059 18946 9090 18946 9219 18946 9097 18947 9093 18947 9214 18947 9099 18948 9219 18948 9090 18948 9091 18949 9042 18949 9058 18949 9219 18950 9099 18950 9094 18950 9219 18951 9094 18951 9091 18951 9214 18952 9096 18952 9213 18952 9213 18953 9096 18953 9098 18953 9214 18954 9095 18954 9096 18954 9211 18955 9213 18955 9098 18955 9211 18956 9098 18956 9210 18956 9099 18957 9210 18957 9094 18957 9213 18958 9211 18958 9100 18958 9213 18959 9100 18959 9228 18959 9227 18960 9101 18960 9039 18960 9214 18961 9093 18961 9092 18961 9214 18962 9092 18962 9102 18962 9226 18963 9039 18963 9101 18963 9214 18964 9102 18964 9095 18964 9095 18965 9102 18965 9103 18965 9103 18966 9102 18966 9039 18966 9103 18967 9039 18967 9048 18967 9226 18968 9217 18968 9039 18968 9039 18969 9217 18969 9048 18969 9048 18970 9217 18970 9108 18970 9108 18971 9217 18971 9105 18971 9106 18972 9108 18972 9104 18972 9104 18973 9108 18973 9105 18973 9106 18974 9104 18974 9107 18974 9106 18975 9040 18975 9108 18975 9108 18976 9040 18976 9047 18976 9118 18977 9110 18977 9109 18977 9109 18978 9110 18978 9043 18978 9109 18979 9043 18979 9111 18979 9111 18980 9043 18980 9152 18980 9120 18981 9152 18981 9112 18981 9120 18982 9112 18982 9115 18982 9115 18983 9155 18983 9117 18983 9117 18984 9155 18984 9176 18984 9117 18985 9176 18985 9177 18985 9177 18986 9176 18986 9156 18986 9177 18987 9156 18987 9113 18987 9178 18988 9177 18988 9113 18988 9178 18989 9113 18989 9114 18989 9114 18990 9179 18990 9178 18990 9117 18991 9116 18991 9115 18991 9117 18992 9177 18992 9178 18992 9126 18993 9178 18993 9179 18993 9126 18994 9179 18994 9128 18994 9128 18995 9179 18995 9118 18995 9115 18996 9119 18996 9120 18996 9111 18997 9120 18997 9122 18997 9111 18998 9122 18998 9109 18998 9116 18999 9117 18999 9125 18999 9125 19000 9117 19000 9178 19000 9125 19001 9178 19001 9126 19001 9044 19002 9128 19002 9118 19002 9116 19003 9125 19003 9124 19003 9126 19004 9128 19004 9173 19004 9125 19005 9126 19005 9172 19005 9115 19006 9116 19006 9123 19006 9120 19007 9119 19007 9121 19007 9120 19008 9121 19008 9122 19008 9116 19009 9124 19009 9171 19009 9171 19010 9046 19010 9123 19010 9171 19011 9123 19011 9116 19011 9125 19012 9172 19012 9124 19012 9126 19013 9127 19013 9172 19013 9126 19014 9173 19014 9127 19014 9128 19015 9175 19015 9173 19015 9044 19016 9174 19016 9175 19016 9044 19017 9175 19017 9128 19017 9127 19018 9065 19018 9172 19018 9172 19019 9065 19019 9129 19019 9172 19020 9129 19020 9124 19020 9124 19021 9129 19021 9089 19021 9124 19022 9089 19022 9171 19022 9171 19023 9089 19023 9066 19023 9171 19024 9066 19024 9046 19024 9046 19025 9066 19025 9086 19025 9046 19026 9086 19026 9131 19026 9046 19027 9131 19027 9130 19027 9130 19028 9131 19028 9166 19028 9130 19029 9166 19029 9132 19029 9132 19030 9166 19030 9053 19030 9132 19031 9053 19031 9134 19031 9132 19032 9134 19032 9133 19032 9133 19033 9134 19033 9135 19033 9133 19034 9135 19034 9041 19034 9041 19035 9135 19035 9162 19035 9041 19036 9162 19036 9174 19036 9174 19037 9162 19037 9136 19037 9174 19038 9136 19038 9083 19038 9174 19039 9083 19039 9175 19039 9175 19040 9083 19040 9137 19040 9175 19041 9137 19041 9163 19041 9175 19042 9163 19042 9173 19042 9173 19043 9163 19043 9138 19043 9173 19044 9138 19044 9127 19044 9127 19045 9138 19045 9065 19045 9064 19046 9223 19046 9207 19046 9143 19047 9140 19047 9142 19047 9142 19048 9140 19048 9207 19048 9139 19049 9142 19049 9223 19049 9223 19050 9142 19050 9207 19050 9159 19051 9139 19051 9185 19051 9185 19052 9139 19052 9222 19052 9225 19053 9140 19053 9184 19053 9158 19054 9184 19054 9143 19054 9143 19055 9184 19055 9140 19055 9159 19056 9141 19056 9139 19056 9139 19057 9141 19057 9182 19057 9139 19058 9182 19058 9142 19058 9142 19059 9182 19059 9181 19059 9142 19060 9181 19060 9143 19060 9143 19061 9181 19061 9180 19061 9143 19062 9180 19062 9158 19062 9150 19063 9176 19063 9180 19063 9040 19064 9176 19064 9151 19064 9176 19065 9040 19065 9180 19065 9186 19066 9146 19066 9154 19066 9186 19067 9154 19067 9141 19067 9141 19068 9154 19068 9182 19068 9182 19069 9154 19069 9150 19069 9182 19070 9150 19070 9181 19070 9181 19071 9150 19071 9180 19071 9153 19072 9145 19072 9144 19072 9144 19073 9145 19073 9049 19073 9144 19074 9049 19074 9151 19074 9151 19075 9049 19075 9047 19075 9151 19076 9047 19076 9040 19076 9146 19077 9186 19077 9183 19077 9146 19078 9183 19078 9050 19078 9146 19079 9050 19079 9153 19079 9153 19080 9050 19080 9147 19080 9153 19081 9147 19081 9148 19081 9153 19082 9148 19082 9145 19082 9150 19083 9149 19083 9156 19083 9150 19084 9156 19084 9176 19084 9151 19085 9112 19085 9144 19085 9154 19086 9110 19086 9118 19086 9156 19087 9149 19087 9113 19087 9114 19088 9113 19088 9154 19088 9114 19089 9154 19089 9179 19089 9179 19090 9154 19090 9118 19090 9186 19091 9058 19091 9042 19091 9141 19092 9159 19092 9185 19092 9157 19093 9184 19093 9180 19093 9180 19094 9184 19094 9158 19094 9161 19095 9162 19095 9082 19095 9051 19096 9164 19096 9163 19096 9195 19097 9081 19097 9089 19097 9170 19098 9086 19098 9088 19098 9167 19099 9166 19099 9198 19099 9169 19100 9134 19100 9168 19100 9110 19101 9154 19101 9146 19101 9113 19102 9149 19102 9154 19102 9154 19103 9149 19103 9150 19103 9155 19104 9151 19104 9176 19104 9186 19105 9141 19105 9057 19105 9157 19106 9040 19106 9069 19106 9204 19107 9212 19107 9390 19107 9076 19108 9078 19108 9052 19108 9063 19109 9077 19109 9076 19109 9187 19110 9074 19110 9062 19110 9061 19111 9191 19111 9060 19111 9192 19112 9209 19112 9194 19112 9209 19113 9069 19113 9192 19113 9190 19114 9067 19114 9189 19114 9082 19115 9215 19115 9063 19115 9070 19116 9193 19116 9195 19116 9070 19117 9195 19117 9055 19117 9055 19118 9195 19118 9068 19118 9188 19119 9201 19119 9200 19119 9188 19120 9200 19120 9187 19120 9201 19121 9188 19121 9215 19121 9082 19122 9063 19122 9203 19122 9203 19123 9063 19123 9076 19123 9212 19124 9204 19124 9205 19124 9212 19125 9205 19125 9052 19125 9068 19126 9197 19126 9189 19126 9220 19127 9221 19127 9202 19127 9054 19128 9087 19128 9074 19128 9071 19129 9196 19129 9194 19129 9191 19130 9196 19130 9071 19130 9197 19131 9190 19131 9189 19131 9204 19132 9220 19132 9202 19132 9061 19133 9072 19133 9074 19133 9074 19134 9087 19134 9061 19134 9199 19135 9084 19135 9208 19135 9052 19136 9206 19136 9076 19136 9191 19137 9061 19137 9198 19137 9193 19138 9209 19138 9192 19138 9192 19139 9194 19139 9088 19139 9084 19140 9056 19140 9208 19140 9203 19141 9076 19141 9206 19141 9070 19142 9209 19142 9193 19142 9051 19143 9221 19143 9080 19143 9054 19144 9074 19144 9168 19144 9196 19145 9191 19145 9198 19145 9208 19146 9190 19146 9085 19146 9187 19147 9200 19147 9074 19147 9074 19148 9200 19148 9168 19148 9085 19149 9199 19149 9208 19149 9056 19150 9084 19150 9051 19150 9056 19151 9051 19151 9080 19151 9068 19152 9225 19152 9224 19152 9140 19153 9225 19153 9068 19153 9140 19154 9068 19154 9189 19154 9140 19155 9189 19155 9207 19155 9223 19156 9208 19156 9139 19156 9139 19157 9208 19157 9199 19157 9139 19158 9199 19158 9222 19158 9192 19159 9106 19159 9209 19159 9209 19160 9106 19160 9107 19160 9106 19161 9192 19161 9069 19161 9099 19162 9212 19162 9075 19162 9099 19163 9075 19163 9210 19163 9210 19164 9075 19164 9211 19164 9211 19165 9075 19165 9078 19165 9075 19166 9212 19166 9078 19166 9213 19167 9228 19167 9215 19167 9213 19168 9215 19168 9214 19168 9214 19169 9215 19169 9097 19169 9097 19170 9215 19170 9188 19170 9215 19171 9228 19171 9188 19171 9102 19172 9072 19172 9216 19172 9216 19173 9072 19173 9073 19173 9217 19174 9226 19174 9218 19174 9191 19175 9218 19175 9226 19175 9191 19176 9226 19176 9105 19176 9191 19177 9105 19177 9218 19177 9091 19178 9079 19178 9080 19178 9091 19179 9080 19179 9219 19179 9219 19180 9080 19180 9221 19180 9219 19181 9221 19181 9059 19181 9059 19182 9221 19182 9220 19182 9220 19183 9080 19183 9079 19183 9064 19184 9208 19184 9223 19184 9072 19185 9102 19185 9092 19185 9079 19186 9091 19186 9058 19186 9069 19187 9209 19187 9157 19187 9080 19188 9220 19188 9221 19188 9603 19189 9335 19189 9336 19189 9342 19190 9400 19190 9595 19190 9238 19191 9596 19191 9400 19191 9400 19192 9596 19192 9401 19192 9401 19193 9237 19193 9236 19193 9239 19194 9591 19194 9397 19194 9551 19195 9263 19195 9232 19195 9297 19196 9457 19196 9459 19196 9297 19197 9459 19197 9457 19197 9295 19198 9455 19198 9460 19198 9295 19199 9460 19199 9455 19199 9444 19200 9428 19200 9323 19200 9323 19201 9428 19201 9444 19201 9239 19202 9442 19202 9404 19202 9404 19203 9442 19203 9239 19203 9588 19204 9346 19204 9291 19204 9359 19205 9253 19205 9248 19205 9370 19206 9357 19206 9359 19206 9248 19207 9249 19207 9362 19207 9362 19208 9250 19208 9234 19208 9375 19209 9426 19209 9380 19209 9420 19210 9484 19210 9329 19210 9420 19211 9329 19211 9422 19211 9194 19212 9593 19212 9345 19212 9236 19213 9237 19213 9344 19213 9344 19214 9237 19214 9343 19214 9236 19215 9590 19215 9239 19215 9442 19216 9590 19216 9344 19216 9344 19217 9590 19217 9236 19217 9342 19218 9595 19218 9390 19218 9335 19219 9238 19219 9400 19219 9335 19220 9400 19220 9342 19220 9238 19221 9335 19221 9596 19221 9596 19222 9335 19222 9343 19222 9401 19223 9596 19223 9343 19223 9401 19224 9343 19224 9237 19224 9239 19225 9590 19225 9442 19225 9442 19226 9591 19226 9239 19226 9591 19227 9442 19227 9334 19227 9591 19228 9334 19228 9397 19228 9345 19229 9397 19229 9334 19229 9397 19230 9345 19230 9411 19230 9411 19231 9345 19231 9593 19231 9240 19232 9385 19232 9242 19232 9242 19233 9385 19233 9243 19233 9385 19234 9240 19234 9241 19234 9385 19235 9241 19235 9414 19235 9244 19236 9241 19236 9240 19236 9244 19237 9240 19237 9242 19237 9244 19238 9242 19238 9245 19238 9245 19239 9242 19239 9243 19239 9245 19240 9243 19240 9246 19240 9246 19241 9243 19241 9386 19241 9246 19242 9386 19242 9379 19242 9244 19243 9373 19243 9241 19243 9245 19244 9247 19244 9244 19244 9246 19245 9372 19245 9371 19245 9379 19246 9372 19246 9246 19246 9371 19247 9247 19247 9245 19247 9371 19248 9245 19248 9246 19248 9244 19249 9247 19249 9373 19249 9377 19250 9241 19250 9373 19250 9370 19251 9356 19251 9357 19251 9357 19252 9358 19252 9359 19252 9253 19253 9360 19253 9248 19253 9248 19254 9360 19254 9361 19254 9248 19255 9361 19255 9249 19255 9362 19256 9363 19256 9250 19256 9250 19257 9255 19257 9234 19257 9370 19258 9347 19258 9356 19258 9356 19259 9347 19259 9349 19259 9356 19260 9349 19260 9251 19260 9356 19261 9251 19261 9357 19261 9357 19262 9251 19262 9252 19262 9357 19263 9252 19263 9358 19263 9358 19264 9252 19264 9359 19264 9359 19265 9252 19265 9338 19265 9359 19266 9338 19266 9253 19266 9253 19267 9338 19267 9337 19267 9253 19268 9337 19268 9360 19268 9360 19269 9337 19269 9339 19269 9360 19270 9339 19270 9361 19270 9361 19271 9339 19271 9249 19271 9249 19272 9339 19272 9254 19272 9249 19273 9254 19273 9340 19273 9249 19274 9340 19274 9362 19274 9362 19275 9340 19275 9363 19275 9363 19276 9340 19276 9341 19276 9363 19277 9341 19277 9250 19277 9250 19278 9341 19278 9255 19278 9255 19279 9341 19279 9233 19279 9329 19280 9325 19280 9257 19280 9329 19281 9257 19281 9256 19281 9257 19282 9325 19282 9259 19282 9257 19283 9259 19283 9256 19283 9256 19284 9259 19284 9424 19284 9259 19285 9260 19285 9424 19285 9424 19286 9260 19286 9426 19286 9426 19287 9260 19287 9258 19287 9321 19288 9258 19288 9260 19288 9325 19289 9320 19289 9316 19289 9325 19290 9316 19290 9259 19290 9259 19291 9316 19291 9315 19291 9259 19292 9315 19292 9260 19292 9317 19293 9260 19293 9315 19293 9317 19294 9321 19294 9260 19294 9446 19295 9261 19295 9314 19295 9314 19296 9261 19296 9431 19296 9314 19297 9431 19297 9387 19297 9314 19298 9387 19298 9445 19298 9311 19299 9543 19299 9570 19299 9311 19300 9570 19300 9232 19300 9232 19301 9570 19301 9551 19301 9263 19302 9551 19302 9576 19302 9263 19303 9576 19303 9453 19303 9453 19304 9576 19304 9547 19304 9453 19305 9547 19305 9231 19305 9231 19306 9547 19306 9309 19306 9231 19307 9309 19307 9507 19307 9294 19308 9398 19308 9399 19308 9294 19309 9399 19309 9618 19309 9618 19310 9399 19310 9266 19310 9399 19311 9402 19311 9266 19311 9266 19312 9402 19312 9616 19312 9616 19313 9402 19313 9403 19313 9403 19314 9404 19314 9616 19314 9616 19315 9404 19315 9615 19315 9615 19316 9404 19316 9405 19316 9615 19317 9405 19317 9264 19317 9264 19318 9405 19318 9407 19318 9264 19319 9407 19319 9408 19319 9264 19320 9408 19320 9605 19320 9539 19321 9271 19321 9265 19321 9539 19322 9265 19322 9534 19322 9534 19323 9265 19323 9529 19323 9529 19324 9265 19324 9266 19324 9529 19325 9266 19325 9511 19325 9529 19326 9511 19326 9541 19326 9541 19327 9511 19327 9510 19327 9541 19328 9510 19328 9585 19328 9585 19329 9510 19329 9615 19329 9585 19330 9615 19330 9267 19330 9267 19331 9615 19331 9515 19331 9267 19332 9515 19332 9528 19332 9528 19333 9515 19333 9286 19333 9566 19334 9520 19334 9519 19334 9566 19335 9519 19335 9562 19335 9562 19336 9519 19336 9577 19336 9562 19337 9577 19337 9569 19337 9569 19338 9577 19338 9268 19338 9569 19339 9268 19339 9558 19339 9558 19340 9268 19340 9575 19340 9575 19341 9268 19341 9522 19341 9575 19342 9522 19342 9553 19342 9553 19343 9522 19343 9526 19343 9553 19344 9526 19344 9557 19344 9557 19345 9526 19345 9269 19345 9544 19346 9571 19346 9556 19346 9544 19347 9556 19347 9552 19347 9270 19348 9536 19348 9579 19348 9270 19349 9579 19349 9580 19349 9598 19350 9468 19350 9597 19350 9597 19351 9468 19351 9232 19351 9597 19352 9232 19352 9463 19352 9600 19353 9471 19353 9602 19353 9271 19354 9617 19354 9508 19354 9614 19355 9620 19355 9512 19355 9517 19356 9276 19356 9607 19356 9517 19357 9607 19357 9516 19357 9511 19358 9622 19358 9272 19358 9272 19359 9622 19359 9273 19359 9272 19360 9273 19360 9277 19360 9277 19361 9273 19361 9621 19361 9512 19362 9620 19362 9274 19362 9274 19363 9620 19363 9619 19363 9274 19364 9619 19364 9275 19364 9275 19365 9619 19365 9617 19365 9516 19366 9611 19366 9513 19366 9513 19367 9611 19367 9609 19367 9514 19368 9612 19368 9517 19368 9508 19369 9617 19369 9610 19369 9508 19370 9610 19370 9266 19370 9511 19371 9266 19371 9622 19371 9517 19372 9612 19372 9276 19372 9516 19373 9607 19373 9606 19373 9516 19374 9606 19374 9611 19374 9513 19375 9609 19375 9614 19375 9275 19376 9617 19376 9271 19376 9277 19377 9621 19377 9615 19377 9615 19378 9612 19378 9514 19378 9454 19379 9471 19379 9600 19379 9597 19380 9463 19380 9599 19380 9599 19381 9463 19381 9468 19381 9599 19382 9468 19382 9598 19382 9578 19383 9531 19383 9278 19383 9278 19384 9531 19384 9537 19384 9278 19385 9537 19385 9523 19385 9523 19386 9537 19386 9585 19386 9279 19387 9542 19387 9280 19387 9280 19388 9542 19388 9540 19388 9280 19389 9540 19389 9524 19389 9524 19390 9540 19390 9538 19390 9584 19391 9535 19391 9279 19391 9279 19392 9535 19392 9542 19392 9580 19393 9530 19393 9582 19393 9527 19394 9525 19394 9536 19394 9230 19395 9561 19395 9550 19395 9550 19396 9561 19396 9281 19396 9550 19397 9281 19397 9586 19397 9586 19398 9281 19398 9575 19398 9282 19399 9554 19399 9546 19399 9546 19400 9554 19400 9567 19400 9546 19401 9567 19401 9229 19401 9229 19402 9567 19402 9565 19402 9574 19403 9564 19403 9282 19403 9282 19404 9564 19404 9554 19404 9572 19405 9283 19405 9571 19405 9557 19406 9269 19406 9284 19406 9557 19407 9284 19407 9555 19407 9555 19408 9284 19408 9285 19408 9555 19409 9285 19409 9563 19409 9563 19410 9285 19410 9583 19410 9563 19411 9583 19411 9560 19411 9560 19412 9583 19412 9518 19412 9560 19413 9518 19413 9521 19413 9560 19414 9521 19414 9568 19414 9568 19415 9521 19415 9520 19415 9568 19416 9520 19416 9566 19416 9528 19417 9286 19417 9287 19417 9528 19418 9287 19418 9581 19418 9581 19419 9287 19419 9288 19419 9581 19420 9288 19420 9583 19420 9583 19421 9288 19421 9512 19421 9583 19422 9512 19422 9289 19422 9289 19423 9512 19423 9533 19423 9533 19424 9512 19424 9509 19424 9533 19425 9509 19425 9271 19425 9533 19426 9271 19426 9539 19426 9605 19427 9408 19427 9406 19427 9605 19428 9406 19428 9608 19428 9608 19429 9406 19429 9409 19429 9608 19430 9409 19430 9606 19430 9606 19431 9409 19431 9290 19431 9606 19432 9290 19432 9609 19432 9609 19433 9290 19433 9291 19433 9609 19434 9291 19434 9613 19434 9613 19435 9291 19435 9292 19435 9292 19436 9291 19436 9293 19436 9292 19437 9293 19437 9294 19437 9294 19438 9293 19438 9398 19438 9448 19439 9473 19439 9501 19439 9451 19440 9295 19440 9478 19440 9478 19441 9295 19441 9331 19441 9331 19442 9295 19442 9479 19442 9479 19443 9295 19443 9296 19443 9479 19444 9296 19444 9297 19444 9297 19445 9450 19445 9479 19445 9450 19446 9498 19446 9479 19446 9479 19447 9498 19447 9489 19447 9299 19448 9477 19448 9300 19448 9300 19449 9477 19449 9489 19449 9300 19450 9489 19450 9498 19450 9306 19451 9305 19451 9304 19451 9499 19452 9301 19452 9302 19452 9301 19453 9499 19453 9487 19453 9298 19454 9477 19454 9308 19454 9477 19455 9298 19455 9485 19455 9501 19456 9301 19456 9487 19456 9447 19457 9503 19457 9298 19457 9298 19458 9449 19458 9447 19458 9299 19459 9307 19459 9477 19459 9477 19460 9307 19460 9308 19460 9307 19461 9299 19461 9300 19461 9302 19462 9451 19462 9478 19462 9451 19463 9302 19463 9301 19463 9303 19464 9448 19464 9501 19464 9303 19465 9501 19465 9304 19465 9304 19466 9501 19466 9487 19466 9487 19467 9499 19467 9302 19467 9487 19468 9302 19468 9478 19468 9305 19469 9306 19469 9448 19469 9303 19470 9304 19470 9305 19470 9303 19471 9305 19471 9448 19471 9448 19472 9503 19472 9447 19472 9306 19473 9503 19473 9448 19473 9306 19474 9485 19474 9503 19474 9503 19475 9485 19475 9298 19475 9449 19476 9298 19476 9308 19476 9449 19477 9308 19477 9307 19477 9507 19478 9309 19478 9548 19478 9549 19479 9563 19479 9310 19479 9310 19480 9563 19480 9545 19480 9310 19481 9545 19481 9506 19481 9506 19482 9545 19482 9505 19482 9505 19483 9545 19483 9543 19483 9505 19484 9543 19484 9311 19484 9446 19485 9445 19485 9312 19485 9446 19486 9312 19486 9262 19486 9446 19487 9262 19487 9261 19487 9446 19488 9314 19488 9445 19488 9316 19489 9320 19489 9314 19489 9413 19490 9314 19490 9446 19490 9413 19491 9446 19491 9313 19491 9317 19492 9314 19492 9413 19492 9315 19493 9314 19493 9317 19493 9315 19494 9316 19494 9314 19494 9446 19495 9314 19495 9320 19495 9446 19496 9319 19496 9313 19496 9446 19497 9320 19497 9319 19497 9321 19498 9317 19498 9413 19498 9413 19499 9318 19499 9321 19499 9313 19500 9318 19500 9413 19500 9319 19501 9318 19501 9313 19501 9319 19502 9322 19502 9318 19502 9322 19503 9319 19503 9320 19503 9322 19504 9320 19504 9325 19504 9332 19505 9258 19505 9321 19505 9332 19506 9321 19506 9318 19506 9332 19507 9318 19507 9443 19507 9443 19508 9318 19508 9323 19508 9318 19509 9322 19509 9323 19509 9323 19510 9322 19510 9324 19510 9324 19511 9322 19511 9325 19511 9416 19512 9326 19512 9601 19512 9416 19513 9601 19513 9415 19513 9332 19514 9443 19514 9235 19514 9235 19515 9443 19515 9415 19515 9600 19516 9415 19516 9601 19516 9415 19517 9600 19517 9235 19517 9493 19518 9332 19518 9480 19518 9416 19519 9597 19519 9326 19519 9327 19520 9597 19520 9416 19520 9329 19521 9418 19521 9324 19521 9484 19522 9418 19522 9329 19522 9329 19523 9256 19523 9328 19523 9331 19524 9481 19524 9424 19524 9424 19525 9481 19525 9256 19525 9481 19526 9333 19526 9330 19526 9493 19527 9258 19527 9332 19527 9493 19528 9331 19528 9425 19528 9425 19529 9331 19529 9424 19529 9416 19530 9323 19530 9324 19530 9418 19531 9484 19531 9327 19531 9327 19532 9484 19532 9597 19532 9597 19533 9484 19533 9598 19533 9330 19534 9333 19534 9328 19534 9235 19535 9600 19535 9480 19535 9235 19536 9480 19536 9332 19536 9443 19537 9323 19537 9415 19537 9328 19538 9256 19538 9330 19538 9328 19539 9333 19539 9420 19539 9420 19540 9333 19540 9484 19540 9434 19541 9442 19541 9344 19541 9434 19542 9344 19542 9435 19542 9434 19543 9351 19543 9442 19543 9442 19544 9351 19544 9433 19544 9442 19545 9433 19545 9334 19545 9334 19546 9433 19546 9350 19546 9343 19547 9436 19547 9435 19547 9436 19548 9343 19548 9437 19548 9437 19549 9343 19549 9335 19549 9437 19550 9335 19550 9438 19550 9438 19551 9335 19551 9336 19551 9438 19552 9336 19552 9439 19552 9439 19553 9336 19553 9349 19553 9439 19554 9349 19554 9347 19554 9396 19555 9251 19555 9349 19555 9337 19556 9338 19556 9346 19556 9346 19557 9338 19557 9252 19557 9346 19558 9252 19558 9396 19558 9396 19559 9252 19559 9251 19559 9254 19560 9339 19560 9392 19560 9254 19561 9392 19561 9340 19561 9340 19562 9392 19562 9393 19562 9340 19563 9393 19563 9341 19563 9432 19564 9255 19564 9233 19564 9432 19565 9233 19565 9604 19565 9604 19566 9233 19566 9341 19566 9604 19567 9341 19567 9393 19567 9432 19568 9604 19568 9194 19568 9342 19569 9349 19569 9336 19569 9336 19570 9335 19570 9342 19570 9344 19571 9343 19571 9435 19571 9432 19572 9345 19572 9334 19572 9432 19573 9334 19573 9350 19573 9194 19574 9345 19574 9432 19574 9388 19575 9440 19575 9392 19575 9388 19576 9392 19576 9339 19576 9339 19577 9337 19577 9388 19577 9388 19578 9337 19578 9346 19578 9348 19579 9396 19579 9349 19579 9342 19580 9390 19580 9349 19580 9348 19581 9349 19581 9391 19581 9391 19582 9349 19582 9390 19582 9367 19583 9255 19583 9432 19583 9367 19584 9432 19584 9364 19584 9364 19585 9432 19585 9350 19585 9364 19586 9350 19586 9365 19586 9365 19587 9350 19587 9433 19587 9365 19588 9433 19588 9366 19588 9366 19589 9433 19589 9427 19589 9427 19590 9433 19590 9351 19590 9427 19591 9351 19591 9368 19591 9368 19592 9351 19592 9430 19592 9430 19593 9351 19593 9434 19593 9430 19594 9434 19594 9352 19594 9352 19595 9434 19595 9353 19595 9353 19596 9434 19596 9435 19596 9353 19597 9435 19597 9354 19597 9354 19598 9435 19598 9436 19598 9354 19599 9436 19599 9437 19599 9354 19600 9437 19600 9369 19600 9369 19601 9437 19601 9438 19601 9369 19602 9438 19602 9355 19602 9355 19603 9438 19603 9370 19603 9370 19604 9438 19604 9439 19604 9370 19605 9439 19605 9347 19605 9234 19606 9255 19606 9367 19606 9234 19607 9367 19607 9365 19607 9365 19608 9367 19608 9364 19608 9365 19609 9366 19609 9427 19609 9427 19610 9368 19610 9430 19610 9428 19611 9430 19611 9352 19611 9428 19612 9352 19612 9353 19612 9428 19613 9353 19613 9429 19613 9429 19614 9353 19614 9354 19614 9429 19615 9354 19615 9369 19615 9429 19616 9369 19616 9374 19616 9374 19617 9369 19617 9355 19617 9374 19618 9355 19618 9370 19618 9428 19619 9365 19619 9430 19619 9371 19620 9372 19620 9365 19620 9371 19621 9365 19621 9428 19621 9371 19622 9428 19622 9247 19622 9429 19623 9374 19623 9428 19623 9378 19624 9362 19624 9375 19624 9375 19625 9362 19625 9234 19625 9375 19626 9234 19626 9372 19626 9372 19627 9234 19627 9365 19627 9374 19628 9373 19628 9247 19628 9378 19629 9248 19629 9362 19629 9377 19630 9359 19630 9376 19630 9428 19631 9374 19631 9247 19631 9248 19632 9378 19632 9376 19632 9359 19633 9248 19633 9376 19633 9359 19634 9377 19634 9370 19634 9373 19635 9374 19635 9370 19635 9373 19636 9370 19636 9377 19636 9380 19637 9375 19637 9379 19637 9380 19638 9378 19638 9375 19638 9381 19639 9378 19639 9380 19639 9383 19640 9377 19640 9376 19640 9241 19641 9377 19641 9383 19641 9376 19642 9381 19642 9383 19642 9376 19643 9378 19643 9381 19643 9372 19644 9379 19644 9375 19644 9379 19645 9386 19645 9384 19645 9379 19646 9384 19646 9380 19646 9380 19647 9384 19647 9412 19647 9380 19648 9412 19648 9381 19648 9381 19649 9412 19649 9382 19649 9381 19650 9382 19650 9383 19650 9383 19651 9382 19651 9414 19651 9383 19652 9414 19652 9241 19652 9414 19653 9382 19653 9412 19653 9412 19654 9384 19654 9386 19654 9414 19655 9262 19655 9385 19655 9262 19656 9414 19656 9261 19656 9261 19657 9414 19657 9412 19657 9412 19658 9386 19658 9431 19658 9412 19659 9431 19659 9261 19659 9385 19660 9262 19660 9312 19660 9385 19661 9312 19661 9243 19661 9431 19662 9386 19662 9243 19662 9431 19663 9243 19663 9445 19663 9431 19664 9445 19664 9387 19664 9312 19665 9445 19665 9243 19665 9604 19666 9592 19666 9194 19666 9410 19667 9594 19667 9588 19667 9594 19668 9388 19668 9346 19668 9410 19669 9389 19669 9388 19669 9410 19670 9388 19670 9594 19670 9388 19671 9389 19671 9440 19671 9595 19672 9391 19672 9390 19672 9348 19673 9391 19673 9595 19673 9592 19674 9593 19674 9194 19674 9587 19675 9592 19675 9604 19675 9587 19676 9604 19676 9393 19676 9587 19677 9393 19677 9392 19677 9392 19678 9440 19678 9394 19678 9394 19679 9440 19679 9389 19679 9588 19680 9594 19680 9346 19680 9346 19681 9395 19681 9588 19681 9395 19682 9346 19682 9396 19682 9395 19683 9396 19683 9589 19683 9589 19684 9396 19684 9348 19684 9589 19685 9348 19685 9441 19685 9441 19686 9348 19686 9595 19686 9589 19687 9293 19687 9588 19687 9397 19688 9405 19688 9239 19688 9406 19689 9587 19689 9409 19689 9290 19690 9410 19690 9291 19690 9291 19691 9588 19691 9293 19691 9293 19692 9441 19692 9398 19692 9400 19693 9399 19693 9595 19693 9595 19694 9399 19694 9398 19694 9399 19695 9400 19695 9402 19695 9402 19696 9400 19696 9401 19696 9402 19697 9401 19697 9403 19697 9403 19698 9401 19698 9236 19698 9404 19699 9403 19699 9239 19699 9236 19700 9239 19700 9403 19700 9405 19701 9404 19701 9239 19701 9405 19702 9397 19702 9407 19702 9407 19703 9411 19703 9408 19703 9587 19704 9406 19704 9593 19704 9593 19705 9406 19705 9408 19705 9411 19706 9407 19706 9397 19706 9408 19707 9411 19707 9593 19707 9394 19708 9410 19708 9290 19708 9587 19709 9394 19709 9409 19709 9409 19710 9394 19710 9290 19710 9291 19711 9410 19711 9588 19711 9441 19712 9595 19712 9398 19712 9589 19713 9441 19713 9293 19713 9323 19714 9416 19714 9444 19714 9444 19715 9416 19715 9415 19715 9444 19716 9415 19716 9323 19716 9417 19717 9332 19717 9235 19717 9417 19718 9235 19718 9332 19718 9419 19719 9324 19719 9418 19719 9327 19720 9416 19720 9324 19720 9327 19721 9324 19721 9419 19721 9419 19722 9418 19722 9327 19722 9422 19723 9329 19723 9328 19723 9422 19724 9328 19724 9421 19724 9421 19725 9328 19725 9420 19725 9420 19726 9422 19726 9421 19726 9423 19727 9256 19727 9481 19727 9423 19728 9330 19728 9256 19728 9423 19729 9481 19729 9330 19729 9426 19730 9258 19730 9425 19730 9425 19731 9258 19731 9493 19731 9426 19732 9425 19732 9424 19732 9426 19733 9375 19733 9380 19733 9430 19734 9365 19734 9427 19734 9291 19735 9346 19735 9588 19735 9325 19736 9329 19736 9324 19736 9462 19737 9301 19737 9501 19737 9462 19738 9501 19738 9472 19738 9447 19739 9469 19739 9448 19739 9470 19740 9448 19740 9469 19740 9467 19741 9449 19741 9466 19741 9466 19742 9449 19742 9307 19742 9300 19743 9465 19743 9466 19743 9300 19744 9466 19744 9307 19744 9451 19745 9461 19745 9460 19745 9451 19746 9460 19746 9295 19746 9295 19747 9460 19747 9296 19747 9296 19748 9460 19748 9459 19748 9296 19749 9459 19749 9297 19749 9297 19750 9459 19750 9450 19750 9450 19751 9459 19751 9458 19751 9450 19752 9458 19752 9498 19752 9498 19753 9458 19753 9465 19753 9498 19754 9465 19754 9300 19754 9451 19755 9452 19755 9461 19755 9452 19756 9451 19756 9301 19756 9452 19757 9301 19757 9462 19757 9232 19758 9468 19758 9311 19758 9263 19759 9602 19759 9471 19759 9602 19760 9453 19760 9231 19760 9471 19761 9454 19761 9504 19761 9504 19762 9454 19762 9472 19762 9472 19763 9454 19763 9602 19763 9456 19764 9468 19764 9463 19764 9461 19765 9507 19765 9455 19765 9310 19766 9460 19766 9455 19766 9310 19767 9455 19767 9507 19767 9461 19768 9455 19768 9460 19768 9505 19769 9311 19769 9464 19769 9465 19770 9458 19770 9505 19770 9505 19771 9458 19771 9506 19771 9457 19772 9459 19772 9460 19772 9506 19773 9458 19773 9459 19773 9506 19774 9459 19774 9310 19774 9310 19775 9459 19775 9457 19775 9457 19776 9460 19776 9310 19776 9462 19777 9500 19777 9452 19777 9507 19778 9461 19778 9452 19778 9453 19779 9602 19779 9263 19779 9263 19780 9471 19780 9502 19780 9232 19781 9263 19781 9463 19781 9507 19782 9452 19782 9500 19782 9507 19783 9500 19783 9231 19783 9464 19784 9465 19784 9505 19784 9464 19785 9466 19785 9465 19785 9468 19786 9469 19786 9467 19786 9472 19787 9470 19787 9504 19787 9468 19788 9467 19788 9464 19788 9464 19789 9467 19789 9466 19789 9464 19790 9311 19790 9468 19790 9469 19791 9468 19791 9456 19791 9456 19792 9463 19792 9469 19792 9469 19793 9463 19793 9263 19793 9469 19794 9263 19794 9502 19794 9471 19795 9469 19795 9502 19795 9469 19796 9504 19796 9470 19796 9469 19797 9471 19797 9504 19797 9231 19798 9500 19798 9462 19798 9231 19799 9462 19799 9602 19799 9602 19800 9462 19800 9472 19800 9472 19801 9501 19801 9473 19801 9472 19802 9473 19802 9470 19802 9470 19803 9473 19803 9448 19803 9449 19804 9467 19804 9447 19804 9447 19805 9467 19805 9469 19805 9483 19806 9491 19806 9497 19806 9483 19807 9497 19807 9599 19807 9599 19808 9497 19808 9476 19808 9599 19809 9476 19809 9474 19809 9474 19810 9476 19810 9475 19810 9475 19811 9476 19811 9486 19811 9475 19812 9486 19812 9496 19812 9485 19813 9497 19813 9477 19813 9477 19814 9497 19814 9491 19814 9477 19815 9491 19815 9490 19815 9476 19816 9306 19816 9486 19816 9486 19817 9306 19817 9304 19817 9487 19818 9492 19818 9496 19818 9479 19819 9489 19819 9488 19819 9490 19820 9489 19820 9477 19820 9478 19821 9492 19821 9487 19821 9479 19822 9494 19822 9331 19822 9479 19823 9482 19823 9494 19823 9482 19824 9479 19824 9495 19824 9495 19825 9479 19825 9488 19825 9326 19826 9599 19826 9474 19826 9454 19827 9601 19827 9475 19827 9475 19828 9601 19828 9474 19828 9474 19829 9601 19829 9326 19829 9602 19830 9454 19830 9480 19830 9480 19831 9454 19831 9475 19831 9480 19832 9475 19832 9493 19832 9494 19833 9481 19833 9331 19833 9491 19834 9484 19834 9490 19834 9484 19835 9333 19835 9490 19835 9490 19836 9333 19836 9488 19836 9488 19837 9333 19837 9495 19837 9481 19838 9495 19838 9333 19838 9481 19839 9494 19839 9482 19839 9481 19840 9482 19840 9495 19840 9483 19841 9599 19841 9598 19841 9483 19842 9598 19842 9484 19842 9491 19843 9483 19843 9484 19843 9497 19844 9485 19844 9476 19844 9476 19845 9485 19845 9306 19845 9486 19846 9304 19846 9496 19846 9496 19847 9304 19847 9487 19847 9488 19848 9489 19848 9490 19848 9478 19849 9331 19849 9493 19849 9478 19850 9493 19850 9492 19850 9492 19851 9475 19851 9496 19851 9492 19852 9493 19852 9475 19852 9549 19853 9310 19853 9548 19853 9548 19854 9310 19854 9507 19854 9508 19855 9265 19855 9271 19855 9286 19856 9517 19856 9287 19856 9287 19857 9517 19857 9516 19857 9509 19858 9275 19858 9271 19858 9512 19859 9274 19859 9509 19859 9509 19860 9274 19860 9275 19860 9515 19861 9615 19861 9514 19861 9287 19862 9516 19862 9288 19862 9516 19863 9513 19863 9288 19863 9277 19864 9615 19864 9510 19864 9511 19865 9272 19865 9510 19865 9510 19866 9272 19866 9277 19866 9265 19867 9508 19867 9266 19867 9614 19868 9512 19868 9513 19868 9513 19869 9512 19869 9288 19869 9515 19870 9514 19870 9517 19870 9515 19871 9517 19871 9286 19871 9577 19872 9519 19872 9524 19872 9524 19873 9519 19873 9520 19873 9527 19874 9270 19874 9269 19874 9269 19875 9270 19875 9284 19875 9284 19876 9270 19876 9580 19876 9521 19877 9524 19877 9520 19877 9518 19878 9279 19878 9521 19878 9524 19879 9532 19879 9577 19879 9279 19880 9280 19880 9521 19880 9521 19881 9280 19881 9524 19881 9526 19882 9522 19882 9525 19882 9284 19883 9580 19883 9285 19883 9580 19884 9582 19884 9285 19884 9523 19885 9522 19885 9268 19885 9578 19886 9278 19886 9268 19886 9268 19887 9278 19887 9523 19887 9268 19888 9577 19888 9578 19888 9279 19889 9518 19889 9584 19889 9584 19890 9518 19890 9583 19890 9583 19891 9285 19891 9582 19891 9525 19892 9527 19892 9526 19892 9526 19893 9527 19893 9269 19893 9536 19894 9267 19894 9528 19894 9532 19895 9534 19895 9529 19895 9533 19896 9542 19896 9289 19896 9542 19897 9535 19897 9289 19897 9581 19898 9579 19898 9528 19898 9528 19899 9579 19899 9536 19899 9532 19900 9538 19900 9534 19900 9585 19901 9267 19901 9525 19901 9525 19902 9267 19902 9536 19902 9529 19903 9541 19903 9531 19903 9534 19904 9538 19904 9539 19904 9530 19905 9581 19905 9583 19905 9583 19906 9289 19906 9535 19906 9585 19907 9537 19907 9541 19907 9541 19908 9537 19908 9531 19908 9539 19909 9538 19909 9533 19909 9538 19910 9540 19910 9533 19910 9533 19911 9540 19911 9542 19911 9524 19912 9538 19912 9532 19912 9229 19913 9570 19913 9543 19913 9572 19914 9544 19914 9309 19914 9309 19915 9544 19915 9548 19915 9548 19916 9544 19916 9552 19916 9229 19917 9559 19917 9570 19917 9282 19918 9546 19918 9545 19918 9545 19919 9546 19919 9543 19919 9543 19920 9546 19920 9229 19920 9547 19921 9576 19921 9283 19921 9548 19922 9552 19922 9549 19922 9552 19923 9573 19923 9549 19923 9586 19924 9576 19924 9551 19924 9230 19925 9550 19925 9551 19925 9551 19926 9550 19926 9586 19926 9551 19927 9570 19927 9230 19927 9282 19928 9545 19928 9574 19928 9574 19929 9545 19929 9563 19929 9573 19930 9563 19930 9549 19930 9283 19931 9572 19931 9547 19931 9547 19932 9572 19932 9309 19932 9571 19933 9553 19933 9557 19933 9559 19934 9562 19934 9569 19934 9554 19935 9564 19935 9560 19935 9555 19936 9556 19936 9557 19936 9557 19937 9556 19937 9571 19937 9559 19938 9565 19938 9562 19938 9575 19939 9553 19939 9283 19939 9283 19940 9553 19940 9571 19940 9554 19941 9560 19941 9568 19941 9569 19942 9558 19942 9561 19942 9562 19943 9565 19943 9566 19943 9573 19944 9555 19944 9563 19944 9564 19945 9563 19945 9560 19945 9575 19946 9281 19946 9558 19946 9558 19947 9281 19947 9561 19947 9566 19948 9565 19948 9568 19948 9565 19949 9567 19949 9568 19949 9568 19950 9567 19950 9554 19950 9229 19951 9565 19951 9559 19951 9570 19952 9559 19952 9569 19952 9570 19953 9569 19953 9230 19953 9230 19954 9569 19954 9561 19954 9572 19955 9571 19955 9544 19955 9552 19956 9556 19956 9555 19956 9574 19957 9563 19957 9564 19957 9586 19958 9575 19958 9576 19958 9576 19959 9575 19959 9283 19959 9577 19960 9532 19960 9529 19960 9577 19961 9529 19961 9578 19961 9578 19962 9529 19962 9531 19962 9527 19963 9536 19963 9270 19963 9580 19964 9579 19964 9581 19964 9582 19965 9530 19965 9583 19965 9584 19966 9583 19966 9535 19966 9523 19967 9585 19967 9522 19967 9522 19968 9585 19968 9525 19968 9530 19969 9580 19969 9581 19969 9573 19970 9552 19970 9555 19970 9592 19971 9587 19971 9593 19971 9394 19972 9587 19972 9392 19972 9394 19973 9389 19973 9410 19973 9588 19974 9395 19974 9589 19974 9599 19975 9326 19975 9597 19975 9600 19976 9601 19976 9454 19976 9602 19977 9480 19977 9600 19977 9603 19978 9336 19978 9335 19978 9276 19979 9264 19979 9605 19979 9264 19980 9276 19980 9612 19980 9608 19981 9606 19981 9607 19981 9608 19982 9607 19982 9276 19982 9608 19983 9276 19983 9605 19983 9266 19984 9610 19984 9618 19984 9620 19985 9613 19985 9292 19985 9620 19986 9614 19986 9613 19986 9610 19987 9617 19987 9618 19987 9611 19988 9606 19988 9609 19988 9614 19989 9609 19989 9613 19989 9621 19990 9616 19990 9615 19990 9615 19991 9264 19991 9612 19991 9266 19992 9616 19992 9622 19992 9618 19993 9617 19993 9294 19993 9617 19994 9619 19994 9294 19994 9294 19995 9619 19995 9292 19995 9616 19996 9273 19996 9622 19996 9621 19997 9273 19997 9616 19997 9292 19998 9619 19998 9620 19998

+
+
+
+
+ + + + + + + + + + + + + + +
diff --git a/descriptions/deep_robotics/x30_description/package.xml b/descriptions/deep_robotics/x30_description/package.xml new file mode 100644 index 0000000..d13b3ad --- /dev/null +++ b/descriptions/deep_robotics/x30_description/package.xml @@ -0,0 +1,18 @@ + + + x30_description + 0.0.0 + The x30_description package + + ZhenyuXu + MIT + + xacro + joint_state_publisher + robot_state_publisher + imu_sensor_broadcaster + + ament_cmake + + + diff --git a/descriptions/deep_robotics/x30_description/urdf/robot.urdf b/descriptions/deep_robotics/x30_description/urdf/robot.urdf new file mode 100755 index 0000000..27d7ef8 --- /dev/null +++ b/descriptions/deep_robotics/x30_description/urdf/robot.urdf @@ -0,0 +1,481 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/descriptions/deep_robotics/x30_description/xacro/body.xacro b/descriptions/deep_robotics/x30_description/xacro/body.xacro new file mode 100644 index 0000000..4aa55df --- /dev/null +++ b/descriptions/deep_robotics/x30_description/xacro/body.xacro @@ -0,0 +1,474 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/descriptions/deep_robotics/x30_description/xacro/gazebo.xacro b/descriptions/deep_robotics/x30_description/xacro/gazebo.xacro new file mode 100644 index 0000000..74a9cdd --- /dev/null +++ b/descriptions/deep_robotics/x30_description/xacro/gazebo.xacro @@ -0,0 +1,195 @@ + + + + + + gz_ros2_control/GazeboSimSystem + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + $(find x30_description)/config/gazebo.yaml + + + + + + + 0.6 + 0.6 + 1 + + + .05 .05 .05 1.0 + .05 .05 .05 1.0 + .05 .05 .05 1.0 + + + + + + + 1 + 500 + true + imu + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + + + diff --git a/descriptions/deep_robotics/x30_description/xacro/imu_link.xacro b/descriptions/deep_robotics/x30_description/xacro/imu_link.xacro new file mode 100644 index 0000000..b90aa0a --- /dev/null +++ b/descriptions/deep_robotics/x30_description/xacro/imu_link.xacro @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/descriptions/deep_robotics/x30_description/xacro/materials.xacro b/descriptions/deep_robotics/x30_description/xacro/materials.xacro new file mode 100644 index 0000000..e99425d --- /dev/null +++ b/descriptions/deep_robotics/x30_description/xacro/materials.xacro @@ -0,0 +1,36 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/descriptions/deep_robotics/x30_description/xacro/robot.xacro b/descriptions/deep_robotics/x30_description/xacro/robot.xacro new file mode 100644 index 0000000..b933077 --- /dev/null +++ b/descriptions/deep_robotics/x30_description/xacro/robot.xacro @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/descriptions/deep_robotics/x30_description/xacro/ros2_control.xacro b/descriptions/deep_robotics/x30_description/xacro/ros2_control.xacro new file mode 100644 index 0000000..3154c41 --- /dev/null +++ b/descriptions/deep_robotics/x30_description/xacro/ros2_control.xacro @@ -0,0 +1,176 @@ + + + + + + + hardware_unitree_mujoco/HardwareUnitree + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/descriptions/deep_robotics/x30_description/xacro/transmission.xacro b/descriptions/deep_robotics/x30_description/xacro/transmission.xacro new file mode 100644 index 0000000..c1769d2 --- /dev/null +++ b/descriptions/deep_robotics/x30_description/xacro/transmission.xacro @@ -0,0 +1,129 @@ + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + +