diff --git a/aerial_robot/package.xml b/aerial_robot/package.xml index 779d323cd..532a16b4d 100644 --- a/aerial_robot/package.xml +++ b/aerial_robot/package.xml @@ -20,6 +20,7 @@ dragon hydrus hydrus_xi + mini_quadrotor motor_test spinal python-is-python3 diff --git a/aerial_robot_base/config/sensors/imu/spinal.yaml b/aerial_robot_base/config/sensors/imu/spinal.yaml new file mode 100644 index 000000000..a3a92f89f --- /dev/null +++ b/aerial_robot_base/config/sensors/imu/spinal.yaml @@ -0,0 +1,9 @@ +sensor_plugin: + imu: + imu_topic_name: imu + level_acc_noise_sigma: 0.05 + z_acc_noise_sigma: 0.05 + level_acc_bias_noise_sigma: 0.001 # (> 0 means to do the acc bias estimation by kalman filter) + z_acc_bias_noise_sigma: 0.001 # (= 0 means not to do the acc bias estimation by kalman filter) + angle_bias_noise_sigma: 0.0002 #good for EKF + calib_time: 2.0 diff --git a/robots/mini_quadrotor/CMakeLists.txt b/robots/mini_quadrotor/CMakeLists.txt new file mode 100644 index 000000000..46145fb0d --- /dev/null +++ b/robots/mini_quadrotor/CMakeLists.txt @@ -0,0 +1,18 @@ +cmake_minimum_required(VERSION 3.0.2) +project(mini_quadrotor) + +find_package(catkin REQUIRED) + +catkin_package( + CATKIN_DEPENDS aerial_robot_control aerial_robot_estimation aerial_robot_model +) + +install(DIRECTORY config launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + USE_SOURCE_PERMISSIONS +) + +if(CATKIN_ENABLE_TESTING) + find_package(rostest REQUIRED) + add_subdirectory(test) +endif() diff --git a/robots/mini_quadrotor/config/Battery.yaml b/robots/mini_quadrotor/config/Battery.yaml new file mode 100644 index 000000000..cc7a84066 --- /dev/null +++ b/robots/mini_quadrotor/config/Battery.yaml @@ -0,0 +1,5 @@ +bat_info: + bat_cell: 3 + bat_resistance: 0.04 # [m Ohm] + hovering_current: 15 #[A] + low_voltage_thre: 10 #[100%] diff --git a/robots/mini_quadrotor/config/FlightControl.yaml b/robots/mini_quadrotor/config/FlightControl.yaml new file mode 100644 index 000000000..b1e1fe000 --- /dev/null +++ b/robots/mini_quadrotor/config/FlightControl.yaml @@ -0,0 +1,54 @@ +aerial_robot_control_name: aerial_robot_control/under_actuated_tilted_lqi_controller + +controller: + xy: + p_gain: 5.0 + i_gain: 0.05 + d_gain: 3.0 + limit_sum: 3 + limit_p: 3 + limit_i: 1.5 + limit_d: 3 + + z: + p_gain: 5.0 + i_gain: 2.5 + d_gain: 5.0 + limit_err_p: 1.0 + limit_sum: 10 # N for clamping thrust force + limit_p: 20 # m / s^2 + limit_i: 40 # m / s^2 + limit_d: 20 # m / s^2 + landing_err_z: -0.2 + force_landing_descending_rate: -0.6 + + yaw: + limit_sum: 6.0 # N for clamping thrust force + limit_p: 4.0 + limit_i: 4.0 + limit_d: 4.0 + limit_err_p: 0.4 + need_d_control: false + + # LQI gain generator + lqi: + gain_generate_rate: 15.0 + gyro_moment_compensation: true + clamp_gain: true + + roll_pitch_p: 20 + roll_pitch_i: 0.5 + roll_pitch_d: 0.15 + + yaw_p: 60 + yaw_i: 0.5 + yaw_d: 1.0 + + r1: 1.0 + r2: 1.0 + r3: 1.0 + r4: 1.0 + + trans_constraint_weight: 100 + att_control_weight: 1 + diff --git a/robots/mini_quadrotor/config/MotorInfo.yaml b/robots/mini_quadrotor/config/MotorInfo.yaml new file mode 100644 index 000000000..05d69dada --- /dev/null +++ b/robots/mini_quadrotor/config/MotorInfo.yaml @@ -0,0 +1,24 @@ +motor_info: # TODO: update + min_pwm: 0.6 # 1200 [ms] + max_pwm: 0.975 # 1950 [ms] + min_thrust: 0 # [N] + force_landing_thrust: 1.0 #[N] + pwm_conversion_mode: 1 # Polynominal Mode + vel_ref_num: 2 + ref1: + voltage: 11 + max_thrust: 7.2 # N + polynominal4: -168.952346 # -0.0168952346 x10^4 + polynominal3: 308.7473666 # 0.3087473666 x10^3 + polynominal2: -203.28702334 # -2.0328702334 x10^2 + polynominal1: 106.787265636 # 10.6787265636 x10 + polynominal0: 56.3518258750 # 56.3518258750 x1 + ref2: + voltage: 12 + max_thrust: 8.0 # N + polynominal4: -39.838825 # -0.0039838825 x10^4 + polynominal3: 112.1897517 # 0.1121897517 x10^3 + polynominal2: -101.84075291 # -1.0184075291 x10^2 + polynominal1: 81.582961230 # 8.1582961230 x10 + polynominal0: 56.9010618089 # 56.9010618089 x1 + diff --git a/robots/mini_quadrotor/config/NavigationConfig.yaml b/robots/mini_quadrotor/config/NavigationConfig.yaml new file mode 100644 index 000000000..9431be56e --- /dev/null +++ b/robots/mini_quadrotor/config/NavigationConfig.yaml @@ -0,0 +1,30 @@ +# Teleop Basic Param + +navigation: + xy_control_mode: 0 + # World Pos Control Mode: 0 + # World Vel Control Mode: 2 + # Local Vel Control Mode: 3 + # Attitude Control Mode: 4 + + + takeoff_height: 1.0 #1.0 + outdoor_takeoff_height: 1.5 + + # teleop operation + max_target_vel: 0.5 + joy_target_vel_interval: 0.005 # 0.2 / 20 = 0.01, 0.005 ~ 0.01 m/s + joy_target_z_interval: 0.02 + max_target_yaw_rate: 0.1 # 0.05 + teleop_local_frame: fc + + cmd_vel_lev2_gain : 2.0 + nav_vel_limit : 1.0 + + gain_tunning_mode: 0 + max_target_tilt_angle: 0.2 + cmd_angle_lev2_gain : 1.5 + + # gps waypoint + gps_waypoint_threshold: 3.0 + gps_waypoint_check_du: 1.0 diff --git a/robots/mini_quadrotor/config/RobotModel.yaml b/robots/mini_quadrotor/config/RobotModel.yaml new file mode 100644 index 000000000..2df0aa340 --- /dev/null +++ b/robots/mini_quadrotor/config/RobotModel.yaml @@ -0,0 +1,11 @@ +# robot model plugin +robot_model_plugin_name: multirotor_robot_model + +wrench_mat_det_thre: 0 + +# feasible control configuration +fc_t_min_thre: 0.01 +fc_rp_min_thre: 1.8 +rp_position_margin_thre: 0.13 # deprecated + + diff --git a/robots/mini_quadrotor/config/RvizInit.yaml b/robots/mini_quadrotor/config/RvizInit.yaml new file mode 100644 index 000000000..b3bbaabd4 --- /dev/null +++ b/robots/mini_quadrotor/config/RvizInit.yaml @@ -0,0 +1,9 @@ +zeros: + rotor1: 0 + rotor2: 0 + rotor3: 0 + rotor4: 0 + rotor5: 0 + rotor6: 0 + rotor7: 0 + rotor8: 0 \ No newline at end of file diff --git a/robots/mini_quadrotor/config/Simulation.yaml b/robots/mini_quadrotor/config/Simulation.yaml new file mode 100644 index 000000000..0d17670f5 --- /dev/null +++ b/robots/mini_quadrotor/config/Simulation.yaml @@ -0,0 +1,28 @@ +# overwrite parameter for simulation + +sensor_plugin: + mocap: + ground_truth_sub_name: ground_truth + gps: + estimate_mode: 4 #1 << 2 + ned_flag: true # hector_gazebo_plugins/GPS + +# ground truth parameter +# global namespace +simulation: + # gaussian noise + ground_truth_pos_noise: 0.001 + ground_truth_vel_noise: 0.005 + ground_truth_rot_noise: 0.001 + ground_truth_angular_noise: 0.005 + + # drift model: e^(-dt * drift_frequency) * curr_drift + dt * gaussian_kernel(sqrt( 2 * drift_frequency) * drfit)) + # drift diviation: + ground_truth_vel_drift: 0 + ground_truth_rot_drift: 0 + ground_truth_angular_drift: 0 + + # drift frequency: + ground_truth_vel_drift_frequency: 0 + ground_truth_rot_drift_frequency: 0 + ground_truth_angular_drift_frequency: 0 diff --git a/robots/mini_quadrotor/config/StateEstimation.yaml b/robots/mini_quadrotor/config/StateEstimation.yaml new file mode 100644 index 000000000..2dc2b44ef --- /dev/null +++ b/robots/mini_quadrotor/config/StateEstimation.yaml @@ -0,0 +1,47 @@ +# Sensor Fuser Loader +estimation: + # sensor plugin + sensor_list: + - sensor_plugin/imu + - sensor_plugin/mocap + + # egomotion estimation + egomotion_list: + - kalman_filter/kf_pos_vel_acc + - kalman_filter/kf_pos_vel_acc + - kalman_filter/kf_pos_vel_acc + + # experiment estimation + experiment_list: + - kalman_filter/kf_pos_vel_acc + - kalman_filter/kf_pos_vel_acc + - kalman_filter/kf_pos_vel_acc + + # specific id(int) of sensor fuser, axis for kf + fuser_egomotion_id1: 8 # 1 << 3 + fuser_egomotion_id2: 16 # 1 << 4 + fuser_egomotion_id3: 32 # 1 << 5 + + fuser_experiment_id1: 8 # 1 << 3 + fuser_experiment_id2: 16 # 1 << 4 + fuser_experiment_id3: 32 # 1 << 5 + + # specific name of sensor fuser + fuser_egomotion_name1: /ee/x + fuser_egomotion_name2: /ee/y + fuser_egomotion_name3: /ee/z + + fuser_experiment_name1: /ex/x + fuser_experiment_name2: /ex/y + fuser_experiment_name3: /ex/z + + +# EGOMOTION_ESTIMATION_MODE = 0 +# EXPERIMENT_MODE = 1 +# GROUND_TRUTH_MODE = 2 + +sensor_plugin: + imu: + estimate_mode: 3 # 1<<0 + 1<<1 + mocap: + estimate_mode: 6 # 1<<1 + 1<<2 diff --git a/robots/mini_quadrotor/config/rviz_config b/robots/mini_quadrotor/config/rviz_config new file mode 100644 index 000000000..246418020 --- /dev/null +++ b/robots/mini_quadrotor/config/rviz_config @@ -0,0 +1,226 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /TF1 + - /RobotModel1 + Splitter Ratio: 0.5 + Tree Height: 539 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Name: Time + SyncMode: 0 + SyncSource: "" +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: rviz/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: true + quadrotor/battery: + Value: true + quadrotor/cog: + Value: true + quadrotor/fc: + Value: true + quadrotor/main_body: + Value: true + quadrotor/root: + Value: true + quadrotor/thrust1: + Value: true + quadrotor/thrust2: + Value: true + quadrotor/thrust3: + Value: true + quadrotor/thrust4: + Value: true + world: + Value: true + Marker Alpha: 1 + Marker Scale: 0.30000001192092896 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + world: + quadrotor/root: + quadrotor/cog: + {} + quadrotor/main_body: + quadrotor/battery: + {} + quadrotor/fc: + {} + quadrotor/thrust1: + {} + quadrotor/thrust2: + {} + quadrotor/thrust3: + {} + quadrotor/thrust4: + {} + Update Interval: 0 + Value: true + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + battery: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fc: + Alpha: 1 + Show Axes: false + Show Trail: false + main_body: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + root: + Alpha: 1 + Show Axes: false + Show Trail: false + thrust1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + thrust2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + thrust3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + thrust4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + Robot Description: quadrotor/robot_description + TF Prefix: quadrotor + Update Interval: 0 + Value: true + Visual Enabled: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: world + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 0.6198296546936035 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 + Focal Point: + X: 0.11685173213481903 + Y: 0.015681469812989235 + Z: -0.10268925130367279 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.1597973108291626 + Target Frame: + Yaw: 2.920400381088257 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 836 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd00000004000000000000016a000002a6fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002a6000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002a6fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002a6000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005f80000003efc0100000002fb0000000800540069006d00650100000000000005f8000003bc00fffffffb0000000800540069006d0065010000000000000450000000000000000000000373000002a600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1528 + X: 72 + Y: 27 diff --git a/robots/mini_quadrotor/launch/bringup.launch b/robots/mini_quadrotor/launch/bringup.launch new file mode 100644 index 000000000..0730937ab --- /dev/null +++ b/robots/mini_quadrotor/launch/bringup.launch @@ -0,0 +1,93 @@ + + + ########### launch config ########### + + + + + + + + + + + + + + + + + + + + ########### Parameters ########### + + + ########### Basic Param ########### + # EGOMOTION_ESTIMATE = 0 + # EXPERIMENT_ESTIMATE = 1. for unstable mocap, use this mode + # GROUND_TRUTH = 2 + + + + + + + ########### Motor Config ########### + + + ########### Battery Config ########### + + + ########### Control ########### + + + ########### Sensor Fusion ########### + + + + ########### Navigation ########### + + + + ########### Base Platform ########### + + + + + + + ########### Robot Model ########### + + + + + + + + + + + + + ########### Sensors ########### + + + + + + + ########## Simulation in Gazebo ######### + + + + + + + + + + + + + diff --git a/robots/mini_quadrotor/launch/includes/sensors.launch.xml b/robots/mini_quadrotor/launch/includes/sensors.launch.xml new file mode 100644 index 000000000..50075cd09 --- /dev/null +++ b/robots/mini_quadrotor/launch/includes/sensors.launch.xml @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/robots/mini_quadrotor/package.xml b/robots/mini_quadrotor/package.xml new file mode 100644 index 000000000..a6eb1696d --- /dev/null +++ b/robots/mini_quadrotor/package.xml @@ -0,0 +1,23 @@ + + + mini_quadrotor + 1.3.2 + The basic packages for mini quadrotor + + Bakui Chou + BSD + https://github.com/JSKAerialRobot/aerial_robot + Bakui Chou + + catkin + + aerial_robot_base + aerial_robot_control + aerial_robot_estimation + aerial_robot_model + aerial_robot_msgs + aerial_robot_simulation + + rostest + + diff --git a/robots/mini_quadrotor/test/CMakeLists.txt b/robots/mini_quadrotor/test/CMakeLists.txt new file mode 100644 index 000000000..4cf080779 --- /dev/null +++ b/robots/mini_quadrotor/test/CMakeLists.txt @@ -0,0 +1 @@ +add_rostest(flight_control.test ARGS headless:=true) diff --git a/robots/mini_quadrotor/test/flight_control.test b/robots/mini_quadrotor/test/flight_control.test new file mode 100644 index 000000000..646b531fc --- /dev/null +++ b/robots/mini_quadrotor/test/flight_control.test @@ -0,0 +1,32 @@ + + + + + + + + + + + + + + + + + topics: + - name: uav/cog/odom + timeout: 5.0 + + + + + + + hovering_delay: 5.0 + hovering_duration: 10.0 + convergence_thresholds: [0.02, 0.02, 0.02] # hovering threshold + + + + diff --git a/robots/mini_quadrotor/urdf/mesh/main_body.dae b/robots/mini_quadrotor/urdf/mesh/main_body.dae new file mode 100644 index 000000000..873a9144e --- /dev/null +++ b/robots/mini_quadrotor/urdf/mesh/main_body.dae @@ -0,0 +1,224 @@ + + + + + Blender User + Blender 3.0.1 commit date:2022-01-25, commit time:17:19, hash:dc2d18018171 + + 2022-12-17T11:01:08 + 2022-12-17T11:01:08 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0.00111109 + + + + + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + 0 + 1000 + 29.99998 + 75 + 0.15 + 0 + 1 + 2 + 0.04999995 + 30.002 + 1 + 3 + 2880 + 3 + 1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 1 0 0 1 + + + 0.5 + + + + + + + + + + + 0 0 0 1 + + + 0.04202906 0.04202906 0.04202906 1 + + + 0.5 + + + + + + + + + + + + + + + + + + + + -67.6807 -83.8171 4 -67.14727 -84.59965 4 -66.93825 -84.96327 4 -72.62995 -83.74659 4 -73.18547 -84.51363 4 -73.16667 -83.19436 4 -51.61468 -69.78584 4 -52.95014 -69.50035 4 -52.93643 -68.53826 4 -54.38531 -76.21417 4 -53.04986 -76.49964 4 -53.05231 -76.67168 4 -83.64081 -92.89661 4 -84.68542 -90.11648 4 -82.58677 -90.95832 4 -84.35826 -81.32931 4 -82.43943 -80.61566 4 -82.47428 -83.06176 4 -59.8511 -59.656 4 -59.29836 -59.38638 4 -59.36755 -65.53112 4 -51.19499 -58.109 4 -48.29653 -58.75649 4 -47.42467 -65.70127 4 -41.12165 -63.84004 4 -39.54977 -66.35987 4 -44.02822 -85.02111 4 -47.69785 -84.87673 4 -47.67905 -83.55747 4 -58.8301 -75.874 4 -59.41022 -75.21231 4 -59.47264 -72.90779 4 -61.45298 -78.80838 4 -60.58988 -78.63682 4 -59.58709 -80.94123 4 -60.24346 -74.92932 4 -61.10656 -75.10086 4 -63.36205 -72.85238 4 -62.0932 -75.58723 4 -62.75489 -76.16735 4 -63.41436 -76.52406 4 -63.03788 -77.00059 4 -63.4765 -80.88581 4 -62.86633 -77.86369 4 -62.28622 -78.52539 4 -58.47024 -72.92207 4 -58.52255 -76.59375 4 -58.65856 -76.7371 4 -58.94155 -77.57034 4 -58.58469 -80.95551 4 -59.60324 -78.15045 4 -57.03776 -93.4678 4 -57.68088 -91.31314 4 -55.87478 -90.73507 4 -57.65441 -89.45478 4 -55.27301 -87.82678 4 -57.58718 -84.73585 4 -52.30727 -87.984 4 -46.57247 -86.55312 4 -49.3687 -87.55382 4 -53.16809 -84.7988 4 -41.83566 -83.01786 4 -47.6442 -81.11137 4 -40.08077 -80.62191 4 -47.58206 -76.74961 4 -38.83232 -77.92716 4 -47.52976 -73.07793 4 -46.58978 -70.7877 4 -45.75654 -71.07069 4 -38.13927 -75.03926 4 -38.02877 -72.07142 4 -44.89344 -70.89914 4 -45.41012 -67.36318 4 -44.54702 -67.19164 4 -43.71378 -67.47463 4 -46.39675 -67.84955 4 -47.05845 -68.42966 4 -47.46619 -68.61619 4 -47.34144 -69.2629 4 -47.16989 -70.126 4 -43.9068 -70.41278 4 -43.2451 -69.83266 4 -38.50516 -69.13999 4 -42.96212 -68.99942 4 -43.13367 -68.13632 4 -45.58246 -59.96236 4 -43.15917 -61.67931 4 -62.34585 -61.26735 4 -63.29849 -68.39064 4 -66.15283 -65.78868 4 -63.25696 -65.47571 4 -64.47425 -63.33865 4 -67.3158 -68.5214 4 -66.91562 -68.33911 4 -67.91758 -71.42969 4 -66.97918 -72.80084 4 -70.88331 -71.27247 4 -76.61811 -72.70336 4 -74.87574 -72.68835 4 -79.16237 -74.23535 4 -74.92804 -76.36003 4 -81.35492 -76.2386 4 -74.99018 -80.72179 4 -83.10981 -78.63456 4 -85.05132 -84.21721 4 -82.49308 -84.38103 4 -85.16181 -87.18505 4 -82.5603 -89.09996 4 -74.89405 -100.5 4 -77.60812 -99.29412 4 -75.13753 -91.06444 4 -80.03141 -97.57716 4 -82.06893 -95.41643 4 -67.76538 -94.24773 4 -67.981 -93.39457 4 -67.24098 -91.17694 4 -68.59432 -92.76353 4 -69.44098 -92.52369 4 -70.29414 -92.73931 4 -70.92518 -93.35263 4 -71.95989 -91.10971 4 -71.16503 -94.1993 4 -73.27916 -91.09091 4 -72.10485 -101.1338 4 -70.9494 -95.05245 4 -70.33609 -95.6835 4 -71.9956 -101.1475 4 -69.48941 -95.92334 4 -69.02639 -101.2112 4 -66.10282 -100.6887 4 -68.63626 -95.70771 4 -68.00521 -95.0944 4 -63.62385 -91.22846 4 -63.33948 -99.60047 4 -60.84473 -97.98912 4 -59.73444 -91.28388 4 -59.70796 -89.42552 4 -58.02143 -66.65342 4 -57.40811 -67.28447 4 -57.35553 -68.4753 4 -56.56144 -67.52431 4 -55.70829 -67.30869 4 -55.07724 -66.69537 4 -52.89491 -65.62333 4 -54.8374 -65.8487 4 -55.05302 -64.99554 4 -54.16419 -58.04524 4 -55.66634 -64.3645 4 -57.08777 -58.56774 4 -56.51301 -64.12466 4 -57.21985 -58.6058 4 -57.36617 -64.34028 4 -58.29884 -58.9671 4 -57.99721 -64.9536 4 -58.36515 -65.54541 4 -58.23705 -65.80027 4 -58.40668 -68.46032 4 -47.97857 -79.34658 4 -48.59189 -78.71553 4 -49.43856 -78.4757 4 -50.29172 -78.69132 4 -50.92276 -79.30464 4 -53.11445 -81.03343 4 -47.76295 -80.19973 4 -51.1626 -80.1513 4 -50.94697 -81.00446 4 -53.14929 -83.47953 4 -50.33366 -81.6355 4 -49.48699 -81.87535 4 -48.63383 -81.65972 4 -48.00279 -81.0464 4 -67.03149 -76.47252 4 -67.09363 -80.83428 4 -69.45599 -79.1603 4 -69.21614 -78.31364 4 -69.43177 -77.46048 4 -70.04508 -76.82944 4 -72.40017 -79.11837 4 -71.78685 -79.74941 4 -71.81255 -80.76705 4 -70.94019 -79.98925 4 -70.08703 -79.77362 4 -71.74491 -76.80522 4 -72.37596 -77.41854 4 -73.06968 -76.3865 4 -72.61579 -78.26521 4 -73.13182 -80.74826 4 -63.70774 -86.36003 4 -63.09442 -86.99108 4 -63.59737 -89.37011 4 -62.24775 -87.23091 4 -61.39459 -87.01529 4 -60.76355 -86.40197 4 -59.64073 -84.70659 4 -60.52371 -85.5553 4 -60.73933 -84.70214 4 -59.62194 -83.38732 4 -61.35265 -84.07109 4 -63.51135 -83.33191 4 -62.19932 -83.83126 4 -63.05248 -84.04688 4 -51.7068 -76.25234 4 -54.29319 -69.74768 4 -55.43937 -70.49012 4 -56.21417 -71.61469 4 -57.41909 -72.93704 4 -56.49964 -72.95014 4 -57.4714 -76.60872 4 -56.25233 -74.29319 4 -55.50988 -75.43937 4 -50.56063 -75.50988 4 -49.78583 -74.38532 4 -49.50035 -73.04986 4 -49.74767 -71.7068 4 -50.49012 -70.56063 4 -66.97641 -87.64179 4 -67.2145 -89.31858 4 -67.75122 -88.76634 4 -68.89739 -89.5088 4 -70.24044 -89.75611 4 -71.5759 -89.47064 4 -71.93342 -89.25135 4 -72.70046 -88.69583 4 -73.25269 -89.23255 4 -73.44292 -87.54966 4 -75.11106 -89.20608 4 -73.69023 -86.20661 4 -75.04383 -84.48715 4 -73.40476 -84.87115 4 -71.8474 -83.21315 4 -71.48377 -83.00414 4 -70.14073 -82.75682 4 -68.80527 -83.0423 4 -67.12848 -83.28038 4 -66.69094 -86.30632 4 -63.92337 -85.50686 4 -63.68352 -84.6602 4 -76.67343 -86.15291 4 -77.28675 -85.52187 4 -76.4578 -87.00607 4 -76.69764 -87.85274 4 -78.13341 -85.28202 4 -78.98657 -85.49765 4 -79.61761 -86.11096 4 -79.85746 -86.95764 4 -79.64183 -87.8108 4 -79.02851 -88.44184 4 -78.18184 -88.68168 4 -77.32868 -88.46606 4 -58.71634 -95.91783 4 -58.73204 -91.29816 4 -58.70556 -89.4398 4 -58.63833 -84.72087 4 -58.61954 -83.40161 4 -75.02503 -83.16789 4 -57.56839 -83.41658 4 -57.53354 -80.97048 4 -70.89176 -76.58959 4 -71.75041 -76.4053 4 -71.69811 -72.73362 4 -73.01737 -72.71482 4 -73.82189 -71.70265 4 -59.40908 -68.44605 4 -55.27301 -87.82678 9 -55.87478 -90.73507 9 -57.03776 -93.4678 9 -58.71634 -95.91783 9 -60.84473 -97.98912 9 -63.33948 -99.60047 9 -66.10282 -100.6887 9 -69.02639 -101.2112 9 -71.9956 -101.1475 9 -72.10485 -101.1338 9 -74.89405 -100.5 9 -77.60812 -99.29412 9 -80.03141 -97.57716 9 -82.06893 -95.41643 9 -83.64081 -92.89661 9 -84.68542 -90.11648 9 -85.16181 -87.18505 9 -85.05132 -84.21721 9 -84.35826 -81.32931 9 -83.10981 -78.63456 9 -81.35492 -76.2386 9 -79.16237 -74.23535 9 -76.61811 -72.70336 9 -73.82189 -71.70265 9 -70.88331 -71.27247 9 -67.91758 -71.42969 9 -67.3158 -68.5214 9 -66.15283 -65.78868 9 -64.47425 -63.33865 9 -62.34585 -61.26735 9 -59.8511 -59.656 9 -59.29836 -59.38638 9 -58.29884 -58.9671 9 -57.21985 -58.6058 9 -57.08777 -58.56774 9 -54.16419 -58.04524 9 -51.19499 -58.109 9 -48.29653 -58.75649 9 -45.58246 -59.96236 9 -43.15917 -61.67931 9 -41.12165 -63.84004 9 -39.54977 -66.35987 9 -38.50516 -69.13999 9 -38.02877 -72.07142 9 -38.13927 -75.03926 9 -38.83232 -77.92716 9 -40.08077 -80.62191 9 -41.83566 -83.01786 9 -44.02822 -85.02111 9 -46.57247 -86.55312 9 -49.3687 -87.55382 9 -52.30727 -87.984 9 -73.01737 -72.71482 9 -74.87574 -72.68835 9 -74.92804 -76.36003 9 -59.40908 -68.44605 9 -63.29849 -68.39064 9 -63.36205 -72.85238 9 -60.24346 -74.92932 9 -59.41022 -75.21231 9 -59.47264 -72.90779 9 -72.62995 -83.74659 9 -73.18547 -84.51363 9 -73.40476 -84.87115 9 -63.92337 -85.50686 9 -63.68352 -84.6602 9 -67.14727 -84.59965 9 -56.56144 -67.52431 9 -57.40811 -67.28447 9 -57.35553 -68.4753 9 -75.13753 -91.06444 9 -57.68088 -91.31314 9 -58.73204 -91.29816 9 -47.69785 -84.87673 9 -71.69811 -72.73362 9 -66.97918 -72.80084 9 -66.91562 -68.33911 9 -63.25696 -65.47571 9 -59.36755 -65.53112 9 -58.36515 -65.54541 9 -47.42467 -65.70127 9 -45.41012 -67.36318 9 -44.54702 -67.19164 9 -45.75654 -71.07069 9 -46.58978 -70.7877 9 -47.52976 -73.07793 9 -44.89344 -70.89914 9 -47.16989 -70.126 9 -47.34144 -69.2629 9 -47.46619 -68.61619 9 -47.05845 -68.42966 9 -46.39675 -67.84955 9 -43.71378 -67.47463 9 -43.13367 -68.13632 9 -42.96212 -68.99942 9 -43.2451 -69.83266 9 -43.9068 -70.41278 9 -47.67905 -83.55747 9 -47.6442 -81.11137 9 -47.58206 -76.74961 9 -53.16809 -84.7988 9 -57.65441 -89.45478 9 -57.58718 -84.73585 9 -59.73444 -91.28388 9 -63.62385 -91.22846 9 -67.24098 -91.17694 9 -69.44098 -92.52369 9 -68.59432 -92.76353 9 -68.63626 -95.70771 9 -69.48941 -95.92334 9 -70.33609 -95.6835 9 -70.9494 -95.05245 9 -71.16503 -94.1993 9 -70.92518 -93.35263 9 -70.29414 -92.73931 9 -71.95989 -91.10971 9 -67.981 -93.39457 9 -67.76538 -94.24773 9 -68.00521 -95.0944 9 -73.27916 -91.09091 9 -82.58677 -90.95832 9 -82.43943 -80.61566 9 -82.47428 -83.06176 9 -74.99018 -80.72179 9 -52.89491 -65.62333 9 -54.8374 -65.8487 9 -52.93643 -68.53826 9 -55.07724 -66.69537 9 -55.70829 -67.30869 9 -58.02143 -66.65342 9 -58.40668 -68.46032 9 -58.23705 -65.80027 9 -49.43856 -78.4757 9 -48.59189 -78.71553 9 -53.11445 -81.03343 9 -51.1626 -80.1513 9 -53.05231 -76.67168 9 -50.92276 -79.30464 9 -50.29172 -78.69132 9 -47.97857 -79.34658 9 -47.76295 -80.19973 9 -48.00279 -81.0464 9 -48.63383 -81.65972 9 -49.48699 -81.87535 9 -53.14929 -83.47953 9 -50.33366 -81.6355 9 -50.94697 -81.00446 9 -72.37596 -77.41854 9 -71.74491 -76.80522 9 -71.75041 -76.4053 9 -70.89176 -76.58959 9 -70.04508 -76.82944 9 -69.43177 -77.46048 9 -67.03149 -76.47252 9 -69.21614 -78.31364 9 -67.09363 -80.83428 9 -70.94019 -79.98925 9 -71.81255 -80.76705 9 -70.08703 -79.77362 9 -69.45599 -79.1603 9 -71.78685 -79.74941 9 -72.40017 -79.11837 9 -73.13182 -80.74826 9 -72.61579 -78.26521 9 -59.64073 -84.70659 9 -60.73933 -84.70214 9 -60.52371 -85.5553 9 -59.70796 -89.42552 9 -60.76355 -86.40197 9 -61.39459 -87.01529 9 -63.59737 -89.37011 9 -62.24775 -87.23091 9 -63.09442 -86.99108 9 -61.35265 -84.07109 9 -59.62194 -83.38732 9 -62.19932 -83.83126 9 -63.51135 -83.33191 9 -63.05248 -84.04688 9 -67.12848 -83.28038 9 -66.93825 -84.96327 9 -66.69094 -86.30632 9 -63.70774 -86.36003 9 -66.97641 -87.64179 9 -52.95014 -69.50035 9 -51.61468 -69.78584 9 -55.43937 -70.49012 9 -54.29319 -69.74768 9 -54.38531 -76.21417 9 -55.50988 -75.43937 9 -57.4714 -76.60872 9 -56.25233 -74.29319 9 -57.41909 -72.93704 9 -56.49964 -72.95014 9 -56.21417 -71.61469 9 -50.56063 -75.50988 9 -51.7068 -76.25234 9 -53.04986 -76.49964 9 -50.49012 -70.56063 9 -49.74767 -71.7068 9 -49.50035 -73.04986 9 -49.78583 -74.38532 9 -73.44292 -87.54966 9 -73.69023 -86.20661 9 -75.04383 -84.48715 9 -68.89739 -89.5088 9 -70.24044 -89.75611 9 -67.2145 -89.31858 9 -67.75122 -88.76634 9 -58.94155 -77.57034 9 -59.60324 -78.15045 9 -59.58709 -80.94123 9 -60.58988 -78.63682 9 -61.45298 -78.80838 9 -62.28622 -78.52539 9 -63.4765 -80.88581 9 -62.86633 -77.86369 9 -63.41436 -76.52406 9 -58.58469 -80.95551 9 -58.65856 -76.7371 9 -58.52255 -76.59375 9 -58.8301 -75.874 9 -58.47024 -72.92207 9 -61.10656 -75.10086 9 -62.0932 -75.58723 9 -62.75489 -76.16735 9 -63.03788 -77.00059 9 -57.99721 -64.9536 9 -57.36617 -64.34028 9 -56.51301 -64.12466 9 -55.66634 -64.3645 9 -55.05302 -64.99554 9 -73.06968 -76.3865 9 -73.16667 -83.19436 9 -71.8474 -83.21315 9 -82.5603 -89.09996 9 -82.49308 -84.38103 9 -75.02503 -83.16789 9 -57.56839 -83.41658 9 -57.53354 -80.97048 9 -67.6807 -83.8171 9 -68.80527 -83.0423 9 -70.14073 -82.75682 9 -71.48377 -83.00414 9 -58.61954 -83.40161 9 -58.63833 -84.72087 9 -58.70556 -89.4398 9 -76.4578 -87.00607 9 -76.69764 -87.85274 9 -75.11106 -89.20608 9 -79.02851 -88.44184 9 -78.18184 -88.68168 9 -77.32868 -88.46606 9 -79.64183 -87.8108 9 -79.85746 -86.95764 9 -79.61761 -86.11096 9 -78.98657 -85.49765 9 -78.13341 -85.28202 9 -77.28675 -85.52187 9 -76.67343 -86.15291 9 -73.25269 -89.23255 9 -72.70046 -88.69583 9 -71.93342 -89.25135 9 -71.5759 -89.47064 9 116.304 141.6081 34 114.3555 143.1749 34 118.197 139.9746 34 36.69919 150.0419 34 34.50592 148.8412 34 38.9328 151.1656 34 138.9757 64.83538 34 139.6776 67.23521 34 138.1909 62.46134 34 81.2535 95.62993 9 81.2535 95.62993 12 83.39624 92.24485 12 83.39624 92.24485 9 84.53088 88.40264 12 84.53088 88.40264 9 84.57081 84.39659 12 84.57081 84.39659 9 83.08413 79.62273 12 80.28582 75.84799 12 83.08413 79.62273 9 80.28582 75.84799 9 78.69588 74.51296 9 78.69588 74.51296 12 76.42736 73.16629 9 76.42736 73.16629 12 71.91394 71.85925 12 71.91394 71.85925 9 67.21956 72.06411 12 67.21956 72.06411 9 62.83717 73.75937 12 62.83717 73.75937 9 59.227 76.76701 12 59.227 76.76701 9 58.44852 77.74919 9 58.44852 77.74919 12 56.76816 80.77117 9 56.76816 80.77117 12 55.71886 85.35137 12 55.71886 85.35137 9 56.1893 90.02661 12 56.1893 90.02661 9 57.10413 92.50105 9 57.10413 92.50105 12 58.13006 94.30593 9 58.13006 94.30593 12 61.33736 97.73995 12 61.33736 97.73995 9 73.69557 100.3265 12 69.71162 100.7486 9 69.71162 100.7486 12 65.76423 100.0643 9 65.76423 100.0643 12 77.41196 98.83032 12 77.41196 98.83032 9 76.45053 99.33557 12 76.45053 99.33557 9 73.69557 100.3265 9 72.49552 84.33623 9 73.14683 85.74596 9 94.32586 81.35867 9 92.83918 76.5848 9 83.95173 106.6802 9 87.79328 103.4799 9 72.11082 88.5614 9 73.00602 87.29248 9 70.70109 89.21271 9 69.15457 89.0719 9 78.4299 88.55852 9 79.18176 88.21115 9 79.6592 87.53439 9 79.73429 86.70958 9 65.22119 85.80401 9 67.88565 88.17671 9 67.23434 86.76698 9 77.1335 85.75256 9 77.88536 85.40519 9 78.71017 85.48029 9 79.38693 85.95773 9 67.37515 85.22046 9 68.27035 83.95154 9 77.60509 88.48342 9 76.92833 88.00598 9 76.58097 87.25412 9 76.65606 86.42932 9 71.2266 83.44104 9 69.68008 83.30023 9 56.58763 106.786 9 61.01451 109.1103 9 68.2359 95.24764 9 69.19293 92.64685 9 70.01774 92.72195 9 67.88854 94.49578 9 67.96363 93.67098 9 68.44107 92.99422 9 70.6945 93.19939 9 71.04187 93.95124 9 70.96677 94.77605 9 70.48933 95.45281 9 69.73747 95.80018 9 68.91266 95.72508 9 63.45283 84.50696 9 63.8002 85.25881 9 63.7251 86.08362 9 63.24766 86.76038 9 62.49581 87.10774 9 61.671 87.03265 9 60.99424 86.55521 9 60.64687 85.80335 9 60.72197 84.97855 9 61.19941 84.30179 9 61.95126 83.95442 9 62.77607 84.02952 9 70.36343 79.79099 9 69.68667 79.31355 9 72.49263 78.01715 9 72.14527 77.2653 9 71.46851 76.78786 9 72.41754 78.84196 9 71.9401 79.51872 9 71.18824 79.86608 9 69.3393 78.56169 9 69.4144 77.73689 9 69.89184 77.06013 9 70.64369 76.71276 9 61.57482 108.0432 12 57.14794 105.7188 12 65.22119 85.80401 12 68.44107 92.99422 12 67.96363 93.67098 12 70.6945 93.19939 12 70.01774 92.72195 12 69.19293 92.64685 12 67.88854 94.49578 12 68.2359 95.24764 12 68.91266 95.72508 12 69.73747 95.80018 12 70.48933 95.45281 12 70.96677 94.77605 12 71.04187 93.95124 12 91.68841 76.94318 12 93.17509 81.71704 12 87.0218 102.5538 12 83.18025 105.7542 12 77.60509 88.48342 12 78.4299 88.55852 12 68.27035 83.95154 12 67.37515 85.22046 12 67.23434 86.76698 12 67.88565 88.17671 12 73.14683 85.74596 12 77.1335 85.75256 12 76.65606 86.42932 12 76.92833 88.00598 12 79.38693 85.95773 12 79.73429 86.70958 12 79.6592 87.53439 12 79.18176 88.21115 12 78.71017 85.48029 12 77.88536 85.40519 12 73.00602 87.29248 12 72.49552 84.33623 12 71.2266 83.44104 12 69.68008 83.30023 12 69.15457 89.0719 12 70.70109 89.21271 12 72.11082 88.5614 12 76.58097 87.25412 12 69.3393 78.56169 12 69.68667 79.31355 12 70.36343 79.79099 12 72.49263 78.01715 12 72.14527 77.2653 12 71.18824 79.86608 12 71.9401 79.51872 12 72.41754 78.84196 12 62.49581 87.10774 12 63.24766 86.76038 12 63.7251 86.08362 12 63.8002 85.25881 12 63.45283 84.50696 12 62.77607 84.02952 12 61.95126 83.95442 12 61.19941 84.30179 12 60.72197 84.97855 12 60.64687 85.80335 12 60.99424 86.55521 12 61.671 87.03265 12 69.4144 77.73689 12 69.89184 77.06013 12 70.64369 76.71276 12 71.46851 76.78786 12 87.60772 111.0687 14.47296 86.64222 109.9097 17.18251 116.2757 145.4799 26 114.3555 143.1749 28.32566 116.2757 145.4799 34 120.1172 142.2795 34 120.1172 142.2795 26 118.197 139.9746 28.32566 91.44927 107.8683 14.47296 90.48377 106.7093 17.18251 53.93235 111.843 14.47296 54.63357 110.5075 17.18251 33.11129 151.4974 26 34.50592 148.8412 28.32566 33.11129 151.4974 34 33.11129 151.4974 37 34.50592 148.8412 37 37.53816 153.8218 34 37.53816 153.8218 26 38.9328 151.1656 28.32566 58.35922 114.1674 14.47296 59.06045 112.8319 17.18251 99.77932 79.66035 14.47296 98.33913 80.10885 17.18251 142.5419 66.3432 26 139.6776 67.23521 28.32566 142.5419 66.3432 34 141.0552 61.56933 37 138.1909 62.46134 37 141.0552 61.56933 34 141.0552 61.56933 26 138.1909 62.46134 28.32566 98.29264 74.88648 14.47296 96.85245 75.33499 17.18251 120.1322 138.1803 34 122.2063 140.3455 34 127.0083 130.551 34 129.3616 132.4089 34 132.7295 122.0214 34 135.317 123.5364 34 137.1798 112.765 34 139.9519 113.908 34 140.2685 102.9698 34 143.1722 103.719 34 141.933 92.8349 34 144.9125 93.17575 34 142.1394 82.56632 34 145.1378 82.49226 34 140.8835 72.37275 34 143.8432 71.88509 34 43.76807 153.2796 34 42.75391 156.1026 34 53.56722 156.3558 34 52.95286 159.2915 34 63.70422 158.0073 34 63.50136 160.9994 34 73.97306 158.2005 34 74.18551 161.1917 34 84.16502 156.9315 34 84.78865 159.8645 34 94.07295 154.2262 34 95.09577 157.0447 34 103.4955 150.1394 34 104.8979 152.7896 34 112.2412 144.7543 34 113.9962 147.1853 34 118.2231 143.9117 34 35.30536 152.6964 34 141.8383 63.94388 34 143.8432 71.88509 37 145.1378 82.49226 37 144.9125 93.17575 37 143.1722 103.719 37 139.9519 113.908 37 135.317 123.5364 37 129.3616 132.4089 37 122.2063 140.3455 37 113.9962 147.1853 37 104.8979 152.7896 37 95.09577 157.0447 37 84.78865 159.8645 37 74.18551 161.1917 37 63.50136 160.9994 37 52.95286 159.2915 37 42.75391 156.1026 37 43.76807 153.2796 37 53.56722 156.3558 37 63.70422 158.0073 37 73.97306 158.2005 37 84.16502 156.9315 37 94.07295 154.2262 37 103.4955 150.1394 37 112.2412 144.7543 37 120.1322 138.1803 37 127.0083 130.551 37 132.7295 122.0214 37 137.1798 112.765 37 140.2685 102.9698 37 141.933 92.8349 37 142.1394 82.56632 37 140.8835 72.37275 37 116.304 -141.6081 34 118.197 -139.9746 34 114.3555 -143.1749 34 138.9757 -64.83538 34 138.1909 -62.46134 34 139.6776 -67.23521 34 36.69919 -150.0419 34 38.9328 -151.1656 34 34.50592 -148.8412 34 77.41196 -98.83032 9 77.41196 -98.83032 12 73.69557 -100.3265 12 73.69557 -100.3265 9 69.71162 -100.7486 12 69.71162 -100.7486 9 65.76423 -100.0643 12 65.76423 -100.0643 9 61.33736 -97.73995 12 58.13006 -94.30593 12 61.33736 -97.73995 9 58.13006 -94.30593 9 57.10413 -92.50105 9 57.10413 -92.50105 12 56.1893 -90.02661 9 56.1893 -90.02661 12 55.71886 -85.35137 12 55.71886 -85.35137 9 56.76816 -80.77117 12 56.76816 -80.77117 9 59.227 -76.76701 12 59.227 -76.76701 9 62.83717 -73.75937 12 62.83717 -73.75937 9 63.94379 -73.17107 9 63.94379 -73.17107 12 67.21956 -72.06411 9 67.21956 -72.06411 12 71.91394 -71.85925 12 71.91394 -71.85925 9 76.42736 -73.16629 12 76.42736 -73.16629 9 78.69588 -74.51296 9 78.69588 -74.51296 12 80.28582 -75.84799 9 80.28582 -75.84799 12 83.08413 -79.62273 12 83.08413 -79.62273 9 83.39624 -92.24485 12 84.53088 -88.40264 9 84.53088 -88.40264 12 84.57081 -84.39659 9 84.57081 -84.39659 12 81.2535 -95.62993 12 81.2535 -95.62993 9 81.92408 -94.77556 12 81.92408 -94.77556 9 83.39624 -92.24485 9 67.88565 -88.17671 9 69.15457 -89.0719 9 61.01451 -109.1103 9 56.58763 -106.786 9 87.79328 -103.4799 9 83.95173 -106.6802 9 72.11082 -88.5614 9 70.70109 -89.21271 9 73.00602 -87.29248 9 73.14683 -85.74596 9 70.96677 -94.77605 9 70.48933 -95.45281 9 69.73747 -95.80018 9 68.91266 -95.72508 9 70.64304 -81.28707 9 72.49552 -84.33623 9 71.2266 -83.44104 9 68.44107 -92.99422 9 67.96363 -93.67098 9 67.88854 -94.49578 9 68.2359 -95.24764 9 69.68008 -83.30023 9 68.27035 -83.95154 9 71.04187 -93.95124 9 70.6945 -93.19939 9 70.01774 -92.72195 9 69.19293 -92.64685 9 67.23434 -86.76698 9 67.37515 -85.22046 9 92.83918 -76.5848 9 94.32586 -81.35867 9 79.38693 -85.95773 9 76.65606 -86.42932 9 76.58097 -87.25412 9 78.71017 -85.48029 9 77.88536 -85.40519 9 77.1335 -85.75256 9 76.92833 -88.00598 9 77.60509 -88.48342 9 78.4299 -88.55852 9 79.18176 -88.21115 9 79.6592 -87.53439 9 79.73429 -86.70958 9 69.68667 -79.31355 9 70.36343 -79.79099 9 71.18824 -79.86608 9 71.9401 -79.51872 9 72.41754 -78.84196 9 72.49263 -78.01715 9 72.14527 -77.2653 9 71.46851 -76.78786 9 70.64369 -76.71276 9 69.89184 -77.06013 9 69.4144 -77.73689 9 69.3393 -78.56169 9 63.8002 -85.25881 9 63.45283 -84.50696 9 61.671 -87.03265 9 60.99424 -86.55521 9 60.64687 -85.80335 9 62.49581 -87.10774 9 63.24766 -86.76038 9 63.7251 -86.08362 9 62.77607 -84.02952 9 61.95126 -83.95442 9 61.19941 -84.30179 9 60.72197 -84.97855 9 93.17509 -81.71704 12 91.68841 -76.94318 12 70.64304 -81.28707 12 77.1335 -85.75256 12 77.88536 -85.40519 12 76.92833 -88.00598 12 76.58097 -87.25412 12 76.65606 -86.42932 12 78.71017 -85.48029 12 79.38693 -85.95773 12 79.73429 -86.70958 12 79.6592 -87.53439 12 79.18176 -88.21115 12 78.4299 -88.55852 12 77.60509 -88.48342 12 57.14794 -105.7188 12 61.57482 -108.0432 12 83.18025 -105.7542 12 87.0218 -102.5538 12 71.04187 -93.95124 12 70.96677 -94.77605 12 68.27035 -83.95154 12 69.68008 -83.30023 12 71.2266 -83.44104 12 72.49552 -84.33623 12 69.15457 -89.0719 12 68.44107 -92.99422 12 69.19293 -92.64685 12 70.6945 -93.19939 12 68.2359 -95.24764 12 68.91266 -95.72508 12 69.73747 -95.80018 12 70.48933 -95.45281 12 67.88854 -94.49578 12 67.96363 -93.67098 12 70.70109 -89.21271 12 67.88565 -88.17671 12 67.23434 -86.76698 12 67.37515 -85.22046 12 73.14683 -85.74596 12 73.00602 -87.29248 12 72.11082 -88.5614 12 70.01774 -92.72195 12 62.77607 -84.02952 12 63.45283 -84.50696 12 63.8002 -85.25881 12 61.671 -87.03265 12 60.99424 -86.55521 12 63.7251 -86.08362 12 63.24766 -86.76038 12 62.49581 -87.10774 12 72.41754 -78.84196 12 71.9401 -79.51872 12 71.18824 -79.86608 12 70.36343 -79.79099 12 69.68667 -79.31355 12 69.3393 -78.56169 12 69.4144 -77.73689 12 69.89184 -77.06013 12 70.64369 -76.71276 12 71.46851 -76.78786 12 72.14527 -77.2653 12 72.49263 -78.01715 12 61.95126 -83.95442 12 61.19941 -84.30179 12 60.72197 -84.97855 12 60.64687 -85.80335 12 91.44927 -107.8683 14.47296 90.48377 -106.7093 17.18251 120.1172 -142.2795 26 118.197 -139.9746 28.32566 120.1172 -142.2795 34 116.2757 -145.4799 34 116.2757 -145.4799 26 114.3555 -143.1749 28.32566 87.60772 -111.0687 14.47296 86.64222 -109.9097 17.18251 98.29264 -74.88648 14.47296 96.85245 -75.33499 17.18251 141.0552 -61.56933 26 138.1909 -62.46134 28.32566 141.0552 -61.56933 34 141.0552 -61.56933 37 138.1909 -62.46134 37 142.5419 -66.3432 34 142.5419 -66.3432 26 139.6776 -67.23521 28.32566 99.77932 -79.66035 14.47296 98.33913 -80.10885 17.18251 58.35922 -114.1674 14.47296 59.06045 -112.8319 17.18251 37.53816 -153.8218 26 38.9328 -151.1656 28.32566 37.53816 -153.8218 34 33.11129 -151.4974 37 34.50592 -148.8412 37 33.11129 -151.4974 34 33.11129 -151.4974 26 34.50592 -148.8412 28.32566 53.93235 -111.843 14.47296 54.63357 -110.5075 17.18251 112.2412 -144.7543 34 113.9962 -147.1853 34 103.4955 -150.1394 34 104.8979 -152.7896 34 94.07295 -154.2262 34 95.09577 -157.0447 34 84.16502 -156.9315 34 84.78865 -159.8645 34 73.97306 -158.2005 34 74.18551 -161.1917 34 63.70422 -158.0073 34 63.50136 -160.9994 34 53.56722 -156.3558 34 52.95286 -159.2915 34 43.76807 -153.2796 34 42.75391 -156.1026 34 140.8835 -72.37275 34 143.8432 -71.88509 34 142.1394 -82.56632 34 145.1378 -82.49226 34 141.933 -92.8349 34 144.9125 -93.17575 34 140.2685 -102.9698 34 143.1722 -103.719 34 137.1798 -112.765 34 139.9519 -113.908 34 132.7295 -122.0214 34 135.317 -123.5364 34 127.0083 -130.551 34 129.3616 -132.4089 34 120.1322 -138.1803 34 122.2063 -140.3455 34 118.2231 -143.9117 34 141.8383 -63.94388 34 35.30536 -152.6964 34 42.75391 -156.1026 37 52.95286 -159.2915 37 63.50136 -160.9994 37 74.18551 -161.1917 37 84.78865 -159.8645 37 95.09577 -157.0447 37 104.8979 -152.7896 37 113.9962 -147.1853 37 122.2063 -140.3455 37 129.3616 -132.4089 37 135.317 -123.5364 37 139.9519 -113.908 37 143.1722 -103.719 37 144.9125 -93.17575 37 145.1378 -82.49226 37 143.8432 -71.88509 37 140.8835 -72.37275 37 142.1394 -82.56632 37 141.933 -92.8349 37 140.2685 -102.9698 37 137.1798 -112.765 37 132.7295 -122.0214 37 127.0083 -130.551 37 120.1322 -138.1803 37 112.2412 -144.7543 37 103.4955 -150.1394 37 94.07295 -154.2262 37 84.16502 -156.9315 37 73.97306 -158.2005 37 63.70422 -158.0073 37 53.56722 -156.3558 37 43.76807 -153.2796 37 67.6807 -83.8171 9 67.14727 -84.59965 9 66.93825 -84.96327 9 72.62995 -83.74659 9 73.18547 -84.51363 9 73.16667 -83.19436 9 51.61468 -69.78584 9 52.95014 -69.50035 9 52.93643 -68.53826 9 54.38531 -76.21417 9 53.04986 -76.49964 9 53.05231 -76.67168 9 83.64081 -92.89661 9 84.68542 -90.11648 9 82.58677 -90.95832 9 84.35826 -81.32931 9 82.43943 -80.61566 9 82.47428 -83.06176 9 59.8511 -59.656 9 59.29836 -59.38638 9 59.36755 -65.53112 9 51.19499 -58.109 9 48.29653 -58.75649 9 47.42467 -65.70127 9 41.12165 -63.84004 9 39.54977 -66.35987 9 44.02822 -85.02111 9 47.69785 -84.87673 9 47.67905 -83.55747 9 58.8301 -75.874 9 59.41022 -75.21231 9 59.47264 -72.90779 9 61.45298 -78.80838 9 60.58988 -78.63682 9 59.58709 -80.94123 9 60.24346 -74.92932 9 61.10656 -75.10086 9 63.36205 -72.85238 9 62.0932 -75.58723 9 62.75489 -76.16735 9 63.41436 -76.52406 9 63.03788 -77.00059 9 63.4765 -80.88581 9 62.86633 -77.86369 9 62.28622 -78.52539 9 58.47024 -72.92207 9 58.52255 -76.59375 9 58.65856 -76.7371 9 58.94155 -77.57034 9 58.58469 -80.95551 9 59.60324 -78.15045 9 57.03776 -93.4678 9 57.68088 -91.31314 9 55.87478 -90.73507 9 57.65441 -89.45478 9 55.27301 -87.82678 9 57.58718 -84.73585 9 52.30727 -87.984 9 46.57247 -86.55312 9 49.3687 -87.55382 9 53.16809 -84.7988 9 41.83566 -83.01786 9 47.6442 -81.11137 9 40.08077 -80.62191 9 47.58206 -76.74961 9 38.83232 -77.92716 9 47.52976 -73.07793 9 46.58978 -70.7877 9 45.75654 -71.07069 9 38.13927 -75.03926 9 38.02877 -72.07142 9 44.89344 -70.89914 9 45.41012 -67.36318 9 44.54702 -67.19164 9 43.71378 -67.47463 9 46.39675 -67.84955 9 47.05845 -68.42966 9 47.46619 -68.61619 9 47.34144 -69.2629 9 47.16989 -70.126 9 43.9068 -70.41278 9 43.2451 -69.83266 9 38.50516 -69.13999 9 42.96212 -68.99942 9 43.13367 -68.13632 9 45.58246 -59.96236 9 43.15917 -61.67931 9 62.34585 -61.26735 9 63.29849 -68.39064 9 66.15283 -65.78868 9 63.25696 -65.47571 9 64.47425 -63.33865 9 67.3158 -68.5214 9 66.91562 -68.33911 9 67.91758 -71.42969 9 66.97918 -72.80084 9 70.88331 -71.27247 9 76.61811 -72.70336 9 74.87574 -72.68835 9 79.16237 -74.23535 9 74.92804 -76.36003 9 81.35492 -76.2386 9 74.99018 -80.72179 9 83.10981 -78.63456 9 85.05132 -84.21721 9 82.49308 -84.38103 9 85.16181 -87.18505 9 82.5603 -89.09996 9 74.89405 -100.5 9 77.60812 -99.29412 9 75.13753 -91.06444 9 80.03141 -97.57716 9 82.06893 -95.41643 9 67.76538 -94.24773 9 67.981 -93.39457 9 67.24098 -91.17694 9 68.59432 -92.76353 9 69.44098 -92.52369 9 70.29414 -92.73931 9 70.92518 -93.35263 9 71.95989 -91.10971 9 71.16503 -94.1993 9 73.27916 -91.09091 9 72.10485 -101.1338 9 70.9494 -95.05245 9 70.33609 -95.6835 9 71.9956 -101.1475 9 69.48941 -95.92334 9 69.02639 -101.2112 9 66.10282 -100.6887 9 68.63626 -95.70771 9 68.00521 -95.0944 9 63.62385 -91.22846 9 63.33948 -99.60047 9 60.84473 -97.98912 9 59.73444 -91.28388 9 59.70796 -89.42552 9 58.02143 -66.65342 9 57.40811 -67.28447 9 57.35553 -68.4753 9 56.56144 -67.52431 9 55.70829 -67.30869 9 55.07724 -66.69537 9 52.89491 -65.62333 9 54.8374 -65.8487 9 55.05302 -64.99554 9 54.16419 -58.04524 9 55.66634 -64.3645 9 57.08777 -58.56774 9 56.51301 -64.12466 9 57.21985 -58.6058 9 57.36617 -64.34028 9 58.29884 -58.9671 9 57.99721 -64.9536 9 58.36515 -65.54541 9 58.23705 -65.80027 9 58.40668 -68.46032 9 47.97857 -79.34658 9 48.59189 -78.71553 9 49.43856 -78.4757 9 50.29172 -78.69132 9 50.92276 -79.30464 9 53.11445 -81.03343 9 47.76295 -80.19973 9 51.1626 -80.1513 9 50.94697 -81.00446 9 53.14929 -83.47953 9 50.33366 -81.6355 9 49.48699 -81.87535 9 48.63383 -81.65972 9 48.00279 -81.0464 9 67.03149 -76.47252 9 67.09363 -80.83428 9 69.45599 -79.1603 9 69.21614 -78.31364 9 69.43177 -77.46048 9 70.04508 -76.82944 9 72.40017 -79.11837 9 71.78685 -79.74941 9 71.81255 -80.76705 9 70.94019 -79.98925 9 70.08703 -79.77362 9 71.74491 -76.80522 9 72.37596 -77.41854 9 73.06968 -76.3865 9 72.61579 -78.26521 9 73.13182 -80.74826 9 63.70774 -86.36003 9 63.09442 -86.99108 9 63.59737 -89.37011 9 62.24775 -87.23091 9 61.39459 -87.01529 9 60.76355 -86.40197 9 59.64073 -84.70659 9 60.52371 -85.5553 9 60.73933 -84.70214 9 59.62194 -83.38732 9 61.35265 -84.07109 9 63.51135 -83.33191 9 62.19932 -83.83126 9 63.05248 -84.04688 9 51.7068 -76.25234 9 54.29319 -69.74768 9 55.43937 -70.49012 9 56.21417 -71.61469 9 57.41909 -72.93704 9 56.49964 -72.95014 9 57.4714 -76.60872 9 56.25233 -74.29319 9 55.50988 -75.43937 9 50.56063 -75.50988 9 49.78583 -74.38532 9 49.50035 -73.04986 9 49.74767 -71.7068 9 50.49012 -70.56063 9 66.97641 -87.64179 9 67.2145 -89.31858 9 67.75122 -88.76634 9 68.89739 -89.5088 9 70.24044 -89.75611 9 71.5759 -89.47064 9 71.93342 -89.25135 9 72.70046 -88.69583 9 73.25269 -89.23255 9 73.44292 -87.54966 9 75.11106 -89.20608 9 73.69023 -86.20661 9 75.04383 -84.48715 9 73.40476 -84.87115 9 71.8474 -83.21315 9 71.48377 -83.00414 9 70.14073 -82.75682 9 68.80527 -83.0423 9 67.12848 -83.28038 9 66.69094 -86.30632 9 63.92337 -85.50686 9 63.68352 -84.6602 9 76.67343 -86.15291 9 77.28675 -85.52187 9 76.4578 -87.00607 9 76.69764 -87.85274 9 78.13341 -85.28202 9 78.98657 -85.49765 9 79.61761 -86.11096 9 79.85746 -86.95764 9 79.64183 -87.8108 9 79.02851 -88.44184 9 78.18184 -88.68168 9 77.32868 -88.46606 9 58.71634 -95.91783 9 58.73204 -91.29816 9 58.70556 -89.4398 9 58.63833 -84.72087 9 58.61954 -83.40161 9 75.02503 -83.16789 9 57.56839 -83.41658 9 57.53354 -80.97048 9 70.89176 -76.58959 9 71.75041 -76.4053 9 71.69811 -72.73362 9 73.01737 -72.71482 9 73.82189 -71.70265 9 59.40908 -68.44605 9 55.27301 -87.82678 4 55.87478 -90.73507 4 57.03776 -93.4678 4 58.71634 -95.91783 4 60.84473 -97.98912 4 63.33948 -99.60047 4 66.10282 -100.6887 4 69.02639 -101.2112 4 71.9956 -101.1475 4 72.10485 -101.1338 4 74.89405 -100.5 4 77.60812 -99.29412 4 80.03141 -97.57716 4 82.06893 -95.41643 4 83.64081 -92.89661 4 84.68542 -90.11648 4 85.16181 -87.18505 4 85.05132 -84.21721 4 84.35826 -81.32931 4 83.10981 -78.63456 4 81.35492 -76.2386 4 79.16237 -74.23535 4 76.61811 -72.70336 4 73.82189 -71.70265 4 70.88331 -71.27247 4 67.91758 -71.42969 4 67.3158 -68.5214 4 66.15283 -65.78868 4 64.47425 -63.33865 4 62.34585 -61.26735 4 59.8511 -59.656 4 59.29836 -59.38638 4 58.29884 -58.9671 4 57.21985 -58.6058 4 57.08777 -58.56774 4 54.16419 -58.04524 4 51.19499 -58.109 4 48.29653 -58.75649 4 45.58246 -59.96236 4 43.15917 -61.67931 4 41.12165 -63.84004 4 39.54977 -66.35987 4 38.50516 -69.13999 4 38.02877 -72.07142 4 38.13927 -75.03926 4 38.83232 -77.92716 4 40.08077 -80.62191 4 41.83566 -83.01786 4 44.02822 -85.02111 4 46.57247 -86.55312 4 49.3687 -87.55382 4 52.30727 -87.984 4 73.01737 -72.71482 4 74.87574 -72.68835 4 74.92804 -76.36003 4 59.40908 -68.44605 4 63.29849 -68.39064 4 63.36205 -72.85238 4 60.24346 -74.92932 4 59.41022 -75.21231 4 59.47264 -72.90779 4 72.62995 -83.74659 4 73.18547 -84.51363 4 73.40476 -84.87115 4 63.92337 -85.50686 4 63.68352 -84.6602 4 67.14727 -84.59965 4 56.56144 -67.52431 4 57.40811 -67.28447 4 57.35553 -68.4753 4 75.13753 -91.06444 4 57.68088 -91.31314 4 58.73204 -91.29816 4 47.69785 -84.87673 4 71.69811 -72.73362 4 66.97918 -72.80084 4 66.91562 -68.33911 4 63.25696 -65.47571 4 59.36755 -65.53112 4 58.36515 -65.54541 4 47.42467 -65.70127 4 45.41012 -67.36318 4 44.54702 -67.19164 4 45.75654 -71.07069 4 46.58978 -70.7877 4 47.52976 -73.07793 4 44.89344 -70.89914 4 47.16989 -70.126 4 47.34144 -69.2629 4 47.46619 -68.61619 4 47.05845 -68.42966 4 46.39675 -67.84955 4 43.71378 -67.47463 4 43.13367 -68.13632 4 42.96212 -68.99942 4 43.2451 -69.83266 4 43.9068 -70.41278 4 47.67905 -83.55747 4 47.6442 -81.11137 4 47.58206 -76.74961 4 53.16809 -84.7988 4 57.65441 -89.45478 4 57.58718 -84.73585 4 59.73444 -91.28388 4 63.62385 -91.22846 4 67.24098 -91.17694 4 69.44098 -92.52369 4 68.59432 -92.76353 4 68.63626 -95.70771 4 69.48941 -95.92334 4 70.33609 -95.6835 4 70.9494 -95.05245 4 71.16503 -94.1993 4 70.92518 -93.35263 4 70.29414 -92.73931 4 71.95989 -91.10971 4 67.981 -93.39457 4 67.76538 -94.24773 4 68.00521 -95.0944 4 73.27916 -91.09091 4 82.58677 -90.95832 4 82.43943 -80.61566 4 82.47428 -83.06176 4 74.99018 -80.72179 4 52.89491 -65.62333 4 54.8374 -65.8487 4 52.93643 -68.53826 4 55.07724 -66.69537 4 55.70829 -67.30869 4 58.02143 -66.65342 4 58.40668 -68.46032 4 58.23705 -65.80027 4 49.43856 -78.4757 4 48.59189 -78.71553 4 53.11445 -81.03343 4 51.1626 -80.1513 4 53.05231 -76.67168 4 50.92276 -79.30464 4 50.29172 -78.69132 4 47.97857 -79.34658 4 47.76295 -80.19973 4 48.00279 -81.0464 4 48.63383 -81.65972 4 49.48699 -81.87535 4 53.14929 -83.47953 4 50.33366 -81.6355 4 50.94697 -81.00446 4 72.37596 -77.41854 4 71.74491 -76.80522 4 71.75041 -76.4053 4 70.89176 -76.58959 4 70.04508 -76.82944 4 69.43177 -77.46048 4 67.03149 -76.47252 4 69.21614 -78.31364 4 67.09363 -80.83428 4 70.94019 -79.98925 4 71.81255 -80.76705 4 70.08703 -79.77362 4 69.45599 -79.1603 4 71.78685 -79.74941 4 72.40017 -79.11837 4 73.13182 -80.74826 4 72.61579 -78.26521 4 59.64073 -84.70659 4 60.73933 -84.70214 4 60.52371 -85.5553 4 59.70796 -89.42552 4 60.76355 -86.40197 4 61.39459 -87.01529 4 63.59737 -89.37011 4 62.24775 -87.23091 4 63.09442 -86.99108 4 61.35265 -84.07109 4 59.62194 -83.38732 4 62.19932 -83.83126 4 63.51135 -83.33191 4 63.05248 -84.04688 4 67.12848 -83.28038 4 66.93825 -84.96327 4 66.69094 -86.30632 4 63.70774 -86.36003 4 66.97641 -87.64179 4 52.95014 -69.50035 4 51.61468 -69.78584 4 55.43937 -70.49012 4 54.29319 -69.74768 4 54.38531 -76.21417 4 55.50988 -75.43937 4 57.4714 -76.60872 4 56.25233 -74.29319 4 57.41909 -72.93704 4 56.49964 -72.95014 4 56.21417 -71.61469 4 50.56063 -75.50988 4 51.7068 -76.25234 4 53.04986 -76.49964 4 50.49012 -70.56063 4 49.74767 -71.7068 4 49.50035 -73.04986 4 49.78583 -74.38532 4 73.44292 -87.54966 4 73.69023 -86.20661 4 75.04383 -84.48715 4 68.89739 -89.5088 4 70.24044 -89.75611 4 67.2145 -89.31858 4 67.75122 -88.76634 4 58.94155 -77.57034 4 59.60324 -78.15045 4 59.58709 -80.94123 4 60.58988 -78.63682 4 61.45298 -78.80838 4 62.28622 -78.52539 4 63.4765 -80.88581 4 62.86633 -77.86369 4 63.41436 -76.52406 4 58.58469 -80.95551 4 58.65856 -76.7371 4 58.52255 -76.59375 4 58.8301 -75.874 4 58.47024 -72.92207 4 61.10656 -75.10086 4 62.0932 -75.58723 4 62.75489 -76.16735 4 63.03788 -77.00059 4 57.99721 -64.9536 4 57.36617 -64.34028 4 56.51301 -64.12466 4 55.66634 -64.3645 4 55.05302 -64.99554 4 73.06968 -76.3865 4 73.16667 -83.19436 4 71.8474 -83.21315 4 82.5603 -89.09996 4 82.49308 -84.38103 4 75.02503 -83.16789 4 57.56839 -83.41658 4 57.53354 -80.97048 4 67.6807 -83.8171 4 68.80527 -83.0423 4 70.14073 -82.75682 4 71.48377 -83.00414 4 58.61954 -83.40161 4 58.63833 -84.72087 4 58.70556 -89.4398 4 76.4578 -87.00607 4 76.69764 -87.85274 4 75.11106 -89.20608 4 79.02851 -88.44184 4 78.18184 -88.68168 4 77.32868 -88.46606 4 79.64183 -87.8108 4 79.85746 -86.95764 4 79.61761 -86.11096 4 78.98657 -85.49765 4 78.13341 -85.28202 4 77.28675 -85.52187 4 76.67343 -86.15291 4 73.25269 -89.23255 4 72.70046 -88.69583 4 71.93342 -89.25135 4 71.5759 -89.47064 4 67.6807 83.8171 4 67.14727 84.59965 4 66.93825 84.96327 4 72.62995 83.74659 4 73.18547 84.51363 4 73.16667 83.19436 4 51.61468 69.78584 4 52.95014 69.50035 4 52.93643 68.53826 4 54.38531 76.21417 4 53.04986 76.49964 4 53.05231 76.67168 4 83.64081 92.89661 4 84.68542 90.11648 4 82.58677 90.95832 4 84.35826 81.32931 4 82.43943 80.61566 4 82.47428 83.06176 4 59.8511 59.656 4 59.29836 59.38638 4 59.36755 65.53112 4 51.19499 58.109 4 48.29653 58.75649 4 47.42467 65.70127 4 41.12165 63.84004 4 39.54977 66.35987 4 44.02822 85.02111 4 47.69785 84.87673 4 47.67905 83.55747 4 58.8301 75.874 4 59.41022 75.21231 4 59.47264 72.90779 4 61.45298 78.80838 4 60.58988 78.63682 4 59.58709 80.94123 4 60.24346 74.92932 4 61.10656 75.10086 4 63.36205 72.85238 4 62.0932 75.58723 4 62.75489 76.16735 4 63.41436 76.52406 4 63.03788 77.00059 4 63.4765 80.88581 4 62.86633 77.86369 4 62.28622 78.52539 4 58.47024 72.92207 4 58.52255 76.59375 4 58.65856 76.7371 4 58.94155 77.57034 4 58.58469 80.95551 4 59.60324 78.15045 4 57.03776 93.4678 4 57.68088 91.31314 4 55.87478 90.73507 4 57.65441 89.45478 4 55.27301 87.82678 4 57.58718 84.73585 4 52.30727 87.984 4 46.57247 86.55312 4 49.3687 87.55382 4 53.16809 84.7988 4 41.83566 83.01786 4 47.6442 81.11137 4 40.08077 80.62191 4 47.58206 76.74961 4 38.83232 77.92716 4 47.52976 73.07793 4 46.58978 70.7877 4 45.75654 71.07069 4 38.13927 75.03926 4 38.02877 72.07142 4 44.89344 70.89914 4 45.41012 67.36318 4 44.54702 67.19164 4 43.71378 67.47463 4 46.39675 67.84955 4 47.05845 68.42966 4 47.46619 68.61619 4 47.34144 69.2629 4 47.16989 70.126 4 43.9068 70.41278 4 43.2451 69.83266 4 38.50516 69.13999 4 42.96212 68.99942 4 43.13367 68.13632 4 45.58246 59.96236 4 43.15917 61.67931 4 62.34585 61.26735 4 63.29849 68.39064 4 66.15283 65.78868 4 63.25696 65.47571 4 64.47425 63.33865 4 67.3158 68.5214 4 66.91562 68.33911 4 67.91758 71.42969 4 66.97918 72.80084 4 70.88331 71.27247 4 76.61811 72.70336 4 74.87574 72.68835 4 79.16237 74.23535 4 74.92804 76.36003 4 81.35492 76.2386 4 74.99018 80.72179 4 83.10981 78.63456 4 85.05132 84.21721 4 82.49308 84.38103 4 85.16181 87.18505 4 82.5603 89.09996 4 74.89405 100.5 4 77.60812 99.29412 4 75.13753 91.06444 4 80.03141 97.57716 4 82.06893 95.41643 4 67.76538 94.24773 4 67.981 93.39457 4 67.24098 91.17694 4 68.59432 92.76353 4 69.44098 92.52369 4 70.29414 92.73931 4 70.92518 93.35263 4 71.95989 91.10971 4 71.16503 94.1993 4 73.27916 91.09091 4 72.10485 101.1338 4 70.9494 95.05245 4 70.33609 95.6835 4 71.9956 101.1475 4 69.48941 95.92334 4 69.02639 101.2112 4 66.10282 100.6887 4 68.63626 95.70771 4 68.00521 95.0944 4 63.62385 91.22846 4 63.33948 99.60047 4 60.84473 97.98912 4 59.73444 91.28388 4 59.70796 89.42552 4 58.02143 66.65342 4 57.40811 67.28447 4 57.35553 68.4753 4 56.56144 67.52431 4 55.70829 67.30869 4 55.07724 66.69537 4 52.89491 65.62333 4 54.8374 65.8487 4 55.05302 64.99554 4 54.16419 58.04524 4 55.66634 64.3645 4 57.08777 58.56774 4 56.51301 64.12466 4 57.21985 58.6058 4 57.36617 64.34028 4 58.29884 58.9671 4 57.99721 64.9536 4 58.36515 65.54541 4 58.23705 65.80027 4 58.40668 68.46032 4 47.97857 79.34658 4 48.59189 78.71553 4 49.43856 78.4757 4 50.29172 78.69132 4 50.92276 79.30464 4 53.11445 81.03343 4 47.76295 80.19973 4 51.1626 80.1513 4 50.94697 81.00446 4 53.14929 83.47953 4 50.33366 81.6355 4 49.48699 81.87535 4 48.63383 81.65972 4 48.00279 81.0464 4 67.03149 76.47252 4 67.09363 80.83428 4 69.45599 79.1603 4 69.21614 78.31364 4 69.43177 77.46048 4 70.04508 76.82944 4 72.40017 79.11837 4 71.78685 79.74941 4 71.81255 80.76705 4 70.94019 79.98925 4 70.08703 79.77362 4 71.74491 76.80522 4 72.37596 77.41854 4 73.06968 76.3865 4 72.61579 78.26521 4 73.13182 80.74826 4 63.70774 86.36003 4 63.09442 86.99108 4 63.59737 89.37011 4 62.24775 87.23091 4 61.39459 87.01529 4 60.76355 86.40197 4 59.64073 84.70659 4 60.52371 85.5553 4 60.73933 84.70214 4 59.62194 83.38732 4 61.35265 84.07109 4 63.51135 83.33191 4 62.19932 83.83126 4 63.05248 84.04688 4 51.7068 76.25234 4 54.29319 69.74768 4 55.43937 70.49012 4 56.21417 71.61469 4 57.41909 72.93704 4 56.49964 72.95014 4 57.4714 76.60872 4 56.25233 74.29319 4 55.50988 75.43937 4 50.56063 75.50988 4 49.78583 74.38532 4 49.50035 73.04986 4 49.74767 71.7068 4 50.49012 70.56063 4 66.97641 87.64179 4 67.2145 89.31858 4 67.75122 88.76634 4 68.89739 89.5088 4 70.24044 89.75611 4 71.5759 89.47064 4 71.93342 89.25135 4 72.70046 88.69583 4 73.25269 89.23255 4 73.44292 87.54966 4 75.11106 89.20608 4 73.69023 86.20661 4 75.04383 84.48715 4 73.40476 84.87115 4 71.8474 83.21315 4 71.48377 83.00414 4 70.14073 82.75682 4 68.80527 83.0423 4 67.12848 83.28038 4 66.69094 86.30632 4 63.92337 85.50686 4 63.68352 84.6602 4 76.67343 86.15291 4 77.28675 85.52187 4 76.4578 87.00607 4 76.69764 87.85274 4 78.13341 85.28202 4 78.98657 85.49765 4 79.61761 86.11096 4 79.85746 86.95764 4 79.64183 87.8108 4 79.02851 88.44184 4 78.18184 88.68168 4 77.32868 88.46606 4 58.71634 95.91783 4 58.73204 91.29816 4 58.70556 89.4398 4 58.63833 84.72087 4 58.61954 83.40161 4 75.02503 83.16789 4 57.56839 83.41658 4 57.53354 80.97048 4 70.89176 76.58959 4 71.75041 76.4053 4 71.69811 72.73362 4 73.01737 72.71482 4 73.82189 71.70265 4 59.40908 68.44605 4 55.27301 87.82678 9 55.87478 90.73507 9 57.03776 93.4678 9 58.71634 95.91783 9 60.84473 97.98912 9 63.33948 99.60047 9 66.10282 100.6887 9 69.02639 101.2112 9 71.9956 101.1475 9 72.10485 101.1338 9 74.89405 100.5 9 77.60812 99.29412 9 80.03141 97.57716 9 82.06893 95.41643 9 83.64081 92.89661 9 84.68542 90.11648 9 85.16181 87.18505 9 85.05132 84.21721 9 84.35826 81.32931 9 83.10981 78.63456 9 81.35492 76.2386 9 79.16237 74.23535 9 76.61811 72.70336 9 73.82189 71.70265 9 70.88331 71.27247 9 67.91758 71.42969 9 67.3158 68.5214 9 66.15283 65.78868 9 64.47425 63.33865 9 62.34585 61.26735 9 59.8511 59.656 9 59.29836 59.38638 9 58.29884 58.9671 9 57.21985 58.6058 9 57.08777 58.56774 9 54.16419 58.04524 9 51.19499 58.109 9 48.29653 58.75649 9 45.58246 59.96236 9 43.15917 61.67931 9 41.12165 63.84004 9 39.54977 66.35987 9 38.50516 69.13999 9 38.02877 72.07142 9 38.13927 75.03926 9 38.83232 77.92716 9 40.08077 80.62191 9 41.83566 83.01786 9 44.02822 85.02111 9 46.57247 86.55312 9 49.3687 87.55382 9 52.30727 87.984 9 73.01737 72.71482 9 74.87574 72.68835 9 74.92804 76.36003 9 59.40908 68.44605 9 63.29849 68.39064 9 63.36205 72.85238 9 60.24346 74.92932 9 59.41022 75.21231 9 59.47264 72.90779 9 72.62995 83.74659 9 73.18547 84.51363 9 73.40476 84.87115 9 63.92337 85.50686 9 63.68352 84.6602 9 67.14727 84.59965 9 56.56144 67.52431 9 57.40811 67.28447 9 57.35553 68.4753 9 75.13753 91.06444 9 57.68088 91.31314 9 58.73204 91.29816 9 47.69785 84.87673 9 71.69811 72.73362 9 66.97918 72.80084 9 66.91562 68.33911 9 63.25696 65.47571 9 59.36755 65.53112 9 58.36515 65.54541 9 47.42467 65.70127 9 45.41012 67.36318 9 44.54702 67.19164 9 45.75654 71.07069 9 46.58978 70.7877 9 47.52976 73.07793 9 44.89344 70.89914 9 47.16989 70.126 9 47.34144 69.2629 9 47.46619 68.61619 9 47.05845 68.42966 9 46.39675 67.84955 9 43.71378 67.47463 9 43.13367 68.13632 9 42.96212 68.99942 9 43.2451 69.83266 9 43.9068 70.41278 9 47.67905 83.55747 9 47.6442 81.11137 9 47.58206 76.74961 9 53.16809 84.7988 9 57.65441 89.45478 9 57.58718 84.73585 9 59.73444 91.28388 9 63.62385 91.22846 9 67.24098 91.17694 9 69.44098 92.52369 9 68.59432 92.76353 9 68.63626 95.70771 9 69.48941 95.92334 9 70.33609 95.6835 9 70.9494 95.05245 9 71.16503 94.1993 9 70.92518 93.35263 9 70.29414 92.73931 9 71.95989 91.10971 9 67.981 93.39457 9 67.76538 94.24773 9 68.00521 95.0944 9 73.27916 91.09091 9 82.58677 90.95832 9 82.43943 80.61566 9 82.47428 83.06176 9 74.99018 80.72179 9 52.89491 65.62333 9 54.8374 65.8487 9 52.93643 68.53826 9 55.07724 66.69537 9 55.70829 67.30869 9 58.02143 66.65342 9 58.40668 68.46032 9 58.23705 65.80027 9 49.43856 78.4757 9 48.59189 78.71553 9 53.11445 81.03343 9 51.1626 80.1513 9 53.05231 76.67168 9 50.92276 79.30464 9 50.29172 78.69132 9 47.97857 79.34658 9 47.76295 80.19973 9 48.00279 81.0464 9 48.63383 81.65972 9 49.48699 81.87535 9 53.14929 83.47953 9 50.33366 81.6355 9 50.94697 81.00446 9 72.37596 77.41854 9 71.74491 76.80522 9 71.75041 76.4053 9 70.89176 76.58959 9 70.04508 76.82944 9 69.43177 77.46048 9 67.03149 76.47252 9 69.21614 78.31364 9 67.09363 80.83428 9 70.94019 79.98925 9 71.81255 80.76705 9 70.08703 79.77362 9 69.45599 79.1603 9 71.78685 79.74941 9 72.40017 79.11837 9 73.13182 80.74826 9 72.61579 78.26521 9 59.64073 84.70659 9 60.73933 84.70214 9 60.52371 85.5553 9 59.70796 89.42552 9 60.76355 86.40197 9 61.39459 87.01529 9 63.59737 89.37011 9 62.24775 87.23091 9 63.09442 86.99108 9 61.35265 84.07109 9 59.62194 83.38732 9 62.19932 83.83126 9 63.51135 83.33191 9 63.05248 84.04688 9 67.12848 83.28038 9 66.93825 84.96327 9 66.69094 86.30632 9 63.70774 86.36003 9 66.97641 87.64179 9 52.95014 69.50035 9 51.61468 69.78584 9 55.43937 70.49012 9 54.29319 69.74768 9 54.38531 76.21417 9 55.50988 75.43937 9 57.4714 76.60872 9 56.25233 74.29319 9 57.41909 72.93704 9 56.49964 72.95014 9 56.21417 71.61469 9 50.56063 75.50988 9 51.7068 76.25234 9 53.04986 76.49964 9 50.49012 70.56063 9 49.74767 71.7068 9 49.50035 73.04986 9 49.78583 74.38532 9 73.44292 87.54966 9 73.69023 86.20661 9 75.04383 84.48715 9 68.89739 89.5088 9 70.24044 89.75611 9 67.2145 89.31858 9 67.75122 88.76634 9 58.94155 77.57034 9 59.60324 78.15045 9 59.58709 80.94123 9 60.58988 78.63682 9 61.45298 78.80838 9 62.28622 78.52539 9 63.4765 80.88581 9 62.86633 77.86369 9 63.41436 76.52406 9 58.58469 80.95551 9 58.65856 76.7371 9 58.52255 76.59375 9 58.8301 75.874 9 58.47024 72.92207 9 61.10656 75.10086 9 62.0932 75.58723 9 62.75489 76.16735 9 63.03788 77.00059 9 57.99721 64.9536 9 57.36617 64.34028 9 56.51301 64.12466 9 55.66634 64.3645 9 55.05302 64.99554 9 73.06968 76.3865 9 73.16667 83.19436 9 71.8474 83.21315 9 82.5603 89.09996 9 82.49308 84.38103 9 75.02503 83.16789 9 57.56839 83.41658 9 57.53354 80.97048 9 67.6807 83.8171 9 68.80527 83.0423 9 70.14073 82.75682 9 71.48377 83.00414 9 58.61954 83.40161 9 58.63833 84.72087 9 58.70556 89.4398 9 76.4578 87.00607 9 76.69764 87.85274 9 75.11106 89.20608 9 79.02851 88.44184 9 78.18184 88.68168 9 77.32868 88.46606 9 79.64183 87.8108 9 79.85746 86.95764 9 79.61761 86.11096 9 78.98657 85.49765 9 78.13341 85.28202 9 77.28675 85.52187 9 76.67343 86.15291 9 73.25269 89.23255 9 72.70046 88.69583 9 71.93342 89.25135 9 71.5759 89.47064 9 -62.36835 81.27551 -3 -62.36835 81.27551 0 -61.21956 82.41748 0 -44.72449 82.36836 -3 -44.72449 82.36836 0 -43.58252 81.21956 0 -43.63164 64.7245 -3 -43.63164 64.7245 0 -44.78044 63.58252 0 -61.2755 63.63164 -3 -61.2755 63.63164 0 -62.41748 64.78044 0 -59.62588 62.40058 -6 -58.55513 61.80221 -3 -60.63296 63.10112 -3 -58.55513 61.80221 -6 -57.43088 61.31166 -6 -56.2638 60.93362 -3 -56.2638 60.93362 -6 -55.06525 60.67179 -6 -55.45265 60.74298 -3 -53.84706 60.52873 -6 -55.45265 60.74298 0 -41.80221 67.44488 -3 -43.10112 65.36704 -3 -42.40063 66.37403 -6 -41.80221 67.44488 -6 -41.31162 68.56922 -6 -40.93362 69.7362 -3 -40.93362 69.7362 -6 -40.67178 70.9348 -6 -40.74298 70.54735 -3 -40.52873 72.15295 -6 -40.74298 70.54735 0 -46.37412 83.59942 -6 -47.44487 84.19779 -3 -45.36703 82.89888 -3 -47.44487 84.19779 -6 -48.56912 84.68834 -6 -49.73619 85.06639 -3 -49.73619 85.06639 -6 -50.93474 85.32821 -6 -50.54735 85.25702 -3 -52.15294 85.47127 -6 -50.54735 85.25702 0 -64.19779 78.55513 -3 -62.89888 80.63297 -3 -63.59936 79.62597 -6 -64.19779 78.55513 -6 -64.68838 77.43079 -6 -65.06639 76.2638 -3 -65.06639 76.2638 -6 -65.32822 75.0652 -6 -65.25702 75.45265 -3 -65.47127 73.84706 -6 -65.25702 75.45265 0 -53.84706 60.52873 0 -52.62068 60.50576 -6 -51.39776 60.60311 0 -51.39776 60.60311 -6 -50.19031 60.81986 -6 -49.01003 61.1539 0 -49.01003 61.1539 -6 -47.86821 61.60198 -6 -46.77564 62.15992 0 -46.77564 62.15992 -6 -45.743 62.82228 -6 -44.78044 63.58252 -6 -43.89707 64.4334 -6 -43.10112 65.36704 -6 -40.52873 72.15295 0 -40.50576 73.3793 -6 -40.60311 74.60224 0 -40.60311 74.60224 -6 -40.81988 75.80973 -6 -41.1539 76.98997 0 -41.1539 76.98997 -6 -41.602 78.13183 -6 -42.15992 79.22437 0 -42.15992 79.22437 -6 -42.82227 80.25699 -6 -43.58252 81.21956 -6 -44.43344 82.10297 -6 -45.36703 82.89888 -6 -52.15294 85.47127 0 -53.37932 85.49424 -6 -54.60224 85.39689 0 -54.60224 85.39689 -6 -55.80969 85.18013 -6 -56.98997 84.8461 0 -56.98997 84.8461 -6 -58.13179 84.39802 -6 -59.22436 83.84008 0 -59.22436 83.84008 -6 -60.257 83.17771 -6 -61.21956 82.41748 -6 -62.10293 81.56661 -6 -62.89888 80.63297 -6 -65.47127 73.84706 0 -65.49425 72.62071 -6 -65.39689 71.39776 0 -65.39689 71.39776 -6 -65.18013 70.19027 -6 -64.8461 69.01004 0 -64.8461 69.01004 -6 -64.398 67.86817 -6 -63.84008 66.77564 0 -63.84008 66.77564 -6 -63.17773 65.74301 -6 -62.41748 64.78044 -6 -61.56656 63.89703 -6 -60.63296 63.10112 -6 -46.53329 78.72225 0 -57.18873 77.85717 0 -56.92305 76.76016 0 -53.692 74.04098 0 -46.59842 72.6034 0 -51.75249 73.07881 0 -47.63261 72.15126 0 -48.4498 71.37268 0 -52.15126 78.36739 0 -52.6034 79.40158 0 -53.0788 74.24752 0 -51.95902 73.692 0 -48.1864 67.20287 0 -47.27774 66.5333 0 -45.47195 72.67456 0 -44.38908 72.35615 0 -48.95141 70.36155 0 -51.88022 72.44449 0 -49.07695 69.23984 0 -52.308 71.95903 0 -48.81126 68.14284 0 -52.9212 71.75249 0 -53.55551 71.88022 0 -55.63845 68.95142 0 -56.76016 69.07695 0 -54.04098 72.308 0 -57.85716 68.81127 0 -54.11978 73.55551 0 -57.04859 75.63845 0 -54.24751 72.9212 0 -57.81359 78.79714 0 -54.62733 68.4498 0 -53.84874 67.63262 0 -53.3966 66.59842 0 -58.72225 79.46671 0 -47.20286 77.81359 0 -48.14284 77.18874 0 -49.23983 76.92305 0 -52.44449 74.11978 0 -50.36154 77.04859 0 -51.37267 77.5502 0 -52.67456 80.52806 0 -52.35615 81.61093 0 -53.32544 65.47195 0 -53.64385 64.38908 0 -58.79713 68.18641 0 -59.4667 67.27775 0 -57.5502 74.62733 0 -58.36738 73.84874 0 -59.40158 73.3966 0 -61.61092 73.64385 0 -60.52805 73.32545 0 -59.4667 67.27775 -3 -56.76016 69.07695 -3 -57.85716 68.81127 -3 -58.79713 68.18641 -3 -53.32544 65.47195 -3 -53.3966 66.59842 -3 -53.64385 64.38908 -3 -53.84874 67.63262 -3 -55.63845 68.95142 -3 -54.62733 68.4498 -3 -47.27774 66.5333 -3 -49.07695 69.23984 -3 -48.81126 68.14284 -3 -48.1864 67.20287 -3 -48.95141 70.36155 -3 -48.4498 71.37268 -3 -47.63261 72.15126 -3 -45.47195 72.67456 -3 -46.59842 72.6034 -3 -44.38908 72.35615 -3 -46.53329 78.72225 -3 -49.23983 76.92305 -3 -48.14284 77.18874 -3 -47.20286 77.81359 -3 -52.67456 80.52806 -3 -52.6034 79.40158 -3 -52.35615 81.61093 -3 -52.15126 78.36739 -3 -50.36154 77.04859 -3 -51.37267 77.5502 -3 -58.72225 79.46671 -3 -56.92305 76.76016 -3 -57.18873 77.85717 -3 -57.81359 78.79714 -3 -57.04859 75.63845 -3 -57.5502 74.62733 -3 -58.36738 73.84874 -3 -60.52805 73.32545 -3 -59.40158 73.3966 -3 -61.61092 73.64385 -3 -63.77059 75.24914 -36 -63.87324 75.3734 -36 -60.33038 74.46366 -36 -63.14314 74.7052 -36 -58.80344 75.92854 -36 -58.88462 75.77085 -36 -59.20205 79.13825 -36 -59.13472 75.39004 -36 -64.37444 76.32891 -36 -64.48551 76.83736 -36 -64.31875 78.27649 -36 -64.19779 78.55513 -36 -63.88592 79.05376 -36 -63.61851 79.35634 -36 -63.48308 79.4822 -36 -63.00413 79.82346 -36 -62.80775 79.9268 -36 -59.95109 79.78488 -36 -59.25005 79.19466 -36 -59.49555 74.99898 -36 -61.25027 74.23326 -36 -61.71362 74.22869 -36 -64.11186 75.72808 -36 -64.34616 76.24281 -36 -62.23642 74.31118 -36 -62.8436 74.53433 -36 -64.50933 77.30307 -36 -64.40613 78.00514 -36 -62.46793 80.06506 -36 -61.85814 80.20157 -36 -61.30702 80.21511 -36 -60.86953 80.1526 -36 -60.17705 79.90946 -36 -58.90879 78.71571 -36 -58.70393 78.28237 -36 -58.61451 76.43865 -36 -58.57984 77.8639 -36 -58.52985 76.87951 -36 -64.5048 77.79547 -32.24064 -48.52439 80.74758 -12.18479 -48.08144 79.95732 -12.11001 -49.40013 80.06043 -13.81585 -55.75307 83.91298 -16.46771 -55.02767 83.79077 -16.36865 -56.50296 83.22256 -20.10123 -64.9867 70.01679 -9.578104 -59.50582 66.68027 -15.86541 -60.23121 66.80249 -15.96447 -59.3725 67.55599 -17.60387 -64.68704 77.36865 -24.72781 -64.19779 78.55513 -24.75 -64.19779 78.55513 -28.5 -53.94957 75.02956 -20.7737 -54.48141 73.73491 -20.74984 -55.42436 74.20271 -22.77367 -62.66482 80.39157 -32.17309 -52.6772 74.20761 -18.32012 -53.02312 74.24979 -18.84821 -52.86478 74.62071 -18.81511 -51.79729 73.34058 -16.66576 -51.91441 73.61968 -16.96337 -51.68341 74.16395 -16.92479 -51.97679 73.71801 -17.09632 -52.18855 73.95082 -17.50084 -52.44449 74.11978 -17.94282 -51.75484 72.89008 -16.36751 -50.40813 73.6606 -15.10746 -51.81069 72.61524 -16.27942 -51.06109 72.03813 -15.08312 -51.88006 72.4448 -16.26292 -51.75016 73.02013 -16.43364 -51.75267 73.08165 -16.47038 -51.78608 73.29818 -16.629 -52.70497 71.78532 -16.8229 -52.61537 71.81065 -16.7336 -51.95791 70.53662 -15.10746 -52.34062 71.93806 -16.49341 -52.31408 71.95501 -16.47316 -52.094 72.1388 -16.33068 -51.93407 72.34709 -16.26893 -54.18984 72.61688 -19.39413 -54.05746 72.33346 -18.97327 -54.20864 71.91181 -18.81511 -53.85657 72.08963 -18.50168 -53.55973 71.88233 -17.94985 -53.23006 71.77136 -17.45069 -53.13022 71.24751 -16.92479 -53.02933 71.75035 -17.18899 -52.92533 71.75224 -17.06424 -54.12007 73.55493 -20.04162 -54.19238 73.37513 -20.01302 -54.23854 73.16888 -19.91851 -54.24334 73.12883 -19.89332 -55.19048 72.52819 -20.7737 -54.24731 72.91799 -19.72688 -54.24295 72.86745 -19.67877 -53.07783 74.24758 -18.92813 -53.23747 74.22724 -19.15504 -53.54477 74.12505 -19.55847 -53.60097 74.09606 -19.62598 -53.68757 74.04391 -19.72495 -53.8284 73.93608 -19.8692 -53.99501 73.75661 -19.99929 -54.1026 73.58889 -20.04056 -60.21736 82.69806 -20.65473 -60.88002 82.08943 -24.4412 -61.40261 81.97471 -20.79608 -62.28346 80.93882 -28.36113 -62.48577 81.01664 -20.90505 -63.02172 80.26792 -28.43534 -63.42723 79.86065 -20.97518 -63.66632 79.46204 -28.4831 -64.19779 78.55513 -32.25 -61.47825 81.44883 -28.26487 -62.00868 80.77461 -32.11979 -60.61937 81.0987 -31.98632 -61.31795 81.01303 -32.05671 -60.63541 81.77659 -28.15098 -52.51392 76.0697 -18.88524 -58.80391 79.5857 -33.82795 -58.53891 75.74781 -33.69046 -58.28058 76.4023 -33.69534 -57.83136 76.30876 -31.426 -57.64958 77.09555 -31.45245 -57.05104 77.05227 -29.23449 -56.98154 77.94036 -29.29326 -56.25855 77.94992 -27.13403 -56.33961 78.8996 -27.23029 -55.52319 78.96327 -25.13328 -55.795 79.92639 -25.26708 -54.9202 80.04348 -23.23205 -55.41462 80.96613 -23.399 -54.51798 81.13368 -21.42225 -57.54267 81.13818 -27.60724 -56.99466 80.52524 -27.4713 -57.67436 80.25007 -29.56035 -57.29879 79.57025 -29.45968 -57.92362 79.32913 -31.60992 -57.69558 78.63491 -31.54685 -58.23056 78.43163 -33.75836 -58.12229 77.76984 -33.73056 -58.7457 80.4349 -31.7556 -58.27806 79.9372 -31.68032 -58.46099 79.04463 -33.79125 -59.24666 80.03339 -33.86721 -59.7712 80.37094 -33.90773 -59.30705 80.80351 -31.83332 -59.94016 81.02747 -31.91104 -58.96799 81.84527 -27.88792 -59.78757 81.91078 -28.02386 -58.81847 82.65476 -24.12468 -59.85223 82.49022 -24.29162 -58.97342 83.15641 -20.48749 -56.07307 73.09535 -22.79587 -56.85955 72.11116 -22.85859 -56.05286 71.45732 -20.84115 -57.76009 71.29163 -22.95606 -57.04223 70.56729 -20.94596 -58.74213 70.66841 -23.08247 -58.12266 69.89241 -21.08189 -59.76992 70.26761 -23.23205 -59.25473 69.46096 -21.24273 -60.80368 70.10308 -23.399 -60.39462 69.28778 -21.42225 -61.80283 70.18232 -23.57752 -56.85374 73.61193 -24.87689 -57.5676 72.71607 -24.933 -58.38439 71.96956 -25.02019 -59.27463 71.40126 -25.13328 -60.20594 71.035 -25.26708 -61.14228 70.88342 -25.41643 -62.04686 70.95343 -25.57613 -62.88368 71.24011 -25.74102 -64.08315 70.50526 -20.30083 -64.70071 71.61157 -20.48749 -64.70195 72.71435 -24.29162 -61.49765 69.38088 -21.61422 -62.52002 69.73406 -21.81242 -62.72762 70.49987 -23.76184 -63.25875 69.6045 -20.10123 -63.53996 71.0441 -23.94615 -64.20754 71.7917 -24.12468 -63.65346 72.40049 -27.88792 -64.20147 73.01343 -28.02386 -64.60757 73.76969 -28.15098 -64.85004 76.58247 -28.43534 -64.93759 75.58876 -28.36113 -65.10256 74.93416 -24.56761 -65.12194 75.70275 -20.90505 -64.77109 77.15174 -20.97518 -64.5107 77.8624 -20.99366 -62.98685 71.95412 -27.74758 -62.22813 71.6934 -27.60724 -61.40856 71.62789 -27.4713 -60.56071 71.76208 -27.34418 -59.71788 72.08984 -27.23029 -58.91267 72.59985 -27.13403 -58.17441 73.27075 -27.05982 -63.03578 72.64121 -29.77914 -62.34505 72.40145 -29.668 -61.60068 72.33557 -29.56035 -60.83216 72.44782 -29.45968 -60.06959 72.733 -29.36949 -59.34247 73.18129 -29.29326 -59.36156 74.62064 -33.70914 -58.90375 75.14615 -33.69534 -58.55749 74.84506 -31.426 -58.13837 75.54911 -31.41664 -57.62395 75.2939 -29.18328 -57.26954 76.15934 -29.19666 -56.59777 75.95539 -27.01206 -56.34609 76.9562 -27.05982 -55.53731 76.80863 -24.933 -55.43708 77.91061 -25.02019 -54.5196 77.82367 -22.95606 -54.61751 78.98265 -23.08247 -53.62486 78.9589 -21.08189 -53.96623 80.12131 -21.24273 -52.93516 80.16088 -19.3028 -53.55272 81.26719 -19.48945 -52.5207 81.36758 -17.60387 -63.02911 73.30072 -31.83332 -62.396 73.07676 -31.7556 -61.7168 73.00553 -31.68032 -61.01821 73.0912 -31.60992 -60.32749 73.32963 -31.54685 -64.41255 74.7751 -32.05671 -64.05811 74.16703 -31.98632 -63.59047 73.66933 -31.91104 -62.9655 73.93199 -33.90773 -62.37939 73.71856 -33.86721 -61.75506 73.63688 -33.82795 -61.11679 73.69118 -33.79125 -64.73256 76.22349 -32.17309 -64.68659 77.00868 -32.21419 -59.16596 62.76757 -7.574367 -58.12701 62.31663 -7.546219 -57.04709 61.97266 -7.518291 -55.93691 61.73849 -7.490804 -50.69436 69.78048 -13.36782 -49.73284 71.3792 -13.34503 -48.79355 69.80541 -11.69547 -49.34225 68.98041 -11.7106 -49.95612 68.2089 -11.73501 -51.8913 68.3782 -13.43225 -50.63016 67.4989 -11.76804 -51.35892 66.85801 -11.80902 -53.28418 67.23007 -13.53236 -53.80054 65.40481 -11.97305 -54.82066 66.37957 -13.66221 -52.95167 65.80577 -11.91218 -52.13528 66.2919 -11.85729 -54.15386 70.00794 -16.99541 -53.06673 69.21497 -15.17623 -55.33562 68.98421 -17.10515 -54.35177 68.12792 -15.28309 -56.63193 68.21549 -17.24748 -55.76522 67.31684 -15.4217 -57.99514 67.73392 -17.4159 -55.62523 66.07785 -13.73643 -56.44378 65.86215 -13.81585 -57.25489 66.81561 -15.58569 -57.26828 65.7341 -13.89973 -58.76314 66.64132 -15.76873 -58.0907 65.69537 -13.98732 -58.24303 64.7853 -12.34363 -60.75622 65.54496 -12.59514 -61.60149 67.28993 -16.16656 -59.95111 65.20037 -12.51042 -60.93216 67.00627 -16.06512 -59.11055 64.94645 -12.42636 -55.1501 70.75581 -18.88524 -56.23325 69.79774 -18.99421 -57.4185 69.0744 -19.13556 -58.66245 68.61605 -19.3028 -59.91695 68.43845 -19.48945 -59.73723 63.71379 -9.199934 -58.78007 63.30022 -9.148432 -57.78377 62.98816 -9.097333 -56.75824 62.7802 -9.047039 -57.35704 64.71903 -12.26288 -56.46109 64.74913 -12.18479 -55.56387 64.87455 -12.11001 -54.67411 65.09366 -12.03921 -62.22839 66.49318 -12.76392 -61.51768 65.97753 -12.67986 -60.64561 64.22569 -9.251435 -64.17334 68.04347 -9.494842 -64.43139 69.27365 -13.08026 -63.62759 67.13529 -9.449384 -63.98844 68.48338 -13.00549 -62.99562 66.29156 -9.401911 -63.47035 67.7518 -12.92739 -62.28286 65.52092 -9.352827 -62.88155 67.08644 -12.84665 -61.49684 64.83018 -9.302534 -64.60885 70.46384 -16.74743 -64.25435 69.78437 -16.65789 -63.83513 69.1575 -16.56439 -61.13291 68.5499 -19.68906 -62.26223 68.94335 -19.89515 -62.23229 67.65126 -16.268 -62.81863 68.08608 -16.36865 -63.3548 68.58972 -16.46771 -65.00465 73.77518 -24.4412 -65.08835 72.87934 -20.65473 -65.19009 73.55904 -20.72905 -65.111 71.9532 -16.91143 -65.27031 71.91693 -13.27809 -65.076 70.99847 -13.21723 -65.22948 74.26068 -20.79608 -64.85652 74.63907 -28.26487 -64.64059 75.46932 -32.11979 -64.60135 77.64752 -13.49481 -64.92627 76.7115 -13.47968 -65.16918 75.75596 -13.45526 -65.3267 74.78973 -13.42224 -65.39609 73.82173 -13.38126 -65.37715 72.86107 -13.33299 -65.20671 74.97751 -20.85502 -64.99485 76.14701 -24.66508 -64.59836 77.58328 -28.4831 -64.62801 69.00701 -9.537883 -64.79523 70.11466 -13.15107 -64.89546 71.18907 -16.8322 -54.80716 61.61697 -7.463978 -53.6686 61.61018 -7.438032 -52.53215 61.7173 -7.413187 -51.4088 61.93673 -7.389663 -50.30953 62.2669 -7.367681 -49.2451 62.70553 -7.34746 -48.22534 63.24755 -7.329221 -47.25986 63.8872 -7.313184 -46.35829 64.61872 -7.299569 -45.52973 65.43578 -7.288596 -44.78129 66.32984 -7.280486 -44.11959 67.2918 -7.275458 -43.55125 68.31256 -7.273733 -43.08234 69.38265 -7.275458 -42.71673 70.4915 -7.280486 -42.45766 71.62833 -7.288596 -42.30837 72.78237 -7.299569 -42.27137 73.9428 -7.313184 -42.34617 75.09852 -7.329221 -42.53156 76.23841 -7.34746 -42.8263 77.35131 -7.367681 -43.22846 78.42633 -7.389663 -43.73337 79.45352 -7.413187 -44.33563 80.42319 -7.438032 -45.02986 81.32564 -7.463978 -45.81012 82.15165 -7.490804 -46.66823 82.89394 -7.518291 -47.59546 83.5457 -7.546219 -48.58308 84.10012 -7.574367 -50.63925 84.39608 -9.251435 -51.63556 84.70814 -9.302534 -52.66109 84.9161 -9.352827 -53.70591 85.01738 -9.401911 -54.76005 85.01011 -9.449384 -55.81335 84.89521 -9.494842 -56.85561 84.67428 -9.537883 -57.87664 84.34896 -9.578104 -58.86644 83.92152 -9.615102 -59.81592 83.39688 -9.648474 -60.71616 82.78066 -9.677818 -61.55826 82.07842 -9.702729 -62.33382 81.29631 -9.722806 -63.03628 80.44254 -9.737646 -63.65962 79.5259 -9.746845 -64.19779 78.55513 -9.75 -55.71342 62.67892 -8.997956 -54.65928 62.68619 -8.950483 -53.60598 62.80109 -8.905024 -52.56372 63.02202 -8.861984 -51.54269 63.34734 -8.821763 -50.55288 63.77479 -8.784765 -49.60341 64.29942 -8.751393 -48.70317 64.91565 -8.722049 -47.86106 65.61788 -8.697138 -47.08551 66.4 -8.677061 -46.38304 67.25376 -8.662221 -45.7597 68.17041 -8.653022 -45.22153 69.14118 -8.649867 -44.77418 70.15699 -8.653022 -44.42144 71.20788 -8.662221 -44.16664 72.28373 -8.677061 -44.01311 73.37442 -8.697138 -43.96345 74.46978 -8.722049 -44.01744 75.5594 -8.751393 -44.17414 76.63279 -8.784765 -44.43264 77.67951 -8.821763 -44.79132 78.6893 -8.861984 -45.24599 79.65283 -8.905024 -45.79174 80.56101 -8.950483 -46.4237 81.40475 -8.997956 -47.13646 82.17539 -9.047039 -47.92249 82.86612 -9.097333 -48.77372 83.47061 -9.148432 -49.6821 83.98251 -9.199934 -63.30097 80.05663 -17.22566 -64.19779 78.55513 -17.25 -64.19779 78.55513 -13.5 -60.90711 82.46533 -17.05003 -62.19215 81.37828 -17.15689 -61.88267 81.73206 -13.42224 -59.56116 83.4252 -13.27809 -60.21326 82.90775 -16.9843 -60.37755 82.93907 -13.33299 -61.15391 82.37295 -13.38126 -63.71928 79.42555 -13.49481 -63.17058 80.25055 -13.47968 -62.55671 81.02207 -13.45526 -58.71229 83.82615 -13.21723 -57.83872 84.1373 -13.15107 -58.75484 83.56709 -16.8322 -58.00399 83.77764 -16.74743 -53.40227 84.28451 -12.76392 -54.2698 84.44566 -12.84665 -55.15579 84.51193 -12.92739 -56.94896 84.35641 -13.08026 -56.05174 84.48184 -13.00549 -57.2485 83.90647 -16.65789 -56.49575 83.95193 -16.56439 -57.71892 83.334 -20.30083 -59.49366 83.27641 -16.91143 -57.81933 82.57551 -23.94615 -56.89453 82.25796 -23.76184 -58.20928 81.58455 -27.74758 -64.19779 78.55513 -21 -50.28444 82.73778 -12.42636 -51.38891 82.63565 -14.17069 -50.99515 83.25343 -12.51042 -52.03536 83.10987 -14.26498 -51.75661 83.68601 -12.59514 -52.72939 83.50578 -14.36001 -53.65739 83.30333 -16.16656 -53.02659 82.942 -16.06512 -52.44025 82.50717 -15.96447 -50.79629 82.08823 -14.07789 -49.63128 82.14453 -12.34363 -49.07666 79.27818 -13.73643 -47.7176 79.11631 -12.03921 -48.83014 78.45502 -13.66221 -47.43684 78.23249 -11.97305 -47.24252 77.31404 -11.91218 -48.57776 76.71707 -13.53236 -47.34365 73.475 -11.73501 -49.04162 73.11199 -13.36782 -48.64924 74.91342 -13.43225 -47.13568 76.36989 -11.85729 -47.11674 75.40924 -11.80902 -47.18613 74.44123 -11.76804 -47.58656 72.51946 -11.7106 -47.91148 71.58345 -11.69547 -48.31504 70.67584 -11.69028 -56.0822 81.71374 -23.57752 -55.37363 82.8291 -19.89515 -54.37712 82.16795 -19.68906 -54.53926 83.07799 -18.0124 -53.43686 82.35153 -17.80487 -60.48929 73.87858 -33.75836 -59.89685 74.19275 -33.73056 -59.67135 73.71266 -31.49354 -59.07398 74.22432 -31.45245 -58.6774 73.77393 -29.23449 -58.09862 74.48812 -29.19666 -57.52981 74.07663 -27.01206 -56.99834 74.98354 -26.99516 -56.26424 74.61936 -24.85704 -55.81874 75.69823 -24.87689 -54.93511 75.38918 -22.79587 -54.62731 76.61083 -22.85859 -53.61864 76.36409 -20.84115 -53.50855 77.69032 -20.94596 -52.40639 77.51177 -18.99421 -52.54752 78.89312 -19.13556 -51.38777 78.78646 -17.24748 -51.82907 80.16324 -17.4159 -50.65003 80.12941 -15.58569 -51.42375 81.43576 -15.76873 -49.79701 80.79438 -13.89973 -50.26373 81.47265 -13.98732 -49.04248 81.47917 -12.26288 -50.02663 75.34308 -15.17623 -51.31572 75.72893 -16.99541 -49.93854 77.02393 -15.28309 -51.21557 77.28923 -17.10515 -50.14788 78.64005 -15.4217 -54.32672 83.58699 -16.268 -52.56172 84.03059 -12.67986 -50.74039 83.8447 -10.87432 -49.90745 83.37344 -10.80403 -49.12843 82.81433 -10.7343 -48.41076 82.1733 -10.66566 -58.13913 77.08476 -33.70914 -57.6036 77.88075 -31.49354 -57.06451 78.79053 -29.36949 -56.58856 79.76898 -27.34418 -56.24079 80.76362 -25.41643 -47.76186 81.45623 -10.59868 -47.18865 80.66947 -10.53389 -46.69604 79.82111 -10.47185 -46.28843 78.91965 -10.41311 -45.97024 77.97361 -10.35822 -45.74525 76.99173 -10.30773 -45.61475 75.98359 -10.26219 -45.57941 74.95902 -10.22214 -45.63989 73.92781 -10.18815 -45.79619 72.89973 -10.16075 -46.04561 71.88431 -10.1405 -46.38479 70.89103 -10.12794 -46.81037 69.92938 -10.12364 -47.31858 69.00872 -10.12794 -47.90425 68.13773 -10.1405 -48.56185 67.32481 -10.16075 -49.28588 66.57837 -10.18815 -50.07036 65.90634 -10.22214 -50.90754 65.31461 -10.26219 -51.7892 64.80859 -10.30773 -52.70712 64.39369 -10.35822 -53.65288 64.07469 -10.41311 -54.61725 63.85385 -10.47185 -55.59077 63.73283 -10.53389 -56.56399 63.71324 -10.59868 -116.304 -141.6081 34 -114.3555 -143.1749 34 -118.197 -139.9746 34 -36.69919 -150.0419 34 -34.50592 -148.8412 34 -38.9328 -151.1656 34 -138.9757 -64.83538 34 -139.6776 -67.23521 34 -138.1909 -62.46134 34 -81.2535 -95.62993 9 -81.2535 -95.62993 12 -83.39624 -92.24485 12 -83.39624 -92.24485 9 -84.53088 -88.40264 12 -84.53088 -88.40264 9 -84.57081 -84.39659 12 -84.57081 -84.39659 9 -83.08413 -79.62273 12 -80.28582 -75.84799 12 -83.08413 -79.62273 9 -80.28582 -75.84799 9 -78.69588 -74.51296 9 -78.69588 -74.51296 12 -76.42736 -73.16629 9 -76.42736 -73.16629 12 -71.91394 -71.85925 12 -71.91394 -71.85925 9 -67.21956 -72.06411 12 -67.21956 -72.06411 9 -62.83717 -73.75937 12 -62.83717 -73.75937 9 -59.227 -76.76701 12 -59.227 -76.76701 9 -58.44852 -77.74919 9 -58.44852 -77.74919 12 -56.76816 -80.77117 9 -56.76816 -80.77117 12 -55.71886 -85.35137 12 -55.71886 -85.35137 9 -56.1893 -90.02661 12 -56.1893 -90.02661 9 -57.10413 -92.50105 9 -57.10413 -92.50105 12 -58.13006 -94.30593 9 -58.13006 -94.30593 12 -61.33736 -97.73995 12 -61.33736 -97.73995 9 -73.69557 -100.3265 12 -69.71162 -100.7486 9 -69.71162 -100.7486 12 -65.76423 -100.0643 9 -65.76423 -100.0643 12 -77.41196 -98.83032 12 -77.41196 -98.83032 9 -76.45053 -99.33557 12 -76.45053 -99.33557 9 -73.69557 -100.3265 9 -72.49552 -84.33623 9 -73.14683 -85.74596 9 -94.32586 -81.35867 9 -92.83918 -76.5848 9 -83.95173 -106.6802 9 -87.79328 -103.4799 9 -72.11082 -88.5614 9 -73.00602 -87.29248 9 -70.70109 -89.21271 9 -69.15457 -89.0719 9 -78.4299 -88.55852 9 -79.18176 -88.21115 9 -79.6592 -87.53439 9 -79.73429 -86.70958 9 -65.22119 -85.80401 9 -67.88565 -88.17671 9 -67.23434 -86.76698 9 -77.1335 -85.75256 9 -77.88536 -85.40519 9 -78.71017 -85.48029 9 -79.38693 -85.95773 9 -67.37515 -85.22046 9 -68.27035 -83.95154 9 -77.60509 -88.48342 9 -76.92833 -88.00598 9 -76.58097 -87.25412 9 -76.65606 -86.42932 9 -71.2266 -83.44104 9 -69.68008 -83.30023 9 -56.58763 -106.786 9 -61.01451 -109.1103 9 -68.2359 -95.24764 9 -69.19293 -92.64685 9 -70.01774 -92.72195 9 -67.88854 -94.49578 9 -67.96363 -93.67098 9 -68.44107 -92.99422 9 -70.6945 -93.19939 9 -71.04187 -93.95124 9 -70.96677 -94.77605 9 -70.48933 -95.45281 9 -69.73747 -95.80018 9 -68.91266 -95.72508 9 -63.45283 -84.50696 9 -63.8002 -85.25881 9 -63.7251 -86.08362 9 -63.24766 -86.76038 9 -62.49581 -87.10774 9 -61.671 -87.03265 9 -60.99424 -86.55521 9 -60.64687 -85.80335 9 -60.72197 -84.97855 9 -61.19941 -84.30179 9 -61.95126 -83.95442 9 -62.77607 -84.02952 9 -70.36343 -79.79099 9 -69.68667 -79.31355 9 -72.49263 -78.01715 9 -72.14527 -77.2653 9 -71.46851 -76.78786 9 -72.41754 -78.84196 9 -71.9401 -79.51872 9 -71.18824 -79.86608 9 -69.3393 -78.56169 9 -69.4144 -77.73689 9 -69.89184 -77.06013 9 -70.64369 -76.71276 9 -61.57482 -108.0432 12 -57.14794 -105.7188 12 -65.22119 -85.80401 12 -68.44107 -92.99422 12 -67.96363 -93.67098 12 -70.6945 -93.19939 12 -70.01774 -92.72195 12 -69.19293 -92.64685 12 -67.88854 -94.49578 12 -68.2359 -95.24764 12 -68.91266 -95.72508 12 -69.73747 -95.80018 12 -70.48933 -95.45281 12 -70.96677 -94.77605 12 -71.04187 -93.95124 12 -91.68841 -76.94318 12 -93.17509 -81.71704 12 -87.0218 -102.5538 12 -83.18025 -105.7542 12 -77.60509 -88.48342 12 -78.4299 -88.55852 12 -68.27035 -83.95154 12 -67.37515 -85.22046 12 -67.23434 -86.76698 12 -67.88565 -88.17671 12 -73.14683 -85.74596 12 -77.1335 -85.75256 12 -76.65606 -86.42932 12 -76.92833 -88.00598 12 -79.38693 -85.95773 12 -79.73429 -86.70958 12 -79.6592 -87.53439 12 -79.18176 -88.21115 12 -78.71017 -85.48029 12 -77.88536 -85.40519 12 -73.00602 -87.29248 12 -72.49552 -84.33623 12 -71.2266 -83.44104 12 -69.68008 -83.30023 12 -69.15457 -89.0719 12 -70.70109 -89.21271 12 -72.11082 -88.5614 12 -76.58097 -87.25412 12 -69.3393 -78.56169 12 -69.68667 -79.31355 12 -70.36343 -79.79099 12 -72.49263 -78.01715 12 -72.14527 -77.2653 12 -71.18824 -79.86608 12 -71.9401 -79.51872 12 -72.41754 -78.84196 12 -62.49581 -87.10774 12 -63.24766 -86.76038 12 -63.7251 -86.08362 12 -63.8002 -85.25881 12 -63.45283 -84.50696 12 -62.77607 -84.02952 12 -61.95126 -83.95442 12 -61.19941 -84.30179 12 -60.72197 -84.97855 12 -60.64687 -85.80335 12 -60.99424 -86.55521 12 -61.671 -87.03265 12 -69.4144 -77.73689 12 -69.89184 -77.06013 12 -70.64369 -76.71276 12 -71.46851 -76.78786 12 -87.60772 -111.0687 14.47296 -86.64222 -109.9097 17.18251 -116.2757 -145.4799 26 -114.3555 -143.1749 28.32566 -116.2757 -145.4799 34 -120.1172 -142.2795 34 -120.1172 -142.2795 26 -118.197 -139.9746 28.32566 -91.44927 -107.8683 14.47296 -90.48377 -106.7093 17.18251 -53.93235 -111.843 14.47296 -54.63357 -110.5075 17.18251 -33.11129 -151.4974 26 -34.50592 -148.8412 28.32566 -33.11129 -151.4974 34 -33.11129 -151.4974 37 -34.50592 -148.8412 37 -37.53816 -153.8218 34 -37.53816 -153.8218 26 -38.9328 -151.1656 28.32566 -58.35922 -114.1674 14.47296 -59.06045 -112.8319 17.18251 -99.77932 -79.66035 14.47296 -98.33913 -80.10885 17.18251 -142.5419 -66.3432 26 -139.6776 -67.23521 28.32566 -142.5419 -66.3432 34 -141.0552 -61.56933 37 -138.1909 -62.46134 37 -141.0552 -61.56933 34 -141.0552 -61.56933 26 -138.1909 -62.46134 28.32566 -98.29264 -74.88648 14.47296 -96.85245 -75.33499 17.18251 -120.1322 -138.1803 34 -122.2063 -140.3455 34 -127.0083 -130.551 34 -129.3616 -132.4089 34 -132.7295 -122.0214 34 -135.317 -123.5364 34 -137.1798 -112.765 34 -139.9519 -113.908 34 -140.2685 -102.9698 34 -143.1722 -103.719 34 -141.933 -92.8349 34 -144.9125 -93.17575 34 -142.1394 -82.56632 34 -145.1378 -82.49226 34 -140.8835 -72.37275 34 -143.8432 -71.88509 34 -43.76807 -153.2796 34 -42.75391 -156.1026 34 -53.56722 -156.3558 34 -52.95286 -159.2915 34 -63.70422 -158.0073 34 -63.50136 -160.9994 34 -73.97306 -158.2005 34 -74.18551 -161.1917 34 -84.16502 -156.9315 34 -84.78865 -159.8645 34 -94.07295 -154.2262 34 -95.09577 -157.0447 34 -103.4955 -150.1394 34 -104.8979 -152.7896 34 -112.2412 -144.7543 34 -113.9962 -147.1853 34 -118.2231 -143.9117 34 -35.30536 -152.6964 34 -141.8383 -63.94388 34 -143.8432 -71.88509 37 -145.1378 -82.49226 37 -144.9125 -93.17575 37 -143.1722 -103.719 37 -139.9519 -113.908 37 -135.317 -123.5364 37 -129.3616 -132.4089 37 -122.2063 -140.3455 37 -113.9962 -147.1853 37 -104.8979 -152.7896 37 -95.09577 -157.0447 37 -84.78865 -159.8645 37 -74.18551 -161.1917 37 -63.50136 -160.9994 37 -52.95286 -159.2915 37 -42.75391 -156.1026 37 -43.76807 -153.2796 37 -53.56722 -156.3558 37 -63.70422 -158.0073 37 -73.97306 -158.2005 37 -84.16502 -156.9315 37 -94.07295 -154.2262 37 -103.4955 -150.1394 37 -112.2412 -144.7543 37 -120.1322 -138.1803 37 -127.0083 -130.551 37 -132.7295 -122.0214 37 -137.1798 -112.765 37 -140.2685 -102.9698 37 -141.933 -92.8349 37 -142.1394 -82.56632 37 -140.8835 -72.37275 37 -67.6807 83.8171 9 -67.14727 84.59965 9 -66.93825 84.96327 9 -72.62995 83.74659 9 -73.18547 84.51363 9 -73.16667 83.19436 9 -51.61468 69.78584 9 -52.95014 69.50035 9 -52.93643 68.53826 9 -54.38531 76.21417 9 -53.04986 76.49964 9 -53.05231 76.67168 9 -83.64081 92.89661 9 -84.68542 90.11648 9 -82.58677 90.95832 9 -84.35826 81.32931 9 -82.43943 80.61566 9 -82.47428 83.06176 9 -59.8511 59.656 9 -59.29836 59.38638 9 -59.36755 65.53112 9 -51.19499 58.109 9 -48.29653 58.75649 9 -47.42467 65.70127 9 -41.12165 63.84004 9 -39.54977 66.35987 9 -44.02822 85.02111 9 -47.69785 84.87673 9 -47.67905 83.55747 9 -58.8301 75.874 9 -59.41022 75.21231 9 -59.47264 72.90779 9 -61.45298 78.80838 9 -60.58988 78.63682 9 -59.58709 80.94123 9 -60.24346 74.92932 9 -61.10656 75.10086 9 -63.36205 72.85238 9 -62.0932 75.58723 9 -62.75489 76.16735 9 -63.41436 76.52406 9 -63.03788 77.00059 9 -63.4765 80.88581 9 -62.86633 77.86369 9 -62.28622 78.52539 9 -58.47024 72.92207 9 -58.52255 76.59375 9 -58.65856 76.7371 9 -58.94155 77.57034 9 -58.58469 80.95551 9 -59.60324 78.15045 9 -57.03776 93.4678 9 -57.68088 91.31314 9 -55.87478 90.73507 9 -57.65441 89.45478 9 -55.27301 87.82678 9 -57.58718 84.73585 9 -52.30727 87.984 9 -46.57247 86.55312 9 -49.3687 87.55382 9 -53.16809 84.7988 9 -41.83566 83.01786 9 -47.6442 81.11137 9 -40.08077 80.62191 9 -47.58206 76.74961 9 -38.83232 77.92716 9 -47.52976 73.07793 9 -46.58978 70.7877 9 -45.75654 71.07069 9 -38.13927 75.03926 9 -38.02877 72.07142 9 -44.89344 70.89914 9 -45.41012 67.36318 9 -44.54702 67.19164 9 -43.71378 67.47463 9 -46.39675 67.84955 9 -47.05845 68.42966 9 -47.46619 68.61619 9 -47.34144 69.2629 9 -47.16989 70.126 9 -43.9068 70.41278 9 -43.2451 69.83266 9 -38.50516 69.13999 9 -42.96212 68.99942 9 -43.13367 68.13632 9 -45.58246 59.96236 9 -43.15917 61.67931 9 -62.34585 61.26735 9 -63.29849 68.39064 9 -66.15283 65.78868 9 -63.25696 65.47571 9 -64.47425 63.33865 9 -67.3158 68.5214 9 -66.91562 68.33911 9 -67.91758 71.42969 9 -66.97918 72.80084 9 -70.88331 71.27247 9 -76.61811 72.70336 9 -74.87574 72.68835 9 -79.16237 74.23535 9 -74.92804 76.36003 9 -81.35492 76.2386 9 -74.99018 80.72179 9 -83.10981 78.63456 9 -85.05132 84.21721 9 -82.49308 84.38103 9 -85.16181 87.18505 9 -82.5603 89.09996 9 -74.89405 100.5 9 -77.60812 99.29412 9 -75.13753 91.06444 9 -80.03141 97.57716 9 -82.06893 95.41643 9 -67.76538 94.24773 9 -67.981 93.39457 9 -67.24098 91.17694 9 -68.59432 92.76353 9 -69.44098 92.52369 9 -70.29414 92.73931 9 -70.92518 93.35263 9 -71.95989 91.10971 9 -71.16503 94.1993 9 -73.27916 91.09091 9 -72.10485 101.1338 9 -70.9494 95.05245 9 -70.33609 95.6835 9 -71.9956 101.1475 9 -69.48941 95.92334 9 -69.02639 101.2112 9 -66.10282 100.6887 9 -68.63626 95.70771 9 -68.00521 95.0944 9 -63.62385 91.22846 9 -63.33948 99.60047 9 -60.84473 97.98912 9 -59.73444 91.28388 9 -59.70796 89.42552 9 -58.02143 66.65342 9 -57.40811 67.28447 9 -57.35553 68.4753 9 -56.56144 67.52431 9 -55.70829 67.30869 9 -55.07724 66.69537 9 -52.89491 65.62333 9 -54.8374 65.8487 9 -55.05302 64.99554 9 -54.16419 58.04524 9 -55.66634 64.3645 9 -57.08777 58.56774 9 -56.51301 64.12466 9 -57.21985 58.6058 9 -57.36617 64.34028 9 -58.29884 58.9671 9 -57.99721 64.9536 9 -58.36515 65.54541 9 -58.23705 65.80027 9 -58.40668 68.46032 9 -47.97857 79.34658 9 -48.59189 78.71553 9 -49.43856 78.4757 9 -50.29172 78.69132 9 -50.92276 79.30464 9 -53.11445 81.03343 9 -47.76295 80.19973 9 -51.1626 80.1513 9 -50.94697 81.00446 9 -53.14929 83.47953 9 -50.33366 81.6355 9 -49.48699 81.87535 9 -48.63383 81.65972 9 -48.00279 81.0464 9 -67.03149 76.47252 9 -67.09363 80.83428 9 -69.45599 79.1603 9 -69.21614 78.31364 9 -69.43177 77.46048 9 -70.04508 76.82944 9 -72.40017 79.11837 9 -71.78685 79.74941 9 -71.81255 80.76705 9 -70.94019 79.98925 9 -70.08703 79.77362 9 -71.74491 76.80522 9 -72.37596 77.41854 9 -73.06968 76.3865 9 -72.61579 78.26521 9 -73.13182 80.74826 9 -63.70774 86.36003 9 -63.09442 86.99108 9 -63.59737 89.37011 9 -62.24775 87.23091 9 -61.39459 87.01529 9 -60.76355 86.40197 9 -59.64073 84.70659 9 -60.52371 85.5553 9 -60.73933 84.70214 9 -59.62194 83.38732 9 -61.35265 84.07109 9 -63.51135 83.33191 9 -62.19932 83.83126 9 -63.05248 84.04688 9 -51.7068 76.25234 9 -54.29319 69.74768 9 -55.43937 70.49012 9 -56.21417 71.61469 9 -57.41909 72.93704 9 -56.49964 72.95014 9 -57.4714 76.60872 9 -56.25233 74.29319 9 -55.50988 75.43937 9 -50.56063 75.50988 9 -49.78583 74.38532 9 -49.50035 73.04986 9 -49.74767 71.7068 9 -50.49012 70.56063 9 -66.97641 87.64179 9 -67.2145 89.31858 9 -67.75122 88.76634 9 -68.89739 89.5088 9 -70.24044 89.75611 9 -71.5759 89.47064 9 -71.93342 89.25135 9 -72.70046 88.69583 9 -73.25269 89.23255 9 -73.44292 87.54966 9 -75.11106 89.20608 9 -73.69023 86.20661 9 -75.04383 84.48715 9 -73.40476 84.87115 9 -71.8474 83.21315 9 -71.48377 83.00414 9 -70.14073 82.75682 9 -68.80527 83.0423 9 -67.12848 83.28038 9 -66.69094 86.30632 9 -63.92337 85.50686 9 -63.68352 84.6602 9 -76.67343 86.15291 9 -77.28675 85.52187 9 -76.4578 87.00607 9 -76.69764 87.85274 9 -78.13341 85.28202 9 -78.98657 85.49765 9 -79.61761 86.11096 9 -79.85746 86.95764 9 -79.64183 87.8108 9 -79.02851 88.44184 9 -78.18184 88.68168 9 -77.32868 88.46606 9 -58.71634 95.91783 9 -58.73204 91.29816 9 -58.70556 89.4398 9 -58.63833 84.72087 9 -58.61954 83.40161 9 -75.02503 83.16789 9 -57.56839 83.41658 9 -57.53354 80.97048 9 -70.89176 76.58959 9 -71.75041 76.4053 9 -71.69811 72.73362 9 -73.01737 72.71482 9 -73.82189 71.70265 9 -59.40908 68.44605 9 -55.27301 87.82678 4 -55.87478 90.73507 4 -57.03776 93.4678 4 -58.71634 95.91783 4 -60.84473 97.98912 4 -63.33948 99.60047 4 -66.10282 100.6887 4 -69.02639 101.2112 4 -71.9956 101.1475 4 -72.10485 101.1338 4 -74.89405 100.5 4 -77.60812 99.29412 4 -80.03141 97.57716 4 -82.06893 95.41643 4 -83.64081 92.89661 4 -84.68542 90.11648 4 -85.16181 87.18505 4 -85.05132 84.21721 4 -84.35826 81.32931 4 -83.10981 78.63456 4 -81.35492 76.2386 4 -79.16237 74.23535 4 -76.61811 72.70336 4 -73.82189 71.70265 4 -70.88331 71.27247 4 -67.91758 71.42969 4 -67.3158 68.5214 4 -66.15283 65.78868 4 -64.47425 63.33865 4 -62.34585 61.26735 4 -59.8511 59.656 4 -59.29836 59.38638 4 -58.29884 58.9671 4 -57.21985 58.6058 4 -57.08777 58.56774 4 -54.16419 58.04524 4 -51.19499 58.109 4 -48.29653 58.75649 4 -45.58246 59.96236 4 -43.15917 61.67931 4 -41.12165 63.84004 4 -39.54977 66.35987 4 -38.50516 69.13999 4 -38.02877 72.07142 4 -38.13927 75.03926 4 -38.83232 77.92716 4 -40.08077 80.62191 4 -41.83566 83.01786 4 -44.02822 85.02111 4 -46.57247 86.55312 4 -49.3687 87.55382 4 -52.30727 87.984 4 -73.01737 72.71482 4 -74.87574 72.68835 4 -74.92804 76.36003 4 -59.40908 68.44605 4 -63.29849 68.39064 4 -63.36205 72.85238 4 -60.24346 74.92932 4 -59.41022 75.21231 4 -59.47264 72.90779 4 -72.62995 83.74659 4 -73.18547 84.51363 4 -73.40476 84.87115 4 -63.92337 85.50686 4 -63.68352 84.6602 4 -67.14727 84.59965 4 -56.56144 67.52431 4 -57.40811 67.28447 4 -57.35553 68.4753 4 -75.13753 91.06444 4 -57.68088 91.31314 4 -58.73204 91.29816 4 -47.69785 84.87673 4 -71.69811 72.73362 4 -66.97918 72.80084 4 -66.91562 68.33911 4 -63.25696 65.47571 4 -59.36755 65.53112 4 -58.36515 65.54541 4 -47.42467 65.70127 4 -45.41012 67.36318 4 -44.54702 67.19164 4 -45.75654 71.07069 4 -46.58978 70.7877 4 -47.52976 73.07793 4 -44.89344 70.89914 4 -47.16989 70.126 4 -47.34144 69.2629 4 -47.46619 68.61619 4 -47.05845 68.42966 4 -46.39675 67.84955 4 -43.71378 67.47463 4 -43.13367 68.13632 4 -42.96212 68.99942 4 -43.2451 69.83266 4 -43.9068 70.41278 4 -47.67905 83.55747 4 -47.6442 81.11137 4 -47.58206 76.74961 4 -53.16809 84.7988 4 -57.65441 89.45478 4 -57.58718 84.73585 4 -59.73444 91.28388 4 -63.62385 91.22846 4 -67.24098 91.17694 4 -69.44098 92.52369 4 -68.59432 92.76353 4 -68.63626 95.70771 4 -69.48941 95.92334 4 -70.33609 95.6835 4 -70.9494 95.05245 4 -71.16503 94.1993 4 -70.92518 93.35263 4 -70.29414 92.73931 4 -71.95989 91.10971 4 -67.981 93.39457 4 -67.76538 94.24773 4 -68.00521 95.0944 4 -73.27916 91.09091 4 -82.58677 90.95832 4 -82.43943 80.61566 4 -82.47428 83.06176 4 -74.99018 80.72179 4 -52.89491 65.62333 4 -54.8374 65.8487 4 -52.93643 68.53826 4 -55.07724 66.69537 4 -55.70829 67.30869 4 -58.02143 66.65342 4 -58.40668 68.46032 4 -58.23705 65.80027 4 -49.43856 78.4757 4 -48.59189 78.71553 4 -53.11445 81.03343 4 -51.1626 80.1513 4 -53.05231 76.67168 4 -50.92276 79.30464 4 -50.29172 78.69132 4 -47.97857 79.34658 4 -47.76295 80.19973 4 -48.00279 81.0464 4 -48.63383 81.65972 4 -49.48699 81.87535 4 -53.14929 83.47953 4 -50.33366 81.6355 4 -50.94697 81.00446 4 -72.37596 77.41854 4 -71.74491 76.80522 4 -71.75041 76.4053 4 -70.89176 76.58959 4 -70.04508 76.82944 4 -69.43177 77.46048 4 -67.03149 76.47252 4 -69.21614 78.31364 4 -67.09363 80.83428 4 -70.94019 79.98925 4 -71.81255 80.76705 4 -70.08703 79.77362 4 -69.45599 79.1603 4 -71.78685 79.74941 4 -72.40017 79.11837 4 -73.13182 80.74826 4 -72.61579 78.26521 4 -59.64073 84.70659 4 -60.73933 84.70214 4 -60.52371 85.5553 4 -59.70796 89.42552 4 -60.76355 86.40197 4 -61.39459 87.01529 4 -63.59737 89.37011 4 -62.24775 87.23091 4 -63.09442 86.99108 4 -61.35265 84.07109 4 -59.62194 83.38732 4 -62.19932 83.83126 4 -63.51135 83.33191 4 -63.05248 84.04688 4 -67.12848 83.28038 4 -66.93825 84.96327 4 -66.69094 86.30632 4 -63.70774 86.36003 4 -66.97641 87.64179 4 -52.95014 69.50035 4 -51.61468 69.78584 4 -55.43937 70.49012 4 -54.29319 69.74768 4 -54.38531 76.21417 4 -55.50988 75.43937 4 -57.4714 76.60872 4 -56.25233 74.29319 4 -57.41909 72.93704 4 -56.49964 72.95014 4 -56.21417 71.61469 4 -50.56063 75.50988 4 -51.7068 76.25234 4 -53.04986 76.49964 4 -50.49012 70.56063 4 -49.74767 71.7068 4 -49.50035 73.04986 4 -49.78583 74.38532 4 -73.44292 87.54966 4 -73.69023 86.20661 4 -75.04383 84.48715 4 -68.89739 89.5088 4 -70.24044 89.75611 4 -67.2145 89.31858 4 -67.75122 88.76634 4 -58.94155 77.57034 4 -59.60324 78.15045 4 -59.58709 80.94123 4 -60.58988 78.63682 4 -61.45298 78.80838 4 -62.28622 78.52539 4 -63.4765 80.88581 4 -62.86633 77.86369 4 -63.41436 76.52406 4 -58.58469 80.95551 4 -58.65856 76.7371 4 -58.52255 76.59375 4 -58.8301 75.874 4 -58.47024 72.92207 4 -61.10656 75.10086 4 -62.0932 75.58723 4 -62.75489 76.16735 4 -63.03788 77.00059 4 -57.99721 64.9536 4 -57.36617 64.34028 4 -56.51301 64.12466 4 -55.66634 64.3645 4 -55.05302 64.99554 4 -73.06968 76.3865 4 -73.16667 83.19436 4 -71.8474 83.21315 4 -82.5603 89.09996 4 -82.49308 84.38103 4 -75.02503 83.16789 4 -57.56839 83.41658 4 -57.53354 80.97048 4 -67.6807 83.8171 4 -68.80527 83.0423 4 -70.14073 82.75682 4 -71.48377 83.00414 4 -58.61954 83.40161 4 -58.63833 84.72087 4 -58.70556 89.4398 4 -76.4578 87.00607 4 -76.69764 87.85274 4 -75.11106 89.20608 4 -79.02851 88.44184 4 -78.18184 88.68168 4 -77.32868 88.46606 4 -79.64183 87.8108 4 -79.85746 86.95764 4 -79.61761 86.11096 4 -78.98657 85.49765 4 -78.13341 85.28202 4 -77.28675 85.52187 4 -76.67343 86.15291 4 -73.25269 89.23255 4 -72.70046 88.69583 4 -71.93342 89.25135 4 -71.5759 89.47064 4 -116.304 141.6081 34 -118.197 139.9746 34 -114.3555 143.1749 34 -138.9757 64.83538 34 -138.1909 62.46134 34 -139.6776 67.23521 34 -36.69919 150.0419 34 -38.9328 151.1656 34 -34.50592 148.8412 34 -77.41196 98.83032 9 -77.41196 98.83032 12 -73.69557 100.3265 12 -73.69557 100.3265 9 -69.71162 100.7486 12 -69.71162 100.7486 9 -65.76423 100.0643 12 -65.76423 100.0643 9 -61.33736 97.73995 12 -58.13006 94.30593 12 -61.33736 97.73995 9 -58.13006 94.30593 9 -57.10413 92.50105 9 -57.10413 92.50105 12 -56.1893 90.02661 9 -56.1893 90.02661 12 -55.71886 85.35137 12 -55.71886 85.35137 9 -56.76816 80.77117 12 -56.76816 80.77117 9 -59.227 76.76701 12 -59.227 76.76701 9 -62.83717 73.75937 12 -62.83717 73.75937 9 -63.94379 73.17107 9 -63.94379 73.17107 12 -67.21956 72.06411 9 -67.21956 72.06411 12 -71.91394 71.85925 12 -71.91394 71.85925 9 -76.42736 73.16629 12 -76.42736 73.16629 9 -78.69588 74.51296 9 -78.69588 74.51296 12 -80.28582 75.84799 9 -80.28582 75.84799 12 -83.08413 79.62273 12 -83.08413 79.62273 9 -83.39624 92.24485 12 -84.53088 88.40264 9 -84.53088 88.40264 12 -84.57081 84.39659 9 -84.57081 84.39659 12 -81.2535 95.62993 12 -81.2535 95.62993 9 -81.92408 94.77556 12 -81.92408 94.77556 9 -83.39624 92.24485 9 -67.88565 88.17671 9 -69.15457 89.0719 9 -61.01451 109.1103 9 -56.58763 106.786 9 -87.79328 103.4799 9 -83.95173 106.6802 9 -72.11082 88.5614 9 -70.70109 89.21271 9 -73.00602 87.29248 9 -73.14683 85.74596 9 -70.96677 94.77605 9 -70.48933 95.45281 9 -69.73747 95.80018 9 -68.91266 95.72508 9 -70.64304 81.28707 9 -72.49552 84.33623 9 -71.2266 83.44104 9 -68.44107 92.99422 9 -67.96363 93.67098 9 -67.88854 94.49578 9 -68.2359 95.24764 9 -69.68008 83.30023 9 -68.27035 83.95154 9 -71.04187 93.95124 9 -70.6945 93.19939 9 -70.01774 92.72195 9 -69.19293 92.64685 9 -67.23434 86.76698 9 -67.37515 85.22046 9 -92.83918 76.5848 9 -94.32586 81.35867 9 -79.38693 85.95773 9 -76.65606 86.42932 9 -76.58097 87.25412 9 -78.71017 85.48029 9 -77.88536 85.40519 9 -77.1335 85.75256 9 -76.92833 88.00598 9 -77.60509 88.48342 9 -78.4299 88.55852 9 -79.18176 88.21115 9 -79.6592 87.53439 9 -79.73429 86.70958 9 -69.68667 79.31355 9 -70.36343 79.79099 9 -71.18824 79.86608 9 -71.9401 79.51872 9 -72.41754 78.84196 9 -72.49263 78.01715 9 -72.14527 77.2653 9 -71.46851 76.78786 9 -70.64369 76.71276 9 -69.89184 77.06013 9 -69.4144 77.73689 9 -69.3393 78.56169 9 -63.8002 85.25881 9 -63.45283 84.50696 9 -61.671 87.03265 9 -60.99424 86.55521 9 -60.64687 85.80335 9 -62.49581 87.10774 9 -63.24766 86.76038 9 -63.7251 86.08362 9 -62.77607 84.02952 9 -61.95126 83.95442 9 -61.19941 84.30179 9 -60.72197 84.97855 9 -93.17509 81.71704 12 -91.68841 76.94318 12 -70.64304 81.28707 12 -77.1335 85.75256 12 -77.88536 85.40519 12 -76.92833 88.00598 12 -76.58097 87.25412 12 -76.65606 86.42932 12 -78.71017 85.48029 12 -79.38693 85.95773 12 -79.73429 86.70958 12 -79.6592 87.53439 12 -79.18176 88.21115 12 -78.4299 88.55852 12 -77.60509 88.48342 12 -57.14794 105.7188 12 -61.57482 108.0432 12 -83.18025 105.7542 12 -87.0218 102.5538 12 -71.04187 93.95124 12 -70.96677 94.77605 12 -68.27035 83.95154 12 -69.68008 83.30023 12 -71.2266 83.44104 12 -72.49552 84.33623 12 -69.15457 89.0719 12 -68.44107 92.99422 12 -69.19293 92.64685 12 -70.6945 93.19939 12 -68.2359 95.24764 12 -68.91266 95.72508 12 -69.73747 95.80018 12 -70.48933 95.45281 12 -67.88854 94.49578 12 -67.96363 93.67098 12 -70.70109 89.21271 12 -67.88565 88.17671 12 -67.23434 86.76698 12 -67.37515 85.22046 12 -73.14683 85.74596 12 -73.00602 87.29248 12 -72.11082 88.5614 12 -70.01774 92.72195 12 -62.77607 84.02952 12 -63.45283 84.50696 12 -63.8002 85.25881 12 -61.671 87.03265 12 -60.99424 86.55521 12 -63.7251 86.08362 12 -63.24766 86.76038 12 -62.49581 87.10774 12 -72.41754 78.84196 12 -71.9401 79.51872 12 -71.18824 79.86608 12 -70.36343 79.79099 12 -69.68667 79.31355 12 -69.3393 78.56169 12 -69.4144 77.73689 12 -69.89184 77.06013 12 -70.64369 76.71276 12 -71.46851 76.78786 12 -72.14527 77.2653 12 -72.49263 78.01715 12 -61.95126 83.95442 12 -61.19941 84.30179 12 -60.72197 84.97855 12 -60.64687 85.80335 12 -91.44927 107.8683 14.47296 -90.48377 106.7093 17.18251 -120.1172 142.2795 26 -118.197 139.9746 28.32566 -120.1172 142.2795 34 -116.2757 145.4799 34 -116.2757 145.4799 26 -114.3555 143.1749 28.32566 -87.60772 111.0687 14.47296 -86.64222 109.9097 17.18251 -98.29264 74.88648 14.47296 -96.85245 75.33499 17.18251 -141.0552 61.56933 26 -138.1909 62.46134 28.32566 -141.0552 61.56933 34 -141.0552 61.56933 37 -138.1909 62.46134 37 -142.5419 66.3432 34 -142.5419 66.3432 26 -139.6776 67.23521 28.32566 -99.77932 79.66035 14.47296 -98.33913 80.10885 17.18251 -58.35922 114.1674 14.47296 -59.06045 112.8319 17.18251 -37.53816 153.8218 26 -38.9328 151.1656 28.32566 -37.53816 153.8218 34 -33.11129 151.4974 37 -34.50592 148.8412 37 -33.11129 151.4974 34 -33.11129 151.4974 26 -34.50592 148.8412 28.32566 -53.93235 111.843 14.47296 -54.63357 110.5075 17.18251 -112.2412 144.7543 34 -113.9962 147.1853 34 -103.4955 150.1394 34 -104.8979 152.7896 34 -94.07295 154.2262 34 -95.09577 157.0447 34 -84.16502 156.9315 34 -84.78865 159.8645 34 -73.97306 158.2005 34 -74.18551 161.1917 34 -63.70422 158.0073 34 -63.50136 160.9994 34 -53.56722 156.3558 34 -52.95286 159.2915 34 -43.76807 153.2796 34 -42.75391 156.1026 34 -140.8835 72.37275 34 -143.8432 71.88509 34 -142.1394 82.56632 34 -145.1378 82.49226 34 -141.933 92.8349 34 -144.9125 93.17575 34 -140.2685 102.9698 34 -143.1722 103.719 34 -137.1798 112.765 34 -139.9519 113.908 34 -132.7295 122.0214 34 -135.317 123.5364 34 -127.0083 130.551 34 -129.3616 132.4089 34 -120.1322 138.1803 34 -122.2063 140.3455 34 -118.2231 143.9117 34 -141.8383 63.94388 34 -35.30536 152.6964 34 -42.75391 156.1026 37 -52.95286 159.2915 37 -63.50136 160.9994 37 -74.18551 161.1917 37 -84.78865 159.8645 37 -95.09577 157.0447 37 -104.8979 152.7896 37 -113.9962 147.1853 37 -122.2063 140.3455 37 -129.3616 132.4089 37 -135.317 123.5364 37 -139.9519 113.908 37 -143.1722 103.719 37 -144.9125 93.17575 37 -145.1378 82.49226 37 -143.8432 71.88509 37 -140.8835 72.37275 37 -142.1394 82.56632 37 -141.933 92.8349 37 -140.2685 102.9698 37 -137.1798 112.765 37 -132.7295 122.0214 37 -127.0083 130.551 37 -120.1322 138.1803 37 -112.2412 144.7543 37 -103.4955 150.1394 37 -94.07295 154.2262 37 -84.16502 156.9315 37 -73.97306 158.2005 37 -63.70422 158.0073 37 -53.56722 156.3558 37 -43.76807 153.2796 37 -18.975 13.31815 16.5 -18.975 18.975 16.5 -24.63186 18.975 16.5 -24.63186 -18.975 16.5 -18.975 -18.975 16.5 -18.975 -13.31815 16.5 25.86709 -23.70231 16.5 24.96079 -24.96079 16.5 25 -25 16.5 25 -19.34315 16.5 24.96079 -19.30393 16.5 18.975 -13.31815 16.5 18.975 -18.975 16.5 24.63186 -18.975 16.5 24.63186 18.975 16.5 18.975 18.975 16.5 18.975 13.31815 16.5 -21.25 22.5 16.5 -21.41747 21.875 16.5 -21.875 21.41747 16.5 -22.5 21.25 16.5 -23.125 21.41747 16.5 -25 19.34315 16.5 -23.58253 21.875 16.5 -25.86709 20.64084 16.5 -26.17157 22.17157 16.5 -23.75 22.5 16.5 -25.86709 23.70231 16.5 -23.58253 23.125 16.5 -25 25 16.5 -23.125 23.58253 16.5 -23.70231 25.86709 16.5 -22.17157 26.17157 16.5 -22.5 23.75 16.5 -20.64084 25.86709 16.5 -21.875 23.58253 16.5 -19.34315 25 16.5 -21.41747 23.125 16.5 -18.975 24.63186 16.5 -13.52776 15.85 16.5 -7.5 13.15685 16.5 -14.15 16.47224 16.5 -13.31815 18.975 16.5 -15 16.7 16.5 -13.15685 7.5 16.5 -15.85 13.52776 16.5 -15.85 16.47224 16.5 -13.3 15 16.5 -13.52776 14.15 16.5 -7.5 7.5 16.5 -14.15 13.52776 16.5 -15 13.3 16.5 -16.47224 14.15 16.5 -16.7 15 16.5 -16.47224 15.85 16.5 -2.828427 8.485281 16.5 -1.530734 7.61819 16.5 -1.530734 -7.61819 16.5 0 -7.313708 16.5 0 -1.7 16.5 1.530734 -7.61819 16.5 0.85 -1.472243 16.5 7.5 -7.5 16.5 1.472243 -0.85 16.5 -7.61819 1.530734 16.5 -7.313708 0 16.5 -1.7 0 16.5 -7.61819 -1.530734 16.5 -1.472243 -0.85 16.5 -7.5 -7.5 16.5 -0.85 -1.472243 16.5 1.530734 7.61819 16.5 0 7.313708 16.5 0 1.7 16.5 -0.85 1.472243 16.5 -1.472243 0.85 16.5 7.61819 -1.530734 16.5 7.313708 0 16.5 1.7 0 16.5 7.61819 1.530734 16.5 1.472243 0.85 16.5 7.5 7.5 16.5 0.85 1.472243 16.5 2.828427 8.485281 16.5 7.5 13.15685 16.5 15.85 13.52776 16.5 13.15685 7.5 16.5 16.47224 14.15 16.5 14.15 16.47224 16.5 13.31815 18.975 16.5 13.52776 15.85 16.5 15 16.7 16.5 15.85 16.47224 16.5 16.47224 15.85 16.5 16.7 15 16.5 15 13.3 16.5 14.15 13.52776 16.5 13.52776 14.15 16.5 13.3 15 16.5 23.125 21.41747 16.5 22.5 21.25 16.5 21.875 21.41747 16.5 21.41747 21.875 16.5 23.58253 21.875 16.5 24.96079 19.30393 16.5 23.75 22.5 16.5 18.975 24.63186 16.5 21.25 22.5 16.5 21.41747 23.125 16.5 19.34315 25 16.5 21.875 23.58253 16.5 20.64084 25.86709 16.5 22.17157 26.17157 16.5 22.5 23.75 16.5 23.70231 25.86709 16.5 23.125 23.58253 16.5 24.96584 25.03376 16.5 23.58253 23.125 16.5 26.17157 22.17157 16.5 25.86709 23.70231 16.5 25 25 16.5 25 19.34315 16.5 25.86709 20.64084 16.5 8.485281 2.828427 16.5 8.485281 -2.828427 16.5 13.15685 -7.5 16.5 15.85 -13.52776 16.5 16.47224 -14.15 16.5 16.7 -15 16.5 16.47224 -15.85 16.5 15.85 -16.47224 16.5 13.3 -15 16.5 13.52776 -14.15 16.5 14.15 -13.52776 16.5 15 -13.3 16.5 15 -16.7 16.5 13.31815 -18.975 16.5 14.15 -16.47224 16.5 7.5 -13.15685 16.5 13.52776 -15.85 16.5 23.125 -23.58253 16.5 22.5 -23.75 16.5 18.975 -24.63186 16.5 21.25 -22.5 16.5 23.125 -21.41747 16.5 19.30393 -24.96079 16.5 21.875 -23.58253 16.5 21.41747 -23.125 16.5 21.41747 -21.875 16.5 21.875 -21.41747 16.5 22.5 -21.25 16.5 23.58253 -21.875 16.5 23.75 -22.5 16.5 23.58253 -23.125 16.5 26.17157 -22.17157 16.5 25.86709 -20.64084 16.5 19.34315 -25 16.5 23.70231 -25.86709 16.5 22.17157 -26.17157 16.5 20.64084 -25.86709 16.5 2.828427 -8.485281 16.5 -2.828427 -8.485281 16.5 -7.5 -13.15685 16.5 -18.975 -24.63186 16.5 -13.31815 -18.975 16.5 -15 -16.7 16.5 -13.52776 -15.85 16.5 -14.15 -16.47224 16.5 -15.85 -16.47224 16.5 -16.47224 -15.85 16.5 -16.7 -15 16.5 -16.47224 -14.15 16.5 -13.15685 -7.5 16.5 -15.85 -13.52776 16.5 -15 -13.3 16.5 -14.15 -13.52776 16.5 -13.52776 -14.15 16.5 -13.3 -15 16.5 -22.5 -23.75 16.5 -23.125 -23.58253 16.5 -25.03376 -24.96584 16.5 -21.875 -23.58253 16.5 -19.30393 -24.96079 16.5 -21.41747 -23.125 16.5 -25.86709 -23.70231 16.5 -23.58253 -23.125 16.5 -26.17157 -22.17157 16.5 -23.75 -22.5 16.5 -25.86709 -20.64084 16.5 -23.58253 -21.875 16.5 -25 -19.34315 16.5 -23.125 -21.41747 16.5 -22.5 -21.25 16.5 -21.875 -21.41747 16.5 -21.41747 -21.875 16.5 -21.25 -22.5 16.5 -25 -25 16.5 -23.70231 -25.86709 16.5 -22.17157 -26.17157 16.5 -19.34315 -25 16.5 -20.64084 -25.86709 16.5 -8.485281 -2.828427 16.5 -8.485281 2.828427 16.5 -18.975 -13.31815 13.5 -18.975 -18.975 13.5 -24.63186 -18.975 13.5 -24.63186 18.975 13.5 -18.975 18.975 13.5 -18.975 13.31815 13.5 18.975 24.63186 13.5 18.975 18.975 13.5 13.31815 18.975 13.5 13.31815 -18.975 13.5 18.975 -18.975 13.5 18.975 -24.63186 13.5 -19.30393 -24.96079 13.5 -21.875 -23.58253 13.5 -18.975 -24.63186 13.5 -21.41747 -23.125 13.5 -25.03376 -24.96584 13.5 -23.125 -23.58253 13.5 -22.5 -23.75 13.5 -22.17157 -26.17157 13.5 -23.70231 -25.86709 13.5 -20.64084 -25.86709 13.5 -25 -25 13.5 -19.34315 -25 13.5 -21.25 -22.5 13.5 -21.41747 -21.875 13.5 -21.875 -21.41747 13.5 -22.5 -21.25 13.5 -23.125 -21.41747 13.5 -25 -19.34315 13.5 -23.58253 -21.875 13.5 -23.58253 -23.125 13.5 -25.86709 -23.70231 13.5 -23.75 -22.5 13.5 -26.17157 -22.17157 13.5 -25.86709 -20.64084 13.5 -16.7 -15 13.5 -16.47224 -15.85 13.5 -15.85 -16.47224 13.5 -13.31815 -18.975 13.5 -13.52776 -15.85 13.5 -7.5 -13.15685 13.5 -14.15 -16.47224 13.5 -15 -16.7 13.5 -13.3 -15 13.5 -13.52776 -14.15 13.5 -7.5 -7.5 13.5 -14.15 -13.52776 13.5 -13.15685 -7.5 13.5 -15 -13.3 13.5 -15.85 -13.52776 13.5 -16.47224 -14.15 13.5 -2.828427 -8.485281 13.5 -1.530734 -7.61819 13.5 1.530734 -7.61819 13.5 0 -7.313708 13.5 0 -1.7 13.5 -0.85 -1.472243 13.5 -1.472243 -0.85 13.5 7.61819 1.530734 13.5 7.313708 0 13.5 1.7 0 13.5 7.61819 -1.530734 13.5 1.472243 -0.85 13.5 7.5 -7.5 13.5 0.85 -1.472243 13.5 -1.530734 7.61819 13.5 0 7.313708 13.5 0 1.7 13.5 1.530734 7.61819 13.5 0.85 1.472243 13.5 7.5 7.5 13.5 1.472243 0.85 13.5 -7.61819 -1.530734 13.5 -7.313708 0 13.5 -1.7 0 13.5 -7.61819 1.530734 13.5 -1.472243 0.85 13.5 -7.5 7.5 13.5 -0.85 1.472243 13.5 2.828427 -8.485281 13.5 7.5 -13.15685 13.5 15 -16.7 13.5 15.85 -16.47224 13.5 16.47224 -15.85 13.5 13.52776 -15.85 13.5 14.15 -16.47224 13.5 15 -13.3 13.5 14.15 -13.52776 13.5 13.52776 -14.15 13.5 13.3 -15 13.5 15.85 -13.52776 13.5 13.15685 -7.5 13.5 16.47224 -14.15 13.5 18.975 -13.31815 13.5 16.7 -15 13.5 24.63186 -18.975 13.5 22.5 -21.25 13.5 22.5 -23.75 13.5 23.125 -23.58253 13.5 24.96079 -24.96079 13.5 23.58253 -23.125 13.5 23.75 -22.5 13.5 21.41747 -23.125 13.5 19.30393 -24.96079 13.5 21.875 -23.58253 13.5 24.96079 -19.30393 13.5 23.58253 -21.875 13.5 23.125 -21.41747 13.5 21.875 -21.41747 13.5 21.41747 -21.875 13.5 21.25 -22.5 13.5 23.70231 -25.86709 13.5 22.17157 -26.17157 13.5 19.34315 -25 13.5 20.64084 -25.86709 13.5 25 -19.34315 13.5 25.86709 -20.64084 13.5 26.17157 -22.17157 13.5 25.86709 -23.70231 13.5 25 -25 13.5 8.485281 -2.828427 13.5 8.485281 2.828427 13.5 13.15685 7.5 13.5 13.3 15 13.5 13.52776 14.15 13.5 14.15 13.52776 13.5 15 13.3 13.5 15.85 13.52776 13.5 18.975 13.31815 13.5 16.47224 14.15 13.5 16.7 15 13.5 16.47224 15.85 13.5 15.85 16.47224 13.5 15 16.7 13.5 14.15 16.47224 13.5 7.5 13.15685 13.5 13.52776 15.85 13.5 24.96584 25.03376 13.5 23.75 22.5 13.5 23.58253 23.125 13.5 24.63186 18.975 13.5 21.875 21.41747 13.5 22.5 21.25 13.5 23.125 21.41747 13.5 24.96079 19.30393 13.5 23.58253 21.875 13.5 23.70231 25.86709 13.5 23.125 23.58253 13.5 22.17157 26.17157 13.5 22.5 23.75 13.5 20.64084 25.86709 13.5 21.875 23.58253 13.5 19.34315 25 13.5 21.41747 23.125 13.5 21.25 22.5 13.5 21.41747 21.875 13.5 25 19.34315 13.5 25 25 13.5 25.86709 23.70231 13.5 26.17157 22.17157 13.5 25.86709 20.64084 13.5 2.828427 8.485281 13.5 -2.828427 8.485281 13.5 -7.5 13.15685 13.5 -15 16.7 13.5 -15.85 16.47224 13.5 -16.47224 15.85 13.5 -15.85 13.52776 13.5 -13.15685 7.5 13.5 -16.47224 14.15 13.5 -16.7 15 13.5 -15 13.3 13.5 -14.15 13.52776 13.5 -13.52776 14.15 13.5 -13.3 15 13.5 -13.52776 15.85 13.5 -13.31815 18.975 13.5 -14.15 16.47224 13.5 -21.875 21.41747 13.5 -21.41747 21.875 13.5 -23.125 23.58253 13.5 -23.70231 25.86709 13.5 -22.5 23.75 13.5 -22.17157 26.17157 13.5 -21.875 23.58253 13.5 -18.975 24.63186 13.5 -21.25 22.5 13.5 -21.41747 23.125 13.5 -19.34315 25 13.5 -20.64084 25.86709 13.5 -22.5 21.25 13.5 -23.125 21.41747 13.5 -25 19.34315 13.5 -23.58253 21.875 13.5 -25.86709 20.64084 13.5 -23.75 22.5 13.5 -26.17157 22.17157 13.5 -23.58253 23.125 13.5 -25.86709 23.70231 13.5 -25 25 13.5 -8.485281 2.828427 13.5 -8.485281 -2.828427 13.5 1.7 0 16.5 -65.25702 -75.45265 -3 -65.25702 -75.45265 0 -65.47127 -73.84706 0 -55.45265 -60.74298 -3 -55.45265 -60.74298 0 -53.84706 -60.52873 0 -40.74298 -70.54735 -3 -40.74298 -70.54735 0 -40.52873 -72.15295 0 -50.54735 -85.25702 -3 -50.54735 -85.25702 0 -52.15294 -85.47127 0 -48.56912 -84.68834 -6 -47.44487 -84.19779 -3 -49.73619 -85.06639 -3 -47.44487 -84.19779 -6 -46.37412 -83.59942 -6 -45.36703 -82.89888 -3 -45.36703 -82.89888 -6 -44.43344 -82.10297 -6 -44.72449 -82.36836 -3 -43.58252 -81.21956 -6 -44.72449 -82.36836 0 -41.80221 -67.44488 -3 -40.93362 -69.7362 -3 -41.31162 -68.56922 -6 -41.80221 -67.44488 -6 -42.40063 -66.37403 -6 -43.10112 -65.36704 -3 -43.10112 -65.36704 -6 -43.89707 -64.4334 -6 -43.63164 -64.7245 -3 -44.78044 -63.58252 -6 -43.63164 -64.7245 0 -57.43088 -61.31166 -6 -58.55513 -61.80221 -3 -56.2638 -60.93362 -3 -58.55513 -61.80221 -6 -59.62588 -62.40058 -6 -60.63296 -63.10112 -3 -60.63296 -63.10112 -6 -61.56656 -63.89703 -6 -61.2755 -63.63164 -3 -62.41748 -64.78044 -6 -61.2755 -63.63164 0 -64.19779 -78.55513 -3 -65.06639 -76.2638 -3 -64.68838 -77.43079 -6 -64.19779 -78.55513 -6 -63.59936 -79.62597 -6 -62.89888 -80.63297 -3 -62.89888 -80.63297 -6 -62.10293 -81.56661 -6 -62.36835 -81.27551 -3 -61.21956 -82.41748 -6 -62.36835 -81.27551 0 -43.58252 -81.21956 0 -42.82227 -80.25699 -6 -42.15992 -79.22437 0 -42.15992 -79.22437 -6 -41.602 -78.13183 -6 -41.1539 -76.98997 0 -41.1539 -76.98997 -6 -40.81988 -75.80973 -6 -40.60311 -74.60224 0 -40.60311 -74.60224 -6 -40.50576 -73.3793 -6 -40.52873 -72.15295 -6 -40.67178 -70.9348 -6 -40.93362 -69.7362 -6 -44.78044 -63.58252 0 -45.743 -62.82228 -6 -46.77564 -62.15992 0 -46.77564 -62.15992 -6 -47.86821 -61.60198 -6 -49.01003 -61.1539 0 -49.01003 -61.1539 -6 -50.19031 -60.81986 -6 -51.39776 -60.60311 0 -51.39776 -60.60311 -6 -52.62068 -60.50576 -6 -53.84706 -60.52873 -6 -55.06525 -60.67179 -6 -56.2638 -60.93362 -6 -62.41748 -64.78044 0 -63.17773 -65.74301 -6 -63.84008 -66.77564 0 -63.84008 -66.77564 -6 -64.398 -67.86817 -6 -64.8461 -69.01004 0 -64.8461 -69.01004 -6 -65.18013 -70.19027 -6 -65.39689 -71.39776 0 -65.39689 -71.39776 -6 -65.49425 -72.62071 -6 -65.47127 -73.84706 -6 -65.32822 -75.0652 -6 -65.06639 -76.2638 -6 -61.21956 -82.41748 0 -60.257 -83.17771 -6 -59.22436 -83.84008 0 -59.22436 -83.84008 -6 -58.13179 -84.39802 -6 -56.98997 -84.8461 0 -56.98997 -84.8461 -6 -55.80969 -85.18013 -6 -54.60224 -85.39689 0 -54.60224 -85.39689 -6 -53.37932 -85.49424 -6 -52.15294 -85.47127 -6 -50.93474 -85.32821 -6 -49.73619 -85.06639 -6 -53.64385 -64.38908 0 -59.40158 -73.3966 0 -58.36738 -73.84874 0 -54.24751 -72.9212 0 -48.81126 -68.14284 0 -52.308 -71.95903 0 -49.07695 -69.23984 0 -48.95141 -70.36155 0 -56.76016 -69.07695 0 -57.85716 -68.81127 0 -54.04098 -72.308 0 -52.9212 -71.75249 0 -45.47195 -72.67456 0 -44.38908 -72.35615 0 -48.1864 -67.20287 0 -47.27774 -66.5333 0 -48.4498 -71.37268 0 -51.88022 -72.44449 0 -47.63261 -72.15126 0 -51.75249 -73.07881 0 -46.59842 -72.6034 0 -51.95902 -73.692 0 -52.44449 -74.11978 0 -51.37267 -77.5502 0 -52.15126 -78.36739 0 -53.0788 -74.24752 0 -52.6034 -79.40158 0 -54.11978 -73.55551 0 -57.5502 -74.62733 0 -53.692 -74.04098 0 -60.52805 -73.32545 0 -50.36154 -77.04859 0 -49.23983 -76.92305 0 -48.14284 -77.18874 0 -61.61092 -73.64385 0 -53.32544 -65.47195 0 -53.3966 -66.59842 0 -53.84874 -67.63262 0 -53.55551 -71.88022 0 -54.62733 -68.4498 0 -55.63845 -68.95142 0 -58.79713 -68.18641 0 -59.4667 -67.27775 0 -47.20286 -77.81359 0 -46.53329 -78.72225 0 -52.67456 -80.52806 0 -52.35615 -81.61093 0 -57.04859 -75.63845 0 -56.92305 -76.76016 0 -57.18873 -77.85717 0 -58.72225 -79.46671 0 -57.81359 -78.79714 0 -52.35615 -81.61093 -3 -52.15126 -78.36739 -3 -52.6034 -79.40158 -3 -52.67456 -80.52806 -3 -47.20286 -77.81359 -3 -48.14284 -77.18874 -3 -46.53329 -78.72225 -3 -49.23983 -76.92305 -3 -51.37267 -77.5502 -3 -50.36154 -77.04859 -3 -44.38908 -72.35615 -3 -47.63261 -72.15126 -3 -46.59842 -72.6034 -3 -45.47195 -72.67456 -3 -48.4498 -71.37268 -3 -48.95141 -70.36155 -3 -49.07695 -69.23984 -3 -48.1864 -67.20287 -3 -48.81126 -68.14284 -3 -47.27774 -66.5333 -3 -53.64385 -64.38908 -3 -53.84874 -67.63262 -3 -53.3966 -66.59842 -3 -53.32544 -65.47195 -3 -58.79713 -68.18641 -3 -57.85716 -68.81127 -3 -59.4667 -67.27775 -3 -56.76016 -69.07695 -3 -54.62733 -68.4498 -3 -55.63845 -68.95142 -3 -61.61092 -73.64385 -3 -58.36738 -73.84874 -3 -59.40158 -73.3966 -3 -60.52805 -73.32545 -3 -57.5502 -74.62733 -3 -57.04859 -75.63845 -3 -56.92305 -76.76016 -3 -57.81359 -78.79714 -3 -57.18873 -77.85717 -3 -58.72225 -79.46671 -3 -61.30702 -80.21511 -36 -61.46807 -80.22166 -36 -58.60028 -77.95113 -36 -60.49432 -80.04459 -36 -58.84286 -75.84909 -36 -58.76642 -76.00913 -36 -61.63967 -74.2246 -36 -58.61451 -76.43865 -36 -62.53209 -80.04263 -36 -63.00413 -79.82346 -36 -64.04912 -78.82001 -36 -64.19779 -78.55513 -36 -64.40613 -78.00514 -36 -64.48528 -77.60916 -36 -64.50355 -77.42518 -36 -64.48551 -76.83736 -36 -64.44898 -76.61848 -36 -62.6077 -74.4298 -36 -61.71362 -74.22869 -36 -58.52144 -76.96255 -36 -58.97336 -78.82295 -36 -59.25005 -79.19466 -36 -61.89484 -80.19706 -36 -62.44643 -80.07221 -36 -59.63203 -79.56102 -36 -60.17705 -79.90946 -36 -63.38935 -79.56067 -36 -63.88592 -79.05376 -36 -64.35348 -76.26425 -36 -64.09325 -75.69614 -36 -63.77059 -75.24914 -36 -63.45614 -74.93861 -36 -62.8436 -74.53433 -36 -61.12581 -74.24674 -36 -60.65684 -74.34579 -36 -59.13472 -75.39004 -36 -60.24856 -74.50016 -36 -59.43452 -75.05591 -36 -63.77868 -79.25917 -32.24064 -56.46109 -64.74913 -12.18479 -55.56387 -64.87455 -12.11001 -56.44378 -65.86215 -13.81585 -63.3548 -68.58972 -16.46771 -62.81863 -68.08608 -16.36865 -63.25875 -69.6045 -20.10123 -57.87664 -84.34896 -9.578104 -51.90408 -82.00354 -15.86541 -52.44025 -82.50717 -15.96447 -52.5207 -81.36758 -17.60387 -63.54909 -79.66249 -24.72781 -64.19779 -78.55513 -24.75 -64.19779 -78.55513 -28.5 -55.19048 -72.52819 -20.7737 -54.48141 -73.73491 -20.74984 -55.42436 -74.20271 -22.77367 -64.73256 -76.22349 -32.17309 -53.76623 -72.01239 -18.32012 -54.0091 -72.26229 -18.84821 -54.20864 -71.91181 -18.81511 -52.54354 -71.83633 -16.66576 -52.83663 -71.76072 -16.96337 -53.13022 -71.24751 -16.92479 -52.95265 -71.7509 -17.09632 -53.26614 -71.77867 -17.50084 -53.55551 -71.88022 -17.94282 -52.15916 -72.07508 -16.36751 -51.95791 -70.53662 -15.10746 -51.97411 -72.28583 -16.27942 -51.06109 -72.03813 -15.08312 -51.88038 -72.44417 -16.26292 -52.25988 -71.99267 -16.43364 -52.31038 -71.95745 -16.47038 -52.503 -71.85305 -16.629 -51.85434 -73.49998 -16.8229 -51.82031 -73.41331 -16.7336 -50.40813 -73.6606 -15.10746 -51.75553 -73.11746 -16.49341 -51.75297 -73.08608 -16.47316 -51.76616 -72.79964 -16.33068 -51.83525 -72.54629 -16.26893 -53.41479 -74.17917 -19.39413 -53.10905 -74.24523 -18.97327 -52.86478 -74.62071 -18.81511 -52.79336 -74.23281 -18.50168 -52.44871 -74.12187 -17.94985 -52.16091 -73.92652 -17.45069 -51.68341 -74.16395 -16.92479 -52.02274 -73.7794 -17.18899 -51.96132 -73.69545 -17.06424 -54.11949 -73.5561 -20.04162 -54.02008 -73.72245 -20.01302 -53.88378 -73.88399 -19.91851 -53.8548 -73.91204 -19.89332 -53.94957 -75.02956 -20.7737 -53.68933 -74.04275 -19.72688 -53.64644 -74.06986 -19.67877 -54.04043 -72.30718 -18.92813 -54.12083 -72.4466 -19.15504 -54.22537 -72.75312 -19.55847 -54.23629 -72.81539 -19.62598 -54.24717 -72.9159 -19.72495 -54.24652 -73.09327 -19.8692 -54.20441 -73.33451 -19.99929 -54.13595 -73.52165 -20.04056 -65.08835 -72.87934 -20.65473 -65.00465 -73.77518 -24.4412 -65.22948 -74.26068 -20.79608 -64.93759 -75.58876 -28.36113 -65.12194 -75.70275 -20.90505 -64.85004 -76.58247 -28.43534 -64.77109 -77.15174 -20.97518 -64.59836 -77.58328 -28.4831 -64.19779 -78.55513 -32.25 -64.85652 -74.63907 -28.26487 -64.64059 -75.46932 -32.11979 -64.05811 -74.16703 -31.98632 -64.41255 -74.7751 -32.05671 -64.60757 -73.76969 -28.15098 -55.1501 -70.75581 -18.88524 -61.75506 -73.63688 -33.82795 -58.53891 -75.74781 -33.69046 -58.90375 -75.14615 -33.69534 -58.55749 -74.84506 -31.426 -59.07398 -74.22432 -31.45245 -58.6774 -73.77393 -29.23449 -59.34247 -73.18129 -29.29326 -58.91267 -72.59985 -27.13403 -59.71788 -72.08984 -27.23029 -59.27463 -71.40126 -25.13328 -60.20594 -71.035 -25.26708 -59.76992 -70.26761 -23.23205 -60.80368 -70.10308 -23.399 -60.39462 -69.28778 -21.42225 -62.22813 -71.6934 -27.60724 -61.40856 -71.62789 -27.4713 -61.60068 -72.33557 -29.56035 -60.83216 -72.44782 -29.45968 -61.01821 -73.0912 -31.60992 -60.32749 -73.32963 -31.54685 -60.48929 -73.87858 -33.75836 -59.89685 -74.19275 -33.73056 -62.396 -73.07676 -31.7556 -61.7168 -73.00553 -31.68032 -61.11679 -73.69118 -33.79125 -62.37939 -73.71856 -33.86721 -62.9655 -73.93199 -33.90773 -63.02911 -73.30072 -31.83332 -63.59047 -73.66933 -31.91104 -63.65346 -72.40049 -27.88792 -64.20147 -73.01343 -28.02386 -64.20754 -71.7917 -24.12468 -64.70195 -72.71435 -24.29162 -64.70071 -71.61157 -20.48749 -54.93511 -75.38918 -22.79587 -54.62731 -76.61083 -22.85859 -53.61864 -76.36409 -20.84115 -54.5196 -77.82367 -22.95606 -53.50855 -77.69032 -20.94596 -54.61751 -78.98265 -23.08247 -53.62486 -78.9589 -21.08189 -54.9202 -80.04348 -23.23205 -53.96623 -80.12131 -21.24273 -55.41462 -80.96613 -23.399 -54.51798 -81.13368 -21.42225 -56.0822 -81.71374 -23.57752 -55.81874 -75.69823 -24.87689 -55.53731 -76.80863 -24.933 -55.43708 -77.91061 -25.02019 -55.52319 -78.96327 -25.13328 -55.795 -79.92639 -25.26708 -56.24079 -80.76362 -25.41643 -56.84381 -81.44152 -25.57613 -57.57835 -81.93437 -25.74102 -57.71892 -83.334 -20.30083 -58.97342 -83.15641 -20.48749 -59.85223 -82.49022 -24.29162 -55.25943 -81.95561 -21.61422 -56.15918 -82.55598 -21.81242 -56.89453 -82.25796 -23.76184 -56.50296 -83.22256 -20.10123 -57.81933 -82.57551 -23.94615 -58.81847 -82.65476 -24.12468 -58.96799 -81.84527 -27.88792 -59.78757 -81.91078 -28.02386 -60.63541 -81.77659 -28.15098 -63.02172 -80.26792 -28.43534 -62.28346 -80.93882 -28.36113 -61.86206 -81.4662 -24.56761 -62.48577 -81.01664 -20.90505 -63.42723 -79.86065 -20.97518 -63.83553 -79.22338 -20.99366 -58.20928 -81.58455 -27.74758 -57.54267 -81.13818 -27.60724 -56.99466 -80.52524 -27.4713 -56.58856 -79.76898 -27.34418 -56.33961 -78.8996 -27.23029 -56.25855 -77.94992 -27.13403 -56.34609 -76.9562 -27.05982 -58.78596 -81.20782 -29.77914 -58.17716 -80.8029 -29.668 -57.67436 -80.25007 -29.56035 -57.29879 -79.57025 -29.45968 -57.06451 -78.79053 -29.36949 -56.98154 -77.94036 -29.29326 -58.13913 -77.08476 -33.70914 -58.28058 -76.4023 -33.69534 -57.83136 -76.30876 -31.426 -58.13837 -75.54911 -31.41664 -57.62395 -75.2939 -29.18328 -58.09862 -74.48812 -29.19666 -57.52981 -74.07663 -27.01206 -58.17441 -73.27075 -27.05982 -57.5676 -72.71607 -24.933 -58.38439 -71.96956 -25.02019 -57.76009 -71.29163 -22.95606 -58.74213 -70.66841 -23.08247 -58.12266 -69.89241 -21.08189 -59.25473 -69.46096 -21.24273 -58.66245 -68.61605 -19.3028 -59.91695 -68.43845 -19.48945 -59.3725 -67.55599 -17.60387 -59.30705 -80.80351 -31.83332 -58.7457 -80.4349 -31.7556 -58.27806 -79.9372 -31.68032 -57.92362 -79.32913 -31.60992 -57.69558 -78.63491 -31.54685 -61.31795 -81.01303 -32.05671 -60.61937 -81.0987 -31.98632 -59.94016 -81.02747 -31.91104 -59.7712 -80.37094 -33.90773 -59.24666 -80.03339 -33.86721 -58.80391 -79.5857 -33.82795 -58.46099 -79.04463 -33.79125 -62.66482 -80.39157 -32.17309 -63.26219 -79.87992 -32.21419 -48.58308 -84.10012 -7.574367 -47.59546 -83.5457 -7.546219 -46.66823 -82.89394 -7.518291 -45.81012 -82.15165 -7.490804 -49.04162 -73.11199 -13.36782 -49.73284 -71.3792 -13.34503 -47.91148 -71.58345 -11.69547 -47.58656 -72.51946 -11.7106 -47.34365 -73.475 -11.73501 -48.64924 -74.91342 -13.43225 -47.18613 -74.44123 -11.76804 -47.11674 -75.40924 -11.80902 -48.57776 -76.71707 -13.53236 -47.43684 -78.23249 -11.97305 -48.83014 -78.45502 -13.66221 -47.24252 -77.31404 -11.91218 -47.13568 -76.36989 -11.85729 -51.31572 -75.72893 -16.99541 -50.02663 -75.34308 -15.17623 -51.21557 -77.28923 -17.10515 -49.93854 -77.02393 -15.28309 -51.38777 -78.78646 -17.24748 -50.14788 -78.64005 -15.4217 -51.82907 -80.16324 -17.4159 -49.07666 -79.27818 -13.73643 -49.40013 -80.06043 -13.81585 -50.65003 -80.12941 -15.58569 -49.79701 -80.79438 -13.89973 -51.42375 -81.43576 -15.76873 -50.26373 -81.47265 -13.98732 -49.63128 -82.14453 -12.34363 -51.75661 -83.68601 -12.59514 -53.65739 -83.30333 -16.16656 -50.99515 -83.25343 -12.51042 -53.02659 -82.942 -16.06512 -50.28444 -82.73778 -12.42636 -52.51392 -76.0697 -18.88524 -52.40639 -77.51177 -18.99421 -52.54752 -78.89312 -19.13556 -52.93516 -80.16088 -19.3028 -53.55272 -81.26719 -19.48945 -49.6821 -83.98251 -9.199934 -48.77372 -83.47061 -9.148432 -47.92249 -82.86612 -9.097333 -47.13646 -82.17539 -9.047039 -49.04248 -81.47917 -12.26288 -48.52439 -80.74758 -12.18479 -48.08144 -79.95732 -12.11001 -47.7176 -79.11631 -12.03921 -53.40227 -84.28451 -12.76392 -52.56172 -84.03059 -12.67986 -50.63925 -84.39608 -9.251435 -55.81335 -84.89521 -9.494842 -56.94896 -84.35641 -13.08026 -54.76005 -85.01011 -9.449384 -56.05174 -84.48184 -13.00549 -53.70591 -85.01738 -9.401911 -55.15579 -84.51193 -12.92739 -52.66109 -84.9161 -9.352827 -54.2698 -84.44566 -12.84665 -51.63556 -84.70814 -9.302534 -58.00399 -83.77764 -16.74743 -57.2485 -83.90647 -16.65789 -56.49575 -83.95193 -16.56439 -54.37712 -82.16795 -19.68906 -55.37363 -82.8291 -19.89515 -54.32672 -83.58699 -16.268 -55.02767 -83.79077 -16.36865 -55.75307 -83.91298 -16.46771 -60.88002 -82.08943 -24.4412 -60.21736 -82.69806 -20.65473 -60.82011 -82.36785 -20.72905 -59.49366 -83.27641 -16.91143 -59.56116 -83.4252 -13.27809 -58.71229 -83.82615 -13.21723 -61.40261 -81.97471 -20.79608 -61.47825 -81.44883 -28.26487 -62.00868 -80.77461 -32.11979 -63.71928 -79.42555 -13.49481 -63.17058 -80.25055 -13.47968 -62.55671 -81.02207 -13.45526 -61.88267 -81.73206 -13.42224 -61.15391 -82.37295 -13.38126 -60.37755 -82.93907 -13.33299 -61.95959 -81.5229 -20.85502 -62.7626 -80.64668 -24.66508 -63.66632 -79.46204 -28.4831 -56.85561 -84.67428 -9.537883 -57.83872 -84.1373 -13.15107 -58.75484 -83.56709 -16.8322 -45.02986 -81.32564 -7.463978 -44.33563 -80.42319 -7.438032 -43.73337 -79.45352 -7.413187 -43.22846 -78.42633 -7.389663 -42.8263 -77.35131 -7.367681 -42.53156 -76.23841 -7.34746 -42.34617 -75.09852 -7.329221 -42.27137 -73.9428 -7.313184 -42.30837 -72.78237 -7.299569 -42.45766 -71.62833 -7.288596 -42.71673 -70.4915 -7.280486 -43.08234 -69.38265 -7.275458 -43.55125 -68.31256 -7.273733 -44.11959 -67.2918 -7.275458 -44.78129 -66.32984 -7.280486 -45.52973 -65.43578 -7.288596 -46.35829 -64.61872 -7.299569 -47.25986 -63.8872 -7.313184 -48.22534 -63.24755 -7.329221 -49.2451 -62.70553 -7.34746 -50.30953 -62.2669 -7.367681 -51.4088 -61.93673 -7.389663 -52.53215 -61.7173 -7.413187 -53.6686 -61.61018 -7.438032 -54.80716 -61.61697 -7.463978 -55.93691 -61.73849 -7.490804 -57.04709 -61.97266 -7.518291 -58.12701 -62.31663 -7.546219 -59.16596 -62.76757 -7.574367 -60.64561 -64.22569 -9.251435 -61.49684 -64.83018 -9.302534 -62.28286 -65.52092 -9.352827 -62.99562 -66.29156 -9.401911 -63.62759 -67.13529 -9.449384 -64.17334 -68.04347 -9.494842 -64.62801 -69.00701 -9.537883 -64.9867 -70.01679 -9.578104 -65.24519 -71.06351 -9.615102 -65.4019 -72.1369 -9.648474 -65.45588 -73.22652 -9.677818 -65.40622 -74.32188 -9.702729 -65.25269 -75.41257 -9.722806 -64.99789 -76.48842 -9.737646 -64.64515 -77.53932 -9.746845 -64.19779 -78.55513 -9.75 -46.4237 -81.40475 -8.997956 -45.79174 -80.56101 -8.950483 -45.24599 -79.65283 -8.905024 -44.79132 -78.6893 -8.861984 -44.43264 -77.67951 -8.821763 -44.17414 -76.63279 -8.784765 -44.01744 -75.5594 -8.751393 -43.96345 -74.46978 -8.722049 -44.01311 -73.37442 -8.697138 -44.16664 -72.28373 -8.677061 -44.42144 -71.20788 -8.662221 -44.77418 -70.15699 -8.653022 -45.22153 -69.14118 -8.649867 -45.7597 -68.17041 -8.653022 -46.38304 -67.25376 -8.662221 -47.08551 -66.4 -8.677061 -47.86106 -65.61788 -8.697138 -48.70317 -64.91565 -8.722049 -49.60341 -64.29942 -8.751393 -50.55288 -63.77479 -8.784765 -51.54269 -63.34734 -8.821763 -52.56372 -63.02202 -8.861984 -53.60598 -62.80109 -8.905024 -54.65928 -62.68619 -8.950483 -55.71342 -62.67892 -8.997956 -56.75824 -62.7802 -9.047039 -57.78377 -62.98816 -9.097333 -58.78007 -63.30022 -9.148432 -59.73723 -63.71379 -9.199934 -64.85076 -76.93265 -17.22566 -64.19779 -78.55513 -17.25 -64.19779 -78.55513 -13.5 -65.32035 -73.56932 -17.05003 -65.23226 -75.25018 -17.15689 -65.3267 -74.78973 -13.42224 -65.27031 -71.91693 -13.27809 -65.25283 -72.74921 -16.9843 -65.37715 -72.86107 -13.33299 -65.39609 -73.82173 -13.38126 -64.60135 -77.64752 -13.49481 -64.92627 -76.7115 -13.47968 -65.16918 -75.75596 -13.45526 -65.076 -70.99847 -13.21723 -64.79523 -70.11466 -13.15107 -64.89546 -71.18907 -16.8322 -64.60885 -70.46384 -16.74743 -62.22839 -66.49318 -12.76392 -62.88155 -67.08644 -12.84665 -63.47035 -67.7518 -12.92739 -64.43139 -69.27365 -13.08026 -63.98844 -68.48338 -13.00549 -64.25435 -69.78437 -16.65789 -63.83513 -69.1575 -16.56439 -64.08315 -70.50526 -20.30083 -65.111 -71.9532 -16.91143 -63.53996 -71.0441 -23.94615 -62.72762 -70.49987 -23.76184 -62.98685 -71.95412 -27.74758 -64.19779 -78.55513 -21 -59.11055 -64.94645 -12.42636 -59.69745 -65.88765 -14.17069 -59.95111 -65.20037 -12.51042 -60.46612 -66.11547 -14.26498 -60.75622 -65.54496 -12.59514 -61.20125 -66.42855 -14.36001 -61.60149 -67.28993 -16.16656 -60.93216 -67.00627 -16.06512 -60.23121 -66.80249 -15.96447 -58.90304 -65.74698 -14.07789 -58.24303 -64.7853 -12.34363 -55.62523 -66.07785 -13.73643 -54.67411 -65.09366 -12.03921 -54.82066 -66.37957 -13.66221 -53.80054 -65.40481 -11.97305 -52.95167 -65.80577 -11.91218 -53.28418 -67.23007 -13.53236 -49.95612 -68.2089 -11.73501 -50.69436 -69.78048 -13.36782 -51.8913 -68.3782 -13.43225 -52.13528 -66.2919 -11.85729 -51.35892 -66.85801 -11.80902 -50.63016 -67.4989 -11.76804 -49.34225 -68.98041 -11.7106 -48.79355 -69.80541 -11.69547 -48.31504 -70.67584 -11.69028 -61.80283 -70.18232 -23.57752 -62.26223 -68.94335 -19.89515 -61.13291 -68.5499 -19.68906 -61.9556 -68.12842 -18.0124 -60.71023 -67.69017 -17.80487 -58.23056 -78.43163 -33.75836 -58.12229 -77.76984 -33.73056 -57.6036 -77.88075 -31.49354 -57.64958 -77.09555 -31.45245 -57.05104 -77.05227 -29.23449 -57.26954 -76.15934 -29.19666 -56.59777 -75.95539 -27.01206 -56.99834 -74.98354 -26.99516 -56.26424 -74.61936 -24.85704 -56.85374 -73.61193 -24.87689 -56.07307 -73.09535 -22.79587 -56.85955 -72.11116 -22.85859 -56.05286 -71.45732 -20.84115 -57.04223 -70.56729 -20.94596 -56.23325 -69.79774 -18.99421 -57.4185 -69.0744 -19.13556 -56.63193 -68.21549 -17.24748 -57.99514 -67.73392 -17.4159 -57.25489 -66.81561 -15.58569 -58.76314 -66.64132 -15.76873 -57.26828 -65.7341 -13.89973 -58.0907 -65.69537 -13.98732 -57.35704 -64.71903 -12.26288 -53.06673 -69.21497 -15.17623 -54.15386 -70.00794 -16.99541 -54.35177 -68.12792 -15.28309 -55.33562 -68.98421 -17.10515 -55.76522 -67.31684 -15.4217 -62.23229 -67.65126 -16.268 -61.51768 -65.97753 -12.67986 -60.26776 -64.63981 -10.87432 -59.3886 -64.26171 -10.80403 -58.47212 -63.97969 -10.7343 -57.52753 -63.79609 -10.66566 -59.36156 -74.62064 -33.70914 -59.67135 -73.71266 -31.49354 -60.06959 -72.733 -29.36949 -60.56071 -71.76208 -27.34418 -61.14228 -70.88342 -25.41643 -56.56399 -63.71324 -10.59868 -55.59077 -63.73283 -10.53389 -54.61725 -63.85385 -10.47185 -53.65288 -64.07469 -10.41311 -52.70712 -64.39369 -10.35822 -51.7892 -64.80859 -10.30773 -50.90754 -65.31461 -10.26219 -50.07036 -65.90634 -10.22214 -49.28588 -66.57837 -10.18815 -48.56185 -67.32481 -10.16075 -47.90425 -68.13773 -10.1405 -47.31858 -69.00872 -10.12794 -46.81037 -69.92938 -10.12364 -46.38479 -70.89103 -10.12794 -46.04561 -71.88431 -10.1405 -45.79619 -72.89973 -10.16075 -45.63989 -73.92781 -10.18815 -45.57941 -74.95902 -10.22214 -45.61475 -75.98359 -10.26219 -45.74525 -76.99173 -10.30773 -45.97024 -77.97361 -10.35822 -46.28843 -78.91965 -10.41311 -46.69604 -79.82111 -10.47185 -47.18865 -80.66947 -10.53389 -47.76186 -81.45623 -10.59868 65.25702 75.45265 -3 65.25702 75.45265 0 65.47127 73.84706 0 55.45265 60.74298 -3 55.45265 60.74298 0 53.84706 60.52873 0 40.74298 70.54735 -3 40.74298 70.54735 0 40.52873 72.15295 0 50.54735 85.25702 -3 50.54735 85.25702 0 52.15294 85.47127 0 48.56912 84.68834 -6 47.44487 84.19779 -3 49.73619 85.06639 -3 47.44487 84.19779 -6 46.37412 83.59942 -6 45.36703 82.89888 -3 45.36703 82.89888 -6 44.43344 82.10297 -6 44.72449 82.36836 -3 43.58252 81.21956 -6 44.72449 82.36836 0 41.80221 67.44488 -3 40.93362 69.7362 -3 41.31162 68.56922 -6 41.80221 67.44488 -6 42.40063 66.37403 -6 43.10112 65.36704 -3 43.10112 65.36704 -6 43.89707 64.4334 -6 43.63164 64.7245 -3 44.78044 63.58252 -6 43.63164 64.7245 0 57.43088 61.31166 -6 58.55513 61.80221 -3 56.2638 60.93362 -3 58.55513 61.80221 -6 59.62588 62.40058 -6 60.63296 63.10112 -3 60.63296 63.10112 -6 61.56656 63.89703 -6 61.2755 63.63164 -3 62.41748 64.78044 -6 61.2755 63.63164 0 64.19779 78.55513 -3 65.06639 76.2638 -3 64.68838 77.43079 -6 64.19779 78.55513 -6 63.59936 79.62597 -6 62.89888 80.63297 -3 62.89888 80.63297 -6 62.10293 81.56661 -6 62.36835 81.27551 -3 61.21956 82.41748 -6 62.36835 81.27551 0 43.58252 81.21956 0 42.82227 80.25699 -6 42.15992 79.22437 0 42.15992 79.22437 -6 41.602 78.13183 -6 41.1539 76.98997 0 41.1539 76.98997 -6 40.81988 75.80973 -6 40.60311 74.60224 0 40.60311 74.60224 -6 40.50576 73.3793 -6 40.52873 72.15295 -6 40.67178 70.9348 -6 40.93362 69.7362 -6 44.78044 63.58252 0 45.743 62.82228 -6 46.77564 62.15992 0 46.77564 62.15992 -6 47.86821 61.60198 -6 49.01003 61.1539 0 49.01003 61.1539 -6 50.19031 60.81986 -6 51.39776 60.60311 0 51.39776 60.60311 -6 52.62068 60.50576 -6 53.84706 60.52873 -6 55.06525 60.67179 -6 56.2638 60.93362 -6 62.41748 64.78044 0 63.17773 65.74301 -6 63.84008 66.77564 0 63.84008 66.77564 -6 64.398 67.86817 -6 64.8461 69.01004 0 64.8461 69.01004 -6 65.18013 70.19027 -6 65.39689 71.39776 0 65.39689 71.39776 -6 65.49425 72.62071 -6 65.47127 73.84706 -6 65.32822 75.0652 -6 65.06639 76.2638 -6 61.21956 82.41748 0 60.257 83.17771 -6 59.22436 83.84008 0 59.22436 83.84008 -6 58.13179 84.39802 -6 56.98997 84.8461 0 56.98997 84.8461 -6 55.80969 85.18013 -6 54.60224 85.39689 0 54.60224 85.39689 -6 53.37932 85.49424 -6 52.15294 85.47127 -6 50.93474 85.32821 -6 49.73619 85.06639 -6 53.64385 64.38908 0 59.40158 73.3966 0 58.36738 73.84874 0 54.24751 72.9212 0 48.81126 68.14284 0 52.308 71.95903 0 49.07695 69.23984 0 48.95141 70.36155 0 56.76016 69.07695 0 57.85716 68.81127 0 54.04098 72.308 0 52.9212 71.75249 0 45.47195 72.67456 0 44.38908 72.35615 0 48.1864 67.20287 0 47.27774 66.5333 0 48.4498 71.37268 0 51.88022 72.44449 0 47.63261 72.15126 0 51.75249 73.07881 0 46.59842 72.6034 0 51.95902 73.692 0 52.44449 74.11978 0 51.37267 77.5502 0 52.15126 78.36739 0 53.0788 74.24752 0 52.6034 79.40158 0 54.11978 73.55551 0 57.5502 74.62733 0 53.692 74.04098 0 60.52805 73.32545 0 50.36154 77.04859 0 49.23983 76.92305 0 48.14284 77.18874 0 61.61092 73.64385 0 53.32544 65.47195 0 53.3966 66.59842 0 53.84874 67.63262 0 53.55551 71.88022 0 54.62733 68.4498 0 55.63845 68.95142 0 58.79713 68.18641 0 59.4667 67.27775 0 47.20286 77.81359 0 46.53329 78.72225 0 52.67456 80.52806 0 52.35615 81.61093 0 57.04859 75.63845 0 56.92305 76.76016 0 57.18873 77.85717 0 58.72225 79.46671 0 57.81359 78.79714 0 52.35615 81.61093 -3 52.15126 78.36739 -3 52.6034 79.40158 -3 52.67456 80.52806 -3 47.20286 77.81359 -3 48.14284 77.18874 -3 46.53329 78.72225 -3 49.23983 76.92305 -3 51.37267 77.5502 -3 50.36154 77.04859 -3 44.38908 72.35615 -3 47.63261 72.15126 -3 46.59842 72.6034 -3 45.47195 72.67456 -3 48.4498 71.37268 -3 48.95141 70.36155 -3 49.07695 69.23984 -3 48.1864 67.20287 -3 48.81126 68.14284 -3 47.27774 66.5333 -3 53.64385 64.38908 -3 53.84874 67.63262 -3 53.3966 66.59842 -3 53.32544 65.47195 -3 58.79713 68.18641 -3 57.85716 68.81127 -3 59.4667 67.27775 -3 56.76016 69.07695 -3 54.62733 68.4498 -3 55.63845 68.95142 -3 61.61092 73.64385 -3 58.36738 73.84874 -3 59.40158 73.3966 -3 60.52805 73.32545 -3 57.5502 74.62733 -3 57.04859 75.63845 -3 56.92305 76.76016 -3 57.81359 78.79714 -3 57.18873 77.85717 -3 58.72225 79.46671 -3 61.30702 80.21511 -36 61.46807 80.22166 -36 58.60028 77.95113 -36 60.49432 80.04459 -36 58.84286 75.84909 -36 58.76642 76.00913 -36 61.63967 74.2246 -36 58.61451 76.43865 -36 62.53209 80.04263 -36 63.00413 79.82346 -36 64.04912 78.82001 -36 64.19779 78.55513 -36 64.40613 78.00514 -36 64.48528 77.60916 -36 64.50355 77.42518 -36 64.48551 76.83736 -36 64.44898 76.61848 -36 62.6077 74.4298 -36 61.71362 74.22869 -36 58.52144 76.96255 -36 58.97336 78.82295 -36 59.25005 79.19466 -36 61.89484 80.19706 -36 62.44643 80.07221 -36 59.63203 79.56102 -36 60.17705 79.90946 -36 63.38935 79.56067 -36 63.88592 79.05376 -36 64.35348 76.26425 -36 64.09325 75.69614 -36 63.77059 75.24914 -36 63.45614 74.93861 -36 62.8436 74.53433 -36 61.12581 74.24674 -36 60.65684 74.34579 -36 59.13472 75.39004 -36 60.24856 74.50016 -36 59.43452 75.05591 -36 63.77868 79.25917 -32.24064 56.46109 64.74913 -12.18479 55.56387 64.87455 -12.11001 56.44378 65.86215 -13.81585 63.3548 68.58972 -16.46771 62.81863 68.08608 -16.36865 63.25875 69.6045 -20.10123 57.87664 84.34896 -9.578104 51.90408 82.00354 -15.86541 52.44025 82.50717 -15.96447 52.5207 81.36758 -17.60387 63.54909 79.66249 -24.72781 64.19779 78.55513 -24.75 64.19779 78.55513 -28.5 55.19048 72.52819 -20.7737 54.48141 73.73491 -20.74984 55.42436 74.20271 -22.77367 64.73256 76.22349 -32.17309 53.76623 72.01239 -18.32012 54.0091 72.26229 -18.84821 54.20864 71.91181 -18.81511 52.54354 71.83633 -16.66576 52.83663 71.76072 -16.96337 53.13022 71.24751 -16.92479 52.95265 71.7509 -17.09632 53.26614 71.77867 -17.50084 53.55551 71.88022 -17.94282 52.15916 72.07508 -16.36751 51.95791 70.53662 -15.10746 51.97411 72.28583 -16.27942 51.06109 72.03813 -15.08312 51.88038 72.44417 -16.26292 52.25988 71.99267 -16.43364 52.31038 71.95745 -16.47038 52.503 71.85305 -16.629 51.85434 73.49998 -16.8229 51.82031 73.41331 -16.7336 50.40813 73.6606 -15.10746 51.75553 73.11746 -16.49341 51.75297 73.08608 -16.47316 51.76616 72.79964 -16.33068 51.83525 72.54629 -16.26893 53.41479 74.17917 -19.39413 53.10905 74.24523 -18.97327 52.86478 74.62071 -18.81511 52.79336 74.23281 -18.50168 52.44871 74.12187 -17.94985 52.16091 73.92652 -17.45069 51.68341 74.16395 -16.92479 52.02274 73.7794 -17.18899 51.96132 73.69545 -17.06424 54.11949 73.5561 -20.04162 54.02008 73.72245 -20.01302 53.88378 73.88399 -19.91851 53.8548 73.91204 -19.89332 53.94957 75.02956 -20.7737 53.68933 74.04275 -19.72688 53.64644 74.06986 -19.67877 54.04043 72.30718 -18.92813 54.12083 72.4466 -19.15504 54.22537 72.75312 -19.55847 54.23629 72.81539 -19.62598 54.24717 72.9159 -19.72495 54.24652 73.09327 -19.8692 54.20441 73.33451 -19.99929 54.13595 73.52165 -20.04056 65.08835 72.87934 -20.65473 65.00465 73.77518 -24.4412 65.22948 74.26068 -20.79608 64.93759 75.58876 -28.36113 65.12194 75.70275 -20.90505 64.85004 76.58247 -28.43534 64.77109 77.15174 -20.97518 64.59836 77.58328 -28.4831 64.19779 78.55513 -32.25 64.85652 74.63907 -28.26487 64.64059 75.46932 -32.11979 64.05811 74.16703 -31.98632 64.41255 74.7751 -32.05671 64.60757 73.76969 -28.15098 55.1501 70.75581 -18.88524 61.75506 73.63688 -33.82795 58.53891 75.74781 -33.69046 58.90375 75.14615 -33.69534 58.55749 74.84506 -31.426 59.07398 74.22432 -31.45245 58.6774 73.77393 -29.23449 59.34247 73.18129 -29.29326 58.91267 72.59985 -27.13403 59.71788 72.08984 -27.23029 59.27463 71.40126 -25.13328 60.20594 71.035 -25.26708 59.76992 70.26761 -23.23205 60.80368 70.10308 -23.399 60.39462 69.28778 -21.42225 62.22813 71.6934 -27.60724 61.40856 71.62789 -27.4713 61.60068 72.33557 -29.56035 60.83216 72.44782 -29.45968 61.01821 73.0912 -31.60992 60.32749 73.32963 -31.54685 60.48929 73.87858 -33.75836 59.89685 74.19275 -33.73056 62.396 73.07676 -31.7556 61.7168 73.00553 -31.68032 61.11679 73.69118 -33.79125 62.37939 73.71856 -33.86721 62.9655 73.93199 -33.90773 63.02911 73.30072 -31.83332 63.59047 73.66933 -31.91104 63.65346 72.40049 -27.88792 64.20147 73.01343 -28.02386 64.20754 71.7917 -24.12468 64.70195 72.71435 -24.29162 64.70071 71.61157 -20.48749 54.93511 75.38918 -22.79587 54.62731 76.61083 -22.85859 53.61864 76.36409 -20.84115 54.5196 77.82367 -22.95606 53.50855 77.69032 -20.94596 54.61751 78.98265 -23.08247 53.62486 78.9589 -21.08189 54.9202 80.04348 -23.23205 53.96623 80.12131 -21.24273 55.41462 80.96613 -23.399 54.51798 81.13368 -21.42225 56.0822 81.71374 -23.57752 55.81874 75.69823 -24.87689 55.53731 76.80863 -24.933 55.43708 77.91061 -25.02019 55.52319 78.96327 -25.13328 55.795 79.92639 -25.26708 56.24079 80.76362 -25.41643 56.84381 81.44152 -25.57613 57.57835 81.93437 -25.74102 57.71892 83.334 -20.30083 58.97342 83.15641 -20.48749 59.85223 82.49022 -24.29162 55.25943 81.95561 -21.61422 56.15918 82.55598 -21.81242 56.89453 82.25796 -23.76184 56.50296 83.22256 -20.10123 57.81933 82.57551 -23.94615 58.81847 82.65476 -24.12468 58.96799 81.84527 -27.88792 59.78757 81.91078 -28.02386 60.63541 81.77659 -28.15098 63.02172 80.26792 -28.43534 62.28346 80.93882 -28.36113 61.86206 81.4662 -24.56761 62.48577 81.01664 -20.90505 63.42723 79.86065 -20.97518 63.83553 79.22338 -20.99366 58.20928 81.58455 -27.74758 57.54267 81.13818 -27.60724 56.99466 80.52524 -27.4713 56.58856 79.76898 -27.34418 56.33961 78.8996 -27.23029 56.25855 77.94992 -27.13403 56.34609 76.9562 -27.05982 58.78596 81.20782 -29.77914 58.17716 80.8029 -29.668 57.67436 80.25007 -29.56035 57.29879 79.57025 -29.45968 57.06451 78.79053 -29.36949 56.98154 77.94036 -29.29326 58.13913 77.08476 -33.70914 58.28058 76.4023 -33.69534 57.83136 76.30876 -31.426 58.13837 75.54911 -31.41664 57.62395 75.2939 -29.18328 58.09862 74.48812 -29.19666 57.52981 74.07663 -27.01206 58.17441 73.27075 -27.05982 57.5676 72.71607 -24.933 58.38439 71.96956 -25.02019 57.76009 71.29163 -22.95606 58.74213 70.66841 -23.08247 58.12266 69.89241 -21.08189 59.25473 69.46096 -21.24273 58.66245 68.61605 -19.3028 59.91695 68.43845 -19.48945 59.3725 67.55599 -17.60387 59.30705 80.80351 -31.83332 58.7457 80.4349 -31.7556 58.27806 79.9372 -31.68032 57.92362 79.32913 -31.60992 57.69558 78.63491 -31.54685 61.31795 81.01303 -32.05671 60.61937 81.0987 -31.98632 59.94016 81.02747 -31.91104 59.7712 80.37094 -33.90773 59.24666 80.03339 -33.86721 58.80391 79.5857 -33.82795 58.46099 79.04463 -33.79125 62.66482 80.39157 -32.17309 63.26219 79.87992 -32.21419 48.58308 84.10012 -7.574367 47.59546 83.5457 -7.546219 46.66823 82.89394 -7.518291 45.81012 82.15165 -7.490804 49.04162 73.11199 -13.36782 49.73284 71.3792 -13.34503 47.91148 71.58345 -11.69547 47.58656 72.51946 -11.7106 47.34365 73.475 -11.73501 48.64924 74.91342 -13.43225 47.18613 74.44123 -11.76804 47.11674 75.40924 -11.80902 48.57776 76.71707 -13.53236 47.43684 78.23249 -11.97305 48.83014 78.45502 -13.66221 47.24252 77.31404 -11.91218 47.13568 76.36989 -11.85729 51.31572 75.72893 -16.99541 50.02663 75.34308 -15.17623 51.21557 77.28923 -17.10515 49.93854 77.02393 -15.28309 51.38777 78.78646 -17.24748 50.14788 78.64005 -15.4217 51.82907 80.16324 -17.4159 49.07666 79.27818 -13.73643 49.40013 80.06043 -13.81585 50.65003 80.12941 -15.58569 49.79701 80.79438 -13.89973 51.42375 81.43576 -15.76873 50.26373 81.47265 -13.98732 49.63128 82.14453 -12.34363 51.75661 83.68601 -12.59514 53.65739 83.30333 -16.16656 50.99515 83.25343 -12.51042 53.02659 82.942 -16.06512 50.28444 82.73778 -12.42636 52.51392 76.0697 -18.88524 52.40639 77.51177 -18.99421 52.54752 78.89312 -19.13556 52.93516 80.16088 -19.3028 53.55272 81.26719 -19.48945 49.6821 83.98251 -9.199934 48.77372 83.47061 -9.148432 47.92249 82.86612 -9.097333 47.13646 82.17539 -9.047039 49.04248 81.47917 -12.26288 48.52439 80.74758 -12.18479 48.08144 79.95732 -12.11001 47.7176 79.11631 -12.03921 53.40227 84.28451 -12.76392 52.56172 84.03059 -12.67986 50.63925 84.39608 -9.251435 55.81335 84.89521 -9.494842 56.94896 84.35641 -13.08026 54.76005 85.01011 -9.449384 56.05174 84.48184 -13.00549 53.70591 85.01738 -9.401911 55.15579 84.51193 -12.92739 52.66109 84.9161 -9.352827 54.2698 84.44566 -12.84665 51.63556 84.70814 -9.302534 58.00399 83.77764 -16.74743 57.2485 83.90647 -16.65789 56.49575 83.95193 -16.56439 54.37712 82.16795 -19.68906 55.37363 82.8291 -19.89515 54.32672 83.58699 -16.268 55.02767 83.79077 -16.36865 55.75307 83.91298 -16.46771 60.88002 82.08943 -24.4412 60.21736 82.69806 -20.65473 60.82011 82.36785 -20.72905 59.49366 83.27641 -16.91143 59.56116 83.4252 -13.27809 58.71229 83.82615 -13.21723 61.40261 81.97471 -20.79608 61.47825 81.44883 -28.26487 62.00868 80.77461 -32.11979 63.71928 79.42555 -13.49481 63.17058 80.25055 -13.47968 62.55671 81.02207 -13.45526 61.88267 81.73206 -13.42224 61.15391 82.37295 -13.38126 60.37755 82.93907 -13.33299 61.95959 81.5229 -20.85502 62.7626 80.64668 -24.66508 63.66632 79.46204 -28.4831 56.85561 84.67428 -9.537883 57.83872 84.1373 -13.15107 58.75484 83.56709 -16.8322 45.02986 81.32564 -7.463978 44.33563 80.42319 -7.438032 43.73337 79.45352 -7.413187 43.22846 78.42633 -7.389663 42.8263 77.35131 -7.367681 42.53156 76.23841 -7.34746 42.34617 75.09852 -7.329221 42.27137 73.9428 -7.313184 42.30837 72.78237 -7.299569 42.45766 71.62833 -7.288596 42.71673 70.4915 -7.280486 43.08234 69.38265 -7.275458 43.55125 68.31256 -7.273733 44.11959 67.2918 -7.275458 44.78129 66.32984 -7.280486 45.52973 65.43578 -7.288596 46.35829 64.61872 -7.299569 47.25986 63.8872 -7.313184 48.22534 63.24755 -7.329221 49.2451 62.70553 -7.34746 50.30953 62.2669 -7.367681 51.4088 61.93673 -7.389663 52.53215 61.7173 -7.413187 53.6686 61.61018 -7.438032 54.80716 61.61697 -7.463978 55.93691 61.73849 -7.490804 57.04709 61.97266 -7.518291 58.12701 62.31663 -7.546219 59.16596 62.76757 -7.574367 60.64561 64.22569 -9.251435 61.49684 64.83018 -9.302534 62.28286 65.52092 -9.352827 62.99562 66.29156 -9.401911 63.62759 67.13529 -9.449384 64.17334 68.04347 -9.494842 64.62801 69.00701 -9.537883 64.9867 70.01679 -9.578104 65.24519 71.06351 -9.615102 65.4019 72.1369 -9.648474 65.45588 73.22652 -9.677818 65.40622 74.32188 -9.702729 65.25269 75.41257 -9.722806 64.99789 76.48842 -9.737646 64.64515 77.53932 -9.746845 64.19779 78.55513 -9.75 46.4237 81.40475 -8.997956 45.79174 80.56101 -8.950483 45.24599 79.65283 -8.905024 44.79132 78.6893 -8.861984 44.43264 77.67951 -8.821763 44.17414 76.63279 -8.784765 44.01744 75.5594 -8.751393 43.96345 74.46978 -8.722049 44.01311 73.37442 -8.697138 44.16664 72.28373 -8.677061 44.42144 71.20788 -8.662221 44.77418 70.15699 -8.653022 45.22153 69.14118 -8.649867 45.7597 68.17041 -8.653022 46.38304 67.25376 -8.662221 47.08551 66.4 -8.677061 47.86106 65.61788 -8.697138 48.70317 64.91565 -8.722049 49.60341 64.29942 -8.751393 50.55288 63.77479 -8.784765 51.54269 63.34734 -8.821763 52.56372 63.02202 -8.861984 53.60598 62.80109 -8.905024 54.65928 62.68619 -8.950483 55.71342 62.67892 -8.997956 56.75824 62.7802 -9.047039 57.78377 62.98816 -9.097333 58.78007 63.30022 -9.148432 59.73723 63.71379 -9.199934 64.85076 76.93265 -17.22566 64.19779 78.55513 -17.25 64.19779 78.55513 -13.5 65.32035 73.56932 -17.05003 65.23226 75.25018 -17.15689 65.3267 74.78973 -13.42224 65.27031 71.91693 -13.27809 65.25283 72.74921 -16.9843 65.37715 72.86107 -13.33299 65.39609 73.82173 -13.38126 64.60135 77.64752 -13.49481 64.92627 76.7115 -13.47968 65.16918 75.75596 -13.45526 65.076 70.99847 -13.21723 64.79523 70.11466 -13.15107 64.89546 71.18907 -16.8322 64.60885 70.46384 -16.74743 62.22839 66.49318 -12.76392 62.88155 67.08644 -12.84665 63.47035 67.7518 -12.92739 64.43139 69.27365 -13.08026 63.98844 68.48338 -13.00549 64.25435 69.78437 -16.65789 63.83513 69.1575 -16.56439 64.08315 70.50526 -20.30083 65.111 71.9532 -16.91143 63.53996 71.0441 -23.94615 62.72762 70.49987 -23.76184 62.98685 71.95412 -27.74758 64.19779 78.55513 -21 59.11055 64.94645 -12.42636 59.69745 65.88765 -14.17069 59.95111 65.20037 -12.51042 60.46612 66.11547 -14.26498 60.75622 65.54496 -12.59514 61.20125 66.42855 -14.36001 61.60149 67.28993 -16.16656 60.93216 67.00627 -16.06512 60.23121 66.80249 -15.96447 58.90304 65.74698 -14.07789 58.24303 64.7853 -12.34363 55.62523 66.07785 -13.73643 54.67411 65.09366 -12.03921 54.82066 66.37957 -13.66221 53.80054 65.40481 -11.97305 52.95167 65.80577 -11.91218 53.28418 67.23007 -13.53236 49.95612 68.2089 -11.73501 50.69436 69.78048 -13.36782 51.8913 68.3782 -13.43225 52.13528 66.2919 -11.85729 51.35892 66.85801 -11.80902 50.63016 67.4989 -11.76804 49.34225 68.98041 -11.7106 48.79355 69.80541 -11.69547 48.31504 70.67584 -11.69028 61.80283 70.18232 -23.57752 62.26223 68.94335 -19.89515 61.13291 68.5499 -19.68906 61.9556 68.12842 -18.0124 60.71023 67.69017 -17.80487 58.23056 78.43163 -33.75836 58.12229 77.76984 -33.73056 57.6036 77.88075 -31.49354 57.64958 77.09555 -31.45245 57.05104 77.05227 -29.23449 57.26954 76.15934 -29.19666 56.59777 75.95539 -27.01206 56.99834 74.98354 -26.99516 56.26424 74.61936 -24.85704 56.85374 73.61193 -24.87689 56.07307 73.09535 -22.79587 56.85955 72.11116 -22.85859 56.05286 71.45732 -20.84115 57.04223 70.56729 -20.94596 56.23325 69.79774 -18.99421 57.4185 69.0744 -19.13556 56.63193 68.21549 -17.24748 57.99514 67.73392 -17.4159 57.25489 66.81561 -15.58569 58.76314 66.64132 -15.76873 57.26828 65.7341 -13.89973 58.0907 65.69537 -13.98732 57.35704 64.71903 -12.26288 53.06673 69.21497 -15.17623 54.15386 70.00794 -16.99541 54.35177 68.12792 -15.28309 55.33562 68.98421 -17.10515 55.76522 67.31684 -15.4217 62.23229 67.65126 -16.268 61.51768 65.97753 -12.67986 60.26776 64.63981 -10.87432 59.3886 64.26171 -10.80403 58.47212 63.97969 -10.7343 57.52753 63.79609 -10.66566 59.36156 74.62064 -33.70914 59.67135 73.71266 -31.49354 60.06959 72.733 -29.36949 60.56071 71.76208 -27.34418 61.14228 70.88342 -25.41643 56.56399 63.71324 -10.59868 55.59077 63.73283 -10.53389 54.61725 63.85385 -10.47185 53.65288 64.07469 -10.41311 52.70712 64.39369 -10.35822 51.7892 64.80859 -10.30773 50.90754 65.31461 -10.26219 50.07036 65.90634 -10.22214 49.28588 66.57837 -10.18815 48.56185 67.32481 -10.16075 47.90425 68.13773 -10.1405 47.31858 69.00872 -10.12794 46.81037 69.92938 -10.12364 46.38479 70.89103 -10.12794 46.04561 71.88431 -10.1405 45.79619 72.89973 -10.16075 45.63989 73.92781 -10.18815 45.57941 74.95902 -10.22214 45.61475 75.98359 -10.26219 45.74525 76.99173 -10.30773 45.97024 77.97361 -10.35822 46.28843 78.91965 -10.41311 46.69604 79.82111 -10.47185 47.18865 80.66947 -10.53389 47.76186 81.45623 -10.59868 62.36835 -81.27551 -3 62.36835 -81.27551 0 61.21956 -82.41748 0 44.72449 -82.36836 -3 44.72449 -82.36836 0 43.58252 -81.21956 0 43.63164 -64.7245 -3 43.63164 -64.7245 0 44.78044 -63.58252 0 61.2755 -63.63164 -3 61.2755 -63.63164 0 62.41748 -64.78044 0 59.62588 -62.40058 -6 58.55513 -61.80221 -3 60.63296 -63.10112 -3 58.55513 -61.80221 -6 57.43088 -61.31166 -6 56.2638 -60.93362 -3 56.2638 -60.93362 -6 55.06525 -60.67179 -6 55.45265 -60.74298 -3 53.84706 -60.52873 -6 55.45265 -60.74298 0 41.80221 -67.44488 -3 43.10112 -65.36704 -3 42.40063 -66.37403 -6 41.80221 -67.44488 -6 41.31162 -68.56922 -6 40.93362 -69.7362 -3 40.93362 -69.7362 -6 40.67178 -70.9348 -6 40.74298 -70.54735 -3 40.52873 -72.15295 -6 40.74298 -70.54735 0 46.37412 -83.59942 -6 47.44487 -84.19779 -3 45.36703 -82.89888 -3 47.44487 -84.19779 -6 48.56912 -84.68834 -6 49.73619 -85.06639 -3 49.73619 -85.06639 -6 50.93474 -85.32821 -6 50.54735 -85.25702 -3 52.15294 -85.47127 -6 50.54735 -85.25702 0 64.19779 -78.55513 -3 62.89888 -80.63297 -3 63.59936 -79.62597 -6 64.19779 -78.55513 -6 64.68838 -77.43079 -6 65.06639 -76.2638 -3 65.06639 -76.2638 -6 65.32822 -75.0652 -6 65.25702 -75.45265 -3 65.47127 -73.84706 -6 65.25702 -75.45265 0 53.84706 -60.52873 0 52.62068 -60.50576 -6 51.39776 -60.60311 0 51.39776 -60.60311 -6 50.19031 -60.81986 -6 49.01003 -61.1539 0 49.01003 -61.1539 -6 47.86821 -61.60198 -6 46.77564 -62.15992 0 46.77564 -62.15992 -6 45.743 -62.82228 -6 44.78044 -63.58252 -6 43.89707 -64.4334 -6 43.10112 -65.36704 -6 40.52873 -72.15295 0 40.50576 -73.3793 -6 40.60311 -74.60224 0 40.60311 -74.60224 -6 40.81988 -75.80973 -6 41.1539 -76.98997 0 41.1539 -76.98997 -6 41.602 -78.13183 -6 42.15992 -79.22437 0 42.15992 -79.22437 -6 42.82227 -80.25699 -6 43.58252 -81.21956 -6 44.43344 -82.10297 -6 45.36703 -82.89888 -6 52.15294 -85.47127 0 53.37932 -85.49424 -6 54.60224 -85.39689 0 54.60224 -85.39689 -6 55.80969 -85.18013 -6 56.98997 -84.8461 0 56.98997 -84.8461 -6 58.13179 -84.39802 -6 59.22436 -83.84008 0 59.22436 -83.84008 -6 60.257 -83.17771 -6 61.21956 -82.41748 -6 62.10293 -81.56661 -6 62.89888 -80.63297 -6 65.47127 -73.84706 0 65.49425 -72.62071 -6 65.39689 -71.39776 0 65.39689 -71.39776 -6 65.18013 -70.19027 -6 64.8461 -69.01004 0 64.8461 -69.01004 -6 64.398 -67.86817 -6 63.84008 -66.77564 0 63.84008 -66.77564 -6 63.17773 -65.74301 -6 62.41748 -64.78044 -6 61.56656 -63.89703 -6 60.63296 -63.10112 -6 46.53329 -78.72225 0 57.18873 -77.85717 0 56.92305 -76.76016 0 53.692 -74.04098 0 46.59842 -72.6034 0 51.75249 -73.07881 0 47.63261 -72.15126 0 48.4498 -71.37268 0 52.15126 -78.36739 0 52.6034 -79.40158 0 53.0788 -74.24752 0 51.95902 -73.692 0 48.1864 -67.20287 0 47.27774 -66.5333 0 45.47195 -72.67456 0 44.38908 -72.35615 0 48.95141 -70.36155 0 51.88022 -72.44449 0 49.07695 -69.23984 0 52.308 -71.95903 0 48.81126 -68.14284 0 52.9212 -71.75249 0 53.55551 -71.88022 0 55.63845 -68.95142 0 56.76016 -69.07695 0 54.04098 -72.308 0 57.85716 -68.81127 0 54.11978 -73.55551 0 57.04859 -75.63845 0 54.24751 -72.9212 0 57.81359 -78.79714 0 54.62733 -68.4498 0 53.84874 -67.63262 0 53.3966 -66.59842 0 58.72225 -79.46671 0 47.20286 -77.81359 0 48.14284 -77.18874 0 49.23983 -76.92305 0 52.44449 -74.11978 0 50.36154 -77.04859 0 51.37267 -77.5502 0 52.67456 -80.52806 0 52.35615 -81.61093 0 53.32544 -65.47195 0 53.64385 -64.38908 0 58.79713 -68.18641 0 59.4667 -67.27775 0 57.5502 -74.62733 0 58.36738 -73.84874 0 59.40158 -73.3966 0 61.61092 -73.64385 0 60.52805 -73.32545 0 59.4667 -67.27775 -3 56.76016 -69.07695 -3 57.85716 -68.81127 -3 58.79713 -68.18641 -3 53.32544 -65.47195 -3 53.3966 -66.59842 -3 53.64385 -64.38908 -3 53.84874 -67.63262 -3 55.63845 -68.95142 -3 54.62733 -68.4498 -3 47.27774 -66.5333 -3 49.07695 -69.23984 -3 48.81126 -68.14284 -3 48.1864 -67.20287 -3 48.95141 -70.36155 -3 48.4498 -71.37268 -3 47.63261 -72.15126 -3 45.47195 -72.67456 -3 46.59842 -72.6034 -3 44.38908 -72.35615 -3 46.53329 -78.72225 -3 49.23983 -76.92305 -3 48.14284 -77.18874 -3 47.20286 -77.81359 -3 52.67456 -80.52806 -3 52.6034 -79.40158 -3 52.35615 -81.61093 -3 52.15126 -78.36739 -3 50.36154 -77.04859 -3 51.37267 -77.5502 -3 58.72225 -79.46671 -3 56.92305 -76.76016 -3 57.18873 -77.85717 -3 57.81359 -78.79714 -3 57.04859 -75.63845 -3 57.5502 -74.62733 -3 58.36738 -73.84874 -3 60.52805 -73.32545 -3 59.40158 -73.3966 -3 61.61092 -73.64385 -3 63.77059 -75.24914 -36 63.87324 -75.3734 -36 60.33038 -74.46366 -36 63.14314 -74.7052 -36 58.80344 -75.92854 -36 58.88462 -75.77085 -36 59.20205 -79.13825 -36 59.13472 -75.39004 -36 64.37444 -76.32891 -36 64.48551 -76.83736 -36 64.31875 -78.27649 -36 64.19779 -78.55513 -36 63.88592 -79.05376 -36 63.61851 -79.35634 -36 63.48308 -79.4822 -36 63.00413 -79.82346 -36 62.80775 -79.9268 -36 59.95109 -79.78488 -36 59.25005 -79.19466 -36 59.49555 -74.99898 -36 61.25027 -74.23326 -36 61.71362 -74.22869 -36 64.11186 -75.72808 -36 64.34616 -76.24281 -36 62.23642 -74.31118 -36 62.8436 -74.53433 -36 64.50933 -77.30307 -36 64.40613 -78.00514 -36 62.46793 -80.06506 -36 61.85814 -80.20157 -36 61.30702 -80.21511 -36 60.86953 -80.1526 -36 60.17705 -79.90946 -36 58.90879 -78.71571 -36 58.70393 -78.28237 -36 58.61451 -76.43865 -36 58.57984 -77.8639 -36 58.52985 -76.87951 -36 64.5048 -77.79547 -32.24064 48.52439 -80.74758 -12.18479 48.08144 -79.95732 -12.11001 49.40013 -80.06043 -13.81585 55.75307 -83.91298 -16.46771 55.02767 -83.79077 -16.36865 56.50296 -83.22256 -20.10123 64.9867 -70.01679 -9.578104 59.50582 -66.68027 -15.86541 60.23121 -66.80249 -15.96447 59.3725 -67.55599 -17.60387 64.68704 -77.36865 -24.72781 64.19779 -78.55513 -24.75 64.19779 -78.55513 -28.5 53.94957 -75.02956 -20.7737 54.48141 -73.73491 -20.74984 55.42436 -74.20271 -22.77367 62.66482 -80.39157 -32.17309 52.6772 -74.20761 -18.32012 53.02312 -74.24979 -18.84821 52.86478 -74.62071 -18.81511 51.79729 -73.34058 -16.66576 51.91441 -73.61968 -16.96337 51.68341 -74.16395 -16.92479 51.97679 -73.71801 -17.09632 52.18855 -73.95082 -17.50084 52.44449 -74.11978 -17.94282 51.75484 -72.89008 -16.36751 50.40813 -73.6606 -15.10746 51.81069 -72.61524 -16.27942 51.06109 -72.03813 -15.08312 51.88006 -72.4448 -16.26292 51.75016 -73.02013 -16.43364 51.75267 -73.08165 -16.47038 51.78608 -73.29818 -16.629 52.70497 -71.78532 -16.8229 52.61537 -71.81065 -16.7336 51.95791 -70.53662 -15.10746 52.34062 -71.93806 -16.49341 52.31408 -71.95501 -16.47316 52.094 -72.1388 -16.33068 51.93407 -72.34709 -16.26893 54.18984 -72.61688 -19.39413 54.05746 -72.33346 -18.97327 54.20864 -71.91181 -18.81511 53.85657 -72.08963 -18.50168 53.55973 -71.88233 -17.94985 53.23006 -71.77136 -17.45069 53.13022 -71.24751 -16.92479 53.02933 -71.75035 -17.18899 52.92533 -71.75224 -17.06424 54.12007 -73.55493 -20.04162 54.19238 -73.37513 -20.01302 54.23854 -73.16888 -19.91851 54.24334 -73.12883 -19.89332 55.19048 -72.52819 -20.7737 54.24731 -72.91799 -19.72688 54.24295 -72.86745 -19.67877 53.07783 -74.24758 -18.92813 53.23747 -74.22724 -19.15504 53.54477 -74.12505 -19.55847 53.60097 -74.09606 -19.62598 53.68757 -74.04391 -19.72495 53.8284 -73.93608 -19.8692 53.99501 -73.75661 -19.99929 54.1026 -73.58889 -20.04056 60.21736 -82.69806 -20.65473 60.88002 -82.08943 -24.4412 61.40261 -81.97471 -20.79608 62.28346 -80.93882 -28.36113 62.48577 -81.01664 -20.90505 63.02172 -80.26792 -28.43534 63.42723 -79.86065 -20.97518 63.66632 -79.46204 -28.4831 64.19779 -78.55513 -32.25 61.47825 -81.44883 -28.26487 62.00868 -80.77461 -32.11979 60.61937 -81.0987 -31.98632 61.31795 -81.01303 -32.05671 60.63541 -81.77659 -28.15098 52.51392 -76.0697 -18.88524 58.80391 -79.5857 -33.82795 58.53891 -75.74781 -33.69046 58.28058 -76.4023 -33.69534 57.83136 -76.30876 -31.426 57.64958 -77.09555 -31.45245 57.05104 -77.05227 -29.23449 56.98154 -77.94036 -29.29326 56.25855 -77.94992 -27.13403 56.33961 -78.8996 -27.23029 55.52319 -78.96327 -25.13328 55.795 -79.92639 -25.26708 54.9202 -80.04348 -23.23205 55.41462 -80.96613 -23.399 54.51798 -81.13368 -21.42225 57.54267 -81.13818 -27.60724 56.99466 -80.52524 -27.4713 57.67436 -80.25007 -29.56035 57.29879 -79.57025 -29.45968 57.92362 -79.32913 -31.60992 57.69558 -78.63491 -31.54685 58.23056 -78.43163 -33.75836 58.12229 -77.76984 -33.73056 58.7457 -80.4349 -31.7556 58.27806 -79.9372 -31.68032 58.46099 -79.04463 -33.79125 59.24666 -80.03339 -33.86721 59.7712 -80.37094 -33.90773 59.30705 -80.80351 -31.83332 59.94016 -81.02747 -31.91104 58.96799 -81.84527 -27.88792 59.78757 -81.91078 -28.02386 58.81847 -82.65476 -24.12468 59.85223 -82.49022 -24.29162 58.97342 -83.15641 -20.48749 56.07307 -73.09535 -22.79587 56.85955 -72.11116 -22.85859 56.05286 -71.45732 -20.84115 57.76009 -71.29163 -22.95606 57.04223 -70.56729 -20.94596 58.74213 -70.66841 -23.08247 58.12266 -69.89241 -21.08189 59.76992 -70.26761 -23.23205 59.25473 -69.46096 -21.24273 60.80368 -70.10308 -23.399 60.39462 -69.28778 -21.42225 61.80283 -70.18232 -23.57752 56.85374 -73.61193 -24.87689 57.5676 -72.71607 -24.933 58.38439 -71.96956 -25.02019 59.27463 -71.40126 -25.13328 60.20594 -71.035 -25.26708 61.14228 -70.88342 -25.41643 62.04686 -70.95343 -25.57613 62.88368 -71.24011 -25.74102 64.08315 -70.50526 -20.30083 64.70071 -71.61157 -20.48749 64.70195 -72.71435 -24.29162 61.49765 -69.38088 -21.61422 62.52002 -69.73406 -21.81242 62.72762 -70.49987 -23.76184 63.25875 -69.6045 -20.10123 63.53996 -71.0441 -23.94615 64.20754 -71.7917 -24.12468 63.65346 -72.40049 -27.88792 64.20147 -73.01343 -28.02386 64.60757 -73.76969 -28.15098 64.85004 -76.58247 -28.43534 64.93759 -75.58876 -28.36113 65.10256 -74.93416 -24.56761 65.12194 -75.70275 -20.90505 64.77109 -77.15174 -20.97518 64.5107 -77.8624 -20.99366 62.98685 -71.95412 -27.74758 62.22813 -71.6934 -27.60724 61.40856 -71.62789 -27.4713 60.56071 -71.76208 -27.34418 59.71788 -72.08984 -27.23029 58.91267 -72.59985 -27.13403 58.17441 -73.27075 -27.05982 63.03578 -72.64121 -29.77914 62.34505 -72.40145 -29.668 61.60068 -72.33557 -29.56035 60.83216 -72.44782 -29.45968 60.06959 -72.733 -29.36949 59.34247 -73.18129 -29.29326 59.36156 -74.62064 -33.70914 58.90375 -75.14615 -33.69534 58.55749 -74.84506 -31.426 58.13837 -75.54911 -31.41664 57.62395 -75.2939 -29.18328 57.26954 -76.15934 -29.19666 56.59777 -75.95539 -27.01206 56.34609 -76.9562 -27.05982 55.53731 -76.80863 -24.933 55.43708 -77.91061 -25.02019 54.5196 -77.82367 -22.95606 54.61751 -78.98265 -23.08247 53.62486 -78.9589 -21.08189 53.96623 -80.12131 -21.24273 52.93516 -80.16088 -19.3028 53.55272 -81.26719 -19.48945 52.5207 -81.36758 -17.60387 63.02911 -73.30072 -31.83332 62.396 -73.07676 -31.7556 61.7168 -73.00553 -31.68032 61.01821 -73.0912 -31.60992 60.32749 -73.32963 -31.54685 64.41255 -74.7751 -32.05671 64.05811 -74.16703 -31.98632 63.59047 -73.66933 -31.91104 62.9655 -73.93199 -33.90773 62.37939 -73.71856 -33.86721 61.75506 -73.63688 -33.82795 61.11679 -73.69118 -33.79125 64.73256 -76.22349 -32.17309 64.68659 -77.00868 -32.21419 59.16596 -62.76757 -7.574367 58.12701 -62.31663 -7.546219 57.04709 -61.97266 -7.518291 55.93691 -61.73849 -7.490804 50.69436 -69.78048 -13.36782 49.73284 -71.3792 -13.34503 48.79355 -69.80541 -11.69547 49.34225 -68.98041 -11.7106 49.95612 -68.2089 -11.73501 51.8913 -68.3782 -13.43225 50.63016 -67.4989 -11.76804 51.35892 -66.85801 -11.80902 53.28418 -67.23007 -13.53236 53.80054 -65.40481 -11.97305 54.82066 -66.37957 -13.66221 52.95167 -65.80577 -11.91218 52.13528 -66.2919 -11.85729 54.15386 -70.00794 -16.99541 53.06673 -69.21497 -15.17623 55.33562 -68.98421 -17.10515 54.35177 -68.12792 -15.28309 56.63193 -68.21549 -17.24748 55.76522 -67.31684 -15.4217 57.99514 -67.73392 -17.4159 55.62523 -66.07785 -13.73643 56.44378 -65.86215 -13.81585 57.25489 -66.81561 -15.58569 57.26828 -65.7341 -13.89973 58.76314 -66.64132 -15.76873 58.0907 -65.69537 -13.98732 58.24303 -64.7853 -12.34363 60.75622 -65.54496 -12.59514 61.60149 -67.28993 -16.16656 59.95111 -65.20037 -12.51042 60.93216 -67.00627 -16.06512 59.11055 -64.94645 -12.42636 55.1501 -70.75581 -18.88524 56.23325 -69.79774 -18.99421 57.4185 -69.0744 -19.13556 58.66245 -68.61605 -19.3028 59.91695 -68.43845 -19.48945 59.73723 -63.71379 -9.199934 58.78007 -63.30022 -9.148432 57.78377 -62.98816 -9.097333 56.75824 -62.7802 -9.047039 57.35704 -64.71903 -12.26288 56.46109 -64.74913 -12.18479 55.56387 -64.87455 -12.11001 54.67411 -65.09366 -12.03921 62.22839 -66.49318 -12.76392 61.51768 -65.97753 -12.67986 60.64561 -64.22569 -9.251435 64.17334 -68.04347 -9.494842 64.43139 -69.27365 -13.08026 63.62759 -67.13529 -9.449384 63.98844 -68.48338 -13.00549 62.99562 -66.29156 -9.401911 63.47035 -67.7518 -12.92739 62.28286 -65.52092 -9.352827 62.88155 -67.08644 -12.84665 61.49684 -64.83018 -9.302534 64.60885 -70.46384 -16.74743 64.25435 -69.78437 -16.65789 63.83513 -69.1575 -16.56439 61.13291 -68.5499 -19.68906 62.26223 -68.94335 -19.89515 62.23229 -67.65126 -16.268 62.81863 -68.08608 -16.36865 63.3548 -68.58972 -16.46771 65.00465 -73.77518 -24.4412 65.08835 -72.87934 -20.65473 65.19009 -73.55904 -20.72905 65.111 -71.9532 -16.91143 65.27031 -71.91693 -13.27809 65.076 -70.99847 -13.21723 65.22948 -74.26068 -20.79608 64.85652 -74.63907 -28.26487 64.64059 -75.46932 -32.11979 64.60135 -77.64752 -13.49481 64.92627 -76.7115 -13.47968 65.16918 -75.75596 -13.45526 65.3267 -74.78973 -13.42224 65.39609 -73.82173 -13.38126 65.37715 -72.86107 -13.33299 65.20671 -74.97751 -20.85502 64.99485 -76.14701 -24.66508 64.59836 -77.58328 -28.4831 64.62801 -69.00701 -9.537883 64.79523 -70.11466 -13.15107 64.89546 -71.18907 -16.8322 54.80716 -61.61697 -7.463978 53.6686 -61.61018 -7.438032 52.53215 -61.7173 -7.413187 51.4088 -61.93673 -7.389663 50.30953 -62.2669 -7.367681 49.2451 -62.70553 -7.34746 48.22534 -63.24755 -7.329221 47.25986 -63.8872 -7.313184 46.35829 -64.61872 -7.299569 45.52973 -65.43578 -7.288596 44.78129 -66.32984 -7.280486 44.11959 -67.2918 -7.275458 43.55125 -68.31256 -7.273733 43.08234 -69.38265 -7.275458 42.71673 -70.4915 -7.280486 42.45766 -71.62833 -7.288596 42.30837 -72.78237 -7.299569 42.27137 -73.9428 -7.313184 42.34617 -75.09852 -7.329221 42.53156 -76.23841 -7.34746 42.8263 -77.35131 -7.367681 43.22846 -78.42633 -7.389663 43.73337 -79.45352 -7.413187 44.33563 -80.42319 -7.438032 45.02986 -81.32564 -7.463978 45.81012 -82.15165 -7.490804 46.66823 -82.89394 -7.518291 47.59546 -83.5457 -7.546219 48.58308 -84.10012 -7.574367 50.63925 -84.39608 -9.251435 51.63556 -84.70814 -9.302534 52.66109 -84.9161 -9.352827 53.70591 -85.01738 -9.401911 54.76005 -85.01011 -9.449384 55.81335 -84.89521 -9.494842 56.85561 -84.67428 -9.537883 57.87664 -84.34896 -9.578104 58.86644 -83.92152 -9.615102 59.81592 -83.39688 -9.648474 60.71616 -82.78066 -9.677818 61.55826 -82.07842 -9.702729 62.33382 -81.29631 -9.722806 63.03628 -80.44254 -9.737646 63.65962 -79.5259 -9.746845 64.19779 -78.55513 -9.75 55.71342 -62.67892 -8.997956 54.65928 -62.68619 -8.950483 53.60598 -62.80109 -8.905024 52.56372 -63.02202 -8.861984 51.54269 -63.34734 -8.821763 50.55288 -63.77479 -8.784765 49.60341 -64.29942 -8.751393 48.70317 -64.91565 -8.722049 47.86106 -65.61788 -8.697138 47.08551 -66.4 -8.677061 46.38304 -67.25376 -8.662221 45.7597 -68.17041 -8.653022 45.22153 -69.14118 -8.649867 44.77418 -70.15699 -8.653022 44.42144 -71.20788 -8.662221 44.16664 -72.28373 -8.677061 44.01311 -73.37442 -8.697138 43.96345 -74.46978 -8.722049 44.01744 -75.5594 -8.751393 44.17414 -76.63279 -8.784765 44.43264 -77.67951 -8.821763 44.79132 -78.6893 -8.861984 45.24599 -79.65283 -8.905024 45.79174 -80.56101 -8.950483 46.4237 -81.40475 -8.997956 47.13646 -82.17539 -9.047039 47.92249 -82.86612 -9.097333 48.77372 -83.47061 -9.148432 49.6821 -83.98251 -9.199934 63.30097 -80.05663 -17.22566 64.19779 -78.55513 -17.25 64.19779 -78.55513 -13.5 60.90711 -82.46533 -17.05003 62.19215 -81.37828 -17.15689 61.88267 -81.73206 -13.42224 59.56116 -83.4252 -13.27809 60.21326 -82.90775 -16.9843 60.37755 -82.93907 -13.33299 61.15391 -82.37295 -13.38126 63.71928 -79.42555 -13.49481 63.17058 -80.25055 -13.47968 62.55671 -81.02207 -13.45526 58.71229 -83.82615 -13.21723 57.83872 -84.1373 -13.15107 58.75484 -83.56709 -16.8322 58.00399 -83.77764 -16.74743 53.40227 -84.28451 -12.76392 54.2698 -84.44566 -12.84665 55.15579 -84.51193 -12.92739 56.94896 -84.35641 -13.08026 56.05174 -84.48184 -13.00549 57.2485 -83.90647 -16.65789 56.49575 -83.95193 -16.56439 57.71892 -83.334 -20.30083 59.49366 -83.27641 -16.91143 57.81933 -82.57551 -23.94615 56.89453 -82.25796 -23.76184 58.20928 -81.58455 -27.74758 64.19779 -78.55513 -21 50.28444 -82.73778 -12.42636 51.38891 -82.63565 -14.17069 50.99515 -83.25343 -12.51042 52.03536 -83.10987 -14.26498 51.75661 -83.68601 -12.59514 52.72939 -83.50578 -14.36001 53.65739 -83.30333 -16.16656 53.02659 -82.942 -16.06512 52.44025 -82.50717 -15.96447 50.79629 -82.08823 -14.07789 49.63128 -82.14453 -12.34363 49.07666 -79.27818 -13.73643 47.7176 -79.11631 -12.03921 48.83014 -78.45502 -13.66221 47.43684 -78.23249 -11.97305 47.24252 -77.31404 -11.91218 48.57776 -76.71707 -13.53236 47.34365 -73.475 -11.73501 49.04162 -73.11199 -13.36782 48.64924 -74.91342 -13.43225 47.13568 -76.36989 -11.85729 47.11674 -75.40924 -11.80902 47.18613 -74.44123 -11.76804 47.58656 -72.51946 -11.7106 47.91148 -71.58345 -11.69547 48.31504 -70.67584 -11.69028 56.0822 -81.71374 -23.57752 55.37363 -82.8291 -19.89515 54.37712 -82.16795 -19.68906 54.53926 -83.07799 -18.0124 53.43686 -82.35153 -17.80487 60.48929 -73.87858 -33.75836 59.89685 -74.19275 -33.73056 59.67135 -73.71266 -31.49354 59.07398 -74.22432 -31.45245 58.6774 -73.77393 -29.23449 58.09862 -74.48812 -29.19666 57.52981 -74.07663 -27.01206 56.99834 -74.98354 -26.99516 56.26424 -74.61936 -24.85704 55.81874 -75.69823 -24.87689 54.93511 -75.38918 -22.79587 54.62731 -76.61083 -22.85859 53.61864 -76.36409 -20.84115 53.50855 -77.69032 -20.94596 52.40639 -77.51177 -18.99421 52.54752 -78.89312 -19.13556 51.38777 -78.78646 -17.24748 51.82907 -80.16324 -17.4159 50.65003 -80.12941 -15.58569 51.42375 -81.43576 -15.76873 49.79701 -80.79438 -13.89973 50.26373 -81.47265 -13.98732 49.04248 -81.47917 -12.26288 50.02663 -75.34308 -15.17623 51.31572 -75.72893 -16.99541 49.93854 -77.02393 -15.28309 51.21557 -77.28923 -17.10515 50.14788 -78.64005 -15.4217 54.32672 -83.58699 -16.268 52.56172 -84.03059 -12.67986 50.74039 -83.8447 -10.87432 49.90745 -83.37344 -10.80403 49.12843 -82.81433 -10.7343 48.41076 -82.1733 -10.66566 58.13913 -77.08476 -33.70914 57.6036 -77.88075 -31.49354 57.06451 -78.79053 -29.36949 56.58856 -79.76898 -27.34418 56.24079 -80.76362 -25.41643 47.76186 -81.45623 -10.59868 47.18865 -80.66947 -10.53389 46.69604 -79.82111 -10.47185 46.28843 -78.91965 -10.41311 45.97024 -77.97361 -10.35822 45.74525 -76.99173 -10.30773 45.61475 -75.98359 -10.26219 45.57941 -74.95902 -10.22214 45.63989 -73.92781 -10.18815 45.79619 -72.89973 -10.16075 46.04561 -71.88431 -10.1405 46.38479 -70.89103 -10.12794 46.81037 -69.92938 -10.12364 47.31858 -69.00872 -10.12794 47.90425 -68.13773 -10.1405 48.56185 -67.32481 -10.16075 49.28588 -66.57837 -10.18815 50.07036 -65.90634 -10.22214 50.90754 -65.31461 -10.26219 51.7892 -64.80859 -10.30773 52.70712 -64.39369 -10.35822 53.65288 -64.07469 -10.41311 54.61725 -63.85385 -10.47185 55.59077 -63.73283 -10.53389 56.56399 -63.71324 -10.59868 + + + + + + + + + + 0 0 -1 0.9792559 -0.2026274 0 0.9792567 -0.2026235 0 0.9201409 -0.3915875 0 0.8249534 -0.5652008 0 0.8249554 -0.565198 0 0.6974296 -0.7166533 0 0.6974276 -0.7166553 0 0.5425629 -0.8400152 0 0.5425648 -0.8400141 0 0.3664304 -0.9304455 0 0.3664276 -0.9304466 0 0.1759293 -0.9844029 0 0.17593 -0.9844027 0 -0.02146577 -0.9997696 0 -0.02146565 -0.9997696 0 -0.1239665 -0.9922865 0 -0.2216017 -0.9751373 0 -0.4060263 -0.9138615 0 -0.4060278 -0.9138607 0 -0.5781203 -0.8159515 0 -0.7275447 -0.6860603 0 -0.8484541 -0.5292692 0 -0.9361001 -0.351734 0 -0.9361014 -0.3517304 0 -0.987051 -0.160407 0 -0.9993078 0.03720194 0 -0.9993077 0.03720605 0 -0.9723896 0.2333634 0 -0.9723915 0.2333557 0 -0.9073538 0.4203679 0 -0.9073523 0.4203713 0 -0.8067486 0.5908948 0 -0.8067507 0.5908922 0 -0.6745178 0.7382586 0 -0.5158457 0.8566817 0 -0.5158402 0.8566849 0 -0.3369518 0.941522 0 -0.3369505 0.9415224 0 -0.1448455 0.9894543 0 -0.1448449 0.9894544 0 0.05293768 0.9985979 0 0.05293744 0.9985979 0 -0.9792559 0.2026274 0 -0.9201424 0.391584 0 -0.9201409 0.3915875 0 -0.8249549 0.5651987 0 -0.824953 0.5652015 0 -0.6974289 0.7166541 0 -0.6974309 0.716652 0 -0.5425639 0.8400146 0 -0.542562 0.8400159 0 -0.4384137 0.8987734 0 -0.3868224 0.9221543 0 -0.3175197 0.9482518 0 -0.3175229 0.9482507 0 -0.2769123 0.9608953 0 -0.1759299 0.9844028 0 -0.1759306 0.9844026 0 0.02146577 0.9997696 0 0.02146583 0.9997696 0 0.2180193 0.9759445 0 0.2180197 0.9759444 0 0.4060284 0.9138605 0 0.4060292 0.9138602 0 0.5781195 0.8159522 0 0.5781175 0.8159535 0 0.7275469 0.6860579 0 0.7275459 0.6860591 0 0.8484537 0.5292698 0 0.8484545 0.5292683 0 0.9361004 0.351733 0 0.987051 0.160407 0 0.9993078 -0.0372039 0 0.9993076 -0.03720599 0 0.9723906 -0.2333595 0 0.9073546 -0.4203662 0 0.9073538 -0.4203679 0 0.8067477 -0.5908961 0 0.6745178 -0.7382586 0 0.5158439 -0.8566827 0 0.5158457 -0.8566816 0 0.3369489 -0.941523 0 0.3369482 -0.9415233 0 0.144848 -0.989454 0 0.1448477 -0.989454 0 -0.05293768 -0.9985979 0 -0.05293744 -0.9985979 0 0 0 1 3.8996e-7 0 1 -3.70021e-7 0 1 3.9318e-7 0 1 -0.9621364 0.2725686 0 -0.96214 0.2725558 0 -0.696965 0.7171052 0 -0.2450318 0.9695151 0 -0.2450284 0.9695159 0 0.2725484 0.9621421 0 0.7171103 0.6969598 0 0.9695147 0.245033 0 0.96214 -0.2725558 0 0.696965 -0.7171052 0 0.2450284 -0.9695159 0 0.2450318 -0.9695151 0 -0.2725448 -0.9621431 0 -0.2725484 -0.9621421 0 -0.7171061 -0.6969641 0 -0.717113 -0.696957 0 -0.9695153 -0.2450309 0 -0.969512 -0.2450439 0 -0.9621407 0.2725535 0 -0.6969605 0.7171095 0 -0.2450383 0.9695135 0 0.2725546 0.9621403 0 0.7171061 0.6969641 0 0.7171095 0.6969605 0 0.9695164 0.2450264 0 0.9695131 0.2450395 0 0.9621418 -0.2725493 0 -0.7171095 -0.6969605 0 -0.9695131 -0.2450395 0 -0.9695147 -0.245033 0 0.717113 0.696957 0 0.7170991 0.6969712 0 0.9695181 0.2450199 0 0.9621443 -0.2725406 0 0.9621407 -0.2725535 0 0.6969605 -0.7171095 0 0.2450366 -0.9695138 0 0.2450399 -0.969513 0 -0.2725528 -0.9621409 0 -0.2725565 -0.9621399 0 -0.7170991 -0.6969712 0 -0.6969581 0.717112 0 0.2725448 0.9621431 0 0.7171172 0.6969527 0 0.9695153 0.2450309 0 0.9621437 -0.2725429 0 0.6969581 -0.717112 0 0.2450252 -0.9695168 0 -0.2725521 -0.9621411 0 -0.9695186 -0.2450179 0 -0.9621443 0.2725406 0 -0.2450366 0.9695138 0 -0.2450399 0.969513 0 0.2725528 0.9621409 0 0.2725565 0.9621399 0 0.9621364 -0.2725686 0 -0.9695181 -0.2450199 0 0.969512 0.2450439 0 0.9621371 -0.2725663 0 -0.9779068 0.209042 0 -0.823472 0.567357 0 -0.5436689 0.8392998 0 -0.5436729 0.8392972 0 -0.1810931 0.983466 0 0.2090399 0.9779072 0 0.2090381 0.9779075 0 0.5673578 0.8234714 0 0.8392994 0.5436697 0 0.9834648 0.1810993 0 0.9779068 -0.209042 0 0.9779049 -0.2090505 0 0.8234761 -0.567351 0 0.823472 -0.567357 0 0.5436649 -0.8393024 0 0.543669 -0.8392997 0 0.1811039 -0.983464 0 -0.2090488 -0.9779053 0 -0.5673541 -0.8234741 0 -0.8393017 -0.5436659 0 -0.8392977 -0.5436723 0 -0.9834651 -0.1810983 0 -0.977907 0.2090408 0 -0.9779088 0.2090323 0 -0.8234661 0.5673657 0 -0.8234744 0.5673536 0 -0.1811001 0.9834647 0 -0.1810985 0.983465 0 0.2090435 0.9779065 0 0.2090452 0.977906 0 0.5673537 0.8234742 0 0.8393017 0.5436659 0 0.8392936 0.5436785 0 0.9834651 0.1810983 0 0.9834682 0.181081 0 0.9779086 -0.2090334 0 0.8234661 -0.5673657 0 0.8234744 -0.5673536 0 0.5436689 -0.8392998 0 0.1811001 -0.9834647 0 0.1810985 -0.983465 0 -0.2090435 -0.9779065 0 -0.2090452 -0.977906 0 -0.5673537 -0.8234742 0 -0.5673578 -0.8234714 0 -0.8392936 -0.5436785 0 -0.9834648 -0.1810993 0 -0.983468 -0.181082 0 0.1949355 -0.9808161 0 -0.3215828 -0.9468815 0 -0.3215849 -0.9468808 0 -0.7519365 -0.6592356 0 -0.9808151 -0.1949405 0 -0.9468826 0.3215798 0 -0.659234 0.7519378 0 -0.1949425 0.9808147 0 -0.1949439 0.9808145 0 0.3215849 0.9468808 0 0.3215828 0.9468815 0 0.7519403 0.6592313 0 0.7519437 0.6592274 0 0.9808148 0.1949422 0 0.9468834 -0.3215771 0 0.6592257 -0.7519453 0 0.6592291 -0.7519422 0 -0.4421494 0.8969414 0 -0.4421517 0.8969404 0 0.4421573 -0.8969377 0 -0.1949522 0.9808128 0 0.7519334 0.6592392 0 0.7519472 0.6592234 0 0.9808121 0.1949555 0 0.9468792 -0.3215895 0 0.659234 -0.7519378 0 0.6592271 -0.751944 0 0.1949439 -0.9808145 0 -0.7519297 -0.6592435 0 -0.9468783 0.3215922 0 0.4421517 -0.8969404 0 -0.4421472 0.8969425 0 0.844948 0.5348486 0 0.8449503 0.534845 0 0.9590554 0.2832189 0 0.9999504 0.009968757 0 0.8033312 -0.5955325 0 0.8033322 -0.5955312 0 0.6430464 -0.7658274 0 0.5104647 -0.8598987 0 0.2781621 -0.9605343 0 0.2781626 -0.960534 0 -0.04359889 -0.9990492 0 -0.04359877 -0.9990491 0 -0.3607816 -0.9326503 0 -0.6400793 -0.7683089 0 -0.6400783 -0.7683098 0 -0.7836862 -0.6211569 0 -0.8739755 -0.4859702 0 -0.9747478 -0.2233088 0 -0.9747473 -0.2233108 0 -0.9949753 0.10012 0 -0.9949759 0.1001157 0 -0.9379491 0.3467729 0 -0.8693684 0.4941647 0 -0.8693663 0.4941684 0 -0.7308207 0.6825696 0 -0.7308218 0.6825684 0 0.1053555 0.9944347 0 -0.1707862 0.9853082 0 0.4652006 0.8852053 0 0.3384507 0.9409842 0 0.3384518 0.9409838 0 0.1053557 0.9944346 0 -0.8171238 -0.5764623 0 -0.817118 -0.5764706 0 -0.9958811 -0.09066891 0 -0.99588 -0.09068107 0 -0.9077931 0.4194184 0 -0.5764644 0.8171223 0 -0.09068077 0.99588 0 0.4194221 0.9077914 0 0.817118 0.5764706 0 0.8171238 0.5764623 0 0.9958811 0.09066891 0 0.99588 0.09068107 0 0.9077931 -0.4194184 0 0.5764644 -0.8171223 0 0.09067165 -0.9958809 0 -0.4194145 -0.907795 0 -0.8171296 -0.5764542 0 -0.9958822 -0.09065669 0 -0.9077978 0.4194083 0 -0.09067058 0.995881 0 0.4194192 0.9077927 0 0.4194098 0.9077971 0 0.8171296 0.5764542 0 0.9077978 -0.4194083 0 0.09068191 -0.99588 0 0.0906797 -0.9958801 0 -0.4194221 -0.9077914 0 -0.4194127 -0.9077957 0 -0.09067165 0.9958809 0 0.4194145 0.907795 0 0.9958822 0.09065669 0 0.09068077 -0.99588 0 -0.4194175 -0.9077936 0 -0.4194268 -0.9077892 0 -0.0906797 0.9958801 0 0.4194175 0.9077936 0 0.09067058 -0.995881 0 -0.4194192 -0.9077927 0 -0.4194098 -0.9077971 0 -0.8171215 -0.5764656 0 -0.9958807 -0.0906735 0 -0.9077922 0.4194204 0 -0.9077972 0.4194096 0 -0.5764623 0.8171237 0 -0.09067392 0.9958807 0 -0.09067273 0.9958808 0 0.4194136 0.9077953 0 0.8171215 0.5764656 0 0.9958807 0.0906735 0 0.9077922 -0.4194204 0 0.9077972 -0.4194096 0 0.5764623 -0.8171237 0 0.09067392 -0.9958807 0 0.09067273 -0.9958808 0 -0.4194136 -0.9077953 0 -0.7683101 0.640078 0 -0.768309 0.6400793 0 -0.7683109 0.640077 0 -0.7683106 0.6400774 2.71601e-6 -0.7683089 0.6400794 3.51931e-6 -0.76831 0.640078 0 -0.7683108 0.640077 0 -0.7683108 0.6400771 0 0.7683089 -0.6400794 0 0.7683086 -0.6400798 0 0.7683098 -0.6400783 0 0.7683096 -0.6400784 -3.64055e-6 0.7683106 -0.6400773 0 0.7683068 -0.6400818 -2.716e-6 0.7683089 -0.6400792 0 -0.1595366 -0.1914978 0.9684404 -0.1595364 -0.191497 0.9684406 -0.6400794 -0.7683088 0 -0.6400749 -0.7683126 0 0.6400797 0.7683086 0 0.6400781 0.7683098 0 0.1595369 0.1914969 -0.9684405 0.4428381 0.5315518 -0.7220437 0.4428389 0.5315576 -0.722039 -0.4428388 -0.5315529 0.7220425 -0.4428393 -0.5315546 0.7220409 -0.8853747 -0.4648783 0 -0.8853749 -0.4648778 -2.25759e-6 -0.8853745 -0.4648786 2.57186e-6 -0.8853753 -0.4648771 -5.43201e-6 -0.885375 -0.4648776 -3.51931e-6 -0.8853749 -0.464878 -3.64056e-6 -0.8853745 -0.4648786 0 -0.8853765 -0.464875 0 -0.8853753 -0.4648773 0 0.8853734 0.4648807 0 0.8853753 0.4648771 0 0.8853745 0.4648787 -3.51932e-6 0.8853749 0.464878 0 0.8853747 0.4648784 -1.28594e-6 0.885374 0.4648796 0 0.885375 0.4648776 0 0.8853749 0.4648778 0 0.1158689 -0.2206752 0.9684404 0.1158686 -0.2206748 0.9684405 0.4648799 -0.8853738 0 -0.4648776 0.885375 0 -0.1158689 0.2206763 -0.9684402 -0.1158682 0.2206754 -0.9684405 -0.3216266 0.6125465 -0.722041 -0.3216252 0.6125473 -0.7220409 0.3216255 -0.612545 0.7220427 0.3216261 -0.6125465 0.7220412 0.2973363 0.9547728 0 0.2973363 0.9547728 -4.51518e-6 0.2973358 0.954773 0 0.2973368 0.9547727 -2.71602e-6 0.2973361 0.954773 0 0.2973361 0.9547729 0 0.2973377 0.9547725 0 0.2973368 0.9547728 0 -0.2973365 -0.9547728 0 -0.2973365 -0.9547728 0 -0.2973356 -0.9547731 0 -0.2973362 -0.9547728 0 -0.2973357 -0.954773 0 -0.297336 -0.954773 2.57188e-6 -0.2973377 -0.9547724 0 -0.2973363 -0.9547728 3.98253e-6 -0.2973357 -0.9547731 0 -0.2379729 0.07411009 0.9684403 -0.2379729 0.07410901 0.9684404 -0.9547719 0.2973394 0 -0.9547742 0.2973319 0 0.9547721 -0.2973389 0 0.9547739 -0.2973331 0 0.2379729 -0.07411044 -0.9684404 0.2379727 -0.07410937 -0.9684404 0.6605592 -0.2057161 -0.7220405 0.6605598 -0.2057103 -0.7220416 -0.6605598 0.2057098 0.7220417 -0.6605602 0.2057132 0.7220405 -0.47956 0.8775091 0 0.9496881 -0.3131974 0 0.9592216 -0.2812895 0.02775436 0.9634406 -0.2603877 0.06309133 0.9735206 -0.2285993 0 0.9926347 -0.1211466 0 0.9926349 -0.1211444 0 0.9997779 0.02107638 0 0.9866478 0.1628689 0 0.9866478 0.1628686 0 0.9535117 0.3013563 0 0.9535104 0.3013603 0 0.90104 0.433736 0 0.8302958 0.5573231 0 0.7427192 0.669603 0 0.7427184 0.669604 0 0.6793577 0.7338073 0 0.6524149 0.757108 0.03379774 0.6387918 0.7667672 0.06334924 0.6268365 0.7784172 0.03380566 0.5990425 0.8007172 0 0.5244606 0.8514348 0 0.5244589 0.8514358 0 0.3982062 0.9172959 0 0.3982076 0.9172953 0 0.2638789 0.9645559 0 0.2638794 0.9645557 0 0.1241993 0.9922574 0 -0.01799774 0.9998381 0 -0.1598309 0.9871445 0 -0.1598308 0.9871445 0 -0.298421 0.9544344 0 -0.2984212 0.9544343 0 -0.4309609 0.9023706 0 -0.3978682 0.909843 0.1178419 -0.4498926 0.8926519 0.02773612 -0.9494668 0.3138675 0 0.4801707 -0.8771752 0 0.4492619 -0.8929322 -0.02891415 0.4313367 -0.9001316 -0.06092578 0.4005841 -0.9162601 0 0.299511 -0.954093 0 0.1607969 -0.9869875 0 0.01881301 -0.9998231 0 -0.1235513 -0.9923382 0 -0.123551 -0.9923382 0 -0.2634063 -0.964685 0 -0.3979073 -0.9174256 0 -0.3979066 -0.9174261 0 -0.5243215 -0.8515204 0 -0.5243199 -0.8515214 0 -0.5984632 -0.8011503 0 -0.6263346 -0.7789235 -0.03135991 -0.6388888 -0.7668792 -0.06097322 -0.6529922 -0.7567159 -0.03134375 -0.6798995 -0.7333054 0 -0.7428284 -0.6694819 0 -0.7428265 -0.669484 0 -0.8304791 -0.5570499 0 -0.8304778 -0.5570517 0 -0.9012509 -0.4332976 0 -0.9012513 -0.4332968 0 -0.9537077 -0.3007355 0 -0.9537078 -0.3007349 0 -0.9867809 -0.1620606 0 -0.9867802 -0.1620648 0 -0.9997981 -0.02009415 0 -0.999798 -0.02009809 0 -0.9924961 0.1222764 0 -0.9924956 0.1222806 0 -0.9650219 0.2621693 0 -0.9667417 0.2269223 -0.11797 -0.9593885 0.2806026 -0.02891325 1.98393e-6 0 1 -1.91227e-6 0 1 9.93112e-7 0 1 -7.32654e-5 0 -1 0.3734552 -0.9276483 0 0.3734561 -0.9276478 0 0.1053557 -0.9944346 0 0.1053555 -0.9944347 0 -0.1707862 -0.9853082 0 -0.7308218 -0.6825684 0 -0.7308207 -0.6825696 0 -0.8693663 -0.4941684 0 -0.8693684 -0.4941647 0 -0.9379491 -0.3467729 0 -0.9949759 -0.1001157 0 -0.9949753 -0.10012 0 -0.9747473 0.2233108 0 -0.9747478 0.2233088 0 -0.8521572 0.523286 0 -0.6400783 0.7683098 0 -0.6400793 0.7683089 0 -0.4694114 0.8829796 0 -0.3201382 0.9473709 0 -0.04359877 0.9990491 0 -0.04359889 0.9990492 0 0.2781626 0.960534 0 0.2781621 0.9605343 0 0.5104647 0.8598987 0 0.6430464 0.7658274 0 0.8033322 0.5955312 0 0.8033312 0.5955325 0 0.9590554 -0.2832189 0 0.9999504 -0.009968757 0 0.7866349 -0.6174186 0 0.8643876 -0.5028261 0 -0.4194098 0.9077971 0 -0.4194192 0.9077927 0 0.09067058 0.995881 0 0.5764644 0.8171223 0 0.9077978 0.4194083 0 0.9958822 -0.09065669 0 0.99588 -0.09068107 0 0.817118 -0.5764706 0 0.8171296 -0.5764542 0 0.4194221 -0.9077914 0 0.4194175 -0.9077936 0 -0.0906797 -0.9958801 0 -0.09068077 -0.99588 0 -0.5764644 -0.8171223 0 -0.9077931 -0.4194184 0 -0.9077978 -0.4194083 0 -0.99588 0.09068107 0 -0.9958811 0.09066891 0 -0.8171296 0.5764542 0 -0.817118 0.5764706 0 -0.4194268 0.9077892 0 -0.4194175 0.9077936 0 0.09068077 0.99588 0 0.0906797 0.9958801 0 0.9077931 0.4194184 0 0.8171238 -0.5764623 0 0.4194098 -0.9077971 0 0.4194145 -0.907795 0 -0.09067165 -0.9958809 0 -0.8171238 0.5764623 0 -0.4194127 0.9077957 0 -0.4194221 0.9077914 0 0.09068191 0.99588 0 0.9958811 -0.09066891 0 0.4194192 -0.9077927 0 -0.09067058 -0.995881 0 -0.9958822 0.09065669 0 -0.4194145 0.907795 0 0.09067165 0.9958809 0 -0.4194136 0.9077953 0 0.09067273 0.9958808 0 0.09067392 0.9958807 0 0.5764623 0.8171237 0 0.9077972 0.4194096 0 0.9077922 0.4194204 0 0.9958807 -0.0906735 0 0.8171215 -0.5764656 0 0.4194136 -0.9077953 0 -0.09067273 -0.9958808 0 -0.09067392 -0.9958807 0 -0.5764623 -0.8171237 0 -0.9077972 -0.4194096 0 -0.9077922 -0.4194204 0 -0.9958807 0.0906735 0 -0.8171215 0.5764656 0 0.7683086 0.6400796 0 0.7683102 0.6400778 0 0.7683103 0.6400778 0 0.7683079 0.6400806 -2.716e-6 0.7683106 0.6400773 -3.51932e-6 0.7683088 0.6400795 0 0.7683089 0.6400794 0 0.7683086 0.6400798 0 -0.7683109 -0.6400768 0 -0.7683106 -0.6400774 0 -0.7683096 -0.6400785 3.5193e-6 -0.7683102 -0.6400778 0 -0.7683106 -0.6400773 0 -0.7683108 -0.640077 2.71601e-6 -0.7683089 -0.6400792 0 -0.76831 -0.640078 0 -0.1595366 0.1914978 0.9684404 -0.1595364 0.191497 0.9684406 -0.6400753 0.7683123 0 -0.6400792 0.768309 0 0.6400781 -0.7683098 0 0.6400797 -0.7683086 0 0.1595366 -0.1914965 -0.9684407 0.1595373 -0.1914973 -0.9684404 0.4428383 -0.5315568 -0.7220399 0.4428392 -0.531553 -0.7220422 -0.4428408 0.5315566 0.7220386 -0.4428378 0.5315517 0.722044 -0.2973363 0.9547728 0 -0.2973357 0.9547731 4.51517e-6 -0.2973376 0.9547724 0 -0.2973368 0.9547727 2.71602e-6 -0.2973364 0.9547728 0 -0.2973357 0.954773 0 -0.297335 0.9547732 0 -0.2973376 0.9547725 0 -0.2973365 0.9547728 0 0.2973377 -0.9547725 0 0.2973368 -0.9547728 0 0.2973359 -0.954773 -3.51931e-6 0.2973357 -0.954773 3.64055e-6 0.2973346 -0.9547734 0 0.2973377 -0.9547724 -2.71602e-6 0.2973363 -0.9547728 -3.98253e-6 0.2973363 -0.9547728 0 -0.2379727 -0.07410901 0.9684404 -0.2379724 -0.07410997 0.9684405 -0.9547743 -0.2973316 0 -0.9547718 -0.2973397 0 0.9547737 0.2973334 0 0.9547722 0.2973386 0 0.2379729 0.07410937 -0.9684404 0.2379727 0.07411044 -0.9684404 0.6605599 0.2057103 -0.7220415 0.6605591 0.2057162 -0.7220406 -0.6605595 -0.2057129 0.7220411 -0.6605605 -0.2057101 0.722041 0.8853744 -0.4648786 0 0.8853753 -0.4648769 0 0.8853749 -0.4648779 0 0.8853749 -0.4648779 0 0.8853744 -0.4648787 0 0.8853747 -0.4648783 -3.64056e-6 0.885374 -0.4648796 0 0.8853746 -0.4648786 0 -0.8853745 0.4648786 0 -0.8853753 0.4648773 0 -0.8853765 0.464875 0 -0.8853747 0.4648783 -3.51931e-6 -0.8853754 0.4648768 -3.64055e-6 -0.8853741 0.4648792 0 -0.885375 0.4648774 -2.71601e-6 -0.8853747 0.4648783 -1.99127e-6 -0.8853747 0.464878 0 0.1158689 0.2206752 0.9684404 0.1158686 0.2206748 0.9684405 0.4648799 0.8853738 0 -0.4648776 -0.885375 0 -0.1158687 -0.2206754 -0.9684404 -0.1158684 -0.2206763 -0.9684403 -0.3216263 -0.6125471 -0.7220407 -0.321626 -0.6125478 -0.7220402 0.3216254 0.6125459 0.722042 0.3216265 0.6125465 0.7220411 -1.9112e-6 0 -1 0.9496881 0.3131974 0 -0.47956 -0.8775091 0 -0.4498926 -0.8926519 0.02773612 -0.4301025 -0.9005728 0.06309181 -0.4006595 -0.9162271 0 -0.2984212 -0.9544343 0 -0.298421 -0.9544344 0 -0.1598308 -0.9871445 0 -0.1598309 -0.9871445 0 -0.01799774 -0.9998381 0 0.1241993 -0.9922574 0 0.2638794 -0.9645557 0 0.2638789 -0.9645559 0 0.3982076 -0.9172953 0 0.3982062 -0.9172959 0 0.5244589 -0.8514358 0 0.5244606 -0.8514348 0 0.5990425 -0.8007172 0 0.6268365 -0.7784172 0.03380566 0.6387916 -0.7667675 0.06334924 0.6524149 -0.757108 0.03379774 0.6793577 -0.7338073 0 0.7427192 -0.669603 0 0.7427184 -0.669604 0 0.8302958 -0.5573231 0 0.90104 -0.433736 0 0.9535106 -0.3013597 0 0.9535115 -0.3013568 0 0.9866478 -0.1628689 0 0.9866478 -0.1628686 0 0.9997779 -0.02107638 0 0.9926349 0.1211447 0 0.9926347 0.1211463 0 0.9653639 0.2609075 0 0.9667376 0.2270065 0.117841 0.9592216 0.2812895 0.02775436 0.4801707 0.8771752 0 -0.9494668 -0.3138675 0 -0.9593885 -0.2806026 -0.02891325 -0.9632297 -0.2616801 -0.06092727 -0.9735388 -0.2285221 0 -0.9924957 -0.1222804 0 -0.9924961 -0.1222767 0 -0.999798 0.02009809 0 -0.9997981 0.02009415 0 -0.9867802 0.1620645 0 -0.9867808 0.1620609 0 -0.9537077 0.3007355 0 -0.9537078 0.3007349 0 -0.9012517 0.433296 0 -0.9012505 0.4332984 0 -0.8304773 0.5570527 0 -0.8304796 0.557049 0 -0.7428274 0.669483 0 -0.7428275 0.6694829 0 -0.6798995 0.7333054 0 -0.6529922 0.7567159 -0.03134375 -0.6388888 0.7668792 -0.06097322 -0.6263346 0.7789235 -0.03135991 -0.5984632 0.8011503 0 -0.5243206 0.8515209 0 -0.5243208 0.8515209 0 -0.3979066 0.9174261 0 -0.3979073 0.9174256 0 -0.2634063 0.964685 0 -0.123551 0.9923382 0 -0.1235513 0.9923382 0 0.01881301 0.9998231 0 0.1607969 0.9869875 0 0.299511 0.954093 0 0.4321394 0.9018068 0 0.3977869 0.9098622 -0.1179674 0.4492619 0.8929322 -0.02891415 9.55073e-7 0 1 1.98738e-6 0 1 1.908e-6 0 1 1.98972e-6 0 1 -1.90692e-6 0 1 -3.8996e-7 0 1 -4.90399e-7 0 1 3.70021e-7 0 1 -0.9792559 -0.2026274 0 -0.9792567 -0.2026235 0 -0.9201409 -0.3915875 0 -0.8249534 -0.5652008 0 -0.8249554 -0.565198 0 -0.6974296 -0.7166533 0 -0.6974276 -0.7166553 0 -0.5425629 -0.8400152 0 -0.5425648 -0.8400141 0 -0.3664304 -0.9304455 0 -0.3664276 -0.9304466 0 -0.1759293 -0.9844029 0 -0.17593 -0.9844027 0 0.02146577 -0.9997696 0 0.02146565 -0.9997696 0 0.1239665 -0.9922865 0 0.2216017 -0.9751373 0 0.4060263 -0.9138615 0 0.4060278 -0.9138607 0 0.5781203 -0.8159515 0 0.7275447 -0.6860603 0 0.8484541 -0.5292692 0 0.9361001 -0.351734 0 0.9361014 -0.3517304 0 0.987051 -0.160407 0 0.9993078 0.03720194 0 0.9993077 0.03720605 0 0.9723896 0.2333634 0 0.9723915 0.2333557 0 0.9073538 0.4203679 0 0.9073523 0.4203713 0 0.8067486 0.5908948 0 0.8067507 0.5908922 0 0.6745178 0.7382586 0 0.5158457 0.8566817 0 0.5158402 0.8566849 0 0.3369518 0.941522 0 0.3369505 0.9415224 0 0.1448455 0.9894543 0 0.1448449 0.9894544 0 -0.05293768 0.9985979 0 -0.05293744 0.9985979 0 0.9792559 0.2026274 0 0.9201424 0.391584 0 0.9201409 0.3915875 0 0.8249549 0.5651987 0 0.824953 0.5652015 0 0.6974289 0.7166541 0 0.6974309 0.716652 0 0.5425639 0.8400146 0 0.542562 0.8400159 0 0.4384137 0.8987734 0 0.3868224 0.9221543 0 0.3175197 0.9482518 0 0.3175229 0.9482507 0 0.2769123 0.9608953 0 0.1759299 0.9844028 0 0.1759306 0.9844026 0 -0.02146577 0.9997696 0 -0.02146583 0.9997696 0 -0.2180193 0.9759445 0 -0.2180197 0.9759444 0 -0.4060284 0.9138605 0 -0.4060292 0.9138602 0 -0.5781195 0.8159522 0 -0.5781175 0.8159535 0 -0.7275469 0.6860579 0 -0.7275459 0.6860591 0 -0.8484537 0.5292698 0 -0.8484545 0.5292683 0 -0.9361004 0.351733 0 -0.987051 0.160407 0 -0.9993078 -0.0372039 0 -0.9993076 -0.03720599 0 -0.9723906 -0.2333595 0 -0.9073546 -0.4203662 0 -0.9073538 -0.4203679 0 -0.8067477 -0.5908961 0 -0.6745178 -0.7382586 0 -0.5158439 -0.8566827 0 -0.5158457 -0.8566816 0 -0.3369489 -0.941523 0 -0.3369482 -0.9415233 0 -0.144848 -0.989454 0 -0.1448477 -0.989454 0 0.05293768 -0.9985979 0 0.05293744 -0.9985979 0 0.9621364 0.2725686 0 0.96214 0.2725558 0 0.696965 0.7171052 0 0.2450318 0.9695151 0 0.2450284 0.9695159 0 -0.2725484 0.9621421 0 -0.7171103 0.6969598 0 -0.9695147 0.245033 0 -0.96214 -0.2725558 0 -0.696965 -0.7171052 0 -0.2450284 -0.9695159 0 -0.2450318 -0.9695151 0 0.2725448 -0.9621431 0 0.2725484 -0.9621421 0 0.7171061 -0.6969641 0 0.717113 -0.696957 0 0.9695153 -0.2450309 0 0.969512 -0.2450439 0 0.9621407 0.2725535 0 0.6969605 0.7171095 0 0.2450383 0.9695135 0 -0.2725546 0.9621403 0 -0.7171061 0.6969641 0 -0.7171095 0.6969605 0 -0.9695164 0.2450264 0 -0.9695131 0.2450395 0 -0.9621418 -0.2725493 0 0.7171095 -0.6969605 0 0.9695131 -0.2450395 0 0.9695147 -0.245033 0 -0.717113 0.696957 0 -0.7170991 0.6969712 0 -0.9695181 0.2450199 0 -0.9621443 -0.2725406 0 -0.9621407 -0.2725535 0 -0.6969605 -0.7171095 0 -0.2450366 -0.9695138 0 -0.2450399 -0.969513 0 0.2725528 -0.9621409 0 0.2725565 -0.9621399 0 0.7170991 -0.6969712 0 0.6969581 0.717112 0 -0.2725448 0.9621431 0 -0.7171172 0.6969527 0 -0.9695153 0.2450309 0 -0.9621437 -0.2725429 0 -0.6969581 -0.717112 0 -0.2450252 -0.9695168 0 0.2725521 -0.9621411 0 0.9695186 -0.2450179 0 0.9621443 0.2725406 0 0.2450366 0.9695138 0 0.2450399 0.969513 0 -0.2725528 0.9621409 0 -0.2725565 0.9621399 0 -0.9621364 -0.2725686 0 0.9695181 -0.2450199 0 -0.969512 0.2450439 0 -0.9621371 -0.2725663 0 0.9779068 0.209042 0 0.823472 0.567357 0 0.5436689 0.8392998 0 0.5436729 0.8392972 0 0.1810931 0.983466 0 -0.2090399 0.9779072 0 -0.2090381 0.9779075 0 -0.5673578 0.8234714 0 -0.8392994 0.5436697 0 -0.9834648 0.1810993 0 -0.9779068 -0.209042 0 -0.9779049 -0.2090505 0 -0.8234761 -0.567351 0 -0.823472 -0.567357 0 -0.5436649 -0.8393024 0 -0.543669 -0.8392997 0 -0.1811039 -0.983464 0 0.2090488 -0.9779053 0 0.5673541 -0.8234741 0 0.8393017 -0.5436659 0 0.8392977 -0.5436723 0 0.9834651 -0.1810983 0 0.977907 0.2090408 0 0.9779088 0.2090323 0 0.8234661 0.5673657 0 0.8234744 0.5673536 0 0.1811001 0.9834647 0 0.1810985 0.983465 0 -0.2090435 0.9779065 0 -0.2090452 0.977906 0 -0.5673537 0.8234742 0 -0.8393017 0.5436659 0 -0.8392936 0.5436785 0 -0.9834651 0.1810983 0 -0.9834682 0.181081 0 -0.9779086 -0.2090334 0 -0.8234661 -0.5673657 0 -0.8234744 -0.5673536 0 -0.5436689 -0.8392998 0 -0.1811001 -0.9834647 0 -0.1810985 -0.983465 0 0.2090435 -0.9779065 0 0.2090452 -0.977906 0 0.5673537 -0.8234742 0 0.5673578 -0.8234714 0 0.8392936 -0.5436785 0 0.9834648 -0.1810993 0 0.983468 -0.181082 0 -0.1949355 -0.9808161 0 0.3215828 -0.9468815 0 0.3215849 -0.9468808 0 0.7519365 -0.6592356 0 0.9808151 -0.1949405 0 0.9468826 0.3215798 0 0.659234 0.7519378 0 0.1949425 0.9808147 0 0.1949439 0.9808145 0 -0.3215849 0.9468808 0 -0.3215828 0.9468815 0 -0.7519403 0.6592313 0 -0.7519437 0.6592274 0 -0.9808148 0.1949422 0 -0.9468834 -0.3215771 0 -0.6592257 -0.7519453 0 -0.6592291 -0.7519422 0 0.4421494 0.8969414 0 0.4421517 0.8969404 0 -0.4421573 -0.8969377 0 0.1949522 0.9808128 0 -0.7519334 0.6592392 0 -0.7519472 0.6592234 0 -0.9808121 0.1949555 0 -0.9468792 -0.3215895 0 -0.659234 -0.7519378 0 -0.6592271 -0.751944 0 -0.1949439 -0.9808145 0 0.7519297 -0.6592435 0 0.9468783 0.3215922 0 -0.4421517 -0.8969404 0 0.4421472 0.8969425 0 -0.9792567 0.2026235 0 -0.8249534 0.5652008 0 -0.8249554 0.565198 0 -0.6974296 0.7166533 0 -0.6974276 0.7166553 0 -0.5425629 0.8400152 0 -0.5425648 0.8400141 0 -0.3664304 0.9304455 0 -0.3664276 0.9304466 0 -0.1759293 0.9844029 0 -0.17593 0.9844027 0 0.02146565 0.9997696 0 0.1239665 0.9922865 0 0.2216017 0.9751373 0 0.4060263 0.9138615 0 0.4060278 0.9138607 0 0.5781203 0.8159515 0 0.7275447 0.6860603 0 0.8484541 0.5292692 0 0.9361001 0.351734 0 0.9361014 0.3517304 0 0.9993078 -0.03720194 0 0.9993077 -0.03720605 0 0.9723896 -0.2333634 0 0.9723915 -0.2333557 0 0.9073523 -0.4203713 0 0.8067486 -0.5908948 0 0.8067507 -0.5908922 0 0.5158457 -0.8566817 0 0.5158402 -0.8566849 0 0.3369518 -0.941522 0 0.3369505 -0.9415224 0 0.1448455 -0.9894543 0 0.1448449 -0.9894544 0 0.9201424 -0.391584 0 0.8249549 -0.5651987 0 0.824953 -0.5652015 0 0.6974289 -0.7166541 0 0.6974309 -0.716652 0 0.5425639 -0.8400146 0 0.542562 -0.8400159 0 0.4384137 -0.8987734 0 0.3868224 -0.9221543 0 0.3175197 -0.9482518 0 0.3175229 -0.9482507 0 0.2769123 -0.9608953 0 0.1759299 -0.9844028 0 0.1759306 -0.9844026 0 -0.02146583 -0.9997696 0 -0.2180193 -0.9759445 0 -0.2180197 -0.9759444 0 -0.4060284 -0.9138605 0 -0.4060292 -0.9138602 0 -0.5781195 -0.8159522 0 -0.5781175 -0.8159535 0 -0.7275469 -0.6860579 0 -0.7275459 -0.6860591 0 -0.8484537 -0.5292698 0 -0.8484545 -0.5292683 0 -0.9361004 -0.351733 0 -0.9993078 0.0372039 0 -0.9993076 0.03720599 0 -0.9723906 0.2333595 0 -0.9073546 0.4203662 0 -0.8067477 0.5908961 0 -0.5158439 0.8566827 0 -0.5158457 0.8566816 0 -0.3369489 0.941523 0 -0.3369482 0.9415233 0 -0.144848 0.989454 0 -0.1448477 0.989454 0 -3.8996e-7 0 1 -3.9318e-7 0 1 -0.7171103 -0.6969598 0 0.2450383 -0.9695135 0 -0.2725546 -0.9621403 0 -0.9695164 -0.2450264 0 -0.9621418 0.2725493 0 -0.7171172 -0.6969527 0 -0.9621437 0.2725429 0 -0.2450252 0.9695168 0 0.2725521 0.9621411 0 0.9695186 0.2450179 0 -0.9621371 0.2725663 0 0.5436729 -0.8392972 0 0.1810931 -0.983466 0 -0.2090399 -0.9779072 0 -0.2090381 -0.9779075 0 -0.8392994 -0.5436697 0 -0.9779049 0.2090505 0 -0.8234761 0.567351 0 -0.5436649 0.8393024 0 -0.543669 0.8392997 0 -0.1811039 0.983464 0 0.2090488 0.9779053 0 0.5673541 0.8234741 0 0.8392977 0.5436723 0 0.977907 -0.2090408 0 0.9779088 -0.2090323 0 -0.9834682 -0.181081 0 -0.9779086 0.2090334 0 0.983468 0.181082 0 -0.1949355 0.9808161 0 0.7519365 0.6592356 0 0.9808151 0.1949405 0 0.9468826 -0.3215798 0 0.1949425 -0.9808147 0 -0.7519403 -0.6592313 0 -0.7519437 -0.6592274 0 -0.9808148 -0.1949422 0 -0.9468834 0.3215771 0 -0.6592257 0.7519453 0 -0.6592291 0.7519422 0 0.4421494 -0.8969414 0 -0.4421573 0.8969377 0 0.1949522 -0.9808128 0 -0.7519334 -0.6592392 0 -0.7519472 -0.6592234 0 -0.9808121 -0.1949555 0 -0.9468792 0.3215895 0 -0.6592271 0.751944 0 0.7519297 0.6592435 0 0.9468783 -0.3215922 0 0.4421472 -0.8969425 0 -0.7049936 0.7092137 0 0.7092114 0.7049959 0 0.7049947 -0.7092126 0 -0.7092114 -0.7049959 0 -0.5299692 -0.8477796 0.02005928 -0.487826 -0.872941 0 -0.3999215 -0.9165494 0 -0.3543937 -0.9348813 0.0200572 -0.3081609 -0.9513344 0 -0.2134194 -0.9769607 0 -0.2287788 -0.9734571 -0.006442666 -0.1166297 -0.9931391 0.008504688 -0.1322667 -0.9912142 0 0.8477804 -0.529968 0.02006137 0.8729401 -0.4878276 0 0.9165496 -0.3999211 0 0.9348812 -0.3543937 0.02005875 0.9513365 -0.3081539 0 0.976961 -0.2134183 0 0.9734573 -0.228778 -0.006443917 0.9931393 -0.1166277 0.008507072 0.9912146 -0.132263 0 0.5299692 0.8477796 0.02005928 0.487826 0.872941 0 0.3999215 0.9165494 0 0.3543937 0.9348812 0.02006137 0.3081609 0.9513344 0 0.2134194 0.9769607 0 0.2287788 0.9734571 -0.006442666 0.1166297 0.9931391 0.008508801 0.1322667 0.9912142 0 -0.8477804 0.529968 0.02006137 -0.8729383 0.4878308 0 -0.9165511 0.3999176 0 -0.9348812 0.3543937 0.02005982 -0.9513353 0.3081577 0 -0.9769635 0.2134063 0 -0.9734546 0.2287896 -0.006443858 -0.9931388 0.1166318 0.008507072 -0.9912139 0.1322692 0 -0.1322659 -0.9912143 0 -0.01873159 -0.9998246 0 0.03035187 -0.999489 0.01003116 0.07935678 -0.9968463 0 0.1766919 -0.9842663 0 0.2247596 -0.9743627 0.01003116 0.2723122 -0.962209 0 0.365313 -0.9308848 0 0.4105276 -0.911793 0.0100311 0.4547963 -0.8905956 0 0.5399052 -0.8417258 0 0.5805229 -0.8141822 0.01003217 0.6198084 -0.7847532 0 0.7049979 -0.7092095 0 0.6937087 -0.7202056 0.008507132 0.7711026 -0.6366784 -0.006442666 0.7609911 -0.6487625 0 0.8209163 -0.5710487 0 0.9912143 -0.1322661 0 0.9998245 -0.01873505 0 0.999489 0.03035509 0.01003098 0.9968467 0.07935267 0 0.9842659 0.1766937 0 0.974363 0.2247582 0.01003062 0.962208 0.2723155 0 0.9308842 0.3653146 0 0.9117934 0.4105266 0.01003217 0.890595 0.4547973 0 0.8417252 0.5399062 0 0.8141797 0.5805263 0.01003062 0.784756 0.619805 0 0.7092083 0.7049991 0 0.7202035 0.6937108 0.008500516 0.6366781 0.7711029 -0.006445765 0.6487641 0.7609897 0 0.5710432 0.8209201 0 0.1322659 0.9912143 0 0.01872849 0.9998246 0 -0.03035187 0.999489 0.01003009 -0.07935369 0.9968466 0 -0.1766949 0.9842658 0 -0.2247611 0.9743623 0.01003217 -0.2723122 0.962209 0 -0.3653103 0.9308859 0 -0.4105263 0.9117937 0.0100311 -0.4547963 0.8905956 0 -0.5399075 0.8417245 0 -0.580524 0.8141815 0.0100311 -0.6198084 0.7847532 0 -0.7049967 0.7092106 0 -0.693707 0.7202071 0.008505046 -0.7711026 0.6366784 -0.006445765 -0.7609911 0.6487625 0 -0.8209163 0.5710487 0 -0.9912146 0.132263 0 -0.9998245 0.01873505 0 -0.9994891 -0.03034883 0.01003164 -0.996846 -0.07936096 0 -0.9842644 -0.1767017 0 -0.9743621 -0.2247621 0.0100314 -0.9622092 -0.2723116 0 -0.9308871 -0.3653074 0 -0.9117912 -0.4105318 0.01003164 -0.8905984 -0.4547907 0 -0.8417252 -0.5399062 0 -0.8141807 -0.5805249 0.01003062 -0.784756 -0.619805 0 -0.7092083 -0.7049991 0 -0.720205 -0.6937093 0.008500516 -0.6366781 -0.7711029 -0.006445765 -0.6487623 -0.7609912 0 -0.5710432 -0.8209201 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.8958237 -0.4444097 0 -0.8958224 0.4444125 0 -0.8958233 0.4444104 0 -0.9593874 0.2820919 0 -0.959385 0.2821002 0 -0.9980109 -0.06304216 0 -0.9980115 -0.06303316 0 -0.9162588 -0.400587 0 -0.9162621 -0.4005793 0 -0.723999 -0.689801 0 -0.7239946 -0.6898058 0 -0.4444175 -0.8958199 0 -0.444414 -0.8958216 0 -0.1112183 -0.993796 0 0.235389 -0.9719013 0 0.5536001 -0.8327828 0 0.8050448 -0.5932141 0 0.8050405 -0.5932199 0 -0.4444112 -0.895823 0 -0.4444102 -0.8958235 0 0.4444106 0.8958232 0 0.4444097 0.8958238 0 -0.2820948 -0.9593866 0 -0.2820973 -0.9593858 0 0.06303751 -0.9980112 0 0.06303811 -0.9980112 0 0.4005796 -0.916262 0 0.4005829 -0.9162606 0 0.6898 -0.7240001 0 0.8958243 -0.4444085 0 0.9937955 -0.1112231 0 0.9937965 -0.1112142 0 0.9719036 0.2353795 0 0.9719015 0.2353879 0 0.8327776 0.5536078 0 0.8327859 0.5535954 0 0.5932171 0.8050427 0 0.8958224 -0.4444125 0 0.8958233 -0.4444104 0 -0.8958237 0.4444097 0 0.9593874 -0.2820919 0 0.959385 -0.2821002 0 0.9980109 0.06304216 0 0.9980115 0.06303316 0 0.9162588 0.400587 0 0.9162621 0.4005793 0 0.723999 0.689801 0 0.7239946 0.6898058 0 0.4444175 0.8958199 0 0.444414 0.8958216 0 0.1112183 0.993796 0 -0.235389 0.9719013 0 -0.5536001 0.8327828 0 -0.8050448 0.5932141 0 -0.8050405 0.5932199 0 -0.4444106 -0.8958232 0 -0.4444097 -0.8958238 0 0.2820948 0.9593866 0 0.2820973 0.9593858 0 -0.06303751 0.9980112 0 -0.06303811 0.9980112 0 -0.4005796 0.916262 0 -0.4005829 0.9162606 0 -0.6898 0.7240001 0 -0.8958243 0.4444085 0 -0.9937955 0.1112231 0 -0.9937965 0.1112142 0 -0.9719036 -0.2353795 0 -0.9719015 -0.2353879 0 -0.8327776 -0.5536078 0 -0.8327859 -0.5535954 0 -0.5932171 -0.8050427 0 -0.9518451 0.3064783 -0.007889389 0.7468224 0.3660587 -0.5552094 0.1913203 0.9562805 -0.2211884 -0.9614841 -0.2721109 -0.03878372 -0.9288521 -0.3645123 -0.06606477 -0.08750563 -0.8869518 -0.4534967 -0.9244852 0.3812181 0 0.81795 -0.344502 -0.4607344 -0.5788812 0.8124634 -0.06928229 0.7900676 -0.2890295 -0.5406065 0.7694192 -0.2860738 -0.5711006 0.7688262 -0.2857663 -0.5720525 0.7703077 -0.2879226 -0.5689699 0.7765011 -0.3068635 -0.5503461 0.7388376 -0.3371851 -0.5834597 0.7341102 -0.3045395 -0.6069084 0.7096219 -0.3481241 -0.6125737 0.7386245 -0.3264354 -0.5898083 0.738728 -0.3231567 -0.5914819 0.7388831 -0.3202867 -0.5928477 0.7022882 -0.3941846 -0.5927983 0.7016115 -0.3949422 -0.5930953 0.7031961 -0.393554 -0.5921406 0.7073593 -0.3899976 -0.5895293 0.6891389 -0.4018394 -0.603003 0.7043605 -0.3593432 -0.6121673 0.7071205 -0.3532097 -0.6125549 0.7142857 -0.4554574 -0.5313704 0.7090926 -0.4559841 -0.5378348 0.7065764 -0.4297248 -0.5622157 0.6957682 -0.4384998 -0.56888 0.6932944 -0.4392796 -0.5712936 0.7759007 -0.3908814 -0.4951665 0.7463771 -0.4160385 -0.5194547 0.7462572 -0.4210778 -0.5155519 0.7456024 -0.4244972 -0.5136917 0.7802253 -0.3514371 -0.5174366 0.7879036 -0.3385114 -0.5144102 0.7897953 -0.3359796 -0.5131679 0.7893721 -0.3365162 -0.5134673 0.7872231 -0.3389022 -0.5151943 0.7797881 -0.3454749 -0.5220896 0.7948496 -0.3358367 -0.5053986 0.7814166 -0.3793413 -0.4954677 0.7787638 -0.3850625 -0.4952313 -0.5162618 0.8551346 -0.04710328 -0.5431947 0.8380256 -0.05150401 -0.660857 0.7500697 -0.02575957 -0.6708874 0.7411055 -0.0259388 -0.7751383 0.6317455 -0.007644772 -0.7806472 0.6249167 -0.008318424 -0.8478252 0.530276 0 -0.4974315 0.8635626 -0.08259272 -0.5291074 0.8464987 -0.05903661 -0.5279424 0.8464966 -0.06870645 -0.6698449 0.7414533 -0.03943151 -0.6581162 0.7519587 -0.03796434 -0.7802993 0.6251659 -0.01734524 -0.680666 0.7324479 -0.01462757 -0.7492435 0.6621451 -0.01407659 -0.102617 0.9794648 -0.1735471 -0.02406352 0.9798385 -0.1983367 -0.09966683 0.9752017 -0.1976063 0.1374673 0.9621372 -0.235361 -0.4956535 0.8628461 -0.09911698 -0.3750616 0.9218108 -0.09794723 -0.4638088 0.8813806 -0.08972042 0.7932484 -0.2908909 -0.5349202 0.8046362 -0.3051286 -0.5093693 0.8314272 -0.2258908 -0.5076436 0.7935227 0.5507206 -0.258899 0.9117401 -0.3613272 -0.1953784 0.9535441 -0.2269505 -0.1981084 0.9394293 -0.2257201 -0.2579206 0.9608701 -0.0924775 -0.2611066 0.9441112 -0.09478795 -0.3157045 0.9470658 0.048675 -0.3173281 0.9305859 0.04259264 -0.3635872 0.9096149 0.2066342 -0.3604208 0.8963676 0.1978672 -0.3967038 0.8411238 0.3813428 -0.3835211 0.8329564 0.3722846 -0.4093751 0.7406169 0.59144 -0.3188816 0.8460183 0.4184498 -0.330383 0.853935 0.4279125 -0.2961183 0.9149766 0.2736181 -0.2965654 0.9263955 0.2815987 -0.2499873 0.9583216 0.1464767 -0.245284 0.9702621 0.1507682 -0.1893687 0.9794601 0.04974615 -0.1954056 0.7203637 0.6344684 -0.2802248 0.8188297 0.4998255 -0.2822984 0.8266648 0.5074403 -0.2431663 0.877699 0.4149329 -0.23974 0.6165726 0.7323439 -0.2889824 0.5357082 0.8000211 -0.2701538 0.5341391 0.7957503 -0.2854415 0.3503291 0.8981593 -0.265668 0.3503554 0.8977093 -0.2671502 0.1145757 0.967738 -0.2244008 0.1129417 0.9704509 -0.2132354 -0.1309493 0.9793068 -0.1543067 -0.133369 0.9809874 -0.1409832 0.4641481 0.8417618 -0.2756877 0.3196336 0.910371 -0.2627912 0.3327912 0.903813 -0.269021 0.1271099 0.9636318 -0.235068 0.1262187 0.9662583 -0.2245303 -0.1285941 0.9764687 -0.1731256 -0.1318491 0.9791859 -0.1543076 0.7079264 -0.5364331 -0.4594342 0.7064189 -0.540062 -0.457499 0.6256618 -0.6333394 -0.4554433 0.6224449 -0.6386516 -0.4524229 0.5194885 -0.7277581 -0.4477722 0.5142375 -0.7338458 -0.4438807 0.3814011 -0.8158896 -0.4345772 0.3742265 -0.8215882 -0.4300553 0.2078462 -0.8865472 -0.4133206 0.1996525 -0.8905968 -0.4086274 -0.005388319 -0.9248304 -0.3803416 0.7907114 -0.4549987 -0.4095751 0.769795 -0.4417158 -0.4607633 0.7694432 -0.4430304 -0.4600883 0.7490437 -0.4301758 -0.5038675 0.7466341 -0.4078828 -0.5255181 0.7258217 -0.5527201 -0.4094918 0.7254017 -0.5536118 -0.409031 0.6392225 -0.6517234 -0.4082294 0.6383609 -0.6529958 -0.4075439 0.5279827 -0.7465301 -0.4048792 0.526659 -0.7479288 -0.4040209 0.3847323 -0.8330112 -0.3975845 0.38304 -0.8342365 -0.3966481 0.2068983 -0.8999826 -0.3836985 0.2051842 -0.9007408 -0.3828391 -0.008751749 -0.9331183 -0.3594631 -0.009895086 -0.9333303 -0.3588825 -0.2494649 -0.9133081 -0.3219246 -0.8533563 -0.5007863 -0.1449003 -0.2502059 -0.9099226 -0.3308141 -0.4882938 -0.8286989 -0.273546 -0.4917519 -0.8266507 -0.2735486 -0.7059323 -0.6787179 -0.2024886 -0.7045191 -0.6770644 -0.2126893 -0.7027646 -0.678565 -0.2137089 -0.8594697 -0.4874194 -0.1540591 -0.995921 0.08559864 -0.0285378 -0.9719707 0.2349593 -0.008186578 -0.9389649 0.3440114 -0.001143336 -0.9245109 0.3810961 -0.006731986 -0.2520744 -0.9157309 -0.3128826 -0.2570493 -0.9151656 -0.3104798 -0.01248455 -0.9398729 -0.3412961 -0.01908206 -0.9408146 -0.3383843 0.2044707 -0.9115492 -0.3567493 0.1977363 -0.9141861 -0.3537854 0.3857369 -0.8482765 -0.3628141 0.3799869 -0.8520247 -0.3600887 0.5336291 -0.7636013 -0.3635286 0.5293965 -0.767645 -0.3611934 0.6496933 -0.6686175 -0.3617312 0.6470258 -0.6721767 -0.3599112 0.740667 -0.5676794 -0.3593781 -0.258868 -0.9168741 -0.3038575 -0.2695735 -0.9153188 -0.2992016 -0.02191233 -0.9458888 -0.3237506 -0.03794431 -0.9475071 -0.3174756 0.1957098 -0.9232038 -0.3307456 0.178155 -0.9291168 -0.3240416 0.380541 -0.8642683 -0.3289816 0.3647949 -0.8734242 -0.3225753 0.533688 -0.7816653 -0.3227638 0.5215837 -0.7920804 -0.3171108 0.6554043 -0.6863282 -0.315276 0.5321065 -0.8298096 -0.1681636 0.7473621 -0.6471284 -0.1505819 0.7416131 -0.640884 -0.1981865 0.8438997 -0.4997799 -0.1950727 0.8337894 -0.493049 -0.2483907 0.8950339 -0.3703681 -0.2484787 0.8797683 -0.3649998 -0.3046026 0.9197958 -0.2459017 -0.305791 0.9007828 -0.2436767 -0.3594607 0.926117 -0.1127194 -0.3600024 0.9059693 -0.1146438 -0.407525 0.9138152 0.03304249 -0.4047842 0.8955891 0.0272175 -0.4440491 0.878974 0.1981059 -0.4337729 0.8653364 0.189946 -0.4638032 0.813589 0.3799048 -0.4401651 0.8057528 0.3720377 -0.460815 0.8288227 -0.5443216 -0.1294873 0.8807755 -0.4534736 -0.1363686 0.9214349 -0.3646646 -0.1340804 0.7272874 -0.671077 -0.1439059 0.847254 -0.5126341 -0.1391648 0.8398088 -0.5076838 -0.1922979 0.9089859 -0.3697534 -0.1924248 0.8965286 -0.3654034 -0.2504337 0.9373885 -0.2400685 -0.2523292 0.920708 -0.2383726 -0.3089907 0.9444754 -0.1064206 -0.3108713 0.9258975 -0.1085923 -0.3618309 0.9316751 0.03738564 -0.3613641 0.9142062 0.03137242 -0.4040334 0.8956766 0.1995282 -0.3974316 0.8821449 0.1910063 -0.4305078 0.8287167 0.3785574 -0.4122172 0.8206597 0.3700568 -0.4354029 -0.01272249 -0.926452 -0.3761982 -0.2460963 -0.9101473 -0.3332697 -0.2494502 -0.9133133 -0.3219217 -0.4927266 -0.8270795 -0.2704811 -0.490149 -0.8288521 -0.2697373 -0.4959144 -0.8254108 -0.2697517 -0.4966566 -0.8257596 -0.2673077 -0.4953799 -0.8266221 -0.267011 -0.2705937 -0.9163556 -0.2950789 -0.2876657 -0.9132732 -0.2884106 -0.03981399 -0.9509823 -0.3066716 -0.06692713 -0.9524281 -0.2973244 0.1766726 -0.9356987 -0.3053767 0.1455359 -0.9443026 -0.2951476 0.3651041 -0.8827534 -0.2957118 0.335911 -0.8975104 -0.2857252 0.5247278 -0.8031272 -0.2822192 -0.8563596 -0.4881421 -0.1684207 -0.8408035 -0.5108395 -0.1791439 -0.7017908 -0.6767697 -0.2224244 -0.6924214 -0.6849031 -0.2268488 -0.5028127 -0.8220776 -0.2671477 -0.5031813 -0.8223305 -0.2656713 -0.287994 -0.9136531 -0.2868756 -0.311543 -0.9084823 -0.2785695 -0.06788092 -0.9544269 -0.2906227 -0.1073411 -0.9543753 -0.2786499 0.1446814 -0.9486082 -0.2814423 0.09695404 -0.9585194 -0.2680307 0.3361814 -0.9040779 -0.2638664 -0.997444 0.05605632 -0.04430949 -0.9957987 0.08523792 -0.03345882 -0.9743135 0.2245674 -0.01681494 -0.9743428 0.224691 -0.01304167 -0.9887645 0.1453281 -0.03499519 -0.9975218 0.0561949 -0.04233771 -0.9960683 -0.05094581 -0.07247418 -0.9723693 -0.2124113 -0.09684741 -0.3704372 -0.8489751 -0.3768522 -0.3576429 -0.8483526 -0.390371 -0.2778599 -0.85779 -0.4324237 -0.2604115 -0.8541218 -0.4501797 -0.1863285 -0.8529567 -0.4875928 -0.1657243 -0.8453004 -0.5079398 0.6184232 -0.3619928 -0.6975056 0.6102359 -0.3932408 -0.6877309 0.5800583 -0.4398459 -0.685615 0.5657906 -0.4512347 -0.690122 0.5499089 -0.4906123 -0.6759436 0.5105627 -0.5376715 -0.6709957 0.4980393 -0.5454233 -0.6741442 0.3704741 -0.6899373 -0.6218806 0.4099648 -0.6416618 -0.6482276 0.422204 -0.6361006 -0.6458481 0.4716262 -0.590971 -0.6544631 0.6925886 -0.4392326 -0.5721852 0.6777744 -0.421841 -0.6022226 0.6334037 -0.4888905 -0.5998216 0.6310374 -0.4984905 -0.5943897 0.5598108 -0.5831165 -0.5887166 0.5537502 -0.5976064 -0.5798512 0.464622 -0.6780558 -0.5695322 0.4536246 -0.6952461 -0.5575461 0.3388711 -0.7703931 -0.5400564 0.2624555 -0.7941531 -0.5481222 0.1825235 -0.8282311 -0.5298288 0.1606342 -0.8313543 -0.5320213 0.09334647 -0.8643202 -0.4942034 0.04220145 -0.875731 -0.4809515 -0.3378221 -0.8747364 -0.3474372 -0.3177279 -0.877879 -0.3582978 -0.2304409 -0.8917532 -0.3894524 -0.2013513 -0.892208 -0.4042553 -0.1251699 -0.8943477 -0.4295051 -0.0889135 -0.8900762 -0.4470556 0.01621156 -0.8780637 -0.4782693 0.01161307 -0.89339 -0.4491321 0.1580832 -0.861785 -0.4820131 0.7106657 -0.441172 -0.548016 0.7232894 -0.4090223 -0.5563752 0.6613155 -0.5049293 -0.5547146 0.6589412 -0.5127975 -0.5503047 0.5852742 -0.599606 -0.5458267 0.5796529 -0.6113783 -0.53872 0.4868418 -0.6941223 -0.5302634 0.477019 -0.7079784 -0.5207874 0.3572949 -0.7850677 -0.5059735 0.3431769 -0.7984622 -0.4946593 0.1919345 -0.8612602 -0.4705231 -0.353756 -0.8634748 -0.3595387 -0.3313418 -0.866164 -0.3741292 -0.2538738 -0.8772559 -0.4073944 -0.222074 -0.8765125 -0.4270939 -0.1556302 -0.8772894 -0.4540293 -0.1162625 -0.8709642 -0.4773935 -0.01732027 -0.8576917 -0.5138726 -0.02108836 -0.8738316 -0.4857713 0.07356119 -0.8541066 -0.5148695 0.09608387 -0.8429346 -0.5293669 0.1604456 -0.8214117 -0.5473026 0.1824665 -0.8071566 -0.5614307 0.2384101 -0.7820822 -0.5757675 0.258879 -0.7655454 -0.5890007 -0.4610133 -0.8249568 -0.3269757 -0.4507408 -0.8312198 -0.3254326 -0.3612578 -0.8554753 -0.3710188 -0.3489929 -0.8553596 -0.382837 -0.2649319 -0.8661679 -0.4237505 -0.2478622 -0.8633273 -0.4395797 -0.1702629 -0.8630349 -0.4755853 -0.1494027 -0.8563242 -0.4943559 -0.5449345 -0.7946824 -0.2674441 -0.8487899 -0.515869 -0.1159096 -0.8639466 -0.4936615 -0.09947174 -0.7877177 -0.5982739 -0.1468648 -0.8020617 -0.5822095 -0.1331509 -0.7159529 -0.673823 -0.1826856 -0.7270471 -0.6644031 -0.1731218 -0.6355113 -0.7393685 -0.2223954 -0.8613237 -0.4940083 -0.1186479 -0.8761073 -0.4707853 -0.1039099 -0.7993853 -0.5820191 -0.1491207 -0.813919 -0.5646882 -0.1366131 -0.7249416 -0.6638178 -0.1838631 0.745441 -0.4251734 -0.5133666 0.7408773 -0.4379427 -0.509222 0.686271 -0.5206629 -0.5078804 0.6841537 -0.5265711 -0.5046353 0.6074259 -0.6161768 -0.5013582 0.6026884 -0.6249366 -0.4962066 0.5054136 -0.7105038 -0.4896341 0.4974189 -0.7207115 -0.4828553 0.3718084 -0.8000776 -0.4707806 0.3606054 -0.8098054 -0.4627947 0.2023966 -0.8737161 -0.4423301 0.1892585 -0.8808801 -0.4338566 -0.007586896 -0.9161683 -0.4007221 -0.01973402 -0.9192951 -0.3930739 -0.246201 -0.9059632 -0.3444063 -0.2536277 -0.9057813 -0.3394605 -0.4914774 -0.8264169 -0.2747459 -0.4868674 -0.8240902 -0.2895438 -0.5460965 -0.796479 -0.259615 -0.5452439 -0.7960383 -0.2627397 -0.5462147 -0.7955783 -0.2621164 -0.6466794 -0.7311793 -0.2172156 -0.6456624 -0.7308849 -0.2211953 -0.6976829 -0.68501 -0.2097618 -0.6982181 -0.6850735 -0.2077638 -0.8628295 -0.4869272 -0.1357467 -0.858928 -0.4882304 -0.154511 -0.9863498 -0.1540201 -0.05824029 -0.9873251 -0.1525705 -0.04372012 -0.9868758 -0.1551366 -0.0448203 -0.9767484 -0.2096306 -0.04491996 -0.9980207 -0.05829519 -0.02359062 -0.9972006 -0.0602293 -0.04431128 -0.9944279 -0.08998596 -0.05491626 -0.9941667 -0.0903958 -0.05883365 -0.9941132 -0.09084886 -0.05903762 -0.9934088 -0.09174835 -0.06871062 -0.9885354 -0.126398 -0.08259195 -0.9872348 -0.127173 -0.09588831 -0.9416872 -0.3090502 -0.1330913 -0.9447072 0.3279089 -0.002023816 -0.9389499 0.3440533 7.68408e-4 -0.9691913 0.2462458 -0.005602955 -0.971972 0.2349662 -0.007841706 -0.986985 0.1606425 -0.007406175 -0.9973221 0.07071322 -0.01866346 -0.999368 -0.02112299 -0.02859222 -0.9932734 0.1155635 -0.007294774 -0.9931988 0.1146975 -0.02001881 -0.9697343 0.2441314 -0.003934562 -0.9697642 0.243879 -0.008962929 -0.9245439 0.3810758 -5.22361e-5 -0.9245479 0.3810663 0 -0.9009941 -0.4282377 -0.06944179 -0.8991755 -0.4282994 -0.08968251 -0.9132036 -0.4011096 -0.07190531 -0.9109948 -0.4019119 -0.0924952 -0.9241714 -0.3741922 -0.07672947 -0.9222775 -0.375293 -0.09251827 -0.8730546 -0.4717696 -0.1233249 -0.854492 -0.5004681 -0.1391947 -0.8113777 -0.5649666 -0.1499311 -0.7341096 -0.6528444 -0.1867544 -0.7368087 -0.6531051 -0.1748331 -0.6400719 -0.7356224 -0.2217378 -0.6408684 -0.7359969 -0.2181658 -0.5475689 -0.7935186 -0.2655121 -0.9376508 -0.3202944 -0.1349914 -0.9385472 -0.3200371 -0.1292498 -0.950872 -0.2873713 -0.115153 -0.9527891 -0.2861508 -0.101543 -0.9527783 -0.2861762 -0.1015706 -0.9552638 -0.2841438 -0.08205801 -0.9487186 -0.302289 -0.09249097 -0.9495876 -0.3016296 -0.08545845 -0.9577217 -0.2778709 -0.07454431 -0.9595276 -0.2762874 -0.05451816 -0.9491724 -0.306807 -0.07029557 -0.9508005 -0.305786 -0.04973399 -0.8361545 -0.5363395 -0.1148294 -0.8509053 -0.5162131 -0.09738767 -0.7763155 -0.6131464 -0.1462386 -0.7898233 -0.5989958 -0.1318455 -0.7081124 -0.6820734 -0.1826273 -0.7174804 -0.674633 -0.1734711 -0.6322576 -0.7416336 -0.2241205 -0.6357902 -0.7395766 -0.220901 -0.5498291 -0.7904331 -0.2700063 -0.5459932 -0.7919557 -0.2733088 -0.4501139 -0.8315018 -0.3255801 -0.4530363 -0.8352715 -0.3115762 -0.4408078 -0.8386244 -0.3199963 -0.4446862 -0.8423871 -0.3043653 -0.4344376 -0.8455588 -0.3103131 -0.4377897 -0.8480778 -0.2985032 -0.324184 -0.8847389 -0.334876 -0.2452025 -0.8967508 -0.3683938 -0.2091491 -0.9037932 -0.3733827 -0.01382017 -0.906512 -0.421954 -0.00935167 -0.9067127 -0.4216452 0.175117 -0.8713498 -0.4583488 0.1775993 -0.8489167 -0.4977943 0.3227265 -0.787207 -0.5255025 0.3165819 -0.7515091 -0.5788004 -0.01512235 -0.8071893 -0.5900989 0.009271204 -0.789784 -0.6133151 0.06126242 -0.7695378 -0.6356561 0.08490306 -0.7481799 -0.6580413 0.1301713 -0.7251257 -0.6762013 0.1515815 -0.7013194 -0.6965445 0.1913943 -0.6762852 -0.7113414 0.2101145 -0.6510013 -0.7294171 0.2451664 -0.624731 -0.7413533 0.2611131 -0.598751 -0.7571771 0.2919964 -0.5717976 -0.7666718 0.3046482 -0.5469256 -0.7797833 0.3327797 -0.5188088 -0.7874613 0.3421511 -0.4964332 -0.7978013 0.3685153 -0.4665865 -0.8040483 0.3751043 -0.4471938 -0.811982 0.4000842 -0.4153687 -0.8169464 0.4044533 -0.3990879 -0.8228892 0.4282613 -0.3651083 -0.8266125 0.4307073 -0.3530125 -0.8305862 0.4539932 -0.3158075 -0.8331601 0.4550103 -0.3086183 -0.8352967 0.4781341 -0.2672034 -0.8366542 0.4783201 -0.2649065 -0.837278 0.5012165 -0.2186959 -0.8372302 0.5011572 -0.2209522 -0.836673 0.5235288 -0.1695776 -0.8349618 0.5237339 -0.1764688 -0.8334036 0.5453533 -0.1191293 -0.8296976 0.5463359 -0.1304101 -0.8273513 0.5667066 -0.06654971 -0.8212276 0.5688567 -0.08136802 -0.8184017 0.5871614 -0.01099872 -0.8093953 0.5907207 -0.02829772 -0.8063797 0.6059583 0.04823589 -0.7940327 0.6112679 0.02859222 -0.7909073 0.6225076 0.111752 -0.7745941 0.6298717 0.09009343 -0.7714563 0.635878 0.1799584 -0.750516 0.6453166 0.157322 -0.7475402 0.6446374 0.2529794 -0.7214182 0.6558772 0.2306672 -0.7187612 0.6469775 0.3303856 -0.6872158 0.6600476 0.3087619 -0.6848382 0.6414585 0.4114487 -0.6474883 0.656195 0.3910263 -0.6453732 0.6265299 0.4948402 -0.6021575 0.6421498 0.4767301 -0.6003101 0.6006215 0.5785261 -0.5518707 0.6158429 0.5638585 -0.5502738 0.5625963 0.6599206 -0.4979863 0.5769222 0.6485522 -0.4965288 0.5123733 0.7365759 -0.4415085 0.5251933 0.7283152 -0.4401467 0.4504618 0.8060775 -0.3838272 0.4605281 0.8009366 -0.3826414 0.3779365 0.8661691 -0.3269788 0.3894283 0.8616641 -0.3253931 0.2966158 0.9156901 -0.2711656 0.3003078 0.9142721 -0.2718856 0.2080465 0.9523675 -0.2229642 0.2042265 0.9533399 -0.2223386 0.1147456 0.9771023 -0.1791776 0.1032143 0.9786595 -0.1776865 0.0185424 0.9899007 -0.1405447 -5.81468e-4 0.9903265 -0.1387557 -0.07889384 0.9910678 -0.1075196 -0.1033068 0.9889672 -0.1061688 -0.1761307 0.9811263 -0.07980829 -0.2035672 0.975841 -0.07933974 -0.2718698 0.9606458 -0.05697888 -0.3010207 0.9518728 -0.05766147 -0.3650321 0.9301868 -0.03878295 -0.3948396 0.9178463 -0.04074102 -0.4546531 0.8903189 -0.02495861 -0.4826861 0.8753435 -0.02807134 -0.5398486 0.8416337 -0.01470822 -0.5643455 0.8253282 -0.01864534 -0.6197919 0.784732 -0.007339775 -0.6401935 0.7681235 -0.01177084 -0.6937314 0.7202296 -0.002493023 -0.7099702 0.7041961 -0.007095515 -0.7609877 0.6487663 9.18715e-5 -0.7721728 0.6354003 -0.003987491 -0.8209179 0.5710455 0.001084923 -0.8269082 0.5623342 -0.001719772 -0.8729354 0.4878349 0.001010835 -0.8746009 0.4848437 0 -0.9165499 0.3999204 0 -0.9152948 0.4027834 0.001019358 -0.9513387 0.3081399 -0.002135992 -0.9446874 0.3279668 0.00193417 -0.9769449 0.2134202 -0.005527019 -0.9691573 0.2464339 0.002158284 -0.9931236 0.1166107 -0.01037925 -0.9869614 0.1609528 0.001215875 -0.9996784 0.01873582 -0.01709222 -0.9974453 0.07141685 -0.001641988 -0.9965044 -0.07933819 -0.02616018 -0.9997771 -0.02002716 -0.00669068 -0.9835596 -0.1765661 -0.03788125 0.008161306 -0.8199102 -0.5724341 0.03226941 -0.8043016 -0.5933445 0.08731621 -0.7838109 -0.6148303 0.1108053 -0.764437 -0.6351049 0.1584246 -0.7410939 -0.6524427 0.1801228 -0.7189882 -0.6712763 0.2220096 -0.6935304 -0.6853666 0.2411076 -0.6698865 -0.7022245 0.2784169 -0.6427482 -0.7136938 0.2944493 -0.6188107 -0.7282671 0.3272668 -0.590905 -0.737379 0.3401157 -0.5678611 -0.74957 0.3696668 -0.5389977 -0.7568541 0.3794533 -0.5178204 -0.7667316 0.4070023 -0.487242 -0.7726219 0.4139897 -0.4687687 -0.7803003 0.4402312 -0.4358841 -0.7849852 0.4448047 -0.4207799 -0.7906283 0.4695631 -0.3858714 -0.7941119 0.4721971 -0.3746504 -0.7979142 0.4959793 -0.3369852 -0.8002785 0.4971739 -0.330039 -0.8024291 0.520499 -0.2884524 -0.8036642 0.5207637 -0.2860785 -0.804341 0.5437944 -0.2395819 -0.8042936 0.5436689 -0.2419236 -0.8036772 0.5660349 -0.1902729 -0.8021227 0.566042 -0.1970029 -0.8004913 0.5874571 -0.1395567 -0.7971312 0.5880726 -0.1502386 -0.794732 0.6081073 -0.08616667 -0.7891646 0.6097313 -0.100304 -0.7862359 0.6276561 -0.02914053 -0.7779453 0.6306431 -0.04621368 -0.7746958 0.6452651 0.03117036 -0.7633228 0.6499024 0.01174157 -0.7599271 0.6602517 0.09545481 -0.7449538 0.6667391 0.0742855 -0.7415799 0.6716212 0.1647453 -0.7223463 0.6800963 0.1425325 -0.7191338 0.6780084 0.2394353 -0.6949644 0.6884706 0.216987 -0.692044 0.6779037 0.3180425 -0.6627938 0.6901941 0.296185 -0.6602323 0.6697659 0.3999621 -0.6256549 0.6835303 0.3795497 -0.6234809 0.6517899 0.4846319 -0.5833541 0.6664901 0.4664866 -0.5815335 0.6223078 0.5704253 -0.5360485 0.637152 0.5552433 -0.5345486 0.5809116 0.6535912 -0.4851396 0.5949468 0.6417894 -0.4838852 0.5273567 0.7317509 -0.4317821 0.5395801 0.7234297 -0.4307006 0.4615351 0.8030081 -0.3770458 0.4709819 0.7979328 -0.3761373 0.3897234 0.8613785 -0.325796 -0.8585212 0.5127782 0 -0.6448065 0.7641109 -0.01894849 -0.5098832 0.8597093 -0.03031498 -0.5352525 0.8441113 -0.03132098 -0.588297 0.8084165 -0.01921993 -0.6593595 0.7513976 -0.02543586 -0.8761483 0.4817508 -0.0167424 -0.8326569 0.5537892 3.14805e-4 -0.7659074 0.6429169 -0.006622612 -0.7821452 0.6228618 -0.01709014 -0.7251026 0.6886218 -0.005144596 -0.330573 0.9416356 -0.06359052 -0.2602214 0.9618681 -0.08423101 -0.2591558 0.9613943 -0.09251666 0.1984114 0.9550445 -0.2202793 0.1911171 0.9568136 -0.219048 0.08973646 0.979412 -0.1808302 -0.1283016 0.9852569 -0.1131712 -0.04209059 0.9889709 -0.1420032 -0.04103744 0.9878438 -0.1499357 -0.3595909 0.9310154 -0.06248873 -0.3571124 0.9303511 -0.08317154 -0.3351108 0.9387549 -0.08024924 -0.3340869 0.9385026 -0.08717215 -0.3506833 0.9323047 -0.08848208 -0.3485664 0.931766 -0.1015568 -0.3486086 0.9317501 -0.101557 -0.3454389 0.9305358 -0.121553 -0.3139362 0.9416386 -0.1214942 -0.3102486 0.9386417 -0.1506572 -0.2159633 0.9646796 -0.1508416 -0.02060931 0.9892573 -0.1447253 0.07469677 0.9810856 -0.1785818 0.07567954 0.9794881 -0.1867502 0.1233284 0.9699431 -0.2097633 0.1227052 0.9709546 -0.2054039 0.3606973 0.8916661 -0.2735493 0.3603788 0.892953 -0.2697447 0.5728865 0.7559795 -0.3166959 0.5737128 0.7637565 -0.2958544 0.7479685 0.5837512 -0.3158763 0.717854 0.6295107 -0.2973247 0.837636 0.4528977 -0.3053681 0.8454285 0.4616976 -0.2684885 0.9069368 0.3266475 -0.266021 0.9177144 0.3333854 -0.2159968 0.9360734 0.2775773 -0.2161425 -0.2317447 0.968945 -0.08625537 -0.1543124 0.9818176 -0.1105535 -0.1525856 0.9805642 -0.1233353 -0.1184654 0.9831541 -0.1391912 -0.1182295 0.9829796 -0.140616 0.1137959 0.9720411 -0.2053939 0.115056 0.9701972 -0.2132593 0.3571853 0.8942329 -0.2697523 0.3569886 0.8951289 -0.2670271 0.5524856 0.7786965 -0.2973072 0.5536807 0.7840844 -0.2804453 0.6930744 0.6599928 -0.289927 0.6973735 0.6666111 -0.2632488 0.7346779 0.6251585 -0.2634871 -0.8611815 0.5082976 0 -0.8585364 0.5127485 0.002105295 -0.7751606 0.6317263 -0.006920456 -0.7660445 0.6427845 -0.002008616 -0.6612323 0.7498995 -0.02055937 -0.6450541 0.7639948 -0.01473575 -0.5166494 0.8550837 -0.04365319 -0.5338083 0.8442628 -0.04763525 -0.4513311 0.8909325 -0.05039238 -0.4519016 0.8909379 -0.04488527 -0.4240316 0.904533 -0.04491502 0.5684015 0.7178928 -0.4019325 0.5790917 0.7096136 -0.4013743 0.4911953 0.7948659 -0.3562521 0.4993504 0.789924 -0.3559063 0.5074265 0.7878783 -0.3489502 0.4999258 0.7925531 -0.3491903 0.5906047 0.7058872 -0.3910363 0.5807204 0.7137941 -0.3914868 0.6490826 0.6305317 -0.4255841 0.6444022 0.6222568 -0.4444575 0.6322551 0.634003 -0.445302 0.7714853 0.2600621 -0.5806705 0.7620992 0.2805882 -0.5835025 0.7763315 0.1779791 -0.6046759 0.7687361 0.1987028 -0.6079162 0.7734833 0.1224343 -0.6218791 0.758937 0.06177878 -0.648227 0.7015849 -0.1775038 -0.690124 0.7619151 0.04867017 -0.6458457 0.7558771 -0.01798677 -0.6544663 0.7355946 -0.06656759 -0.6741435 0.7369998 -0.08123928 -0.6709929 0.7233374 -0.1410216 -0.6759408 0.7011513 -0.1957508 -0.6856154 0.6823027 -0.2479698 -0.6877312 0.6623725 -0.2734007 -0.6975061 0.6590771 -0.2969975 -0.6909486 0.6352216 -0.3450874 -0.6909474 0.5679271 0.7510333 -0.3367611 0.5670756 0.7456576 -0.349886 0.5602809 0.7494937 -0.3526253 0.4643174 -0.8551939 -0.2303321 0.6430301 -0.7329254 -0.2221099 0.6382375 -0.7241803 -0.2611817 0.7573752 -0.600152 -0.2572946 0.7475694 -0.5896482 -0.3057042 0.8242488 -0.4773641 -0.3045282 0.8087134 -0.467278 -0.357259 0.860958 -0.3620913 -0.3572695 0.8405374 -0.3546186 -0.4095639 0.8794734 -0.242623 -0.409464 0.8564357 -0.2392699 -0.457458 0.8836652 -0.1093257 -0.4551746 0.8610298 -0.1106999 -0.4963603 0.8716164 0.03905057 -0.4886307 0.8524526 0.03370958 -0.5217167 0.8387645 0.2072559 -0.5035068 0.8253576 0.1999734 -0.5280111 0.7769895 0.3910614 -0.4933137 0.7591357 0.3750687 -0.5320118 0.7446635 0.4485854 -0.4942139 0.7331618 0.4372183 -0.5208781 0.7389902 -0.3190112 -0.5934015 0.7428991 -0.2922132 -0.6022562 0.7750526 -0.2002457 -0.599329 0.7763752 -0.2092307 -0.5945284 0.8052936 -0.07955914 -0.5875141 0.8089689 -0.09275281 -0.5804879 0.8214631 0.05774813 -0.5673304 0.7691818 -0.3045616 -0.5617844 0.7632611 -0.3284215 -0.5563918 0.8042993 -0.2139913 -0.5543558 0.8050079 -0.2215548 -0.5503416 0.8334153 -0.09182631 -0.5449651 0.8157197 0.2159371 -0.5366309 0.8281029 0.04209798 -0.5589933 0.8475068 0.04721564 -0.5286805 0.8359171 -0.103074 -0.5390904 0.8595291 -0.1019368 -0.5008181 0.8316643 -0.2317312 -0.5046138 0.8564618 -0.2355958 -0.4593123 0.8177736 -0.3458206 -0.4600592 0.8405965 -0.3542873 -0.4097293 0.7908177 -0.4546684 -0.4097365 0.8090574 -0.4663657 -0.357672 0.7393408 -0.5701518 -0.3581929 0.7516207 -0.5828896 -0.3087168 0.6474988 -0.6958216 -0.3107695 0.6539593 -0.7072622 -0.2685471 0.5014325 -0.8209285 -0.2732066 0.5037267 -0.8290824 -0.2426562 0.2890593 -0.9239576 -0.2504939 -0.8973392 -0.4084671 -0.1671443 -0.8139029 -0.5475183 -0.1943863 -0.8380145 -0.5107139 -0.1921019 -0.7518568 -0.6210746 -0.2213096 -0.6906357 -0.6843138 -0.2339597 -0.6334701 -0.7307429 -0.2544219 -0.4951483 -0.827768 -0.263872 -0.4772571 -0.8366831 -0.268677 -0.3113836 -0.9082149 -0.2796174 -0.3318495 -0.9029266 -0.2731292 -0.1079152 -0.9559816 -0.2728617 -0.150388 -0.9531232 -0.2625642 0.0966838 -0.9607748 -0.2599308 0.009576499 -0.9710007 -0.2388848 0.2892078 -0.9254856 -0.2446129 0.2364609 -0.9441112 -0.2296528 0.4667884 -0.8632277 -0.1922155 0.6157639 -0.7598846 -0.2083517 0.6153793 -0.7592541 -0.2117581 0.7566018 -0.6207649 -0.2054383 0.7491044 -0.6125403 -0.2522635 0.8360149 -0.4883091 -0.2502667 0.8231925 -0.4798815 -0.3034272 0.879077 -0.3675947 -0.303476 0.8611668 -0.3611571 -0.3577113 0.9005444 -0.2463493 -0.3582345 0.8794271 -0.2435514 -0.4090119 0.9058502 -0.1132501 -0.4081788 0.8843626 -0.1148962 -0.4524397 0.8937422 0.03402024 -0.4472892 0.8749645 0.02842605 -0.4833518 0.8599106 0.2010411 -0.4691869 0.8463264 0.193304 -0.4963518 0.7962301 0.3843408 -0.4672256 0.7887105 0.3771715 -0.4854661 0.7210601 0.4548453 -0.5226741 0.7577756 0.346571 -0.5528696 0.7698783 0.3557467 -0.5298412 0.7911157 0.2714887 -0.5481149 0.7898998 0.202591 -0.578805 0.7956961 0.1863374 -0.5763213 0.8019486 0.0528441 -0.5950514 0.7935222 0.07007187 -0.6044937 0.7801246 -0.08033424 -0.620445 0.7751461 -0.06559032 -0.628368 0.7457195 -0.1951312 -0.637045 0.7436498 -0.1849573 -0.6424763 0.7047027 -0.2932981 -0.6460421 0.7044085 -0.2895177 -0.648065 0.6583302 -0.3826975 -0.6481851 0.6581328 -0.3866091 -0.6460608 0.6028057 -0.4722676 -0.6431086 0.6006486 -0.4834396 -0.6367947 0.5314605 -0.5663301 -0.6299365 0.5253385 -0.5833156 -0.6194857 0.4393588 -0.6618714 -0.6073633 0.4277336 -0.6821886 -0.5930116 0.3330321 -0.7462835 -0.5763251 0.3264641 -0.7198554 -0.6125597 0.308263 -0.7377674 -0.6005607 0.5920884 0.7102869 -0.3806887 0.5576136 0.7371435 -0.3816892 0.5080534 0.7916517 -0.339366 0.4104061 0.860737 -0.3011623 0.4104152 0.8586488 -0.3070531 0.4124944 0.857006 -0.3088514 0.4014944 0.8620439 -0.3093264 0.401211 0.8596743 -0.316212 0.4904982 0.7923632 -0.362729 0.481822 0.7974497 -0.3632103 0.5666301 0.7139182 -0.4114013 0.5553281 0.7223546 -0.4120857 0.6287676 0.6284001 -0.4580008 0.6158756 0.6403539 -0.4589601 0.9711019 -0.1865099 -0.148913 0.9857726 -0.02939862 -0.1654941 0.9740268 -0.03096604 -0.2243056 0.9679677 0.1018376 -0.2294945 0.9541407 0.09634029 -0.2834326 0.9263128 0.245248 -0.2860037 0.9141556 0.2366207 -0.3291357 0.8548739 0.4044334 -0.3249992 0.8467991 0.3948004 -0.3564605 0.7375612 0.5843826 -0.3383791 0.752772 0.5561042 -0.3522535 0.5764908 0.7533056 -0.3165268 0.5756316 0.7452634 -0.3364979 0.3605911 0.8917105 -0.2735444 0.3608543 0.8903427 -0.2776221 0.3616307 0.8897893 -0.2783852 0.3058121 0.9033122 -0.3008423 0.3039397 0.9158175 -0.2624866 0.302998 0.9161794 -0.2623119 0.712108 0.446457 -0.5418288 0.6990489 0.4645534 -0.5436183 0.7343656 0.3569889 -0.5772922 0.7224065 0.3770927 -0.5795947 0.7458921 0.2714853 -0.6082276 0.7354984 0.2927479 -0.6110163 0.7486931 0.1902993 -0.6350157 0.740122 0.2119044 -0.6382131 0.74447 0.1139075 -0.6578675 0.7377902 0.1350451 -0.6613838 0.734782 0.04379481 -0.676888 0.7299286 0.06374651 -0.6805443 0.7210831 -0.02058547 -0.6925427 0.7178825 -0.002447903 -0.69616 0.704415 -0.08034932 -0.7052259 0.7026195 -0.0645675 -0.7086303 0.685528 -0.1362087 -0.7151913 0.6848286 -0.1232552 -0.7182047 0.6653498 -0.1875997 -0.722576 0.6653839 -0.1778967 -0.7249945 0.64433 -0.2354332 -0.7276058 0.6446992 -0.2293593 -0.7292169 0.6225191 -0.2809808 -0.7304244 0.6227744 -0.2788767 -0.731013 0.5997506 -0.3253505 -0.7310584 0.5993843 -0.3274559 -0.7304186 0.5756652 -0.3694922 -0.7294417 0.5741902 -0.3756037 -0.7274802 0.5494813 -0.41425 -0.7255806 0.546481 -0.4240766 -0.7221618 0.5202193 -0.4604141 -0.7192988 0.5152499 -0.4735603 -0.7143237 0.4868816 -0.5082161 -0.7103962 0.4795446 -0.5241866 -0.7037509 0.4493595 -0.5566638 -0.6987143 0.4393213 -0.5748374 -0.6903323 0.4066143 -0.6056155 -0.6840284 0.3936818 -0.6252753 -0.673829 0.3571404 -0.6550251 -0.6658776 0.3412001 -0.6753022 -0.6538726 0.2995669 -0.7041637 -0.6437493 0.2807776 -0.7240287 -0.6300368 0.234057 -0.7509149 -0.6175307 0.212861 -0.7693224 -0.6023566 0.1598739 -0.7937049 -0.5869183 0.1370249 -0.8096657 -0.5706713 0.07596796 -0.830743 -0.5514482 0.05256539 -0.8433768 -0.5347453 -0.004322469 -0.8567392 -0.5157319 -0.917298 0.3982016 0 -0.9271327 0.3747273 0.002062737 -0.9271538 0.3746761 -0.001927733 -0.9698718 0.2433937 -0.01040446 -0.969867 0.2434638 -0.009132742 -0.9958789 0.08616483 -0.02829921 -0.9958646 0.08611619 -0.02894246 -0.9991648 0.02940636 -0.02837258 -0.9994333 0.0305972 -0.01403808 -0.992546 -0.1147123 -0.04115265 -0.9934579 -0.1132674 -0.01456159 -0.9771479 -0.2092217 -0.03752601 -0.9700163 -0.2395873 -0.0408225 -0.9393075 -0.3363344 -0.06768101 -0.9406844 -0.3360112 -0.04700446 -0.8871268 -0.4530293 -0.08815085 0.9285188 -0.3438963 -0.1399579 0.9684686 -0.2036294 -0.1435396 0.9572052 -0.2025902 -0.2066773 0.975065 -0.06814652 -0.2111971 0.9603952 -0.07035416 -0.2696134 0.9594876 0.06913709 -0.2731366 0.9442256 0.0631752 -0.3231827 0.9201653 0.22116 -0.3230856 0.9073787 0.2123076 -0.3627526 0.8501623 0.3894691 -0.3543134 0.84199 0.3800045 -0.3829487 0.7370738 0.5723825 -0.3593057 0.7331215 0.5638103 -0.3803301 0.7391983 0.550206 -0.3884061 0.7188826 0.5696597 -0.3983663 0.7157735 0.5637657 -0.4121125 0.7061324 0.5723018 -0.4169507 0.7032026 0.5671632 -0.4287565 0.6916044 0.5767191 -0.4348316 0.6817616 0.5610452 -0.4694992 0.7012978 0.5378962 -0.4678132 0.6955827 0.530502 -0.4844919 0.6830102 0.5454618 -0.4857659 0.6771153 0.5383033 -0.5017416 0.6636748 0.5535861 -0.5030689 -0.8574739 0.5145194 -0.002894759 -0.8627684 0.5055994 0 -0.8627759 0.5055863 6.31896e-4 -0.8611791 0.5083016 0 -0.9113356 0.4116643 0 -0.9127056 0.4086176 6.75405e-4 -0.913749 0.406279 0 -0.9137462 0.4062856 0 -0.8763098 0.4817481 0 -0.8746 0.4848445 9.39063e-4 -0.8326442 0.5538063 -0.00157243 -0.8269196 0.5623197 8.2626e-4 -0.7824527 0.6226982 -0.003866732 -0.7722063 0.6353716 -5.68306e-4 -0.7250468 0.6886609 -0.007299542 -0.7100278 0.7041643 -0.003647267 -0.6599349 0.7512206 -0.01239168 -0.6402676 0.7681006 -0.008885145 -0.5882813 0.8084223 -0.01946002 -0.5644118 0.8253281 -0.01651805 -0.5099646 0.8597036 -0.02908754 -0.4827272 0.8753529 -0.02705198 -0.4242498 0.9045658 -0.04210591 -0.3948158 0.9178364 -0.04119402 -0.3309533 0.9417818 -0.05930513 -0.3009172 0.951788 -0.05957102 -0.232258 0.9692875 -0.08085936 -0.2034086 0.9756383 -0.08218818 -0.1288717 0.9858359 -0.1073305 -0.10313 0.9886332 -0.1094008 -0.02109873 0.9900099 -0.1394112 -4.44577e-4 0.9899026 -0.1417495 0.0894649 0.9800822 -0.1772996 0.1032606 0.9783633 -0.179284 0.1983965 0.9551221 -0.2199562 0.2042254 0.9536622 -0.2209539 0.303048 0.9149098 -0.2666498 0.30052 0.9158871 -0.266155 0.4018632 0.8591036 -0.316934 0.390437 0.8640074 -0.3178839 0.4810068 0.7950683 -0.3694578 0.4719107 0.8001961 -0.370117 0.5534254 0.7185724 -0.4211581 0.5416178 0.7270195 -0.4220106 0.6122369 0.6349905 -0.471119 0.5987346 0.6469455 -0.472206 0.6575911 0.5466474 -0.5184118 0.6434084 0.5619803 -0.5198112 0.6898556 0.4563336 -0.5620133 0.6759428 0.4745596 -0.5638214 0.7095986 0.3681005 -0.6008094 0.6967098 0.3884916 -0.6030504 0.7187801 0.283642 -0.634746 0.7074244 0.3053387 -0.6374318 0.7193995 0.2034289 -0.6641394 0.7098721 0.22558 -0.6672295 0.7131764 0.1279767 -0.6892035 0.7055948 0.1497647 -0.6926085 0.7017078 0.05875861 -0.7100378 0.6960382 0.07943081 -0.7135976 0.6864799 -0.004741549 -0.7271333 0.682577 0.01414102 -0.7306768 0.6685425 -0.06363534 -0.7409464 0.6661605 -0.04712527 -0.7443181 0.6486654 -0.1186535 -0.7517678 0.6475172 -0.1050434 -0.7547765 0.6277476 -0.1693477 -0.7597725 0.6274753 -0.1591187 -0.7622046 0.6062203 -0.2166799 -0.7652103 0.6064163 -0.2102632 -0.7668433 0.5841287 -0.2619447 -0.768231 0.5843198 -0.2597195 -0.7688409 0.5612802 -0.3062356 -0.7688852 0.5609542 -0.3084813 -0.768225 0.5374157 -0.3503062 -0.7671179 0.536065 -0.3568595 -0.7650397 0.5118184 -0.3950202 -0.7628899 0.5089668 -0.4055775 -0.7592496 0.4834547 -0.4411891 -0.756058 0.4786373 -0.4553441 -0.7507117 0.4513365 -0.4890981 -0.7463769 0.4441168 -0.5063593 -0.7391621 0.4152544 -0.5378515 -0.7336755 0.4052696 -0.5575537 -0.7244933 0.374176 -0.5873435 -0.717649 0.3611744 -0.6087267 -0.7064028 0.3265405 -0.6375138 -0.6978163 0.3104375 -0.6596222 -0.6844905 0.2710145 -0.6875823 -0.6736332 0.2519454 -0.7093346 -0.6583068 0.2076986 -0.73545 -0.6449609 0.1861163 -0.7557243 -0.6278867 0.1358758 -0.7795167 -0.6114667 0.1125655 -0.7971831 -0.5931511 0.05458331 -0.8179061 -0.5727568 0.03068399 -0.8320098 -0.5539117 -0.05820202 -0.852302 -0.5198019 -0.05538707 -0.8359563 -0.5459939 -0.07864034 -0.8471193 -0.5255517 -0.07519346 -0.8232709 -0.5626464 -0.09812772 -0.835595 -0.540511 -0.6410009 0.7675402 4.93003e-5 0.318971 0.9477645 3.64422e-5 0.9963284 0.08561468 -3.50042e-6 -0.1203318 -0.9927337 -4.7645e-4 -0.1974078 -0.980319 -0.002191841 0.4588832 -0.8884966 -3.65255e-4 0.3175416 -0.9482429 -0.001684725 0.3191934 -0.9476883 -0.001641809 0.1263834 -0.9919816 3.13052e-6 0.04041045 -0.9991832 -1.84025e-6 0.8417727 -0.5398321 -1.77139e-4 0.7336894 -0.6794813 -0.002254545 0.7502713 -0.6611281 -0.001659929 0.6079241 -0.7939952 1.85324e-5 0.5158336 -0.8566889 -1.09969e-5 0.9803214 -0.1974089 4.22884e-5 0.9997124 -0.0232917 -0.00570935 0.9926298 -0.1211349 -0.003565609 0.975705 -0.2190828 -0.001564979 0.9277849 -0.3731158 -2.70103e-6 0.889065 -0.457781 6.22907e-7 0.6611212 0.7502791 -6.70023e-5 0.5773859 0.8164623 -0.003881275 0.7716425 0.6360564 1.83721e-4 0.9476809 0.319219 -3.94935e-4 0.9082422 0.4184272 -0.00386554 0.9783336 0.2070346 -3.38496e-4 -0.3192004 0.9476873 -1.14526e-4 -0.5330281 0.8460474 -0.009228408 -0.4174782 0.9086759 -0.004472613 -0.2705435 0.9627065 -0.00159955 -0.1484854 0.9889146 2.10739e-5 0.1974064 0.9803218 -6.21884e-5 -0.008805871 0.9999306 -0.007827877 0.1094691 0.9939815 -0.004156827 -0.9991688 -0.040766 4.08512e-6 -0.9993597 0.03578138 -2.69457e-4 -0.9801007 0.1984894 -0.002147555 -0.980316 0.1974238 -0.002116322 -0.9262317 0.3769547 -2.23083e-6 -0.7502786 0.6611218 5.80023e-6 -0.8749551 0.4841286 -0.008560597 -0.7926369 0.609683 -0.003674745 -0.921809 -0.3876439 -7.71881e-4 -0.9476834 -0.3192024 -0.002465605 -0.9665342 -0.2565339 -0.001435279 -0.9882993 -0.1525273 -1.53303e-5 -0.3530766 -0.9355944 0 -0.5509455 -0.8345413 0 -0.6611209 -0.7502755 -0.002424776 -0.7395271 -0.6731268 -2.55124e-4 -0.8444823 -0.5355834 6.24094e-5 -0.844948 -0.5348486 0 -0.8449503 -0.534845 0 -0.9590554 -0.2832189 0 -0.9999504 -0.009968757 0 -0.8033312 0.5955325 0 -0.8033322 0.5955312 0 -0.6430464 0.7658274 0 -0.5104647 0.8598987 0 -0.2781621 0.9605343 0 -0.2781626 0.960534 0 0.04359889 0.9990492 0 0.04359877 0.9990491 0 0.3607816 0.9326503 0 0.6400793 0.7683089 0 0.6400783 0.7683098 0 0.7836862 0.6211569 0 0.8739755 0.4859702 0 0.9747478 0.2233088 0 0.9747473 0.2233108 0 0.9949753 -0.10012 0 0.9949759 -0.1001157 0 0.9379491 -0.3467729 0 0.8693684 -0.4941647 0 0.8693663 -0.4941684 0 0.7308207 -0.6825696 0 0.7308218 -0.6825684 0 -0.1053555 -0.9944347 0 0.1707862 -0.9853082 0 -0.4652006 -0.8852053 0 -0.3384507 -0.9409842 0 -0.3384518 -0.9409838 0 -0.1053557 -0.9944346 0 -0.09068191 0.99588 0 0.4194127 0.9077957 0 0.4194268 0.9077892 0 0.7683101 -0.640078 0 0.768309 -0.6400793 0 0.7683109 -0.640077 0 0.7683106 -0.6400774 2.71601e-6 0.7683089 -0.6400794 3.51931e-6 0.76831 -0.640078 0 0.7683108 -0.640077 0 0.7683108 -0.6400771 0 -0.7683089 0.6400794 0 -0.7683086 0.6400798 0 -0.7683098 0.6400783 0 -0.7683096 0.6400784 -3.64055e-6 -0.7683106 0.6400773 0 -0.7683068 0.6400818 -2.716e-6 -0.7683089 0.6400792 0 0.1595366 0.1914978 0.9684404 0.1595364 0.191497 0.9684406 0.6400794 0.7683088 0 0.6400749 0.7683126 0 -0.6400797 -0.7683086 0 -0.6400781 -0.7683098 0 -0.1595369 -0.1914969 -0.9684405 -0.4428381 -0.5315518 -0.7220437 -0.4428389 -0.5315576 -0.722039 0.4428388 0.5315529 0.7220425 0.4428393 0.5315546 0.7220409 0.8853747 0.4648783 0 0.8853749 0.4648778 -2.25759e-6 0.8853745 0.4648786 2.57186e-6 0.8853753 0.4648771 -5.43201e-6 0.885375 0.4648776 -3.51931e-6 0.8853749 0.464878 -3.64056e-6 0.8853745 0.4648786 0 0.8853765 0.464875 0 0.8853753 0.4648773 0 -0.8853734 -0.4648807 0 -0.8853753 -0.4648771 0 -0.8853745 -0.4648787 -3.51932e-6 -0.8853749 -0.464878 0 -0.8853747 -0.4648784 -1.28594e-6 -0.885374 -0.4648796 0 -0.885375 -0.4648776 0 -0.8853749 -0.4648778 0 -0.1158689 0.2206752 0.9684404 -0.1158686 0.2206748 0.9684405 -0.4648799 0.8853738 0 0.4648776 -0.885375 0 0.1158689 -0.2206763 -0.9684402 0.1158682 -0.2206754 -0.9684405 0.3216266 -0.6125465 -0.722041 0.3216252 -0.6125473 -0.7220409 -0.3216255 0.612545 0.7220427 -0.3216261 0.6125465 0.7220412 -0.2973363 -0.9547728 0 -0.2973363 -0.9547728 -4.51518e-6 -0.2973358 -0.954773 0 -0.2973368 -0.9547727 -2.71602e-6 -0.2973361 -0.954773 0 -0.2973361 -0.9547729 0 -0.2973377 -0.9547725 0 -0.2973368 -0.9547728 0 0.2973365 0.9547728 0 0.2973365 0.9547728 0 0.2973356 0.9547731 0 0.2973362 0.9547728 0 0.2973357 0.954773 0 0.297336 0.954773 2.57188e-6 0.2973377 0.9547724 0 0.2973363 0.9547728 3.98253e-6 0.2973357 0.9547731 0 0.2379729 -0.07411009 0.9684403 0.2379729 -0.07410901 0.9684404 0.9547719 -0.2973394 0 0.9547742 -0.2973319 0 -0.9547721 0.2973389 0 -0.9547739 0.2973331 0 -0.2379729 0.07411044 -0.9684404 -0.2379727 0.07410937 -0.9684404 -0.6605592 0.2057161 -0.7220405 -0.6605598 0.2057103 -0.7220416 0.6605598 -0.2057098 0.7220417 0.6605602 -0.2057132 0.7220405 0.47956 -0.8775091 0 -0.9496881 0.3131974 0 -0.9592216 0.2812895 0.02775436 -0.9634406 0.2603877 0.06309133 -0.9735206 0.2285993 0 -0.9926347 0.1211466 0 -0.9926349 0.1211444 0 -0.9997779 -0.02107638 0 -0.9866478 -0.1628689 0 -0.9866478 -0.1628686 0 -0.9535117 -0.3013563 0 -0.9535104 -0.3013603 0 -0.90104 -0.433736 0 -0.8302958 -0.5573231 0 -0.7427192 -0.669603 0 -0.7427184 -0.669604 0 -0.6793577 -0.7338073 0 -0.6524149 -0.757108 0.03379774 -0.6387918 -0.7667672 0.06334924 -0.6268365 -0.7784172 0.03380566 -0.5990425 -0.8007172 0 -0.5244606 -0.8514348 0 -0.5244589 -0.8514358 0 -0.3982062 -0.9172959 0 -0.3982076 -0.9172953 0 -0.2638789 -0.9645559 0 -0.2638794 -0.9645557 0 -0.1241993 -0.9922574 0 0.01799774 -0.9998381 0 0.1598309 -0.9871445 0 0.1598308 -0.9871445 0 0.298421 -0.9544344 0 0.2984212 -0.9544343 0 0.4309609 -0.9023706 0 0.3978682 -0.909843 0.1178419 0.4498926 -0.8926519 0.02773612 0.9494668 -0.3138675 0 -0.4801707 0.8771752 0 -0.4492619 0.8929322 -0.02891415 -0.4313367 0.9001316 -0.06092578 -0.4005841 0.9162601 0 -0.299511 0.954093 0 -0.1607969 0.9869875 0 -0.01881301 0.9998231 0 0.1235513 0.9923382 0 0.123551 0.9923382 0 0.2634063 0.964685 0 0.3979073 0.9174256 0 0.3979066 0.9174261 0 0.5243215 0.8515204 0 0.5243199 0.8515214 0 0.5984632 0.8011503 0 0.6263346 0.7789235 -0.03135991 0.6388888 0.7668792 -0.06097322 0.6529922 0.7567159 -0.03134375 0.6798995 0.7333054 0 0.7428284 0.6694819 0 0.7428265 0.669484 0 0.8304791 0.5570499 0 0.8304778 0.5570517 0 0.9012509 0.4332976 0 0.9012513 0.4332968 0 0.9537077 0.3007355 0 0.9537078 0.3007349 0 0.9867809 0.1620606 0 0.9867802 0.1620648 0 0.9997981 0.02009415 0 0.999798 0.02009809 0 0.9924961 -0.1222764 0 0.9924956 -0.1222806 0 0.9650219 -0.2621693 0 0.9667417 -0.2269223 -0.11797 0.9593885 -0.2806026 -0.02891325 -1.98393e-6 0 1 1.91227e-6 0 1 -9.93112e-7 0 1 7.32654e-5 0 -1 3.8996e-7 0 1 4.90399e-7 0 1 0.9792567 0.2026235 0 0.8249534 0.5652008 0 0.8249554 0.565198 0 0.6974296 0.7166533 0 0.6974276 0.7166553 0 0.5425629 0.8400152 0 0.5425648 0.8400141 0 0.3664304 0.9304455 0 0.3664276 0.9304466 0 0.1759293 0.9844029 0 0.17593 0.9844027 0 -0.02146565 0.9997696 0 -0.1239665 0.9922865 0 -0.2216017 0.9751373 0 -0.4060263 0.9138615 0 -0.4060278 0.9138607 0 -0.5781203 0.8159515 0 -0.7275447 0.6860603 0 -0.8484541 0.5292692 0 -0.9361001 0.351734 0 -0.9361014 0.3517304 0 -0.9993078 -0.03720194 0 -0.9993077 -0.03720605 0 -0.9723896 -0.2333634 0 -0.9723915 -0.2333557 0 -0.9073523 -0.4203713 0 -0.8067486 -0.5908948 0 -0.8067507 -0.5908922 0 -0.5158457 -0.8566817 0 -0.5158402 -0.8566849 0 -0.3369518 -0.941522 0 -0.3369505 -0.9415224 0 -0.1448455 -0.9894543 0 -0.1448449 -0.9894544 0 -0.9201424 -0.391584 0 -0.8249549 -0.5651987 0 -0.824953 -0.5652015 0 -0.6974289 -0.7166541 0 -0.6974309 -0.716652 0 -0.5425639 -0.8400146 0 -0.542562 -0.8400159 0 -0.4384137 -0.8987734 0 -0.3868224 -0.9221543 0 -0.3175197 -0.9482518 0 -0.3175229 -0.9482507 0 -0.2769123 -0.9608953 0 -0.1759299 -0.9844028 0 -0.1759306 -0.9844026 0 0.02146583 -0.9997696 0 0.2180193 -0.9759445 0 0.2180197 -0.9759444 0 0.4060284 -0.9138605 0 0.4060292 -0.9138602 0 0.5781195 -0.8159522 0 0.5781175 -0.8159535 0 0.7275469 -0.6860579 0 0.7275459 -0.6860591 0 0.8484537 -0.5292698 0 0.8484545 -0.5292683 0 0.9361004 -0.351733 0 0.9993078 0.0372039 0 0.9993076 0.03720599 0 0.9723906 0.2333595 0 0.9073546 0.4203662 0 0.8067477 0.5908961 0 0.5158439 0.8566827 0 0.5158457 0.8566816 0 0.3369489 0.941523 0 0.3369482 0.9415233 0 0.144848 0.989454 0 0.1448477 0.989454 0 0.7171103 -0.6969598 0 -0.2450383 -0.9695135 0 0.2725546 -0.9621403 0 0.9695164 -0.2450264 0 0.9621418 0.2725493 0 0.7171172 -0.6969527 0 0.9621437 0.2725429 0 0.2450252 0.9695168 0 -0.2725521 0.9621411 0 -0.9695186 0.2450179 0 0.9621371 0.2725663 0 -0.5436729 -0.8392972 0 -0.1810931 -0.983466 0 0.2090399 -0.9779072 0 0.2090381 -0.9779075 0 0.8392994 -0.5436697 0 0.9779049 0.2090505 0 0.8234761 0.567351 0 0.5436649 0.8393024 0 0.543669 0.8392997 0 0.1811039 0.983464 0 -0.2090488 0.9779053 0 -0.5673541 0.8234741 0 -0.8392977 0.5436723 0 -0.977907 -0.2090408 0 -0.9779088 -0.2090323 0 0.9834682 -0.181081 0 0.9779086 0.2090334 0 -0.983468 0.181082 0 0.1949355 0.9808161 0 -0.7519365 0.6592356 0 -0.9808151 0.1949405 0 -0.9468826 -0.3215798 0 -0.1949425 -0.9808147 0 0.7519403 -0.6592313 0 0.7519437 -0.6592274 0 0.9808148 -0.1949422 0 0.9468834 0.3215771 0 0.6592257 0.7519453 0 0.6592291 0.7519422 0 -0.4421494 -0.8969414 0 0.4421573 0.8969377 0 -0.1949522 -0.9808128 0 0.7519334 -0.6592392 0 0.7519472 -0.6592234 0 0.9808121 -0.1949555 0 0.9468792 0.3215895 0 0.6592271 0.751944 0 -0.7519297 0.6592435 0 -0.9468783 -0.3215922 0 -0.4421472 -0.8969425 0 -0.3734552 0.9276483 0 -0.3734561 0.9276478 0 -0.1053557 0.9944346 0 -0.1053555 0.9944347 0 0.1707862 0.9853082 0 0.7308218 0.6825684 0 0.7308207 0.6825696 0 0.8693663 0.4941684 0 0.8693684 0.4941647 0 0.9379491 0.3467729 0 0.9949759 0.1001157 0 0.9949753 0.10012 0 0.9747473 -0.2233108 0 0.9747478 -0.2233088 0 0.8521572 -0.523286 0 0.6400783 -0.7683098 0 0.6400793 -0.7683089 0 0.4694114 -0.8829796 0 0.3201382 -0.9473709 0 0.04359877 -0.9990491 0 0.04359889 -0.9990492 0 -0.2781626 -0.960534 0 -0.2781621 -0.9605343 0 -0.5104647 -0.8598987 0 -0.6430464 -0.7658274 0 -0.8033322 -0.5955312 0 -0.8033312 -0.5955325 0 -0.9590554 0.2832189 0 -0.9999504 0.009968757 0 -0.7866349 0.6174186 0 -0.8643876 0.5028261 0 0.4194268 -0.9077892 0 0.4194127 -0.9077957 0 -0.09068191 -0.99588 0 -0.7683086 -0.6400796 0 -0.7683103 -0.6400778 0 -0.7683079 -0.6400806 -2.716e-6 -0.7683106 -0.6400773 -3.51932e-6 -0.7683088 -0.6400795 0 -0.7683089 -0.6400794 0 -0.7683086 -0.6400798 0 0.7683109 0.6400768 0 0.7683106 0.6400774 0 0.7683096 0.6400785 3.5193e-6 0.7683106 0.6400773 0 0.7683108 0.640077 2.71601e-6 0.7683089 0.6400792 0 0.76831 0.640078 0 0.1595366 -0.1914978 0.9684404 0.1595364 -0.191497 0.9684406 0.6400753 -0.7683123 0 0.6400792 -0.768309 0 -0.6400781 0.7683098 0 -0.6400797 0.7683086 0 -0.1595366 0.1914965 -0.9684407 -0.1595373 0.1914973 -0.9684404 -0.4428383 0.5315568 -0.7220399 -0.4428392 0.531553 -0.7220422 0.4428408 -0.5315566 0.7220386 0.4428378 -0.5315517 0.722044 0.2973363 -0.9547728 0 0.2973357 -0.9547731 4.51517e-6 0.2973376 -0.9547724 0 0.2973368 -0.9547727 2.71602e-6 0.2973364 -0.9547728 0 0.2973357 -0.954773 0 0.297335 -0.9547732 0 0.2973376 -0.9547725 0 0.2973365 -0.9547728 0 -0.2973377 0.9547725 0 -0.2973368 0.9547728 0 -0.2973359 0.954773 -3.51931e-6 -0.2973357 0.954773 3.64055e-6 -0.2973346 0.9547734 0 -0.2973377 0.9547724 -2.71602e-6 -0.2973363 0.9547728 -3.98253e-6 -0.2973363 0.9547728 0 0.2379727 0.07410901 0.9684404 0.2379724 0.07410997 0.9684405 0.9547743 0.2973316 0 0.9547718 0.2973397 0 -0.9547737 -0.2973334 0 -0.9547722 -0.2973386 0 -0.2379729 -0.07410937 -0.9684404 -0.2379727 -0.07411044 -0.9684404 -0.6605599 -0.2057103 -0.7220415 -0.6605591 -0.2057162 -0.7220406 0.6605595 0.2057129 0.7220411 0.6605605 0.2057101 0.722041 -0.8853744 0.4648786 0 -0.8853753 0.4648769 0 -0.8853749 0.4648779 0 -0.8853749 0.4648779 0 -0.8853744 0.4648787 0 -0.8853747 0.4648783 -3.64056e-6 -0.885374 0.4648796 0 -0.8853746 0.4648786 0 0.8853745 -0.4648786 0 0.8853753 -0.4648773 0 0.8853765 -0.464875 0 0.8853747 -0.4648783 -3.51931e-6 0.8853754 -0.4648768 -3.64055e-6 0.8853741 -0.4648792 0 0.885375 -0.4648774 -2.71601e-6 0.8853747 -0.4648783 -1.99127e-6 0.8853747 -0.464878 0 -0.1158689 -0.2206752 0.9684404 -0.1158686 -0.2206748 0.9684405 -0.4648799 -0.8853738 0 0.4648776 0.885375 0 0.1158687 0.2206754 -0.9684404 0.1158684 0.2206763 -0.9684403 0.3216263 0.6125471 -0.7220407 0.321626 0.6125478 -0.7220402 -0.3216254 -0.6125459 0.722042 -0.3216265 -0.6125465 0.7220411 1.9112e-6 0 -1 -0.9496881 -0.3131974 0 0.47956 0.8775091 0 0.4498926 0.8926519 0.02773612 0.4301025 0.9005728 0.06309181 0.4006595 0.9162271 0 0.2984212 0.9544343 0 0.298421 0.9544344 0 0.1598308 0.9871445 0 0.1598309 0.9871445 0 0.01799774 0.9998381 0 -0.1241993 0.9922574 0 -0.2638794 0.9645557 0 -0.2638789 0.9645559 0 -0.3982076 0.9172953 0 -0.3982062 0.9172959 0 -0.5244589 0.8514358 0 -0.5244606 0.8514348 0 -0.5990425 0.8007172 0 -0.6268365 0.7784172 0.03380566 -0.6387916 0.7667675 0.06334924 -0.6524149 0.757108 0.03379774 -0.6793577 0.7338073 0 -0.7427192 0.669603 0 -0.7427184 0.669604 0 -0.8302958 0.5573231 0 -0.90104 0.433736 0 -0.9535106 0.3013597 0 -0.9535115 0.3013568 0 -0.9866478 0.1628689 0 -0.9866478 0.1628686 0 -0.9997779 0.02107638 0 -0.9926349 -0.1211447 0 -0.9926347 -0.1211463 0 -0.9653639 -0.2609075 0 -0.9667376 -0.2270065 0.117841 -0.9592216 -0.2812895 0.02775436 -0.4801707 -0.8771752 0 0.9494668 0.3138675 0 0.9593885 0.2806026 -0.02891325 0.9632297 0.2616801 -0.06092727 0.9735388 0.2285221 0 0.9924957 0.1222804 0 0.9924961 0.1222767 0 0.999798 -0.02009809 0 0.9997981 -0.02009415 0 0.9867802 -0.1620645 0 0.9867808 -0.1620609 0 0.9537077 -0.3007355 0 0.9537078 -0.3007349 0 0.9012517 -0.433296 0 0.9012505 -0.4332984 0 0.8304773 -0.5570527 0 0.8304796 -0.557049 0 0.7428274 -0.669483 0 0.7428275 -0.6694829 0 0.6798995 -0.7333054 0 0.6529922 -0.7567159 -0.03134375 0.6388888 -0.7668792 -0.06097322 0.6263346 -0.7789235 -0.03135991 0.5984632 -0.8011503 0 0.5243206 -0.8515209 0 0.5243208 -0.8515209 0 0.3979066 -0.9174261 0 0.3979073 -0.9174256 0 0.2634063 -0.964685 0 0.123551 -0.9923382 0 0.1235513 -0.9923382 0 -0.01881301 -0.9998231 0 -0.1607969 -0.9869875 0 -0.299511 -0.954093 0 -0.4321394 -0.9018068 0 -0.3977869 -0.9098622 -0.1179674 -0.4492619 -0.8929322 -0.02891415 -9.55073e-7 0 1 -1.98738e-6 0 1 -1.908e-6 0 1 -1.98972e-6 0 1 1.90692e-6 0 1 2.2468e-5 0 1 -1.56063e-6 0 1 7.16476e-6 0 1 -2.14442e-6 0 1 -2.11113e-6 0 1 -1.05765e-6 0 1 1.2511e-6 0 1 2.61552e-6 0 1 -2.00415e-6 0 1 2.33382e-6 0 1 -3.29307e-6 0 1 -5.92835e-7 0 1 2.45998e-6 0 1 7.2535e-7 0 1 7.13056e-7 0 1 -8.4579e-7 0 1 2.01546e-6 0 1 -1.08934e-6 0 1 2.88703e-7 0 1 4.47376e-7 0 1 -3.55141e-6 0 1 2.66356e-6 0 1 -2.83668e-6 0 1 0 0 1 0 0 1 3.55141e-6 0 1 -2.66356e-6 0 1 2.83668e-6 0 1 0 0 1 0 0 1 -7.15801e-7 0 1 1.08934e-6 0 1 -5.38885e-7 0 1 1.23e-6 0 1 -7.2535e-7 0 1 3.35622e-7 0 1 7.13055e-7 0 1 -4.22896e-7 0 1 4.28884e-6 0 1 -1.89577e-6 0 1 1.56063e-6 0 1 -4.2223e-6 0 1 1.46825e-6 0 1 3.29307e-6 0 1 5.52187e-7 0 1 -2.14442e-6 0 1 2.4321e-6 0 1 -2.11529e-6 0 1 2.50221e-6 0 1 3.22128e-6 0 1 8.18458e-6 0 1 8.4965e-6 0 1 1.55543e-6 0 1 -1.43704e-6 0 1 -2.01546e-6 0 1 -7.13056e-7 0 1 8.4579e-7 0 1 -4.91996e-6 0 1 1.64654e-6 0 1 -1.83848e-6 0 1 -3.26366e-6 0 1 5.92835e-7 0 1 -5.87301e-6 0 1 -3.58238e-6 0 1 2.14442e-6 0 1 4.22228e-6 0 1 -1.1139e-6 0 1 2.59409e-6 0 1 -1.41146e-6 0 1 1.55009e-6 0 1 2.95262e-6 0 1 1.21607e-5 0 1 -2.88703e-7 0 1 -4.47376e-7 0 1 7.15801e-7 0 1 1.83846e-6 0 1 -1.64654e-6 0 1 5.38885e-7 0 1 -2.75772e-6 0 1 -3.35622e-7 0 1 -7.13055e-7 0 1 4.22896e-7 0 1 2.11113e-6 0 1 -1.46826e-6 0 1 -5.35091e-7 0 1 -5.19312e-7 0 1 5.24747e-6 0 1 3.79154e-6 0 1 -5.52187e-7 0 1 2.14442e-6 0 1 2.04613e-6 0 1 -2.9526e-6 0 1 1.46826e-6 0 -1 -2.95262e-6 0 -1 -1.56063e-6 0 -1 3.58238e-6 0 -1 -2.14442e-6 0 -1 2.62374e-6 0 -1 -2.11113e-6 0 -1 -1.05765e-6 0 -1 -6.71818e-7 0 -1 -1.08934e-6 0 -1 -1.64654e-6 0 -1 -2.41783e-7 0 -1 -8.4579e-7 0 -1 2.45777e-7 0 -1 9.19228e-7 0 -1 0 0 -1 0 0 -1 6.65889e-7 0 -1 -1.68598e-7 0 -1 0 0 -1 3.54585e-7 0 -1 -4.1501e-7 0 -1 -6.65889e-7 0 -1 1.68598e-7 0 -1 0 0 -1 -3.54585e-7 0 -1 4.1501e-7 0 -1 -1.34364e-6 0 -1 1.08934e-6 0 -1 -1.83846e-6 0 -1 1.64654e-6 0 -1 2.41783e-7 0 -1 7.13055e-7 0 -1 -4.22896e-7 0 -1 -3.26366e-6 0 -1 2.59409e-6 0 -1 -2.11115e-6 0 -1 2.14442e-6 0 -1 1.56063e-6 0 -1 -3.58237e-6 0 -1 2.9526e-6 0 -1 8.18461e-6 0 -1 7.56592e-7 0 -1 8.4579e-7 0 -1 -2.45777e-7 0 -1 -9.19228e-7 0 -1 -2.45998e-6 0 -1 -1.83848e-6 0 -1 3.22128e-6 0 -1 -3.58238e-6 0 -1 -2.93651e-6 0 -1 -2.91333e-6 0 -1 -2.61552e-6 0 -1 1.00208e-6 0 -1 -1.09717e-6 0 -1 6.7972e-5 0 -1 -1.97383e-5 0 -1 4.0923e-6 0 -1 0 0 -1 0 0 -1 -7.13055e-7 0 -1 4.22896e-7 0 -1 1.83846e-6 0 -1 5.28822e-7 0 -1 1.89576e-6 0 -1 2.62374e-6 0 -1 0.7070896 -0.707124 0 0.7071354 -0.7070781 0 0.7071048 -0.7071088 0 0.7071102 -0.7071034 0 0.7071068 -0.7071068 0 0.7071065 -0.7071071 0 -0.707108 0.7071056 0 -0.7071066 0.707107 0 -0.707107 0.7071067 0 -0.7071068 0.7071068 0 -0.7071069 0.7071067 0 0.7071066 -0.707107 0 0.707107 -0.7071067 0 0.7071069 -0.7071067 0 -0.7071065 0.7071071 0 -0.707108 -0.7071056 0 -0.7071068 -0.7071068 0 -0.7071064 -0.7071072 0 -0.7071069 -0.7071067 0 0.707108 0.7071056 0 0.7071066 0.707107 0 0.707107 0.7071067 0 0.7071068 0.7071068 0 0.707107 0.7071066 0 0.7071065 0.7071071 0 0.7070896 0.707124 0 0.7071354 0.7070781 0 0.7071048 0.7071088 0 0.7071102 0.7071034 0 0.7071064 0.7071072 0 0.7071069 0.7071067 0 -0.7071354 -0.7070781 0 -0.7070896 -0.707124 0 -0.7071048 -0.7071088 0 -0.7071102 -0.7071034 0 -0.7071066 -0.707107 0 -0.707107 -0.7071067 0 -0.707107 -0.7071066 0 -0.7071065 -0.7071071 0 -0.5555721 -0.8314684 0 -0.5555691 -0.8314704 0 -0.1950892 -0.9807855 0 0.1950886 -0.9807857 0 0.5555714 -0.8314689 0 0.5555698 -0.8314699 0 -0.9807856 -0.1950886 0 -0.9807857 0.1950883 0 -0.9807851 0.1950915 0 -0.8314696 0.5555704 0 -0.7113301 -0.7028581 0 -0.8347902 -0.5505682 0 -0.980785 -0.1950918 0 0.8314696 -0.5555704 0 0.980785 -0.1950918 0 0.9807856 -0.1950886 0 0.9807857 0.1950883 0 0.9807851 0.1950915 0 0.8314696 0.5555704 0 -0.5555698 -0.8314699 0 -0.5555714 -0.8314689 0 -0.1950886 -0.9807857 0 0.1950892 -0.9807855 0 0.5555691 -0.8314704 0 0.5555721 -0.8314684 0 0.7028447 0.7113434 0 0.5505691 0.8347897 0 0.1950892 0.9807855 0 -0.1950886 0.9807857 0 -0.5555714 0.8314689 0 -0.5555698 0.8314699 0 0.9807851 -0.1950915 0 0.9807857 -0.1950883 0 0.9807856 0.1950886 0 0.980785 0.1950918 0 -0.980785 0.1950918 0 -0.9807856 0.1950886 0 -0.9807857 -0.1950883 0 -0.9807851 -0.1950915 0 -0.8314696 -0.5555704 0 0.5555698 0.8314699 0 0.5555714 0.8314689 0 0.1950886 0.9807857 0 -0.1950892 0.9807855 0 -0.5555691 0.8314704 0 -0.5555721 0.8314684 0 0.83147 0.5555698 0 0.8314692 0.555571 0 0.9807853 0.1950909 0 0.9807854 0.1950901 0 0.9807854 -0.1950901 0 0.9807853 -0.1950909 0 0.8314692 -0.555571 0 0.83147 -0.5555698 0 -0.5555703 -0.8314697 0 -0.55557 -0.8314698 0 -0.1950903 -0.9807853 0 0.1950903 -0.9807853 0 0.5555703 -0.8314697 0 0.55557 -0.8314698 0 -0.83147 -0.5555698 0 -0.8314692 -0.555571 0 -0.9807853 -0.1950909 0 -0.9807854 -0.1950901 0 -0.9807854 0.1950901 0 -0.9807853 0.1950909 0 -0.8314692 0.555571 0 -0.83147 0.5555698 0 0.5555703 0.8314697 0 0.55557 0.8314698 0 0.1950903 0.9807853 0 -0.1950903 0.9807853 0 -0.5555703 0.8314697 0 -0.55557 0.8314698 0 -0.9659263 -0.2588173 0 -0.9659256 -0.2588199 0 -0.7071061 -0.7071076 0 -0.2588184 -0.965926 0 -0.2588192 -0.9659258 0 0.2588184 -0.965926 0 0.7071075 -0.7071061 0 0.9659256 -0.2588199 0 0.9659255 0.2588203 0 0.7071086 0.707105 0 0.2588184 0.965926 0 -0.2588192 0.9659258 0 -0.2588184 0.965926 0 -0.7071072 0.7071064 0 -0.9659255 0.2588203 0 -0.9659263 0.2588176 0 -0.9659258 -0.2588195 0 -0.9659259 -0.2588189 0 -0.2588191 -0.9659259 0 -0.2588192 -0.9659258 0 0.2588191 -0.9659259 0 0.2588192 -0.9659258 0 0.9659259 -0.2588191 0 0.9659259 -0.2588193 0 0.9659258 0.2588195 0 0.9659259 0.2588189 0 0.2588191 0.9659259 0 0.2588192 0.9659258 0 -0.2588191 0.9659259 0 -0.2588192 0.9659258 0 -0.9659259 0.2588191 0 -0.9659259 0.2588193 0 -0.965925 -0.258822 0 -0.7071078 -0.7071058 0 -0.2588202 -0.9659256 0 0.2588202 -0.9659256 0 0.7071078 -0.7071058 0 0.965925 -0.258822 0 0.965925 0.258822 0 0.7071078 0.7071058 0 0.2588202 0.9659256 0 -0.2588202 0.9659256 0 -0.7071078 0.7071058 0 -0.965925 0.258822 0 -0.9659263 -0.2588176 0 -0.9659255 -0.2588203 0 -0.7071072 -0.7071064 0 0.7071086 -0.707105 0 0.9659255 -0.2588203 0 0.9659256 0.2588199 0 0.7071075 0.7071061 0 -0.7071061 0.7071076 0 -0.9659256 0.2588199 0 -0.9659263 0.2588173 0 -0.7071086 -0.707105 0 0.2588192 -0.9659258 0 0.7071072 -0.7071064 0 0.9659263 -0.2588176 0 0.9659263 0.2588173 0 0.7071061 0.7071076 0 0.2588192 0.9659258 0 -0.7071075 0.7071061 0 -0.7071075 -0.7071061 0 0.7071061 -0.7071076 0 0.9659263 -0.2588173 0 0.9659263 0.2588176 0 0.7071072 0.7071064 0 -0.7071086 0.707105 0 -0.9912139 -0.1322692 0 -0.1322667 0.9912142 0 0.9912143 0.1322661 0 0.1322667 -0.9912142 0 0.3543937 -0.9348812 0.02005928 0.3999215 -0.9165494 0 0.487826 -0.872941 0 0.5299692 -0.8477796 0.02005726 0.5710432 -0.8209201 0 0.6487641 -0.7609897 0 0.6366781 -0.7711029 -0.006445765 0.7202035 -0.6937108 0.008500516 0.7092114 -0.7049959 0 0.9348812 0.3543937 0.02005875 0.9165496 0.3999211 0 0.8729401 0.4878276 0 0.8477804 0.529968 0.02006137 0.8209163 0.5710487 0 0.7609911 0.6487625 0 0.7711026 0.6366784 -0.006444215 0.6937087 0.7202056 0.008507132 0.7049947 0.7092126 0 -0.3543937 0.9348812 0.02005928 -0.3999215 0.9165494 0 -0.487826 0.872941 0 -0.5299692 0.8477796 0.02006036 -0.5710432 0.8209201 0 -0.6487623 0.7609912 0 -0.6366781 0.7711029 -0.006444215 -0.720205 0.6937093 0.008500516 -0.7092114 0.7049959 0 -0.9348812 -0.3543937 0.02005982 -0.9165511 -0.3999176 0 -0.8729383 -0.4878308 0 -0.8477804 -0.529968 0.02006137 -0.8209163 -0.5710487 0 -0.7609911 -0.6487625 0 -0.7711026 -0.6366784 -0.006447255 -0.693707 -0.7202071 0.008505046 -0.7049936 -0.7092137 0 0.7092083 -0.7049991 0 0.784756 -0.619805 0 0.8141797 -0.5805263 0.01003062 0.8417252 -0.5399062 0 0.890595 -0.4547973 0 0.9117934 -0.4105266 0.01003217 0.9308842 -0.3653146 0 0.962208 -0.2723155 0 0.974363 -0.2247582 0.01003062 0.9842659 -0.1766937 0 0.9968467 -0.07935267 0 0.999489 -0.03035509 0.01003098 0.9998245 0.01873505 0 0.9931393 0.1166277 0.008507072 0.9734573 0.228778 -0.006444275 0.976961 0.2134183 0 0.9513365 0.3081539 0 0.7049979 0.7092095 0 0.6198084 0.7847532 0 0.5805229 0.8141822 0.01003217 0.5399052 0.8417258 0 0.4547963 0.8905956 0 0.4105276 0.911793 0.0100311 0.365313 0.9308848 0 0.2723122 0.962209 0 0.2247596 0.9743627 0.01003116 0.1766919 0.9842663 0 0.07935678 0.9968463 0 0.03035187 0.999489 0.01003116 -0.01873159 0.9998246 0 -0.1322659 0.9912143 0 -0.1166297 0.9931391 0.008504688 -0.2287788 0.9734571 -0.006445765 -0.2134194 0.9769607 0 -0.3081609 0.9513344 0 -0.7092083 0.7049991 0 -0.784756 0.619805 0 -0.8141807 0.5805249 0.01003062 -0.8417252 0.5399062 0 -0.8905984 0.4547907 0 -0.9117912 0.4105318 0.0100314 -0.9308871 0.3653074 0 -0.9622092 0.2723116 0 -0.9743621 0.2247621 0.0100314 -0.9842644 0.1767017 0 -0.996846 0.07936096 0 -0.9994891 0.03034883 0.01003164 -0.9998245 -0.01873505 0 -0.9912146 -0.132263 0 -0.9931388 -0.1166318 0.008507072 -0.9734546 -0.2287896 -0.006444275 -0.9769635 -0.2134063 0 -0.9513353 -0.3081577 0 -0.7049967 -0.7092106 0 -0.6198084 -0.7847532 0 -0.580524 -0.8141815 0.0100311 -0.5399075 -0.8417245 0 -0.4547963 -0.8905956 0 -0.4105263 -0.9117937 0.0100311 -0.3653103 -0.9308859 0 -0.2723122 -0.962209 0 -0.2247611 -0.9743623 0.01003217 -0.1766949 -0.9842658 0 -0.07935369 -0.9968466 0 -0.03035187 -0.999489 0.01003009 0.01872849 -0.9998246 0 0.1322659 -0.9912143 0 0.1166297 -0.9931391 0.008508801 0.2287788 -0.9734571 -0.006439626 0.2134194 -0.9769607 0 0.3081609 -0.9513344 0 0 0 1 0.8958224 0.4444125 0 0.8958233 0.4444104 0 -0.8958237 -0.4444097 0 -0.8050405 -0.5932199 0 -0.8050448 -0.5932141 0 -0.5536001 -0.8327828 0 -0.235389 -0.9719013 0 0.1112183 -0.993796 0 0.444414 -0.8958216 0 0.4444175 -0.8958199 0 0.7239946 -0.6898058 0 0.723999 -0.689801 0 0.9162621 -0.4005793 0 0.9162588 -0.400587 0 0.9980115 -0.06303316 0 0.9980109 -0.06304216 0 0.959385 0.2821002 0 0.9593874 0.2820919 0 0.4444106 -0.8958232 0 0.4444097 -0.8958238 0 -0.4444112 0.895823 0 -0.4444102 0.8958235 0 0.5932171 -0.8050427 0 0.8327859 -0.5535954 0 0.8327776 -0.5536078 0 0.9719015 -0.2353879 0 0.9719036 -0.2353795 0 0.9937965 0.1112142 0 0.9937955 0.1112231 0 0.8958243 0.4444085 0 0.6898 0.7240001 0 0.4005829 0.9162606 0 0.4005796 0.916262 0 0.06303811 0.9980112 0 0.06303751 0.9980112 0 -0.2820973 0.9593858 0 -0.2820948 0.9593866 0 0.8958237 0.4444097 0 -0.8958224 -0.4444125 0 -0.8958233 -0.4444104 0 0.8050405 0.5932199 0 0.8050448 0.5932141 0 0.5536001 0.8327828 0 0.235389 0.9719013 0 -0.1112183 0.993796 0 -0.444414 0.8958216 0 -0.4444175 0.8958199 0 -0.7239946 0.6898058 0 -0.723999 0.689801 0 -0.9162621 0.4005793 0 -0.9162588 0.400587 0 -0.9980115 0.06303316 0 -0.9980109 0.06304216 0 -0.959385 -0.2821002 0 -0.9593874 -0.2820919 0 -0.4444106 0.8958232 0 -0.4444097 0.8958238 0 -0.5932171 0.8050427 0 -0.8327859 0.5535954 0 -0.8327776 0.5536078 0 -0.9719015 0.2353879 0 -0.9719036 0.2353795 0 -0.9937965 -0.1112142 0 -0.9937955 -0.1112231 0 -0.8958243 -0.4444085 0 -0.6898 -0.7240001 0 -0.4005829 -0.9162606 0 -0.4005796 -0.916262 0 -0.06303811 -0.9980112 0 -0.06303751 -0.9980112 0 0.2820973 -0.9593858 0 0.2820948 -0.9593866 0 -0.8199062 -0.5724438 -0.007883727 0.1603642 0.8161047 -0.5552088 -0.6456617 0.7308857 -0.2211949 -0.3650321 -0.9301869 -0.03878122 -0.2717183 -0.9601067 -0.06606304 0.6532725 -0.6062756 -0.4535032 -0.862848 -0.5054636 0 0.7691609 0.4428483 -0.4607351 -0.9971271 0.03062552 -0.0692808 0.7081175 0.4542019 -0.5406202 0.6932775 0.4395405 -0.5711134 0.6926769 0.4392617 -0.5720559 0.6952887 0.4391376 -0.5689744 0.7141023 0.432617 -0.5503639 0.715457 0.3842934 -0.5834723 0.6866215 0.4002697 -0.6069062 0.7064712 0.3544089 -0.6126115 0.7068038 0.3906066 -0.5897923 0.7042232 0.3926565 -0.5915156 0.702038 0.3945481 -0.5928528 0.738761 0.3206406 -0.5928084 0.7389341 0.3197067 -0.593097 0.7387702 0.3218271 -0.5921537 0.7384811 0.3272595 -0.5895313 0.7368867 0.3056023 -0.602997 0.7122536 0.3434365 -0.6121651 0.7090167 0.3493396 -0.6125825 0.794772 0.2932019 -0.5313854 0.7920768 0.2887373 -0.5378152 0.7696272 0.3026108 -0.5622284 0.770098 0.2886953 -0.5688621 0.7692292 0.2862467 -0.5712699 0.7806119 0.3812898 -0.4952407 0.7829023 0.3427069 -0.5192457 0.7867514 0.3394254 -0.5155702 0.7890835 0.3368821 -0.5136711 0.751872 0.4085426 -0.5174762 0.7462099 0.4225403 -0.5144226 0.7453765 0.4256244 -0.5130865 0.7455156 0.424919 -0.513469 0.7461234 0.4217851 -0.5151674 0.7468411 0.4118888 -0.5220881 0.7482836 0.4297007 -0.5054 0.7747973 0.3927006 -0.4954548 0.7777917 0.3870992 -0.4951711 -0.9932174 0.1063048 -0.0471037 -0.9958912 0.07448613 -0.05150383 -0.997043 -0.07240074 -0.02576011 -0.9959747 -0.08580082 -0.02593815 -0.9719685 -0.234987 -0.007644653 -0.9698659 -0.2434973 -0.00831741 -0.9351569 -0.3542339 0 -0.9885354 0.126398 -0.08259195 -0.9941132 0.09084886 -0.05903762 -0.9934089 0.09174829 -0.06871056 -0.9956206 -0.08476209 -0.03943371 -0.9968876 -0.06909316 -0.03796595 -0.9698541 -0.2430683 -0.01734507 -0.9950034 -0.0987634 -0.01462912 -0.9805051 -0.1959893 -0.01407545 -0.8419642 0.5108594 -0.1735487 -0.7947201 0.5736578 -0.1983352 -0.8367877 0.5106229 -0.197613 -0.6829077 0.6915504 -0.2353617 -0.9868943 0.1273427 -0.09911376 -0.9608711 0.2591031 -0.09794169 -0.9823904 0.1638898 -0.08971726 0.7115554 0.4556287 -0.5348752 0.7297567 0.4560955 -0.5093448 0.6828702 0.5253362 -0.5076516 0.04157733 0.9650062 -0.2589102 0.8392919 0.5073628 -0.1953768 0.7576053 0.6219215 -0.1981113 0.7480783 0.6114376 -0.2579207 0.6549578 0.7091225 -0.2611044 0.6466516 0.694385 -0.3157075 0.5342148 0.7835287 -0.3173287 0.5290925 0.7667199 -0.3635956 0.385786 0.8492781 -0.3604109 0.3847606 0.8334168 -0.3967062 0.205244 0.9004393 -0.3835154 0.2075138 0.8884504 -0.4093825 -0.02285319 0.9475202 -0.3188782 0.1786442 0.9267827 -0.3303939 0.1759133 0.9388121 -0.2961188 0.3357039 0.8940655 -0.2965636 0.3362524 0.9079893 -0.2499796 0.463153 0.8516586 -0.2452893 0.466948 0.8637701 -0.1893693 0.5529729 0.8099608 -0.1954089 -0.0693463 0.9574262 -0.2802252 0.09742385 0.9543684 -0.2822939 0.09609818 0.9652139 -0.2431612 0.2006253 0.949882 -0.2397372 -0.2100832 0.9340021 -0.288973 -0.3128904 0.9105566 -0.2701599 -0.3104396 0.9067226 -0.2854495 -0.5031813 0.8223305 -0.2656713 -0.5028108 0.8220795 -0.2671453 -0.701223 0.6767052 -0.2244028 -0.7043771 0.6770418 -0.213231 -0.8589755 0.4882105 -0.1543101 -0.8617746 0.4873071 -0.1409831 -0.3894513 0.8788178 -0.2756935 -0.5314728 0.8052796 -0.2627954 -0.5183094 0.8117787 -0.2690179 -0.6903598 0.6842131 -0.2350655 -0.6929908 0.6850937 -0.2245227 -0.8552893 0.4883717 -0.1731281 -0.859418 0.4874333 -0.1543033 0.8554198 0.2391243 -0.4594308 0.8573925 0.2357275 -0.4575051 0.8828074 0.114996 -0.4554418 0.8850867 0.1092289 -0.4524278 0.8937459 -0.02666985 -0.4477803 0.8954225 -0.03452837 -0.4438766 0.8803808 -0.1899268 -0.4345776 0.8805725 -0.1990924 -0.4300634 0.8316421 -0.3708598 -0.4133213 0.8299007 -0.379846 -0.4086344 0.7331215 -0.5638103 -0.3803301 0.8406639 0.3543118 -0.4095699 0.8174297 0.3456938 -0.4607651 0.818265 0.3446196 -0.4600868 0.7956866 0.336157 -0.5038664 0.7764943 0.347711 -0.5255033 0.8792101 0.2435323 -0.4094896 0.8796713 0.2426377 -0.4090299 0.905649 0.1146783 -0.4082266 0.9061409 0.1132162 -0.4075424 0.9138404 -0.03125333 -0.4048691 0.9141474 -0.03315502 -0.404024 0.8960307 -0.1976574 -0.3975684 0.8959808 -0.1997218 -0.3966482 0.841757 -0.3797538 -0.3837087 0.8413341 -0.3815683 -0.382835 0.7376734 -0.5715063 -0.3594698 0.7371528 -0.5725429 -0.3588879 0.5762779 -0.7511815 -0.3219166 -0.1175158 -0.9824419 -0.1449072 0.5731288 -0.7497176 -0.3308277 0.3644067 -0.8901585 -0.2735428 0.3606971 -0.8916656 -0.2735512 0.1133311 -0.9727032 -0.2024962 0.1128612 -0.9705795 -0.2126924 0.1151278 -0.97009 -0.2137079 -0.1318905 -0.9792206 -0.1540518 -0.6706919 -0.7411869 -0.0285359 -0.7751173 -0.6317642 -0.008188188 -0.8419876 -0.5394958 -0.001146018 -0.8627702 -0.5055517 -0.006731986 0.5766266 -0.7547231 -0.3128818 0.573169 -0.7583454 -0.3104669 0.7408 -0.5785585 -0.3412998 0.7375612 -0.5843826 -0.3383791 0.8495036 -0.3886929 -0.3567374 0.8475317 -0.3956395 -0.3537787 0.9087879 -0.2060682 -0.362823 0.9082938 -0.2129171 -0.3600953 0.9308485 -0.03708934 -0.3635182 0.9315004 -0.04290652 -0.3612009 0.9254339 0.1127987 -0.36173 0.9266538 0.1085088 -0.3599148 0.9001044 0.2462873 -0.3593811 0.5734268 -0.7608275 -0.3038477 0.5656997 -0.7684156 -0.2992012 0.7398881 -0.5897076 -0.3237448 0.7314745 -0.6034497 -0.3174799 0.8534809 -0.4027174 -0.3307402 0.8475782 -0.4202575 -0.3240293 0.9183828 -0.2198782 -0.3289781 0.9161388 -0.23797 -0.3225834 0.945266 -0.04796659 -0.3227558 0.9462292 -0.06391692 -0.3171199 0.9429903 0.1066247 -0.3152787 0.9826389 -0.07836252 -0.1681673 0.9674134 0.2035548 -0.1505887 0.9589647 0.202756 -0.198184 0.9084893 0.3695874 -0.1950706 0.8970183 0.3655933 -0.2483945 0.8363993 0.488562 -0.2484822 0.8228785 0.4796744 -0.3046041 0.7522724 0.5835919 -0.305789 0.7390035 0.5697939 -0.3594562 0.6500512 0.6692035 -0.3600003 0.6393945 0.651997 -0.4075225 0.5265437 0.7475945 -0.4047889 0.5201542 0.7295615 -0.4440491 0.3740357 0.8197163 -0.4337773 0.3722825 0.8039237 -0.4638022 0.1897393 0.8776393 -0.4401686 0.1912551 0.8666427 -0.4608166 0.9348492 0.330586 -0.1294987 0.8939162 0.4269858 -0.1363716 0.8478333 0.5130323 -0.1340772 0.9743341 0.1731013 -0.1439063 0.9207628 0.3644596 -0.1391584 0.9123145 0.3615283 -0.1923006 0.8443394 0.5000622 -0.1924293 0.8333492 0.4927628 -0.2504277 0.7582582 0.601146 -0.2523255 0.746832 0.5888682 -0.3089927 0.6561432 0.6876313 -0.3108689 0.646627 0.6715256 -0.3618384 0.5338994 0.764441 -0.3613605 0.5281132 0.7468975 -0.4040305 0.3830167 0.8338705 -0.3974398 0.3816183 0.8179484 -0.4304973 0.1999544 0.8888742 -0.4122148 0.201852 0.8773123 -0.4354066 0.7299633 -0.5706291 -0.3762127 0.5757939 -0.7465889 -0.3332661 0.5762902 -0.7511681 -0.3219258 0.360439 -0.892704 -0.2704874 0.3634234 -0.8917204 -0.2697373 0.3571853 -0.8942329 -0.2697523 0.3570131 -0.8950319 -0.2673192 0.3584933 -0.8945327 -0.2670093 0.5659046 -0.7698612 -0.2950693 0.5531401 -0.7815644 -0.2884323 0.7331097 -0.6070502 -0.3066598 0.7178526 -0.6295125 -0.2973241 0.8519185 -0.4254153 -0.3053799 0.8399323 -0.4554191 -0.2951392 0.9237518 -0.2433758 -0.2957211 0.9178495 -0.275533 -0.2857167 0.9569309 -0.06807857 -0.2822212 -0.1294155 -0.9771834 -0.1684172 -0.1019364 -0.9785277 -0.179144 0.1142893 -0.9682272 -0.2224276 0.1264138 -0.96569 -0.2268533 0.3503554 -0.8977102 -0.2671471 0.3503291 -0.8981593 -0.265668 0.5532472 -0.7820684 -0.2868564 0.5348617 -0.7976952 -0.2785776 0.7188727 -0.631477 -0.2906182 0.6949632 -0.6628553 -0.2786556 0.8428474 -0.4586882 -0.2814489 0.821851 -0.5027156 -0.268026 0.9232394 -0.2792925 -0.2638651 -0.6481094 -0.7602578 -0.04429918 -0.6703243 -0.7413134 -0.03346449 -0.7682491 -0.63993 -0.01681989 -0.768369 -0.6398743 -0.0130428 -0.7139149 -0.6993577 -0.03499227 -0.6482554 -0.7602452 -0.04233723 -0.5620428 -0.8239266 -0.07247817 -0.4191561 -0.9027341 -0.09684729 0.451862 -0.8085811 -0.3768519 0.4591081 -0.7980165 -0.3903709 0.5148942 -0.7402053 -0.432412 0.5225261 -0.7240854 -0.4501854 0.5664187 -0.6643986 -0.4875904 0.5727888 -0.6433581 -0.5079402 0.6623725 0.2734007 -0.6975061 0.6823019 0.2479706 -0.6877316 0.7011509 0.1957535 -0.6856151 0.7015851 0.1775057 -0.6901233 0.7233367 0.1410202 -0.6759418 0.7369998 0.08123928 -0.6709929 0.7355946 0.06656759 -0.6741435 0.7734846 -0.1224309 -0.6218782 0.7589372 -0.06177955 -0.6482266 0.7619151 -0.04867017 -0.6458457 0.7558771 0.01798427 -0.6544666 0.7687484 0.2857193 -0.5721805 0.7459303 0.2844495 -0.6022263 0.7724706 0.2085573 -0.5998277 0.7786901 0.2008609 -0.5943876 0.8029793 0.09294551 -0.588715 0.8108461 0.07936108 -0.579854 0.8209767 -0.04027825 -0.5695392 0.8280194 -0.05943614 -0.5575404 0.8184272 -0.1962756 -0.540049 0.7911156 -0.2714848 -0.5481169 0.7698777 -0.3557491 -0.5298406 0.7591357 -0.3750687 -0.5320118 0.744665 -0.4485818 -0.4942151 0.7228017 -0.496227 -0.4809538 0.4921013 -0.7982046 -0.3474275 0.5067691 -0.784093 -0.3583061 0.5706214 -0.7230011 -0.3894365 0.5885811 -0.7000975 -0.404272 0.6363843 -0.6407379 -0.4294998 0.6549058 -0.6093003 -0.4470476 0.7089502 -0.5183132 -0.4782691 0.7183663 -0.5312468 -0.4491401 0.7818083 -0.3955055 -0.4820283 0.7812367 0.2989279 -0.5480068 0.7632688 0.3284139 -0.5563858 0.8021318 0.22108 -0.5547145 0.8069654 0.2144246 -0.5502991 0.8315141 0.1032543 -0.5458232 0.8374807 0.09164679 -0.5387274 0.8472208 -0.03230369 -0.5302578 0.8523055 -0.04851406 -0.5207896 0.8412492 -0.1904781 -0.5059822 0.8433836 -0.2098243 -0.4946492 0.8018817 -0.3682386 -0.470517 0.4735007 -0.8040683 -0.3595432 0.4891981 -0.7878494 -0.3741371 0.5449021 -0.7328827 -0.4073877 0.5635469 -0.7071096 -0.427096 0.6043593 -0.6546787 -0.4540328 0.6231591 -0.6194988 -0.4773826 0.6724287 -0.5326935 -0.5138846 0.6830087 -0.5454646 -0.4857648 0.7245658 -0.4581643 -0.5148687 0.7292979 -0.4334636 -0.5293712 0.7510984 -0.3692036 -0.5473024 0.7530688 -0.3430454 -0.5614333 0.7669559 -0.2833374 -0.5757593 0.7661663 -0.2570202 -0.5890076 0.3779365 -0.8661691 -0.3269788 0.3891306 -0.8617823 -0.3254362 0.462591 -0.8052049 -0.3710184 0.4699215 -0.7953672 -0.382838 0.5293807 -0.7349719 -0.4237601 0.5374439 -0.719673 -0.4395735 0.5841597 -0.6576966 -0.4755972 0.5914385 -0.6370376 -0.4943519 0.303057 -0.9146733 -0.2674497 -0.1027729 -0.987928 -0.115914 -0.1296264 -0.9865612 -0.09946918 -2.08503e-4 -0.9891549 -0.1468759 -0.0216729 -0.9908593 -0.133147 0.1033576 -0.9777237 -0.1826841 0.08914208 -0.9808592 -0.1731153 0.2042254 -0.9533254 -0.2224021 -0.1277652 -0.9846827 -0.1186429 -0.1552 -0.982404 -0.1039012 -0.02020442 -0.9886145 -0.1491079 -0.04280436 -0.9896982 -0.1366206 0.08996838 -0.978828 -0.1838521 0.789523 0.3363156 -0.5133666 0.7969319 0.3249443 -0.5092259 0.8297587 0.2314286 -0.5078794 0.8331841 0.2261673 -0.5046312 0.8581101 0.110854 -0.5013567 0.862212 0.1017884 -0.4962153 0.871501 -0.02743494 -0.4896258 0.8747838 -0.03996574 -0.4828625 0.8619839 -0.1880053 -0.4707842 0.8629553 -0.2028044 -0.4627943 0.818127 -0.3674557 -0.4423174 0.8158767 -0.3822405 -0.4338635 0.7248889 -0.5603197 -0.4007217 0.7200313 -0.5718811 -0.3930738 0.5723965 -0.7441396 -0.3444104 0.5677651 -0.7499449 -0.3394488 0.3606684 -0.89131 -0.2747448 0.3616008 -0.8862336 -0.2895427 0.3037809 -0.9166861 -0.2596226 0.3039549 -0.9157451 -0.2627209 0.3029933 -0.9162349 -0.2621238 0.1909437 -0.9572674 -0.217209 0.1913204 -0.9562811 -0.2211857 0.1233284 -0.9699431 -0.2097633 0.1230412 -0.9704126 -0.2077507 -0.1343116 -0.9815984 -0.1357381 -0.1309123 -0.9792789 -0.1545147 -0.4741175 -0.8785331 -0.05824196 -0.4758536 -0.8784368 -0.04372888 -0.4735264 -0.8796388 -0.04481542 -0.4240324 -0.9045327 -0.04491508 -0.5573946 -0.8299126 -0.02359014 -0.5553568 -0.8304309 -0.04431122 -0.5299711 -0.8462356 -0.05491721 -0.5294879 -0.8462748 -0.05883508 -0.5291074 -0.8464987 -0.05903661 -0.5279422 -0.8464964 -0.06870853 -0.4974315 -0.8635626 -0.08259272 -0.4960092 -0.8630064 -0.0958904 -0.3235789 -0.936793 -0.1331006 -0.8326399 -0.553811 -0.002023816 -0.84201 -0.5394616 7.69078e-4 -0.7824191 -0.6227271 -0.005601882 -0.77513 -0.6317531 -0.00784105 -0.7250416 -0.6886653 -0.007405638 -0.6596745 -0.7513197 -0.01866447 -0.5877882 -0.8085094 -0.0285958 -0.6929541 -0.7209448 -0.007297575 -0.6922041 -0.7214242 -0.02001881 -0.781073 -0.6244273 -0.003934502 -0.7808951 -0.6245981 -0.008964896 -0.8627687 -0.5055988 -5.80401e-5 -0.8627684 -0.5055994 0 -0.2041121 -0.9764813 -0.06944423 -0.202979 -0.9750666 -0.08969253 -0.2330946 -0.9697927 -0.07189631 -0.2311422 -0.9685132 -0.09249669 -0.2611744 -0.962237 -0.07673293 -0.2591559 -0.9613945 -0.09251397 -0.1525856 -0.9805642 -0.1233353 -0.118465 -0.9831541 -0.1391909 -0.04103744 -0.9878438 -0.1499357 0.07567954 -0.9794881 -0.1867502 0.07424765 -0.9817931 -0.1748418 0.1984853 -0.9546875 -0.221755 0.1983076 -0.9555502 -0.2181699 0.3005414 -0.916066 -0.2655148 -0.3122668 -0.9403539 -0.1349965 -0.3129855 -0.940921 -0.129259 -0.3464666 -0.9309679 -0.1151512 -0.3486109 -0.9317504 -0.1015464 -0.348566 -0.9317651 -0.1015657 -0.3516991 -0.9325103 -0.08205121 -0.3332884 -0.9382773 -0.09249168 -0.3343428 -0.9385695 -0.0854541 -0.3581665 -0.9306768 -0.07454866 -0.3605046 -0.9311629 -0.05451697 -0.3299705 -0.9413701 -0.07029902 -0.3317688 -0.942049 -0.04973053 -0.07882928 -0.9902518 -0.1148369 -0.1037787 -0.9898216 -0.09738147 0.0185272 -0.9890769 -0.1462323 -8.99571e-4 -0.9912689 -0.1318528 0.1146719 -0.9764719 -0.1826287 0.1030902 -0.9794304 -0.1734604 0.2079903 -0.9521089 -0.2241175 0.2042236 -0.9536727 -0.2209096 0.2967168 -0.9160002 -0.2700052 0.300252 -0.9138634 -0.2733178 0.3897426 -0.8614544 -0.3255723 0.3909777 -0.8660607 -0.3115692 0.4010405 -0.8583552 -0.3199888 0.401688 -0.8637136 -0.3043776 0.4104204 -0.8574785 -0.3102997 0.4103968 -0.8616688 -0.2984987 0.5083258 -0.7933776 -0.3348986 0.5656673 -0.7377745 -0.3683875 0.5930862 -0.7133221 -0.3733906 0.7134342 -0.5594363 -0.4219509 0.7162925 -0.5560086 -0.421639 0.7997313 -0.3877367 -0.4583559 0.7833864 -0.3721827 -0.497781 0.8220402 -0.2192955 -0.5255089 0.7898998 -0.202591 -0.578805 0.6335542 -0.50039 -0.5901008 0.6344531 -0.4704332 -0.6133205 0.6497907 -0.4167936 -0.6356533 0.6470881 -0.3850453 -0.6580404 0.6561112 -0.3350558 -0.6762069 0.6501106 -0.3036028 -0.6965498 0.6542701 -0.256756 -0.7113418 0.6454626 -0.226557 -0.7294175 0.6457549 -0.1827527 -0.7413516 0.6347061 -0.1543378 -0.7571843 0.6319439 -0.1134454 -0.7666662 0.6197951 -0.08832204 -0.7797778 0.6144213 -0.04891347 -0.7874605 0.602274 -0.02791035 -0.7978015 0.5944595 0.01113831 -0.8040485 0.5830019 0.02811437 -0.8119842 0.5727784 0.06726354 -0.8169459 0.5624618 0.08058261 -0.8228871 0.5498036 0.1201086 -0.8266136 0.5416603 0.12936 -0.8305842 0.5261167 0.1704183 -0.833162 0.5210148 0.1755782 -0.835294 0.5020186 0.219049 -0.836657 0.5003151 0.2205809 -0.8372747 0.4773656 0.2667695 -0.8372312 0.4791269 0.2653617 -0.8366723 0.4517578 0.3142517 -0.8349615 0.4573625 0.3102473 -0.8334064 0.4247983 0.3621485 -0.8296957 0.4343632 0.3561104 -0.8273537 0.395848 0.410961 -0.821228 0.4089441 0.4037128 -0.8184013 0.3639925 0.4608598 -0.8093935 0.3799145 0.4532268 -0.8063812 0.3281949 0.5116637 -0.794033 0.3470516 0.5040004 -0.7909101 0.2876372 0.5632637 -0.7745959 0.3093341 0.5560191 -0.7714631 0.2414167 0.615184 -0.750511 0.2651558 0.6089976 -0.7475389 0.1885764 0.6663287 -0.7214187 0.2131405 0.6617837 -0.7187584 0.1283598 0.7150275 -0.6872115 0.1534896 0.712349 -0.6848357 0.06047654 0.7596715 -0.647489 0.08565127 0.7590489 -0.6453748 -0.01495516 0.7982354 -0.60216 0.00891602 0.7997215 -0.6003051 -0.09726363 0.8282378 -0.5518713 -0.07637083 0.8314796 -0.550281 -0.1850745 0.8472086 -0.4979811 -0.1673598 0.8517265 -0.4965408 -0.2765017 0.8535904 -0.4415092 -0.2621582 0.8588006 -0.440153 -0.3692907 0.8463461 -0.3838266 -0.3591094 0.85125 -0.3826407 -0.4610133 0.8249568 -0.3269757 -0.4504704 0.8313825 -0.3253918 -0.5496469 0.7901666 -0.2711553 -0.5462811 0.7922465 -0.2718871 -0.6324319 0.7418347 -0.2229603 -0.6355212 0.7393792 -0.2223314 -0.7085738 0.682508 -0.1791819 -0.7167864 0.674272 -0.177693 -0.7769648 0.6136568 -0.1405384 -0.7888769 0.5986797 -0.1387663 -0.836844 0.5367792 -0.1075193 -0.8499385 0.516075 -0.106166 -0.8877593 0.4533372 -0.07980549 -0.9001471 0.4282982 -0.07934606 -0.9293745 0.3647144 -0.05697911 -0.9400228 0.336203 -0.05766135 -0.9614841 0.2721109 -0.03878372 -0.9696915 0.2409123 -0.04073971 -0.9839594 0.1766382 -0.02495902 -0.9889956 0.1452579 -0.02807104 -0.9967375 0.07936012 -0.0147081 -0.9985762 0.04997891 -0.01864993 -0.9997975 -0.01873862 -0.007344186 -0.9989164 -0.04502785 -0.01177525 -0.9931727 -0.1166279 -0.002491712 -0.9902296 -0.1392659 -0.007096886 -0.976961 -0.2134179 9.10372e-5 -0.973088 -0.2303994 -0.003986597 -0.9513347 -0.3081577 0.001085758 -0.9480257 -0.3181892 -0.001720666 -0.9165477 -0.3999242 0.001010835 -0.9151819 -0.4030411 0 -0.8729411 -0.4878257 0 -0.8744577 -0.4851008 0.001018941 -0.8209164 -0.5710445 -0.002135992 -0.8326653 -0.5537734 0.001935184 -0.7609801 -0.6487518 -0.00552535 -0.7825509 -0.6225829 0.002156734 -0.6936957 -0.7201934 -0.01037895 -0.7252567 -0.6884775 0.001217961 -0.6197192 -0.7846375 -0.01709347 -0.6603314 -0.7509726 -0.001637578 -0.5397205 -0.8414377 -0.02615952 -0.5889059 -0.808174 -0.006687223 -0.4544682 -0.8899572 -0.03788208 0.6577719 -0.489552 -0.5724292 0.659928 -0.4609028 -0.5933494 0.6769238 -0.404688 -0.6148186 0.6756982 -0.3742584 -0.6351085 0.6859345 -0.3222216 -0.6524317 0.6814476 -0.2915669 -0.6712809 0.6865147 -0.2428152 -0.6853747 0.6792549 -0.2133102 -0.702219 0.6802119 -0.1671703 -0.7136989 0.6708475 -0.1399335 -0.7282735 0.6685035 -0.09692651 -0.7373658 0.6579105 -0.07273918 -0.7495751 0.65281 -0.03175073 -0.7568562 0.6418687 -0.01115792 -0.7667334 0.6341908 0.02928584 -0.7726218 0.6237151 0.04602748 -0.7802955 0.6133944 0.08681076 -0.7849913 0.604143 0.09959822 -0.7906274 0.5913277 0.1404229 -0.7941114 0.5839902 0.1493096 -0.7979111 0.5683811 0.1910369 -0.8002799 0.5635756 0.1961932 -0.8024281 0.5445708 0.2399188 -0.8036676 0.5428518 0.2415683 -0.8043361 0.5197601 0.288033 -0.8042926 0.5215419 0.2865193 -0.8036795 0.4939462 0.3355775 -0.8021253 0.4993164 0.3315151 -0.8004879 0.466536 0.3833108 -0.7971305 0.4754019 0.3773417 -0.7947368 0.4365166 0.4320579 -0.7891637 0.4487493 0.424807 -0.7862335 0.4029299 0.4821205 -0.7779509 0.4183318 0.4741775 -0.7746964 0.3655633 0.5326408 -0.7633199 0.3838497 0.5245685 -0.7599259 0.3234436 0.583461 -0.7449548 0.3442298 0.5758109 -0.7415845 0.2751582 0.6344439 -0.7223358 0.297967 0.6277438 -0.7191339 0.2195535 0.6847053 -0.694964 0.2437521 0.6794552 -0.6920444 0.1569021 0.7321805 -0.6627922 0.1817325 0.7287439 -0.6602315 0.08674877 0.7752596 -0.6256576 0.1113306 0.7738711 -0.6234816 0.008456349 0.8121782 -0.5833481 0.03179687 0.8128943 -0.5815427 -0.07769155 0.8406084 -0.5360426 -0.05662971 0.8432307 -0.5345606 -0.1689579 0.8579627 -0.4851323 -0.1510655 0.8619967 -0.4838811 -0.2635875 0.8626063 -0.4317778 -0.2495631 0.8672975 -0.4307125 -0.3601511 0.8533068 -0.3770395 -0.3503897 0.8577519 -0.37615 -0.4500609 0.8314402 -0.3258107 -0.9276898 -0.373352 0 -0.9985132 -0.05111312 -0.01894783 -0.9930037 0.1141259 -0.03031551 -0.9959303 0.08450967 -0.03132295 -0.9996018 0.02066695 -0.0192157 -0.9971932 -0.07042092 -0.02543127 -0.9136576 -0.4061397 -0.01674664 -0.944697 -0.3279442 3.15833e-4 -0.9752804 -0.220872 -0.006619691 -0.9691379 -0.2459263 -0.01709115 -0.9869838 -0.1607379 -0.005143523 -0.9497489 0.3064853 -0.0635901 -0.9233013 0.3747261 -0.08423358 -0.9222774 0.3752932 -0.09251797 -0.6404002 0.7357759 -0.2202759 -0.646215 0.7310471 -0.2190349 -0.7255414 0.663995 -0.1808322 -0.8621103 0.4939213 -0.1131712 -0.8129094 0.5648126 -0.1420041 -0.8113777 0.5649666 -0.1499311 -0.9588555 0.2769324 -0.06248843 -0.956821 0.2785245 -0.08317285 -0.9502021 0.3011237 -0.08025234 -0.9493787 0.3017956 -0.0871759 -0.9544874 0.284823 -0.08848679 -0.9527744 0.2861942 -0.1015574 -0.9527929 0.2861324 -0.1015588 -0.9499069 0.2879291 -0.1215475 -0.9396914 0.3197169 -0.1214964 -0.9350758 0.3208355 -0.1506582 -0.898754 0.4116894 -0.1508421 -0.8001416 0.58209 -0.1447232 -0.7359803 0.6530255 -0.1785798 -0.7341096 0.6528444 -0.1867544 -0.6976833 0.6850096 -0.2097613 -0.6988535 0.6851361 -0.205408 -0.491752 0.8266509 -0.2735476 -0.4929656 0.8271784 -0.269742 -0.2553289 0.9135146 -0.3166989 -0.2610316 0.9188745 -0.2958585 -0.01227438 0.9487223 -0.3158727 -0.06692808 0.9524287 -0.2973217 0.1461567 0.9409498 -0.3053717 0.1438491 0.9524822 -0.2684868 0.2886254 0.919741 -0.2660301 0.2897827 0.9324021 -0.2159915 0.3452909 0.9132643 -0.2161542 -0.911705 0.4016907 -0.08624845 -0.8751004 0.4711434 -0.1105591 -0.8730546 0.4717696 -0.1233249 -0.8544909 0.50047 -0.1391946 -0.8542121 0.5005489 -0.1406152 -0.705124 0.6786856 -0.2053924 -0.7028896 0.6785761 -0.2132624 -0.4959154 0.8254105 -0.269751 -0.4967397 0.8257999 -0.2670288 -0.2857746 0.9110135 -0.2973003 -0.2893267 0.9152259 -0.2804493 -0.1062083 0.9511384 -0.2899233 -0.108859 0.9585645 -0.2632563 -0.05336135 0.9632039 -0.2634218 -0.9257363 -0.3781697 0 -0.9276775 -0.3733767 0.00210762 -0.971969 -0.2350075 -0.006919145 -0.9752581 -0.2210605 -0.002011597 -0.9971344 -0.07280564 -0.02055579 -0.9985694 -0.05140012 -0.01473635 -0.9934113 0.1059642 -0.04365313 -0.9951771 0.08575284 -0.04763424 -0.9824377 0.1796578 -0.05039292 -0.9827892 0.1791959 -0.0448814 -0.9767478 0.2096331 -0.04492008 -0.227725 0.8869025 -0.4019271 -0.2146562 0.8903997 -0.4013867 -0.3357215 0.871999 -0.3562427 -0.3268557 0.8755005 -0.3558991 -0.3203355 0.8806922 -0.3489506 -0.3285952 0.8775483 -0.3491911 -0.2047339 0.8973137 -0.3910399 -0.217004 0.894231 -0.3914846 -0.1093469 0.8982813 -0.4255985 -0.1056004 0.8895546 -0.4444561 -0.1222958 0.8869875 -0.4453055 0.2596711 0.7716137 -0.5806748 0.2376638 0.7765594 -0.5834993 0.3279716 0.7258096 -0.6046778 0.3068712 0.7323067 -0.607912 0.3704759 0.6899371 -0.6218798 0.4099646 0.6416633 -0.6482263 0.5657925 0.4512354 -0.6901201 0.422204 0.6361006 -0.6458481 0.4716242 0.5909718 -0.654464 0.498038 0.5454219 -0.6741463 0.5105627 0.5376715 -0.6709957 0.5499095 0.4906108 -0.6759443 0.5800563 0.4398472 -0.685616 0.6102371 0.3932428 -0.6877288 0.6184232 0.3619928 -0.6975056 0.6352216 0.3450874 -0.6909474 0.6590771 0.2969975 -0.6909486 -0.2543973 0.9065739 -0.3367577 -0.250633 0.9026427 -0.3498848 -0.257798 0.8995534 -0.3526244 0.9618373 -0.1476833 -0.2303447 0.9726054 0.06859731 -0.2221112 0.962747 0.07004237 -0.2611749 0.9360672 0.2399545 -0.2572939 0.9217722 0.2384938 -0.3057072 0.8787587 0.3674896 -0.3045234 0.8613324 0.3612185 -0.3572505 0.8091822 0.4664542 -0.3572739 0.7908835 0.4547075 -0.4095661 0.725264 0.5534719 -0.4094644 0.7086655 0.5371506 -0.4574522 0.621665 0.6374551 -0.4551745 0.6090658 0.6186016 -0.4963578 0.4962304 0.7176289 -0.4886351 0.4888897 0.6991392 -0.5217196 0.342424 0.7932373 -0.503508 0.3401256 0.7781535 -0.5280072 0.1586986 0.8552522 -0.4933139 0.1606342 0.8313543 -0.5320213 0.09334653 0.8643205 -0.4942029 0.09543108 0.8482754 -0.5208857 0.7011948 0.3953841 -0.5932936 0.6821246 0.4147233 -0.6022546 0.6283404 0.4959701 -0.5993347 0.6363052 0.4915885 -0.5945221 0.5505492 0.5930602 -0.5875162 0.5632765 0.5880078 -0.5804882 0.451003 0.6890061 -0.5673331 0.7078397 0.4281767 -0.5618077 0.7232858 0.4090307 -0.5563736 0.6569775 0.5109441 -0.5543616 0.6634398 0.5069221 -0.5503433 0.5773302 0.6080358 -0.5449609 0.3215716 0.7801378 -0.5366346 0.4674816 0.6848317 -0.5589871 0.4751489 0.7033696 -0.5286821 0.5877998 0.60322 -0.5390892 0.6011863 0.6227028 -0.5008155 0.6876661 0.521997 -0.5046134 0.7057443 0.5394031 -0.4593141 0.7701013 0.4419156 -0.4600595 0.7906518 0.454963 -0.4097297 0.8404635 0.3545934 -0.4097375 0.8608099 0.3620363 -0.3576817 0.9012702 0.2437481 -0.3581882 0.9188451 0.2458025 -0.3087153 0.9457687 0.09458434 -0.3107659 0.9587838 0.09281378 -0.2685502 0.9570121 -0.09740757 -0.2732024 0.9648907 -0.1005286 -0.2426518 0.9105579 -0.3288409 -0.2504959 -0.2176488 -0.9616105 -0.1671357 -0.05644339 -0.9792994 -0.1943885 -0.1003501 -0.9762325 -0.1920937 0.03965687 -0.9744001 -0.2212958 0.1270174 -0.9639134 -0.2339606 0.1985833 -0.9464846 -0.2544243 0.3595435 -0.8950405 -0.263877 0.3774209 -0.8862099 -0.268674 0.5347608 -0.7974012 -0.279611 0.5181723 -0.8104931 -0.2731274 0.6958827 -0.6642998 -0.2728608 0.6679123 -0.6963862 -0.2625632 0.823489 -0.5042809 -0.259936 0.7789443 -0.5798081 -0.2388903 0.9118672 -0.3296377 -0.2446167 0.8947827 -0.3829146 -0.2296527 0.9697293 -0.1505935 -0.1922158 0.977581 0.03054767 -0.2083321 0.9768417 0.03061592 -0.2117618 0.9520125 0.2268669 -0.205435 0.940928 0.2258692 -0.2522652 0.8946042 0.3702042 -0.2502641 0.8801248 0.3651193 -0.3034274 0.824529 0.4775496 -0.3034773 0.8085742 0.4671803 -0.3577019 0.7409691 0.5680039 -0.3582408 0.7259733 0.5528739 -0.4090152 0.6382048 0.6527486 -0.4081838 0.6265177 0.6346458 -0.4524384 0.5136358 0.7321979 -0.4472858 0.50672 0.7138674 -0.483351 0.3601779 0.8063079 -0.4691902 0.3581197 0.790814 -0.4963503 0.1756999 0.866506 -0.4672226 0.1768566 0.8561798 -0.4854667 0.0740801 0.8493129 -0.5226662 0.1825079 0.8130316 -0.5528748 0.1825239 0.8282297 -0.5298308 0.2624549 0.7941538 -0.5481216 0.3165819 0.7515091 -0.5788004 0.3330321 0.7462835 -0.5763251 0.443104 0.6705022 -0.5950509 0.4242906 0.6742159 -0.6044919 0.5359367 0.5725592 -0.6204416 0.5211901 0.5775049 -0.6283701 0.6065308 0.4757083 -0.6370416 0.5971751 0.4802133 -0.6424774 0.6598738 0.38366 -0.646043 0.6566869 0.3857057 -0.648069 0.7030096 0.2926471 -0.6481784 0.7059966 0.2901262 -0.6460617 0.7407249 0.1942415 -0.6431151 0.7483209 0.1857764 -0.6367912 0.7724624 0.0805304 -0.6299339 0.7822753 0.0653854 -0.6194918 0.7928149 -0.05061024 -0.6073576 0.8019493 -0.07214862 -0.5930193 0.7956961 -0.1863374 -0.5763213 0.7706749 -0.1755801 -0.6125619 0.7739274 -0.200893 -0.6005651 -0.2073349 0.9011589 -0.3806899 -0.2495837 0.8899602 -0.381679 -0.3229644 0.8834747 -0.339362 -0.4370448 0.8475243 -0.3011552 -0.4353716 0.8462678 -0.3070544 -0.4328104 0.8469255 -0.3088565 -0.4434739 0.8412172 -0.3093295 -0.4417612 0.8395597 -0.3162066 -0.3341517 0.8699235 -0.3627339 -0.3434416 0.8660956 -0.3632166 -0.2256298 0.8830872 -0.4113981 -0.2391908 0.8791898 -0.4120839 -0.1199426 0.8808216 -0.4580034 -0.1372659 0.8777923 -0.458954 0.7360244 0.6603721 -0.1489186 0.6198037 0.7671082 -0.1654944 0.6139293 0.7568223 -0.2243006 0.5045423 0.8323308 -0.2294833 0.5005459 0.8179977 -0.2834318 0.3651476 0.8859277 -0.286006 0.3646704 0.8710279 -0.3291294 0.1951878 0.9253513 -0.3250027 0.1979679 0.913097 -0.3564584 -0.01908206 0.9408146 -0.3383843 0.0126295 0.9358207 -0.3522502 -0.251021 0.914766 -0.3165307 -0.2451388 0.9092175 -0.3364974 -0.4918462 0.8265948 -0.2735482 -0.4905882 0.8259838 -0.277622 -0.4896864 0.826263 -0.2783824 -0.5342224 0.790004 -0.3008326 -0.5453094 0.7960749 -0.2624933 -0.5461698 0.7955439 -0.2623141 0.0753408 0.8371138 -0.5418159 0.05304181 0.8376545 -0.5436191 0.160049 0.8007022 -0.5772871 0.1368075 0.803339 -0.579595 0.2350984 0.7581452 -0.6082309 0.2118788 0.7627328 -0.6110206 0.3014336 0.7112653 -0.6350114 0.2790518 0.7175034 -0.6382154 0.3597079 0.661671 -0.6578767 0.3388322 0.6691538 -0.6613819 0.4096674 0.6115458 -0.6768934 0.3908544 0.6197479 -0.680548 0.4526449 0.5617037 -0.6925328 0.4362669 0.570115 -0.696161 0.4901484 0.5122666 -0.7052217 0.4764978 0.5203778 -0.7086304 0.523194 0.4634307 -0.7151924 0.5124591 0.4707104 -0.7182043 0.5519058 0.4162716 -0.7225773 0.5442044 0.4221659 -0.7249948 0.5772758 0.3705948 -0.7276073 0.5726704 0.3745594 -0.7292147 0.6003418 0.3256808 -0.7304257 0.5988257 0.3271437 -0.7310163 0.6219086 0.2807061 -0.7310498 0.6233534 0.2791373 -0.7304198 0.6424645 0.2348091 -0.7294546 0.6464607 0.2299451 -0.7274708 0.6622703 0.1868978 -0.7255808 0.6682887 0.1785497 -0.7221567 0.6813274 0.1356675 -0.7192965 0.6887816 0.12375 -0.7143291 0.6992256 0.08018815 -0.7103897 0.7074878 0.06469982 -0.7037578 0.7150875 0.02101373 -0.6987191 0.7234838 0.002027451 -0.6903384 0.7282158 -0.04264175 -0.6840202 0.7360345 -0.06483566 -0.6738321 0.7376317 -0.111934 -0.6658605 0.7441177 -0.1368779 -0.6538756 0.7419168 -0.1874979 -0.6437422 0.746356 -0.2144705 -0.6300439 0.7395041 -0.2679356 -0.6175308 0.7413399 -0.2959565 -0.6023495 0.7286888 -0.3528984 -0.5869203 0.7275788 -0.3807459 -0.5706678 0.7074158 -0.4421134 -0.5514515 0.7033128 -0.4683836 -0.5347598 0.6795532 -0.521768 -0.5157187 -0.8720428 -0.4894297 0 -0.8592772 -0.511506 0.002061486 -0.859257 -0.5115406 -0.001924335 -0.7805736 -0.6249774 -0.01040351 -0.7806202 -0.6249391 -0.009129822 -0.6711123 -0.7408153 -0.0283035 -0.6710599 -0.7408382 -0.02894014 -0.6279127 -0.7777667 -0.02837055 -0.6290184 -0.7772637 -0.01403915 -0.5091496 -0.8596937 -0.04115402 -0.5108458 -0.859549 -0.01456212 -0.4245941 -0.9046059 -0.03752464 -0.396099 -0.9172999 -0.04082322 -0.3004699 -0.9513871 -0.06767964 -0.3015713 -0.9522843 -0.04700452 -0.1760064 -0.9804344 -0.08814787 0.8355751 0.531248 -0.1399645 0.7480528 0.6479309 -0.1435359 0.7404044 0.6395972 -0.2066804 0.6441814 0.7351376 -0.2111944 0.6370586 0.7221233 -0.2696189 0.5254316 0.8058025 -0.2731371 0.5209617 0.7900326 -0.3231835 0.3806033 0.8664621 -0.3230859 0.3799188 0.8509247 -0.3627518 0.2042433 0.9125443 -0.3543272 0.2068339 0.9003139 -0.3829553 -0.009807467 0.9331724 -0.3592956 -0.005388319 0.9248304 -0.3803416 0.009127736 0.9214439 -0.3884044 -0.01865708 0.9170396 -0.3983595 -0.01584559 0.9109885 -0.4121275 -0.02847284 0.9084828 -0.4169512 -0.02615058 0.9030399 -0.42876 -0.04078102 0.89959 -0.4348275 -0.03425663 0.8822712 -0.4694936 -0.003996312 0.8838236 -0.4678031 -0.00156331 0.8747926 -0.4844952 -0.02108877 0.8738324 -0.4857697 -0.01896071 0.8648077 -0.5017452 -0.03925579 0.8633517 -0.5030734 -0.9284473 -0.3714532 -0.002897202 -0.9245479 -0.3810663 0 -0.9245414 -0.3810811 6.32864e-4 -0.8791341 -0.4765746 0 -0.8775364 -0.4795097 6.76703e-4 -0.8763102 -0.4817473 0 -0.8763098 -0.4817481 0 -0.9137462 -0.4062856 0 -0.9151802 -0.4030439 9.40906e-4 -0.9447088 -0.3279071 -0.001574456 -0.9480142 -0.3182271 8.26249e-4 -0.969193 -0.2462723 -0.003866732 -0.9730818 -0.2304592 -5.6738e-4 -0.9869868 -0.1606359 -0.007300794 -0.9902397 -0.1393277 -0.00364542 -0.9974011 -0.07097649 -0.01239693 -0.9989439 -0.04507982 -0.008881568 -0.999597 0.0206682 -0.01946258 -0.9986165 0.04992282 -0.01651763 -0.9930462 0.114076 -0.02908682 -0.989028 0.1452295 -0.02705311 -0.9769067 0.2094771 -0.04210197 -0.9696686 0.2409266 -0.04119491 -0.9500978 0.3062639 -0.0593031 -0.9398927 0.3362331 -0.05957496 -0.9122883 0.4014876 -0.08085769 -0.899897 0.4282882 -0.08218628 -0.8629072 0.4938338 -0.1073285 -0.8495707 0.5160041 -0.1094053 -0.8010352 0.5821582 -0.1394081 -0.7884572 0.5985358 -0.1417403 -0.7262332 0.6641887 -0.1773099 -0.7165195 0.6741335 -0.1792869 -0.6404734 0.7358076 -0.219957 -0.6357787 0.7395714 -0.2209515 -0.5451301 0.7948159 -0.2666476 -0.5474381 0.7933939 -0.2661537 -0.4409098 0.8397326 -0.3169353 -0.4517263 0.8336029 -0.317883 -0.3420441 0.8640071 -0.3694558 -0.3516259 0.8598616 -0.3701316 -0.2373305 0.8753911 -0.4211469 -0.2511976 0.871097 -0.4220067 -0.1351883 0.8716484 -0.4711192 -0.1528839 0.8681288 -0.4722065 -0.03741383 0.8543148 -0.5184078 -0.05820202 0.852302 -0.5198019 0.05401837 0.8253592 -0.562018 0.03108429 0.8253117 -0.5638212 0.1362134 0.7877015 -0.6008097 0.1121848 0.7897704 -0.6030567 0.2090157 0.743918 -0.6347429 0.1848725 0.7479962 -0.6374354 0.2732623 0.695881 -0.6641365 0.2498621 0.7016941 -0.6672289 0.3295705 0.6452776 -0.6892026 0.3076367 0.6524228 -0.6926068 0.3777478 0.5942661 -0.7100383 0.3578599 0.6022585 -0.7135973 0.4190918 0.5437274 -0.7271331 0.4016955 0.5520334 -0.7306846 0.4551419 0.4938171 -0.740939 0.4405545 0.5019025 -0.7443156 0.486918 0.4446991 -0.751767 0.4753836 0.4520193 -0.7547775 0.5146279 0.3973723 -0.7597721 0.5063161 0.4033442 -0.7622057 0.5392919 0.3515968 -0.7652085 0.5342912 0.3556338 -0.7668492 0.5619655 0.3066177 -0.7682321 0.5603058 0.3081188 -0.7688435 0.5834133 0.2616328 -0.7688806 0.5849955 0.2600131 -0.7682275 0.6040648 0.2159664 -0.7671144 0.608459 0.2109344 -0.7650388 0.6241765 0.1685301 -0.7628901 0.6308542 0.1598806 -0.7592505 0.6437762 0.1180183 -0.7560582 0.6521329 0.1056241 -0.7507106 0.6624902 0.0634523 -0.7463783 0.6718544 0.04727321 -0.7391731 0.6794826 0.005240857 -0.7336729 0.6891326 -0.01463454 -0.7244875 0.6940286 -0.05742299 -0.7176538 0.7031962 -0.08069729 -0.7064015 0.70515 -0.1256863 -0.6978299 0.7130341 -0.1518967 -0.6844778 0.7114282 -0.2002006 -0.673639 0.7172162 -0.2285402 -0.6583087 0.7112482 -0.2795746 -0.6449528 0.7143245 -0.3090175 -0.6278924 0.7028888 -0.3634185 -0.6114526 0.7028294 -0.3926708 -0.5931616 0.68426 -0.4513731 -0.572757 0.681037 -0.4789325 -0.5539065 0.6434084 -0.5619803 -0.5198112 0.6321017 -0.5498471 -0.5459997 0.626927 -0.5751254 -0.5255409 0.6100128 -0.5579435 -0.5626577 0.6059593 -0.5836747 -0.5404973 -0.9989398 -0.04603636 4.94459e-5 -0.5616428 0.8273798 3.69768e-5 0.5343787 0.8452453 -3.57228e-6 0.7176344 -0.69642 -4.74718e-4 0.6611226 -0.7502747 -0.002191126 0.9850056 -0.1725224 -3.65802e-4 0.9471352 -0.3208307 -0.00168544 0.9476844 -0.3192048 -0.001640617 0.8663151 -0.499498 3.1305e-6 0.8199543 -0.5724291 -9.20208e-7 0.939123 0.3435813 -1.77373e-4 0.9848975 0.1731238 -0.002254664 0.980318 0.1974183 -0.001660346 0.9999934 0.003652632 1.83892e-5 0.9941999 -0.1075479 -1.15944e-5 0.7502782 0.6611223 4.27367e-5 0.6233596 0.7819146 -0.005709767 0.6972111 0.7168571 -0.003565192 0.7647224 0.6443581 -0.001564919 0.8584051 0.5129725 -2.94654e-6 0.9022493 0.4312147 3.11523e-7 -0.1974082 0.9803215 -6.76604e-5 -0.3007642 0.9536907 -0.003882348 -0.03961175 0.9992152 1.83716e-4 0.3191966 0.9476885 -3.95247e-4 0.2162799 0.9763238 -0.003865897 0.4270713 0.9042179 -3.38017e-4 -0.9476867 0.3192022 -1.13093e-4 -0.996146 0.08722221 -0.009248495 -0.976086 0.2173391 -0.004471302 -0.9302142 0.3670138 -0.001600205 -0.8772332 0.4800648 2.1324e-5 -0.6611265 0.7502745 -6.21884e-5 -0.801474 0.5979785 -0.007819831 -0.7252228 0.6885017 -0.004161536 -0.5720809 -0.8201972 3.29166e-6 -0.633134 -0.7740423 -2.67973e-4 -0.7509958 -0.6603037 -0.002147078 -0.7502817 -0.6611151 -0.002116203 -0.8605366 -0.5093886 -1.59349e-6 -0.9803198 -0.197416 5.80021e-6 -0.9148057 -0.4038036 -0.008562982 -0.9649901 -0.2622605 -0.003675043 -0.2490501 -0.9684903 -7.70389e-4 -0.3191978 -0.947685 -0.002466678 -0.3801853 -0.9249094 -0.001437306 -0.4764766 -0.8791872 -1.58592e-5 0.5313547 -0.8471495 0 0.3311522 -0.9435774 0 0.1974052 -0.980319 -0.002424776 0.08854556 -0.9960721 -2.55129e-4 -0.08439755 -0.9964323 6.24092e-5 0.9912139 0.1322692 0 -0.9912143 -0.1322661 0 -0.5299692 0.8477796 0.02005726 -0.6487641 0.7609897 0 -0.6366781 0.7711029 -0.006445765 -0.7202035 0.6937108 0.008500516 -0.9348812 -0.3543937 0.02005875 -0.9165496 -0.3999211 0 -0.8729401 -0.4878276 0 -0.7711026 -0.6366784 -0.006444215 -0.6937087 -0.7202056 0.008507132 -0.7049947 -0.7092126 0 0.5299692 -0.8477796 0.02006036 0.6487623 -0.7609912 0 0.6366781 -0.7711029 -0.006444215 0.720205 -0.6937093 0.008500516 0.9348812 0.3543937 0.02005982 0.9165511 0.3999176 0 0.8729383 0.4878308 0 0.7711026 0.6366784 -0.006447255 0.693707 0.7202071 0.008505046 0.7049936 0.7092137 0 -0.8141797 0.5805263 0.01003062 -0.890595 0.4547973 0 -0.9117934 0.4105266 0.01003217 -0.9308842 0.3653146 0 -0.962208 0.2723155 0 -0.974363 0.2247582 0.01003062 -0.9842659 0.1766937 0 -0.9968467 0.07935267 0 -0.999489 0.03035509 0.01003098 -0.9931393 -0.1166277 0.008507072 -0.9734573 -0.228778 -0.006444275 -0.976961 -0.2134183 0 -0.9513365 -0.3081539 0 -0.7049979 -0.7092095 0 -0.5805229 -0.8141822 0.01003217 -0.5399052 -0.8417258 0 -0.4105276 -0.911793 0.0100311 -0.365313 -0.9308848 0 -0.2247596 -0.9743627 0.01003116 -0.1766919 -0.9842663 0 -0.07935678 -0.9968463 0 -0.03035187 -0.999489 0.01003116 0.01873159 -0.9998246 0 0.1166297 -0.9931391 0.008504688 0.2287788 -0.9734571 -0.006445765 0.8141807 -0.5805249 0.01003062 0.8905984 -0.4547907 0 0.9117912 -0.4105318 0.0100314 0.9308871 -0.3653074 0 0.9622092 -0.2723116 0 0.9743621 -0.2247621 0.0100314 0.9842644 -0.1767017 0 0.996846 -0.07936096 0 0.9994891 -0.03034883 0.01003164 0.9912146 0.132263 0 0.9931388 0.1166318 0.008507072 0.9734546 0.2287896 -0.006444275 0.9769635 0.2134063 0 0.9513353 0.3081577 0 0.7049967 0.7092106 0 0.580524 0.8141815 0.0100311 0.5399075 0.8417245 0 0.4105263 0.9117937 0.0100311 0.3653103 0.9308859 0 0.2247611 0.9743623 0.01003217 0.1766949 0.9842658 0 0.07935369 0.9968466 0 0.03035187 0.999489 0.01003009 -0.01872849 0.9998246 0 -0.1166297 0.9931391 0.008508801 -0.2287788 0.9734571 -0.006439626 0 0 1 0.4444112 -0.895823 0 0.4444102 -0.8958235 0 0.8199062 0.5724438 -0.007883727 -0.1603642 -0.8161047 -0.5552088 0.6456617 -0.7308857 -0.2211949 0.3650321 0.9301869 -0.03878122 0.2717183 0.9601067 -0.06606304 -0.6532725 0.6062756 -0.4535032 0.862848 0.5054636 0 -0.7691609 -0.4428483 -0.4607351 0.9971271 -0.03062552 -0.0692808 -0.7081175 -0.4542019 -0.5406202 -0.6932775 -0.4395405 -0.5711134 -0.6926769 -0.4392617 -0.5720559 -0.6952887 -0.4391376 -0.5689744 -0.7141023 -0.432617 -0.5503639 -0.715457 -0.3842934 -0.5834723 -0.6866215 -0.4002697 -0.6069062 -0.7064712 -0.3544089 -0.6126115 -0.7068038 -0.3906066 -0.5897923 -0.7042232 -0.3926565 -0.5915156 -0.702038 -0.3945481 -0.5928528 -0.738761 -0.3206406 -0.5928084 -0.7389341 -0.3197067 -0.593097 -0.7387702 -0.3218271 -0.5921537 -0.7384811 -0.3272595 -0.5895313 -0.7368867 -0.3056023 -0.602997 -0.7122536 -0.3434365 -0.6121651 -0.7090167 -0.3493396 -0.6125825 -0.794772 -0.2932019 -0.5313854 -0.7920768 -0.2887373 -0.5378152 -0.7696272 -0.3026108 -0.5622284 -0.770098 -0.2886953 -0.5688621 -0.7692292 -0.2862467 -0.5712699 -0.7806119 -0.3812898 -0.4952407 -0.7829023 -0.3427069 -0.5192457 -0.7867514 -0.3394254 -0.5155702 -0.7890835 -0.3368821 -0.5136711 -0.751872 -0.4085426 -0.5174762 -0.7462099 -0.4225403 -0.5144226 -0.7453765 -0.4256244 -0.5130865 -0.7455156 -0.424919 -0.513469 -0.7461234 -0.4217851 -0.5151674 -0.7468411 -0.4118888 -0.5220881 -0.7482836 -0.4297007 -0.5054 -0.7747973 -0.3927006 -0.4954548 -0.7777917 -0.3870992 -0.4951711 0.9932174 -0.1063048 -0.0471037 0.9958912 -0.07448613 -0.05150383 0.997043 0.07240074 -0.02576011 0.9959747 0.08580082 -0.02593815 0.9719685 0.234987 -0.007644653 0.9698659 0.2434973 -0.00831741 0.9351569 0.3542339 0 0.9885354 -0.126398 -0.08259195 0.9941132 -0.09084886 -0.05903762 0.9934089 -0.09174829 -0.06871056 0.9956206 0.08476209 -0.03943371 0.9968876 0.06909316 -0.03796595 0.9698541 0.2430683 -0.01734507 0.9950034 0.0987634 -0.01462912 0.9805051 0.1959893 -0.01407545 0.8419642 -0.5108594 -0.1735487 0.7947201 -0.5736578 -0.1983352 0.8367877 -0.5106229 -0.197613 0.6829077 -0.6915504 -0.2353617 0.9868943 -0.1273427 -0.09911376 0.9608711 -0.2591031 -0.09794169 0.9823904 -0.1638898 -0.08971726 -0.7115554 -0.4556287 -0.5348752 -0.7297567 -0.4560955 -0.5093448 -0.6828702 -0.5253362 -0.5076516 -0.04157733 -0.9650062 -0.2589102 -0.8392919 -0.5073628 -0.1953768 -0.7576053 -0.6219215 -0.1981113 -0.7480783 -0.6114376 -0.2579207 -0.6549578 -0.7091225 -0.2611044 -0.6466516 -0.694385 -0.3157075 -0.5342148 -0.7835287 -0.3173287 -0.5290925 -0.7667199 -0.3635956 -0.385786 -0.8492781 -0.3604109 -0.3847606 -0.8334168 -0.3967062 -0.205244 -0.9004393 -0.3835154 -0.2075138 -0.8884504 -0.4093825 0.02285319 -0.9475202 -0.3188782 -0.1786442 -0.9267827 -0.3303939 -0.1759133 -0.9388121 -0.2961188 -0.3357039 -0.8940655 -0.2965636 -0.3362524 -0.9079893 -0.2499796 -0.463153 -0.8516586 -0.2452893 -0.466948 -0.8637701 -0.1893693 -0.5529729 -0.8099608 -0.1954089 0.0693463 -0.9574262 -0.2802252 -0.09742385 -0.9543684 -0.2822939 -0.09609818 -0.9652139 -0.2431612 -0.2006253 -0.949882 -0.2397372 0.2100832 -0.9340021 -0.288973 0.3128904 -0.9105566 -0.2701599 0.3104396 -0.9067226 -0.2854495 0.5031813 -0.8223305 -0.2656713 0.5028108 -0.8220795 -0.2671453 0.701223 -0.6767052 -0.2244028 0.7043771 -0.6770418 -0.213231 0.8589755 -0.4882105 -0.1543101 0.8617746 -0.4873071 -0.1409831 0.3894513 -0.8788178 -0.2756935 0.5314728 -0.8052796 -0.2627954 0.5183094 -0.8117787 -0.2690179 0.6903598 -0.6842131 -0.2350655 0.6929908 -0.6850937 -0.2245227 0.8552893 -0.4883717 -0.1731281 0.859418 -0.4874333 -0.1543033 -0.8554198 -0.2391243 -0.4594308 -0.8573925 -0.2357275 -0.4575051 -0.8828074 -0.114996 -0.4554418 -0.8850867 -0.1092289 -0.4524278 -0.8937459 0.02666985 -0.4477803 -0.8954225 0.03452837 -0.4438766 -0.8803808 0.1899268 -0.4345776 -0.8805725 0.1990924 -0.4300634 -0.8316421 0.3708598 -0.4133213 -0.8299007 0.379846 -0.4086344 -0.7331215 0.5638103 -0.3803301 -0.8406639 -0.3543118 -0.4095699 -0.8174297 -0.3456938 -0.4607651 -0.818265 -0.3446196 -0.4600868 -0.7956866 -0.336157 -0.5038664 -0.7764943 -0.347711 -0.5255033 -0.8792101 -0.2435323 -0.4094896 -0.8796713 -0.2426377 -0.4090299 -0.905649 -0.1146783 -0.4082266 -0.9061409 -0.1132162 -0.4075424 -0.9138404 0.03125333 -0.4048691 -0.9141474 0.03315502 -0.404024 -0.8960307 0.1976574 -0.3975684 -0.8959808 0.1997218 -0.3966482 -0.841757 0.3797538 -0.3837087 -0.8413341 0.3815683 -0.382835 -0.7376734 0.5715063 -0.3594698 -0.7371528 0.5725429 -0.3588879 -0.5762779 0.7511815 -0.3219166 0.1175158 0.9824419 -0.1449072 -0.5731288 0.7497176 -0.3308277 -0.3644067 0.8901585 -0.2735428 -0.3606971 0.8916656 -0.2735512 -0.1133311 0.9727032 -0.2024962 -0.1128612 0.9705795 -0.2126924 -0.1151278 0.97009 -0.2137079 0.1318905 0.9792206 -0.1540518 0.6706919 0.7411869 -0.0285359 0.7751173 0.6317642 -0.008188188 0.8419876 0.5394958 -0.001146018 0.8627702 0.5055517 -0.006731986 -0.5766266 0.7547231 -0.3128818 -0.573169 0.7583454 -0.3104669 -0.7408 0.5785585 -0.3412998 -0.7375612 0.5843826 -0.3383791 -0.8495036 0.3886929 -0.3567374 -0.8475317 0.3956395 -0.3537787 -0.9087879 0.2060682 -0.362823 -0.9082938 0.2129171 -0.3600953 -0.9308485 0.03708934 -0.3635182 -0.9315004 0.04290652 -0.3612009 -0.9254339 -0.1127987 -0.36173 -0.9266538 -0.1085088 -0.3599148 -0.9001044 -0.2462873 -0.3593811 -0.5734268 0.7608275 -0.3038477 -0.5656997 0.7684156 -0.2992012 -0.7398881 0.5897076 -0.3237448 -0.7314745 0.6034497 -0.3174799 -0.8534809 0.4027174 -0.3307402 -0.8475782 0.4202575 -0.3240293 -0.9183828 0.2198782 -0.3289781 -0.9161388 0.23797 -0.3225834 -0.945266 0.04796659 -0.3227558 -0.9462292 0.06391692 -0.3171199 -0.9429903 -0.1066247 -0.3152787 -0.9826389 0.07836252 -0.1681673 -0.9674134 -0.2035548 -0.1505887 -0.9589647 -0.202756 -0.198184 -0.9084893 -0.3695874 -0.1950706 -0.8970183 -0.3655933 -0.2483945 -0.8363993 -0.488562 -0.2484822 -0.8228785 -0.4796744 -0.3046041 -0.7522724 -0.5835919 -0.305789 -0.7390035 -0.5697939 -0.3594562 -0.6500512 -0.6692035 -0.3600003 -0.6393945 -0.651997 -0.4075225 -0.5265437 -0.7475945 -0.4047889 -0.5201542 -0.7295615 -0.4440491 -0.3740357 -0.8197163 -0.4337773 -0.3722825 -0.8039237 -0.4638022 -0.1897393 -0.8776393 -0.4401686 -0.1912551 -0.8666427 -0.4608166 -0.9348492 -0.330586 -0.1294987 -0.8939162 -0.4269858 -0.1363716 -0.8478333 -0.5130323 -0.1340772 -0.9743341 -0.1731013 -0.1439063 -0.9207628 -0.3644596 -0.1391584 -0.9123145 -0.3615283 -0.1923006 -0.8443394 -0.5000622 -0.1924293 -0.8333492 -0.4927628 -0.2504277 -0.7582582 -0.601146 -0.2523255 -0.746832 -0.5888682 -0.3089927 -0.6561432 -0.6876313 -0.3108689 -0.646627 -0.6715256 -0.3618384 -0.5338994 -0.764441 -0.3613605 -0.5281132 -0.7468975 -0.4040305 -0.3830167 -0.8338705 -0.3974398 -0.3816183 -0.8179484 -0.4304973 -0.1999544 -0.8888742 -0.4122148 -0.201852 -0.8773123 -0.4354066 -0.7299633 0.5706291 -0.3762127 -0.5757939 0.7465889 -0.3332661 -0.5762902 0.7511681 -0.3219258 -0.360439 0.892704 -0.2704874 -0.3634234 0.8917204 -0.2697373 -0.3571853 0.8942329 -0.2697523 -0.3570131 0.8950319 -0.2673192 -0.3584933 0.8945327 -0.2670093 -0.5659046 0.7698612 -0.2950693 -0.5531401 0.7815644 -0.2884323 -0.7331097 0.6070502 -0.3066598 -0.7178526 0.6295125 -0.2973241 -0.8519185 0.4254153 -0.3053799 -0.8399323 0.4554191 -0.2951392 -0.9237518 0.2433758 -0.2957211 -0.9178495 0.275533 -0.2857167 -0.9569309 0.06807857 -0.2822212 0.1294155 0.9771834 -0.1684172 0.1019364 0.9785277 -0.179144 -0.1142893 0.9682272 -0.2224276 -0.1264138 0.96569 -0.2268533 -0.3503554 0.8977102 -0.2671471 -0.3503291 0.8981593 -0.265668 -0.5532472 0.7820684 -0.2868564 -0.5348617 0.7976952 -0.2785776 -0.7188727 0.631477 -0.2906182 -0.6949632 0.6628553 -0.2786556 -0.8428474 0.4586882 -0.2814489 -0.821851 0.5027156 -0.268026 -0.9232394 0.2792925 -0.2638651 0.6481094 0.7602578 -0.04429918 0.6703243 0.7413134 -0.03346449 0.7682491 0.63993 -0.01681989 0.768369 0.6398743 -0.0130428 0.7139149 0.6993577 -0.03499227 0.6482554 0.7602452 -0.04233723 0.5620428 0.8239266 -0.07247817 0.4191561 0.9027341 -0.09684729 -0.451862 0.8085811 -0.3768519 -0.4591081 0.7980165 -0.3903709 -0.5148942 0.7402053 -0.432412 -0.5225261 0.7240854 -0.4501854 -0.5664187 0.6643986 -0.4875904 -0.5727888 0.6433581 -0.5079402 -0.6623725 -0.2734007 -0.6975061 -0.6823019 -0.2479706 -0.6877316 -0.7011509 -0.1957535 -0.6856151 -0.7015851 -0.1775057 -0.6901233 -0.7233367 -0.1410202 -0.6759418 -0.7369998 -0.08123928 -0.6709929 -0.7355946 -0.06656759 -0.6741435 -0.7734846 0.1224309 -0.6218782 -0.7589372 0.06177955 -0.6482266 -0.7619151 0.04867017 -0.6458457 -0.7558771 -0.01798427 -0.6544666 -0.7687484 -0.2857193 -0.5721805 -0.7459303 -0.2844495 -0.6022263 -0.7724706 -0.2085573 -0.5998277 -0.7786901 -0.2008609 -0.5943876 -0.8029793 -0.09294551 -0.588715 -0.8108461 -0.07936108 -0.579854 -0.8209767 0.04027825 -0.5695392 -0.8280194 0.05943614 -0.5575404 -0.8184272 0.1962756 -0.540049 -0.7911156 0.2714848 -0.5481169 -0.7698777 0.3557491 -0.5298406 -0.7591357 0.3750687 -0.5320118 -0.744665 0.4485818 -0.4942151 -0.7228017 0.496227 -0.4809538 -0.4921013 0.7982046 -0.3474275 -0.5067691 0.784093 -0.3583061 -0.5706214 0.7230011 -0.3894365 -0.5885811 0.7000975 -0.404272 -0.6363843 0.6407379 -0.4294998 -0.6549058 0.6093003 -0.4470476 -0.7089502 0.5183132 -0.4782691 -0.7183663 0.5312468 -0.4491401 -0.7818083 0.3955055 -0.4820283 -0.7812367 -0.2989279 -0.5480068 -0.7632688 -0.3284139 -0.5563858 -0.8021318 -0.22108 -0.5547145 -0.8069654 -0.2144246 -0.5502991 -0.8315141 -0.1032543 -0.5458232 -0.8374807 -0.09164679 -0.5387274 -0.8472208 0.03230369 -0.5302578 -0.8523055 0.04851406 -0.5207896 -0.8412492 0.1904781 -0.5059822 -0.8433836 0.2098243 -0.4946492 -0.8018817 0.3682386 -0.470517 -0.4735007 0.8040683 -0.3595432 -0.4891981 0.7878494 -0.3741371 -0.5449021 0.7328827 -0.4073877 -0.5635469 0.7071096 -0.427096 -0.6043593 0.6546787 -0.4540328 -0.6231591 0.6194988 -0.4773826 -0.6724287 0.5326935 -0.5138846 -0.6830087 0.5454646 -0.4857648 -0.7245658 0.4581643 -0.5148687 -0.7292979 0.4334636 -0.5293712 -0.7510984 0.3692036 -0.5473024 -0.7530688 0.3430454 -0.5614333 -0.7669559 0.2833374 -0.5757593 -0.7661663 0.2570202 -0.5890076 -0.3779365 0.8661691 -0.3269788 -0.3891306 0.8617823 -0.3254362 -0.462591 0.8052049 -0.3710184 -0.4699215 0.7953672 -0.382838 -0.5293807 0.7349719 -0.4237601 -0.5374439 0.719673 -0.4395735 -0.5841597 0.6576966 -0.4755972 -0.5914385 0.6370376 -0.4943519 -0.303057 0.9146733 -0.2674497 0.1027729 0.987928 -0.115914 0.1296264 0.9865612 -0.09946918 2.08503e-4 0.9891549 -0.1468759 0.0216729 0.9908593 -0.133147 -0.1033576 0.9777237 -0.1826841 -0.08914208 0.9808592 -0.1731153 -0.2042254 0.9533254 -0.2224021 0.1277652 0.9846827 -0.1186429 0.1552 0.982404 -0.1039012 0.02020442 0.9886145 -0.1491079 0.04280436 0.9896982 -0.1366206 -0.08996838 0.978828 -0.1838521 -0.789523 -0.3363156 -0.5133666 -0.7969319 -0.3249443 -0.5092259 -0.8297587 -0.2314286 -0.5078794 -0.8331841 -0.2261673 -0.5046312 -0.8581101 -0.110854 -0.5013567 -0.862212 -0.1017884 -0.4962153 -0.871501 0.02743494 -0.4896258 -0.8747838 0.03996574 -0.4828625 -0.8619839 0.1880053 -0.4707842 -0.8629553 0.2028044 -0.4627943 -0.818127 0.3674557 -0.4423174 -0.8158767 0.3822405 -0.4338635 -0.7248889 0.5603197 -0.4007217 -0.7200313 0.5718811 -0.3930738 -0.5723965 0.7441396 -0.3444104 -0.5677651 0.7499449 -0.3394488 -0.3606684 0.89131 -0.2747448 -0.3616008 0.8862336 -0.2895427 -0.3037809 0.9166861 -0.2596226 -0.3039549 0.9157451 -0.2627209 -0.3029933 0.9162349 -0.2621238 -0.1909437 0.9572674 -0.217209 -0.1913204 0.9562811 -0.2211857 -0.1233284 0.9699431 -0.2097633 -0.1230412 0.9704126 -0.2077507 0.1343116 0.9815984 -0.1357381 0.1309123 0.9792789 -0.1545147 0.4741175 0.8785331 -0.05824196 0.4758536 0.8784368 -0.04372888 0.4735264 0.8796388 -0.04481542 0.4240324 0.9045327 -0.04491508 0.5573946 0.8299126 -0.02359014 0.5553568 0.8304309 -0.04431122 0.5299711 0.8462356 -0.05491721 0.5294879 0.8462748 -0.05883508 0.5291074 0.8464987 -0.05903661 0.5279422 0.8464964 -0.06870853 0.4974315 0.8635626 -0.08259272 0.4960092 0.8630064 -0.0958904 0.3235789 0.936793 -0.1331006 0.8326399 0.553811 -0.002023816 0.84201 0.5394616 7.69078e-4 0.7824191 0.6227271 -0.005601882 0.77513 0.6317531 -0.00784105 0.7250416 0.6886653 -0.007405638 0.6596745 0.7513197 -0.01866447 0.5877882 0.8085094 -0.0285958 0.6929541 0.7209448 -0.007297575 0.6922041 0.7214242 -0.02001881 0.781073 0.6244273 -0.003934502 0.7808951 0.6245981 -0.008964896 0.8627687 0.5055988 -5.80401e-5 0.8627684 0.5055994 0 0.2041121 0.9764813 -0.06944423 0.202979 0.9750666 -0.08969253 0.2330946 0.9697927 -0.07189631 0.2311422 0.9685132 -0.09249669 0.2611744 0.962237 -0.07673293 0.2591559 0.9613945 -0.09251397 0.1525856 0.9805642 -0.1233353 0.118465 0.9831541 -0.1391909 0.04103744 0.9878438 -0.1499357 -0.07567954 0.9794881 -0.1867502 -0.07424765 0.9817931 -0.1748418 -0.1984853 0.9546875 -0.221755 -0.1983076 0.9555502 -0.2181699 -0.3005414 0.916066 -0.2655148 0.3122668 0.9403539 -0.1349965 0.3129855 0.940921 -0.129259 0.3464666 0.9309679 -0.1151512 0.3486109 0.9317504 -0.1015464 0.348566 0.9317651 -0.1015657 0.3516991 0.9325103 -0.08205121 0.3332884 0.9382773 -0.09249168 0.3343428 0.9385695 -0.0854541 0.3581665 0.9306768 -0.07454866 0.3605046 0.9311629 -0.05451697 0.3299705 0.9413701 -0.07029902 0.3317688 0.942049 -0.04973053 0.07882928 0.9902518 -0.1148369 0.1037787 0.9898216 -0.09738147 -0.0185272 0.9890769 -0.1462323 8.99571e-4 0.9912689 -0.1318528 -0.1146719 0.9764719 -0.1826287 -0.1030902 0.9794304 -0.1734604 -0.2079903 0.9521089 -0.2241175 -0.2042236 0.9536727 -0.2209096 -0.2967168 0.9160002 -0.2700052 -0.300252 0.9138634 -0.2733178 -0.3897426 0.8614544 -0.3255723 -0.3909777 0.8660607 -0.3115692 -0.4010405 0.8583552 -0.3199888 -0.401688 0.8637136 -0.3043776 -0.4104204 0.8574785 -0.3102997 -0.4103968 0.8616688 -0.2984987 -0.5083258 0.7933776 -0.3348986 -0.5656673 0.7377745 -0.3683875 -0.5930862 0.7133221 -0.3733906 -0.7134342 0.5594363 -0.4219509 -0.7162925 0.5560086 -0.421639 -0.7997313 0.3877367 -0.4583559 -0.7833864 0.3721827 -0.497781 -0.8220402 0.2192955 -0.5255089 -0.7898998 0.202591 -0.578805 -0.6335542 0.50039 -0.5901008 -0.6344531 0.4704332 -0.6133205 -0.6497907 0.4167936 -0.6356533 -0.6470881 0.3850453 -0.6580404 -0.6561112 0.3350558 -0.6762069 -0.6501106 0.3036028 -0.6965498 -0.6542701 0.256756 -0.7113418 -0.6454626 0.226557 -0.7294175 -0.6457549 0.1827527 -0.7413516 -0.6347061 0.1543378 -0.7571843 -0.6319439 0.1134454 -0.7666662 -0.6197951 0.08832204 -0.7797778 -0.6144213 0.04891347 -0.7874605 -0.602274 0.02791035 -0.7978015 -0.5944595 -0.01113831 -0.8040485 -0.5830019 -0.02811437 -0.8119842 -0.5727784 -0.06726354 -0.8169459 -0.5624618 -0.08058261 -0.8228871 -0.5498036 -0.1201086 -0.8266136 -0.5416603 -0.12936 -0.8305842 -0.5261167 -0.1704183 -0.833162 -0.5210148 -0.1755782 -0.835294 -0.5020186 -0.219049 -0.836657 -0.5003151 -0.2205809 -0.8372747 -0.4773656 -0.2667695 -0.8372312 -0.4791269 -0.2653617 -0.8366723 -0.4517578 -0.3142517 -0.8349615 -0.4573625 -0.3102473 -0.8334064 -0.4247983 -0.3621485 -0.8296957 -0.4343632 -0.3561104 -0.8273537 -0.395848 -0.410961 -0.821228 -0.4089441 -0.4037128 -0.8184013 -0.3639925 -0.4608598 -0.8093935 -0.3799145 -0.4532268 -0.8063812 -0.3281949 -0.5116637 -0.794033 -0.3470516 -0.5040004 -0.7909101 -0.2876372 -0.5632637 -0.7745959 -0.3093341 -0.5560191 -0.7714631 -0.2414167 -0.615184 -0.750511 -0.2651558 -0.6089976 -0.7475389 -0.1885764 -0.6663287 -0.7214187 -0.2131405 -0.6617837 -0.7187584 -0.1283598 -0.7150275 -0.6872115 -0.1534896 -0.712349 -0.6848357 -0.06047654 -0.7596715 -0.647489 -0.08565127 -0.7590489 -0.6453748 0.01495516 -0.7982354 -0.60216 -0.00891602 -0.7997215 -0.6003051 0.09726363 -0.8282378 -0.5518713 0.07637083 -0.8314796 -0.550281 0.1850745 -0.8472086 -0.4979811 0.1673598 -0.8517265 -0.4965408 0.2765017 -0.8535904 -0.4415092 0.2621582 -0.8588006 -0.440153 0.3692907 -0.8463461 -0.3838266 0.3591094 -0.85125 -0.3826407 0.4610133 -0.8249568 -0.3269757 0.4504704 -0.8313825 -0.3253918 0.5496469 -0.7901666 -0.2711553 0.5462811 -0.7922465 -0.2718871 0.6324319 -0.7418347 -0.2229603 0.6355212 -0.7393792 -0.2223314 0.7085738 -0.682508 -0.1791819 0.7167864 -0.674272 -0.177693 0.7769648 -0.6136568 -0.1405384 0.7888769 -0.5986797 -0.1387663 0.836844 -0.5367792 -0.1075193 0.8499385 -0.516075 -0.106166 0.8877593 -0.4533372 -0.07980549 0.9001471 -0.4282982 -0.07934606 0.9293745 -0.3647144 -0.05697911 0.9400228 -0.336203 -0.05766135 0.9614841 -0.2721109 -0.03878372 0.9696915 -0.2409123 -0.04073971 0.9839594 -0.1766382 -0.02495902 0.9889956 -0.1452579 -0.02807104 0.9967375 -0.07936012 -0.0147081 0.9985762 -0.04997891 -0.01864993 0.9997975 0.01873862 -0.007344186 0.9989164 0.04502785 -0.01177525 0.9931727 0.1166279 -0.002491712 0.9902296 0.1392659 -0.007096886 0.976961 0.2134179 9.10372e-5 0.973088 0.2303994 -0.003986597 0.9513347 0.3081577 0.001085758 0.9480257 0.3181892 -0.001720666 0.9165477 0.3999242 0.001010835 0.9151819 0.4030411 0 0.8729411 0.4878257 0 0.8744577 0.4851008 0.001018941 0.8209164 0.5710445 -0.002135992 0.8326653 0.5537734 0.001935184 0.7609801 0.6487518 -0.00552535 0.7825509 0.6225829 0.002156734 0.6936957 0.7201934 -0.01037895 0.7252567 0.6884775 0.001217961 0.6197192 0.7846375 -0.01709347 0.6603314 0.7509726 -0.001637578 0.5397205 0.8414377 -0.02615952 0.5889059 0.808174 -0.006687223 0.4544682 0.8899572 -0.03788208 -0.6577719 0.489552 -0.5724292 -0.659928 0.4609028 -0.5933494 -0.6769238 0.404688 -0.6148186 -0.6756982 0.3742584 -0.6351085 -0.6859345 0.3222216 -0.6524317 -0.6814476 0.2915669 -0.6712809 -0.6865147 0.2428152 -0.6853747 -0.6792549 0.2133102 -0.702219 -0.6802119 0.1671703 -0.7136989 -0.6708475 0.1399335 -0.7282735 -0.6685035 0.09692651 -0.7373658 -0.6579105 0.07273918 -0.7495751 -0.65281 0.03175073 -0.7568562 -0.6418687 0.01115792 -0.7667334 -0.6341908 -0.02928584 -0.7726218 -0.6237151 -0.04602748 -0.7802955 -0.6133944 -0.08681076 -0.7849913 -0.604143 -0.09959822 -0.7906274 -0.5913277 -0.1404229 -0.7941114 -0.5839902 -0.1493096 -0.7979111 -0.5683811 -0.1910369 -0.8002799 -0.5635756 -0.1961932 -0.8024281 -0.5445708 -0.2399188 -0.8036676 -0.5428518 -0.2415683 -0.8043361 -0.5197601 -0.288033 -0.8042926 -0.5215419 -0.2865193 -0.8036795 -0.4939462 -0.3355775 -0.8021253 -0.4993164 -0.3315151 -0.8004879 -0.466536 -0.3833108 -0.7971305 -0.4754019 -0.3773417 -0.7947368 -0.4365166 -0.4320579 -0.7891637 -0.4487493 -0.424807 -0.7862335 -0.4029299 -0.4821205 -0.7779509 -0.4183318 -0.4741775 -0.7746964 -0.3655633 -0.5326408 -0.7633199 -0.3838497 -0.5245685 -0.7599259 -0.3234436 -0.583461 -0.7449548 -0.3442298 -0.5758109 -0.7415845 -0.2751582 -0.6344439 -0.7223358 -0.297967 -0.6277438 -0.7191339 -0.2195535 -0.6847053 -0.694964 -0.2437521 -0.6794552 -0.6920444 -0.1569021 -0.7321805 -0.6627922 -0.1817325 -0.7287439 -0.6602315 -0.08674877 -0.7752596 -0.6256576 -0.1113306 -0.7738711 -0.6234816 -0.008456349 -0.8121782 -0.5833481 -0.03179687 -0.8128943 -0.5815427 0.07769155 -0.8406084 -0.5360426 0.05662971 -0.8432307 -0.5345606 0.1689579 -0.8579627 -0.4851323 0.1510655 -0.8619967 -0.4838811 0.2635875 -0.8626063 -0.4317778 0.2495631 -0.8672975 -0.4307125 0.3601511 -0.8533068 -0.3770395 0.3503897 -0.8577519 -0.37615 0.4500609 -0.8314402 -0.3258107 0.9276898 0.373352 0 0.9985132 0.05111312 -0.01894783 0.9930037 -0.1141259 -0.03031551 0.9959303 -0.08450967 -0.03132295 0.9996018 -0.02066695 -0.0192157 0.9971932 0.07042092 -0.02543127 0.9136576 0.4061397 -0.01674664 0.944697 0.3279442 3.15833e-4 0.9752804 0.220872 -0.006619691 0.9691379 0.2459263 -0.01709115 0.9869838 0.1607379 -0.005143523 0.9497489 -0.3064853 -0.0635901 0.9233013 -0.3747261 -0.08423358 0.9222774 -0.3752932 -0.09251797 0.6404002 -0.7357759 -0.2202759 0.646215 -0.7310471 -0.2190349 0.7255414 -0.663995 -0.1808322 0.8621103 -0.4939213 -0.1131712 0.8129094 -0.5648126 -0.1420041 0.8113777 -0.5649666 -0.1499311 0.9588555 -0.2769324 -0.06248843 0.956821 -0.2785245 -0.08317285 0.9502021 -0.3011237 -0.08025234 0.9493787 -0.3017956 -0.0871759 0.9544874 -0.284823 -0.08848679 0.9527744 -0.2861942 -0.1015574 0.9527929 -0.2861324 -0.1015588 0.9499069 -0.2879291 -0.1215475 0.9396914 -0.3197169 -0.1214964 0.9350758 -0.3208355 -0.1506582 0.898754 -0.4116894 -0.1508421 0.8001416 -0.58209 -0.1447232 0.7359803 -0.6530255 -0.1785798 0.7341096 -0.6528444 -0.1867544 0.6976833 -0.6850096 -0.2097613 0.6988535 -0.6851361 -0.205408 0.491752 -0.8266509 -0.2735476 0.4929656 -0.8271784 -0.269742 0.2553289 -0.9135146 -0.3166989 0.2610316 -0.9188745 -0.2958585 0.01227438 -0.9487223 -0.3158727 0.06692808 -0.9524287 -0.2973217 -0.1461567 -0.9409498 -0.3053717 -0.1438491 -0.9524822 -0.2684868 -0.2886254 -0.919741 -0.2660301 -0.2897827 -0.9324021 -0.2159915 -0.3452909 -0.9132643 -0.2161542 0.911705 -0.4016907 -0.08624845 0.8751004 -0.4711434 -0.1105591 0.8730546 -0.4717696 -0.1233249 0.8544909 -0.50047 -0.1391946 0.8542121 -0.5005489 -0.1406152 0.705124 -0.6786856 -0.2053924 0.7028896 -0.6785761 -0.2132624 0.4959154 -0.8254105 -0.269751 0.4967397 -0.8257999 -0.2670288 0.2857746 -0.9110135 -0.2973003 0.2893267 -0.9152259 -0.2804493 0.1062083 -0.9511384 -0.2899233 0.108859 -0.9585645 -0.2632563 0.05336135 -0.9632039 -0.2634218 0.9257363 0.3781697 0 0.9276775 0.3733767 0.00210762 0.971969 0.2350075 -0.006919145 0.9752581 0.2210605 -0.002011597 0.9971344 0.07280564 -0.02055579 0.9985694 0.05140012 -0.01473635 0.9934113 -0.1059642 -0.04365313 0.9951771 -0.08575284 -0.04763424 0.9824377 -0.1796578 -0.05039292 0.9827892 -0.1791959 -0.0448814 0.9767478 -0.2096331 -0.04492008 0.227725 -0.8869025 -0.4019271 0.2146562 -0.8903997 -0.4013867 0.3357215 -0.871999 -0.3562427 0.3268557 -0.8755005 -0.3558991 0.3203355 -0.8806922 -0.3489506 0.3285952 -0.8775483 -0.3491911 0.2047339 -0.8973137 -0.3910399 0.217004 -0.894231 -0.3914846 0.1093469 -0.8982813 -0.4255985 0.1056004 -0.8895546 -0.4444561 0.1222958 -0.8869875 -0.4453055 -0.2596711 -0.7716137 -0.5806748 -0.2376638 -0.7765594 -0.5834993 -0.3279716 -0.7258096 -0.6046778 -0.3068712 -0.7323067 -0.607912 -0.3704759 -0.6899371 -0.6218798 -0.4099646 -0.6416633 -0.6482263 -0.5657925 -0.4512354 -0.6901201 -0.422204 -0.6361006 -0.6458481 -0.4716242 -0.5909718 -0.654464 -0.498038 -0.5454219 -0.6741463 -0.5105627 -0.5376715 -0.6709957 -0.5499095 -0.4906108 -0.6759443 -0.5800563 -0.4398472 -0.685616 -0.6102371 -0.3932428 -0.6877288 -0.6184232 -0.3619928 -0.6975056 -0.6352216 -0.3450874 -0.6909474 -0.6590771 -0.2969975 -0.6909486 0.2543973 -0.9065739 -0.3367577 0.250633 -0.9026427 -0.3498848 0.257798 -0.8995534 -0.3526244 -0.9618373 0.1476833 -0.2303447 -0.9726054 -0.06859731 -0.2221112 -0.962747 -0.07004237 -0.2611749 -0.9360672 -0.2399545 -0.2572939 -0.9217722 -0.2384938 -0.3057072 -0.8787587 -0.3674896 -0.3045234 -0.8613324 -0.3612185 -0.3572505 -0.8091822 -0.4664542 -0.3572739 -0.7908835 -0.4547075 -0.4095661 -0.725264 -0.5534719 -0.4094644 -0.7086655 -0.5371506 -0.4574522 -0.621665 -0.6374551 -0.4551745 -0.6090658 -0.6186016 -0.4963578 -0.4962304 -0.7176289 -0.4886351 -0.4888897 -0.6991392 -0.5217196 -0.342424 -0.7932373 -0.503508 -0.3401256 -0.7781535 -0.5280072 -0.1586986 -0.8552522 -0.4933139 -0.1606342 -0.8313543 -0.5320213 -0.09334653 -0.8643205 -0.4942029 -0.09543108 -0.8482754 -0.5208857 -0.7011948 -0.3953841 -0.5932936 -0.6821246 -0.4147233 -0.6022546 -0.6283404 -0.4959701 -0.5993347 -0.6363052 -0.4915885 -0.5945221 -0.5505492 -0.5930602 -0.5875162 -0.5632765 -0.5880078 -0.5804882 -0.451003 -0.6890061 -0.5673331 -0.7078397 -0.4281767 -0.5618077 -0.7232858 -0.4090307 -0.5563736 -0.6569775 -0.5109441 -0.5543616 -0.6634398 -0.5069221 -0.5503433 -0.5773302 -0.6080358 -0.5449609 -0.3215716 -0.7801378 -0.5366346 -0.4674816 -0.6848317 -0.5589871 -0.4751489 -0.7033696 -0.5286821 -0.5877998 -0.60322 -0.5390892 -0.6011863 -0.6227028 -0.5008155 -0.6876661 -0.521997 -0.5046134 -0.7057443 -0.5394031 -0.4593141 -0.7701013 -0.4419156 -0.4600595 -0.7906518 -0.454963 -0.4097297 -0.8404635 -0.3545934 -0.4097375 -0.8608099 -0.3620363 -0.3576817 -0.9012702 -0.2437481 -0.3581882 -0.9188451 -0.2458025 -0.3087153 -0.9457687 -0.09458434 -0.3107659 -0.9587838 -0.09281378 -0.2685502 -0.9570121 0.09740757 -0.2732024 -0.9648907 0.1005286 -0.2426518 -0.9105579 0.3288409 -0.2504959 0.2176488 0.9616105 -0.1671357 0.05644339 0.9792994 -0.1943885 0.1003501 0.9762325 -0.1920937 -0.03965687 0.9744001 -0.2212958 -0.1270174 0.9639134 -0.2339606 -0.1985833 0.9464846 -0.2544243 -0.3595435 0.8950405 -0.263877 -0.3774209 0.8862099 -0.268674 -0.5347608 0.7974012 -0.279611 -0.5181723 0.8104931 -0.2731274 -0.6958827 0.6642998 -0.2728608 -0.6679123 0.6963862 -0.2625632 -0.823489 0.5042809 -0.259936 -0.7789443 0.5798081 -0.2388903 -0.9118672 0.3296377 -0.2446167 -0.8947827 0.3829146 -0.2296527 -0.9697293 0.1505935 -0.1922158 -0.977581 -0.03054767 -0.2083321 -0.9768417 -0.03061592 -0.2117618 -0.9520125 -0.2268669 -0.205435 -0.940928 -0.2258692 -0.2522652 -0.8946042 -0.3702042 -0.2502641 -0.8801248 -0.3651193 -0.3034274 -0.824529 -0.4775496 -0.3034773 -0.8085742 -0.4671803 -0.3577019 -0.7409691 -0.5680039 -0.3582408 -0.7259733 -0.5528739 -0.4090152 -0.6382048 -0.6527486 -0.4081838 -0.6265177 -0.6346458 -0.4524384 -0.5136358 -0.7321979 -0.4472858 -0.50672 -0.7138674 -0.483351 -0.3601779 -0.8063079 -0.4691902 -0.3581197 -0.790814 -0.4963503 -0.1756999 -0.866506 -0.4672226 -0.1768566 -0.8561798 -0.4854667 -0.0740801 -0.8493129 -0.5226662 -0.1825079 -0.8130316 -0.5528748 -0.1825239 -0.8282297 -0.5298308 -0.2624549 -0.7941538 -0.5481216 -0.3165819 -0.7515091 -0.5788004 -0.3330321 -0.7462835 -0.5763251 -0.443104 -0.6705022 -0.5950509 -0.4242906 -0.6742159 -0.6044919 -0.5359367 -0.5725592 -0.6204416 -0.5211901 -0.5775049 -0.6283701 -0.6065308 -0.4757083 -0.6370416 -0.5971751 -0.4802133 -0.6424774 -0.6598738 -0.38366 -0.646043 -0.6566869 -0.3857057 -0.648069 -0.7030096 -0.2926471 -0.6481784 -0.7059966 -0.2901262 -0.6460617 -0.7407249 -0.1942415 -0.6431151 -0.7483209 -0.1857764 -0.6367912 -0.7724624 -0.0805304 -0.6299339 -0.7822753 -0.0653854 -0.6194918 -0.7928149 0.05061024 -0.6073576 -0.8019493 0.07214862 -0.5930193 -0.7956961 0.1863374 -0.5763213 -0.7706749 0.1755801 -0.6125619 -0.7739274 0.200893 -0.6005651 0.2073349 -0.9011589 -0.3806899 0.2495837 -0.8899602 -0.381679 0.3229644 -0.8834747 -0.339362 0.4370448 -0.8475243 -0.3011552 0.4353716 -0.8462678 -0.3070544 0.4328104 -0.8469255 -0.3088565 0.4434739 -0.8412172 -0.3093295 0.4417612 -0.8395597 -0.3162066 0.3341517 -0.8699235 -0.3627339 0.3434416 -0.8660956 -0.3632166 0.2256298 -0.8830872 -0.4113981 0.2391908 -0.8791898 -0.4120839 0.1199426 -0.8808216 -0.4580034 0.1372659 -0.8777923 -0.458954 -0.7360244 -0.6603721 -0.1489186 -0.6198037 -0.7671082 -0.1654944 -0.6139293 -0.7568223 -0.2243006 -0.5045423 -0.8323308 -0.2294833 -0.5005459 -0.8179977 -0.2834318 -0.3651476 -0.8859277 -0.286006 -0.3646704 -0.8710279 -0.3291294 -0.1951878 -0.9253513 -0.3250027 -0.1979679 -0.913097 -0.3564584 0.01908206 -0.9408146 -0.3383843 -0.0126295 -0.9358207 -0.3522502 0.251021 -0.914766 -0.3165307 0.2451388 -0.9092175 -0.3364974 0.4918462 -0.8265948 -0.2735482 0.4905882 -0.8259838 -0.277622 0.4896864 -0.826263 -0.2783824 0.5342224 -0.790004 -0.3008326 0.5453094 -0.7960749 -0.2624933 0.5461698 -0.7955439 -0.2623141 -0.0753408 -0.8371138 -0.5418159 -0.05304181 -0.8376545 -0.5436191 -0.160049 -0.8007022 -0.5772871 -0.1368075 -0.803339 -0.579595 -0.2350984 -0.7581452 -0.6082309 -0.2118788 -0.7627328 -0.6110206 -0.3014336 -0.7112653 -0.6350114 -0.2790518 -0.7175034 -0.6382154 -0.3597079 -0.661671 -0.6578767 -0.3388322 -0.6691538 -0.6613819 -0.4096674 -0.6115458 -0.6768934 -0.3908544 -0.6197479 -0.680548 -0.4526449 -0.5617037 -0.6925328 -0.4362669 -0.570115 -0.696161 -0.4901484 -0.5122666 -0.7052217 -0.4764978 -0.5203778 -0.7086304 -0.523194 -0.4634307 -0.7151924 -0.5124591 -0.4707104 -0.7182043 -0.5519058 -0.4162716 -0.7225773 -0.5442044 -0.4221659 -0.7249948 -0.5772758 -0.3705948 -0.7276073 -0.5726704 -0.3745594 -0.7292147 -0.6003418 -0.3256808 -0.7304257 -0.5988257 -0.3271437 -0.7310163 -0.6219086 -0.2807061 -0.7310498 -0.6233534 -0.2791373 -0.7304198 -0.6424645 -0.2348091 -0.7294546 -0.6464607 -0.2299451 -0.7274708 -0.6622703 -0.1868978 -0.7255808 -0.6682887 -0.1785497 -0.7221567 -0.6813274 -0.1356675 -0.7192965 -0.6887816 -0.12375 -0.7143291 -0.6992256 -0.08018815 -0.7103897 -0.7074878 -0.06469982 -0.7037578 -0.7150875 -0.02101373 -0.6987191 -0.7234838 -0.002027451 -0.6903384 -0.7282158 0.04264175 -0.6840202 -0.7360345 0.06483566 -0.6738321 -0.7376317 0.111934 -0.6658605 -0.7441177 0.1368779 -0.6538756 -0.7419168 0.1874979 -0.6437422 -0.746356 0.2144705 -0.6300439 -0.7395041 0.2679356 -0.6175308 -0.7413399 0.2959565 -0.6023495 -0.7286888 0.3528984 -0.5869203 -0.7275788 0.3807459 -0.5706678 -0.7074158 0.4421134 -0.5514515 -0.7033128 0.4683836 -0.5347598 -0.6795532 0.521768 -0.5157187 0.8720428 0.4894297 0 0.8592772 0.511506 0.002061486 0.859257 0.5115406 -0.001924335 0.7805736 0.6249774 -0.01040351 0.7806202 0.6249391 -0.009129822 0.6711123 0.7408153 -0.0283035 0.6710599 0.7408382 -0.02894014 0.6279127 0.7777667 -0.02837055 0.6290184 0.7772637 -0.01403915 0.5091496 0.8596937 -0.04115402 0.5108458 0.859549 -0.01456212 0.4245941 0.9046059 -0.03752464 0.396099 0.9172999 -0.04082322 0.3004699 0.9513871 -0.06767964 0.3015713 0.9522843 -0.04700452 0.1760064 0.9804344 -0.08814787 -0.8355751 -0.531248 -0.1399645 -0.7480528 -0.6479309 -0.1435359 -0.7404044 -0.6395972 -0.2066804 -0.6441814 -0.7351376 -0.2111944 -0.6370586 -0.7221233 -0.2696189 -0.5254316 -0.8058025 -0.2731371 -0.5209617 -0.7900326 -0.3231835 -0.3806033 -0.8664621 -0.3230859 -0.3799188 -0.8509247 -0.3627518 -0.2042433 -0.9125443 -0.3543272 -0.2068339 -0.9003139 -0.3829553 0.009807467 -0.9331724 -0.3592956 0.005388319 -0.9248304 -0.3803416 -0.009127736 -0.9214439 -0.3884044 0.01865708 -0.9170396 -0.3983595 0.01584559 -0.9109885 -0.4121275 0.02847284 -0.9084828 -0.4169512 0.02615058 -0.9030399 -0.42876 0.04078102 -0.89959 -0.4348275 0.03425663 -0.8822712 -0.4694936 0.003996312 -0.8838236 -0.4678031 0.00156331 -0.8747926 -0.4844952 0.02108877 -0.8738324 -0.4857697 0.01896071 -0.8648077 -0.5017452 0.03925579 -0.8633517 -0.5030734 0.9284473 0.3714532 -0.002897202 0.9245479 0.3810663 0 0.9245414 0.3810811 6.32864e-4 0.8791341 0.4765746 0 0.8775364 0.4795097 6.76703e-4 0.8763102 0.4817473 0 0.8763098 0.4817481 0 0.9137462 0.4062856 0 0.9151802 0.4030439 9.40906e-4 0.9447088 0.3279071 -0.001574456 0.9480142 0.3182271 8.26249e-4 0.969193 0.2462723 -0.003866732 0.9730818 0.2304592 -5.6738e-4 0.9869868 0.1606359 -0.007300794 0.9902397 0.1393277 -0.00364542 0.9974011 0.07097649 -0.01239693 0.9989439 0.04507982 -0.008881568 0.999597 -0.0206682 -0.01946258 0.9986165 -0.04992282 -0.01651763 0.9930462 -0.114076 -0.02908682 0.989028 -0.1452295 -0.02705311 0.9769067 -0.2094771 -0.04210197 0.9696686 -0.2409266 -0.04119491 0.9500978 -0.3062639 -0.0593031 0.9398927 -0.3362331 -0.05957496 0.9122883 -0.4014876 -0.08085769 0.899897 -0.4282882 -0.08218628 0.8629072 -0.4938338 -0.1073285 0.8495707 -0.5160041 -0.1094053 0.8010352 -0.5821582 -0.1394081 0.7884572 -0.5985358 -0.1417403 0.7262332 -0.6641887 -0.1773099 0.7165195 -0.6741335 -0.1792869 0.6404734 -0.7358076 -0.219957 0.6357787 -0.7395714 -0.2209515 0.5451301 -0.7948159 -0.2666476 0.5474381 -0.7933939 -0.2661537 0.4409098 -0.8397326 -0.3169353 0.4517263 -0.8336029 -0.317883 0.3420441 -0.8640071 -0.3694558 0.3516259 -0.8598616 -0.3701316 0.2373305 -0.8753911 -0.4211469 0.2511976 -0.871097 -0.4220067 0.1351883 -0.8716484 -0.4711192 0.1528839 -0.8681288 -0.4722065 0.03741383 -0.8543148 -0.5184078 0.05820202 -0.852302 -0.5198019 -0.05401837 -0.8253592 -0.562018 -0.03108429 -0.8253117 -0.5638212 -0.1362134 -0.7877015 -0.6008097 -0.1121848 -0.7897704 -0.6030567 -0.2090157 -0.743918 -0.6347429 -0.1848725 -0.7479962 -0.6374354 -0.2732623 -0.695881 -0.6641365 -0.2498621 -0.7016941 -0.6672289 -0.3295705 -0.6452776 -0.6892026 -0.3076367 -0.6524228 -0.6926068 -0.3777478 -0.5942661 -0.7100383 -0.3578599 -0.6022585 -0.7135973 -0.4190918 -0.5437274 -0.7271331 -0.4016955 -0.5520334 -0.7306846 -0.4551419 -0.4938171 -0.740939 -0.4405545 -0.5019025 -0.7443156 -0.486918 -0.4446991 -0.751767 -0.4753836 -0.4520193 -0.7547775 -0.5146279 -0.3973723 -0.7597721 -0.5063161 -0.4033442 -0.7622057 -0.5392919 -0.3515968 -0.7652085 -0.5342912 -0.3556338 -0.7668492 -0.5619655 -0.3066177 -0.7682321 -0.5603058 -0.3081188 -0.7688435 -0.5834133 -0.2616328 -0.7688806 -0.5849955 -0.2600131 -0.7682275 -0.6040648 -0.2159664 -0.7671144 -0.608459 -0.2109344 -0.7650388 -0.6241765 -0.1685301 -0.7628901 -0.6308542 -0.1598806 -0.7592505 -0.6437762 -0.1180183 -0.7560582 -0.6521329 -0.1056241 -0.7507106 -0.6624902 -0.0634523 -0.7463783 -0.6718544 -0.04727321 -0.7391731 -0.6794826 -0.005240857 -0.7336729 -0.6891326 0.01463454 -0.7244875 -0.6940286 0.05742299 -0.7176538 -0.7031962 0.08069729 -0.7064015 -0.70515 0.1256863 -0.6978299 -0.7130341 0.1518967 -0.6844778 -0.7114282 0.2002006 -0.673639 -0.7172162 0.2285402 -0.6583087 -0.7112482 0.2795746 -0.6449528 -0.7143245 0.3090175 -0.6278924 -0.7028888 0.3634185 -0.6114526 -0.7028294 0.3926708 -0.5931616 -0.68426 0.4513731 -0.572757 -0.681037 0.4789325 -0.5539065 -0.6434084 0.5619803 -0.5198112 -0.6321017 0.5498471 -0.5459997 -0.626927 0.5751254 -0.5255409 -0.6100128 0.5579435 -0.5626577 -0.6059593 0.5836747 -0.5404973 0.9989398 0.04603636 4.94459e-5 0.5616428 -0.8273798 3.69768e-5 -0.5343787 -0.8452453 -3.57228e-6 -0.7176344 0.69642 -4.74718e-4 -0.6611226 0.7502747 -0.002191126 -0.9850056 0.1725224 -3.65802e-4 -0.9471352 0.3208307 -0.00168544 -0.9476844 0.3192048 -0.001640617 -0.8663151 0.499498 3.1305e-6 -0.8199543 0.5724291 -9.20208e-7 -0.939123 -0.3435813 -1.77373e-4 -0.9848975 -0.1731238 -0.002254664 -0.980318 -0.1974183 -0.001660346 -0.9999934 -0.003652632 1.83892e-5 -0.9941999 0.1075479 -1.15944e-5 -0.7502782 -0.6611223 4.27367e-5 -0.6233596 -0.7819146 -0.005709767 -0.6972111 -0.7168571 -0.003565192 -0.7647224 -0.6443581 -0.001564919 -0.8584051 -0.5129725 -2.94654e-6 -0.9022493 -0.4312147 3.11523e-7 0.1974082 -0.9803215 -6.76604e-5 0.3007642 -0.9536907 -0.003882348 0.03961175 -0.9992152 1.83716e-4 -0.3191966 -0.9476885 -3.95247e-4 -0.2162799 -0.9763238 -0.003865897 -0.4270713 -0.9042179 -3.38017e-4 0.9476867 -0.3192022 -1.13093e-4 0.996146 -0.08722221 -0.009248495 0.976086 -0.2173391 -0.004471302 0.9302142 -0.3670138 -0.001600205 0.8772332 -0.4800648 2.1324e-5 0.6611265 -0.7502745 -6.21884e-5 0.801474 -0.5979785 -0.007819831 0.7252228 -0.6885017 -0.004161536 0.5720809 0.8201972 3.29166e-6 0.633134 0.7740423 -2.67973e-4 0.7509958 0.6603037 -0.002147078 0.7502817 0.6611151 -0.002116203 0.8605366 0.5093886 -1.59349e-6 0.9803198 0.197416 5.80021e-6 0.9148057 0.4038036 -0.008562982 0.9649901 0.2622605 -0.003675043 0.2490501 0.9684903 -7.70389e-4 0.3191978 0.947685 -0.002466678 0.3801853 0.9249094 -0.001437306 0.4764766 0.8791872 -1.58592e-5 -0.5313547 0.8471495 0 -0.3311522 0.9435774 0 -0.1974052 0.980319 -0.002424776 -0.08854556 0.9960721 -2.55129e-4 0.08439755 0.9964323 6.24092e-5 0.7049936 -0.7092137 0 -0.7049947 0.7092126 0 0.3543937 0.9348813 0.0200572 0.1166297 0.9931391 0.008504688 -0.8729401 0.4878276 0 -0.9165496 0.3999211 0 -0.9348812 0.3543937 0.02005875 -0.9513365 0.3081539 0 -0.976961 0.2134183 0 -0.9734573 0.228778 -0.006443917 -0.9931393 0.1166277 0.008507072 -0.3543937 -0.9348812 0.02006137 -0.1166297 -0.9931391 0.008508801 0.8729383 -0.4878308 0 0.9165511 -0.3999176 0 0.9348812 -0.3543937 0.02005982 0.9513353 -0.3081577 0 0.9769635 -0.2134063 0 0.9734546 -0.2287896 -0.006443858 0.9931388 -0.1166318 0.008507072 0.9912139 -0.1322692 0 0.01873159 0.9998246 0 -0.03035187 0.999489 0.01003116 -0.07935678 0.9968463 0 -0.1766919 0.9842663 0 -0.2247596 0.9743627 0.01003116 -0.365313 0.9308848 0 -0.4105276 0.911793 0.0100311 -0.5399052 0.8417258 0 -0.5805229 0.8141822 0.01003217 -0.7049979 0.7092095 0 -0.6937087 0.7202056 0.008507132 -0.7711026 0.6366784 -0.006442666 -0.9912143 0.1322661 0 -0.999489 -0.03035509 0.01003098 -0.9968467 -0.07935267 0 -0.9842659 -0.1766937 0 -0.974363 -0.2247582 0.01003062 -0.962208 -0.2723155 0 -0.9308842 -0.3653146 0 -0.9117934 -0.4105266 0.01003217 -0.890595 -0.4547973 0 -0.8141797 -0.5805263 0.01003062 -0.7202035 -0.6937108 0.008500516 -0.6487641 -0.7609897 0 -0.01872849 -0.9998246 0 0.03035187 -0.999489 0.01003009 0.07935369 -0.9968466 0 0.1766949 -0.9842658 0 0.2247611 -0.9743623 0.01003217 0.3653103 -0.9308859 0 0.4105263 -0.9117937 0.0100311 0.5399075 -0.8417245 0 0.580524 -0.8141815 0.0100311 0.7049967 -0.7092106 0 0.693707 -0.7202071 0.008505046 0.7711026 -0.6366784 -0.006445765 0.9994891 0.03034883 0.01003164 0.996846 0.07936096 0 0.9842644 0.1767017 0 0.9743621 0.2247621 0.0100314 0.9622092 0.2723116 0 0.9308871 0.3653074 0 0.9117912 0.4105318 0.01003164 0.8905984 0.4547907 0 0.8141807 0.5805249 0.01003062 0.720205 0.6937093 0.008500516 0.6487623 0.7609912 0 0 0 1 0.4444112 0.895823 0 0.4444102 0.8958235 0 0.9518451 -0.3064783 -0.007889389 -0.7468224 -0.3660587 -0.5552094 -0.1913203 -0.9562805 -0.2211884 0.9614841 0.2721109 -0.03878372 0.9288521 0.3645123 -0.06606477 0.08750563 0.8869518 -0.4534967 0.9244852 -0.3812181 0 -0.81795 0.344502 -0.4607344 0.5788812 -0.8124634 -0.06928229 -0.7900676 0.2890295 -0.5406065 -0.7694192 0.2860738 -0.5711006 -0.7688262 0.2857663 -0.5720525 -0.7703077 0.2879226 -0.5689699 -0.7765011 0.3068635 -0.5503461 -0.7388376 0.3371851 -0.5834597 -0.7341102 0.3045395 -0.6069084 -0.7096219 0.3481241 -0.6125737 -0.7386245 0.3264354 -0.5898083 -0.738728 0.3231567 -0.5914819 -0.7388831 0.3202867 -0.5928477 -0.7022882 0.3941846 -0.5927983 -0.7016115 0.3949422 -0.5930953 -0.7031961 0.393554 -0.5921406 -0.7073593 0.3899976 -0.5895293 -0.6891389 0.4018394 -0.603003 -0.7043605 0.3593432 -0.6121673 -0.7071205 0.3532097 -0.6125549 -0.7142857 0.4554574 -0.5313704 -0.7090926 0.4559841 -0.5378348 -0.7065764 0.4297248 -0.5622157 -0.6957682 0.4384998 -0.56888 -0.6932944 0.4392796 -0.5712936 -0.7759007 0.3908814 -0.4951665 -0.7463771 0.4160385 -0.5194547 -0.7462572 0.4210778 -0.5155519 -0.7456024 0.4244972 -0.5136917 -0.7802253 0.3514371 -0.5174366 -0.7879036 0.3385114 -0.5144102 -0.7897953 0.3359796 -0.5131679 -0.7893721 0.3365162 -0.5134673 -0.7872231 0.3389022 -0.5151943 -0.7797881 0.3454749 -0.5220896 -0.7948496 0.3358367 -0.5053986 -0.7814166 0.3793413 -0.4954677 -0.7787638 0.3850625 -0.4952313 0.5162618 -0.8551346 -0.04710328 0.5431947 -0.8380256 -0.05150401 0.660857 -0.7500697 -0.02575957 0.6708874 -0.7411055 -0.0259388 0.7751383 -0.6317455 -0.007644772 0.7806472 -0.6249167 -0.008318424 0.8478252 -0.530276 0 0.4974315 -0.8635626 -0.08259272 0.5291074 -0.8464987 -0.05903661 0.5279424 -0.8464966 -0.06870645 0.6698449 -0.7414533 -0.03943151 0.6581162 -0.7519587 -0.03796434 0.7802993 -0.6251659 -0.01734524 0.680666 -0.7324479 -0.01462757 0.7492435 -0.6621451 -0.01407659 0.102617 -0.9794648 -0.1735471 0.02406352 -0.9798385 -0.1983367 0.09966683 -0.9752017 -0.1976063 -0.1374673 -0.9621372 -0.235361 0.4956535 -0.8628461 -0.09911698 0.3750616 -0.9218108 -0.09794723 0.4638088 -0.8813806 -0.08972042 -0.7932484 0.2908909 -0.5349202 -0.8046362 0.3051286 -0.5093693 -0.8314272 0.2258908 -0.5076436 -0.7935227 -0.5507206 -0.258899 -0.9117401 0.3613272 -0.1953784 -0.9535441 0.2269505 -0.1981084 -0.9394293 0.2257201 -0.2579206 -0.9608701 0.0924775 -0.2611066 -0.9441112 0.09478795 -0.3157045 -0.9470658 -0.048675 -0.3173281 -0.9305859 -0.04259264 -0.3635872 -0.9096149 -0.2066342 -0.3604208 -0.8963676 -0.1978672 -0.3967038 -0.8411238 -0.3813428 -0.3835211 -0.8329564 -0.3722846 -0.4093751 -0.7406169 -0.59144 -0.3188816 -0.8460183 -0.4184498 -0.330383 -0.853935 -0.4279125 -0.2961183 -0.9149766 -0.2736181 -0.2965654 -0.9263955 -0.2815987 -0.2499873 -0.9583216 -0.1464767 -0.245284 -0.9702621 -0.1507682 -0.1893687 -0.9794601 -0.04974615 -0.1954056 -0.7203637 -0.6344684 -0.2802248 -0.8188297 -0.4998255 -0.2822984 -0.8266648 -0.5074403 -0.2431663 -0.877699 -0.4149329 -0.23974 -0.6165726 -0.7323439 -0.2889824 -0.5357082 -0.8000211 -0.2701538 -0.5341391 -0.7957503 -0.2854415 -0.3503291 -0.8981593 -0.265668 -0.3503554 -0.8977093 -0.2671502 -0.1145757 -0.967738 -0.2244008 -0.1129417 -0.9704509 -0.2132354 0.1309493 -0.9793068 -0.1543067 0.133369 -0.9809874 -0.1409832 -0.4641481 -0.8417618 -0.2756877 -0.3196336 -0.910371 -0.2627912 -0.3327912 -0.903813 -0.269021 -0.1271099 -0.9636318 -0.235068 -0.1262187 -0.9662583 -0.2245303 0.1285941 -0.9764687 -0.1731256 0.1318491 -0.9791859 -0.1543076 -0.7079264 0.5364331 -0.4594342 -0.7064189 0.540062 -0.457499 -0.6256618 0.6333394 -0.4554433 -0.6224449 0.6386516 -0.4524229 -0.5194885 0.7277581 -0.4477722 -0.5142375 0.7338458 -0.4438807 -0.3814011 0.8158896 -0.4345772 -0.3742265 0.8215882 -0.4300553 -0.2078462 0.8865472 -0.4133206 -0.1996525 0.8905968 -0.4086274 0.005388319 0.9248304 -0.3803416 -0.7907114 0.4549987 -0.4095751 -0.769795 0.4417158 -0.4607633 -0.7694432 0.4430304 -0.4600883 -0.7490437 0.4301758 -0.5038675 -0.7466341 0.4078828 -0.5255181 -0.7258217 0.5527201 -0.4094918 -0.7254017 0.5536118 -0.409031 -0.6392225 0.6517234 -0.4082294 -0.6383609 0.6529958 -0.4075439 -0.5279827 0.7465301 -0.4048792 -0.526659 0.7479288 -0.4040209 -0.3847323 0.8330112 -0.3975845 -0.38304 0.8342365 -0.3966481 -0.2068983 0.8999826 -0.3836985 -0.2051842 0.9007408 -0.3828391 0.008751749 0.9331183 -0.3594631 0.009895086 0.9333303 -0.3588825 0.2494649 0.9133081 -0.3219246 0.8533563 0.5007863 -0.1449003 0.2502059 0.9099226 -0.3308141 0.4882938 0.8286989 -0.273546 0.4917519 0.8266507 -0.2735486 0.7059323 0.6787179 -0.2024886 0.7045191 0.6770644 -0.2126893 0.7027646 0.678565 -0.2137089 0.8594697 0.4874194 -0.1540591 0.995921 -0.08559864 -0.0285378 0.9719707 -0.2349593 -0.008186578 0.9389649 -0.3440114 -0.001143336 0.9245109 -0.3810961 -0.006731986 0.2520744 0.9157309 -0.3128826 0.2570493 0.9151656 -0.3104798 0.01248455 0.9398729 -0.3412961 0.01908206 0.9408146 -0.3383843 -0.2044707 0.9115492 -0.3567493 -0.1977363 0.9141861 -0.3537854 -0.3857369 0.8482765 -0.3628141 -0.3799869 0.8520247 -0.3600887 -0.5336291 0.7636013 -0.3635286 -0.5293965 0.767645 -0.3611934 -0.6496933 0.6686175 -0.3617312 -0.6470258 0.6721767 -0.3599112 -0.740667 0.5676794 -0.3593781 0.258868 0.9168741 -0.3038575 0.2695735 0.9153188 -0.2992016 0.02191233 0.9458888 -0.3237506 0.03794431 0.9475071 -0.3174756 -0.1957098 0.9232038 -0.3307456 -0.178155 0.9291168 -0.3240416 -0.380541 0.8642683 -0.3289816 -0.3647949 0.8734242 -0.3225753 -0.533688 0.7816653 -0.3227638 -0.5215837 0.7920804 -0.3171108 -0.6554043 0.6863282 -0.315276 -0.5321065 0.8298096 -0.1681636 -0.7473621 0.6471284 -0.1505819 -0.7416131 0.640884 -0.1981865 -0.8438997 0.4997799 -0.1950727 -0.8337894 0.493049 -0.2483907 -0.8950339 0.3703681 -0.2484787 -0.8797683 0.3649998 -0.3046026 -0.9197958 0.2459017 -0.305791 -0.9007828 0.2436767 -0.3594607 -0.926117 0.1127194 -0.3600024 -0.9059693 0.1146438 -0.407525 -0.9138152 -0.03304249 -0.4047842 -0.8955891 -0.0272175 -0.4440491 -0.878974 -0.1981059 -0.4337729 -0.8653364 -0.189946 -0.4638032 -0.813589 -0.3799048 -0.4401651 -0.8057528 -0.3720377 -0.460815 -0.8288227 0.5443216 -0.1294873 -0.8807755 0.4534736 -0.1363686 -0.9214349 0.3646646 -0.1340804 -0.7272874 0.671077 -0.1439059 -0.847254 0.5126341 -0.1391648 -0.8398088 0.5076838 -0.1922979 -0.9089859 0.3697534 -0.1924248 -0.8965286 0.3654034 -0.2504337 -0.9373885 0.2400685 -0.2523292 -0.920708 0.2383726 -0.3089907 -0.9444754 0.1064206 -0.3108713 -0.9258975 0.1085923 -0.3618309 -0.9316751 -0.03738564 -0.3613641 -0.9142062 -0.03137242 -0.4040334 -0.8956766 -0.1995282 -0.3974316 -0.8821449 -0.1910063 -0.4305078 -0.8287167 -0.3785574 -0.4122172 -0.8206597 -0.3700568 -0.4354029 0.01272249 0.926452 -0.3761982 0.2460963 0.9101473 -0.3332697 0.2494502 0.9133133 -0.3219217 0.4927266 0.8270795 -0.2704811 0.490149 0.8288521 -0.2697373 0.4959144 0.8254108 -0.2697517 0.4966566 0.8257596 -0.2673077 0.4953799 0.8266221 -0.267011 0.2705937 0.9163556 -0.2950789 0.2876657 0.9132732 -0.2884106 0.03981399 0.9509823 -0.3066716 0.06692713 0.9524281 -0.2973244 -0.1766726 0.9356987 -0.3053767 -0.1455359 0.9443026 -0.2951476 -0.3651041 0.8827534 -0.2957118 -0.335911 0.8975104 -0.2857252 -0.5247278 0.8031272 -0.2822192 0.8563596 0.4881421 -0.1684207 0.8408035 0.5108395 -0.1791439 0.7017908 0.6767697 -0.2224244 0.6924214 0.6849031 -0.2268488 0.5028127 0.8220776 -0.2671477 0.5031813 0.8223305 -0.2656713 0.287994 0.9136531 -0.2868756 0.311543 0.9084823 -0.2785695 0.06788092 0.9544269 -0.2906227 0.1073411 0.9543753 -0.2786499 -0.1446814 0.9486082 -0.2814423 -0.09695404 0.9585194 -0.2680307 -0.3361814 0.9040779 -0.2638664 0.997444 -0.05605632 -0.04430949 0.9957987 -0.08523792 -0.03345882 0.9743135 -0.2245674 -0.01681494 0.9743428 -0.224691 -0.01304167 0.9887645 -0.1453281 -0.03499519 0.9975218 -0.0561949 -0.04233771 0.9960683 0.05094581 -0.07247418 0.9723693 0.2124113 -0.09684741 0.3704372 0.8489751 -0.3768522 0.3576429 0.8483526 -0.390371 0.2778599 0.85779 -0.4324237 0.2604115 0.8541218 -0.4501797 0.1863285 0.8529567 -0.4875928 0.1657243 0.8453004 -0.5079398 -0.6184232 0.3619928 -0.6975056 -0.6102359 0.3932408 -0.6877309 -0.5800583 0.4398459 -0.685615 -0.5657906 0.4512347 -0.690122 -0.5499089 0.4906123 -0.6759436 -0.5105627 0.5376715 -0.6709957 -0.4980393 0.5454233 -0.6741442 -0.3704741 0.6899373 -0.6218806 -0.4099648 0.6416618 -0.6482276 -0.422204 0.6361006 -0.6458481 -0.4716262 0.590971 -0.6544631 -0.6925886 0.4392326 -0.5721852 -0.6777744 0.421841 -0.6022226 -0.6334037 0.4888905 -0.5998216 -0.6310374 0.4984905 -0.5943897 -0.5598108 0.5831165 -0.5887166 -0.5537502 0.5976064 -0.5798512 -0.464622 0.6780558 -0.5695322 -0.4536246 0.6952461 -0.5575461 -0.3388711 0.7703931 -0.5400564 -0.2624555 0.7941531 -0.5481222 -0.1825235 0.8282311 -0.5298288 -0.1606342 0.8313543 -0.5320213 -0.09334647 0.8643202 -0.4942034 -0.04220145 0.875731 -0.4809515 0.3378221 0.8747364 -0.3474372 0.3177279 0.877879 -0.3582978 0.2304409 0.8917532 -0.3894524 0.2013513 0.892208 -0.4042553 0.1251699 0.8943477 -0.4295051 0.0889135 0.8900762 -0.4470556 -0.01621156 0.8780637 -0.4782693 -0.01161307 0.89339 -0.4491321 -0.1580832 0.861785 -0.4820131 -0.7106657 0.441172 -0.548016 -0.7232894 0.4090223 -0.5563752 -0.6613155 0.5049293 -0.5547146 -0.6589412 0.5127975 -0.5503047 -0.5852742 0.599606 -0.5458267 -0.5796529 0.6113783 -0.53872 -0.4868418 0.6941223 -0.5302634 -0.477019 0.7079784 -0.5207874 -0.3572949 0.7850677 -0.5059735 -0.3431769 0.7984622 -0.4946593 -0.1919345 0.8612602 -0.4705231 0.353756 0.8634748 -0.3595387 0.3313418 0.866164 -0.3741292 0.2538738 0.8772559 -0.4073944 0.222074 0.8765125 -0.4270939 0.1556302 0.8772894 -0.4540293 0.1162625 0.8709642 -0.4773935 0.01732027 0.8576917 -0.5138726 0.02108836 0.8738316 -0.4857713 -0.07356119 0.8541066 -0.5148695 -0.09608387 0.8429346 -0.5293669 -0.1604456 0.8214117 -0.5473026 -0.1824665 0.8071566 -0.5614307 -0.2384101 0.7820822 -0.5757675 -0.258879 0.7655454 -0.5890007 0.4610133 0.8249568 -0.3269757 0.4507408 0.8312198 -0.3254326 0.3612578 0.8554753 -0.3710188 0.3489929 0.8553596 -0.382837 0.2649319 0.8661679 -0.4237505 0.2478622 0.8633273 -0.4395797 0.1702629 0.8630349 -0.4755853 0.1494027 0.8563242 -0.4943559 0.5449345 0.7946824 -0.2674441 0.8487899 0.515869 -0.1159096 0.8639466 0.4936615 -0.09947174 0.7877177 0.5982739 -0.1468648 0.8020617 0.5822095 -0.1331509 0.7159529 0.673823 -0.1826856 0.7270471 0.6644031 -0.1731218 0.6355113 0.7393685 -0.2223954 0.8613237 0.4940083 -0.1186479 0.8761073 0.4707853 -0.1039099 0.7993853 0.5820191 -0.1491207 0.813919 0.5646882 -0.1366131 0.7249416 0.6638178 -0.1838631 -0.745441 0.4251734 -0.5133666 -0.7408773 0.4379427 -0.509222 -0.686271 0.5206629 -0.5078804 -0.6841537 0.5265711 -0.5046353 -0.6074259 0.6161768 -0.5013582 -0.6026884 0.6249366 -0.4962066 -0.5054136 0.7105038 -0.4896341 -0.4974189 0.7207115 -0.4828553 -0.3718084 0.8000776 -0.4707806 -0.3606054 0.8098054 -0.4627947 -0.2023966 0.8737161 -0.4423301 -0.1892585 0.8808801 -0.4338566 0.007586896 0.9161683 -0.4007221 0.01973402 0.9192951 -0.3930739 0.246201 0.9059632 -0.3444063 0.2536277 0.9057813 -0.3394605 0.4914774 0.8264169 -0.2747459 0.4868674 0.8240902 -0.2895438 0.5460965 0.796479 -0.259615 0.5452439 0.7960383 -0.2627397 0.5462147 0.7955783 -0.2621164 0.6466794 0.7311793 -0.2172156 0.6456624 0.7308849 -0.2211953 0.6976829 0.68501 -0.2097618 0.6982181 0.6850735 -0.2077638 0.8628295 0.4869272 -0.1357467 0.858928 0.4882304 -0.154511 0.9863498 0.1540201 -0.05824029 0.9873251 0.1525705 -0.04372012 0.9868758 0.1551366 -0.0448203 0.9767484 0.2096306 -0.04491996 0.9980207 0.05829519 -0.02359062 0.9972006 0.0602293 -0.04431128 0.9944279 0.08998596 -0.05491626 0.9941667 0.0903958 -0.05883365 0.9941132 0.09084886 -0.05903762 0.9934088 0.09174835 -0.06871062 0.9885354 0.126398 -0.08259195 0.9872348 0.127173 -0.09588831 0.9416872 0.3090502 -0.1330913 0.9447072 -0.3279089 -0.002023816 0.9389499 -0.3440533 7.68408e-4 0.9691913 -0.2462458 -0.005602955 0.971972 -0.2349662 -0.007841706 0.986985 -0.1606425 -0.007406175 0.9973221 -0.07071322 -0.01866346 0.999368 0.02112299 -0.02859222 0.9932734 -0.1155635 -0.007294774 0.9931988 -0.1146975 -0.02001881 0.9697343 -0.2441314 -0.003934562 0.9697642 -0.243879 -0.008962929 0.9245439 -0.3810758 -5.22361e-5 0.9245479 -0.3810663 0 0.9009941 0.4282377 -0.06944179 0.8991755 0.4282994 -0.08968251 0.9132037 0.4011093 -0.07190531 0.9109948 0.4019119 -0.0924952 0.9241714 0.3741922 -0.07672947 0.9222775 0.375293 -0.09251827 0.8730546 0.4717696 -0.1233249 0.854492 0.5004681 -0.1391947 0.8113777 0.5649666 -0.1499311 0.7341096 0.6528444 -0.1867544 0.7368087 0.6531051 -0.1748331 0.6400719 0.7356224 -0.2217378 0.6408684 0.7359969 -0.2181658 0.5475689 0.7935186 -0.2655121 0.9376508 0.3202944 -0.1349914 0.9385472 0.3200371 -0.1292498 0.950872 0.2873713 -0.115153 0.9527891 0.2861508 -0.101543 0.9527783 0.2861762 -0.1015706 0.9552638 0.2841438 -0.08205801 0.9487186 0.302289 -0.09249097 0.9495876 0.3016296 -0.08545845 0.9577217 0.2778709 -0.07454431 0.9595276 0.2762874 -0.05451816 0.9491724 0.3068065 -0.07029563 0.9508005 0.305786 -0.04973399 0.8361545 0.5363395 -0.1148294 0.8509053 0.5162131 -0.09738767 0.7763155 0.6131464 -0.1462386 0.7898233 0.5989958 -0.1318455 0.7081124 0.6820734 -0.1826273 0.7174804 0.674633 -0.1734711 0.6322576 0.7416336 -0.2241205 0.6357902 0.7395766 -0.220901 0.5498291 0.7904331 -0.2700063 0.5459932 0.7919557 -0.2733088 0.4501139 0.8315018 -0.3255801 0.4530363 0.8352715 -0.3115762 0.4408078 0.8386244 -0.3199963 0.4446862 0.8423871 -0.3043653 0.4344376 0.8455588 -0.3103131 0.4377897 0.8480778 -0.2985032 0.324184 0.8847389 -0.334876 0.2452025 0.8967508 -0.3683938 0.2091491 0.9037932 -0.3733827 0.01382017 0.906512 -0.421954 0.00935167 0.9067127 -0.4216452 -0.175117 0.8713498 -0.4583488 -0.1775993 0.8489167 -0.4977943 -0.3227265 0.787207 -0.5255025 -0.3165819 0.7515091 -0.5788004 0.01512235 0.8071893 -0.5900989 -0.009271204 0.789784 -0.6133151 -0.06126242 0.7695378 -0.6356561 -0.08490306 0.7481799 -0.6580413 -0.1301713 0.7251257 -0.6762013 -0.1515815 0.7013194 -0.6965445 -0.1913943 0.6762852 -0.7113414 -0.2101145 0.6510013 -0.7294171 -0.2451664 0.624731 -0.7413533 -0.2611131 0.598751 -0.7571771 -0.2919964 0.5717976 -0.7666718 -0.3046482 0.5469256 -0.7797833 -0.3327797 0.5188088 -0.7874613 -0.3421511 0.4964332 -0.7978013 -0.3685153 0.4665865 -0.8040483 -0.3751043 0.4471938 -0.811982 -0.4000842 0.4153687 -0.8169464 -0.4044533 0.3990879 -0.8228892 -0.4282613 0.3651083 -0.8266125 -0.4307073 0.3530125 -0.8305862 -0.4539932 0.3158075 -0.8331601 -0.4550103 0.3086183 -0.8352967 -0.4781341 0.2672034 -0.8366542 -0.4783201 0.2649065 -0.837278 -0.5012165 0.2186959 -0.8372302 -0.5011572 0.2209522 -0.836673 -0.5235288 0.1695776 -0.8349618 -0.5237339 0.1764688 -0.8334036 -0.5453533 0.1191293 -0.8296976 -0.5463359 0.1304101 -0.8273513 -0.5667066 0.06654971 -0.8212276 -0.5688567 0.08136802 -0.8184017 -0.5871614 0.01099872 -0.8093953 -0.5907207 0.02829772 -0.8063797 -0.6059583 -0.04823589 -0.7940327 -0.6112679 -0.02859222 -0.7909073 -0.6225076 -0.111752 -0.7745941 -0.6298717 -0.09009343 -0.7714563 -0.635878 -0.1799584 -0.750516 -0.6453166 -0.157322 -0.7475402 -0.6446374 -0.2529794 -0.7214182 -0.6558772 -0.2306672 -0.7187612 -0.6469775 -0.3303856 -0.6872158 -0.6600476 -0.3087619 -0.6848382 -0.6414585 -0.4114487 -0.6474883 -0.656195 -0.3910263 -0.6453732 -0.6265299 -0.4948402 -0.6021575 -0.6421498 -0.4767301 -0.6003101 -0.6006215 -0.5785261 -0.5518707 -0.6158429 -0.5638585 -0.5502738 -0.5625963 -0.6599206 -0.4979863 -0.5769222 -0.6485522 -0.4965288 -0.5123733 -0.7365759 -0.4415085 -0.5251933 -0.7283152 -0.4401467 -0.4504618 -0.8060775 -0.3838272 -0.4605281 -0.8009366 -0.3826414 -0.3779365 -0.8661691 -0.3269788 -0.3894283 -0.8616641 -0.3253931 -0.2966158 -0.9156901 -0.2711656 -0.3003078 -0.9142721 -0.2718856 -0.2080465 -0.9523675 -0.2229642 -0.2042265 -0.9533399 -0.2223386 -0.1147456 -0.9771023 -0.1791776 -0.1032143 -0.9786595 -0.1776865 -0.0185424 -0.9899007 -0.1405447 5.81468e-4 -0.9903265 -0.1387557 0.07889384 -0.9910678 -0.1075196 0.1033068 -0.9889672 -0.1061688 0.1761307 -0.9811263 -0.07980829 0.2035672 -0.975841 -0.07933974 0.2718698 -0.9606458 -0.05697888 0.3010207 -0.9518728 -0.05766147 0.3650321 -0.9301868 -0.03878295 0.3948396 -0.9178463 -0.04074102 0.4546531 -0.8903189 -0.02495861 0.4826861 -0.8753435 -0.02807134 0.5398486 -0.8416337 -0.01470822 0.5643455 -0.8253282 -0.01864534 0.6197919 -0.784732 -0.007339775 0.6401935 -0.7681235 -0.01177084 0.6937314 -0.7202296 -0.002493023 0.7099702 -0.7041961 -0.007095515 0.7609877 -0.6487663 9.18715e-5 0.7721728 -0.6354003 -0.003987491 0.8209179 -0.5710455 0.001084923 0.8269082 -0.5623342 -0.001719772 0.8729354 -0.4878349 0.001010835 0.8746009 -0.4848437 0 0.9165499 -0.3999204 0 0.9152948 -0.4027834 0.001019358 0.9513387 -0.3081399 -0.002135992 0.9446874 -0.3279668 0.00193417 0.9769449 -0.2134202 -0.005527019 0.9691573 -0.2464339 0.002158284 0.9931236 -0.1166107 -0.01037925 0.9869614 -0.1609528 0.001215875 0.9996784 -0.01873582 -0.01709222 0.9974453 -0.07141685 -0.001641988 0.9965044 0.07933819 -0.02616018 0.9997771 0.02002716 -0.00669068 0.9835596 0.1765661 -0.03788125 -0.008161306 0.8199102 -0.5724341 -0.03226941 0.8043016 -0.5933445 -0.08731621 0.7838109 -0.6148303 -0.1108053 0.764437 -0.6351049 -0.1584246 0.7410939 -0.6524427 -0.1801228 0.7189882 -0.6712763 -0.2220096 0.6935304 -0.6853666 -0.2411076 0.6698865 -0.7022245 -0.2784169 0.6427482 -0.7136938 -0.2944493 0.6188107 -0.7282671 -0.3272668 0.590905 -0.737379 -0.3401157 0.5678611 -0.74957 -0.3696668 0.5389977 -0.7568541 -0.3794533 0.5178204 -0.7667316 -0.4070023 0.487242 -0.7726219 -0.4139897 0.4687687 -0.7803003 -0.4402312 0.4358841 -0.7849852 -0.4448047 0.4207799 -0.7906283 -0.4695631 0.3858714 -0.7941119 -0.4721971 0.3746504 -0.7979142 -0.4959793 0.3369852 -0.8002785 -0.4971739 0.330039 -0.8024291 -0.520499 0.2884524 -0.8036642 -0.5207637 0.2860785 -0.804341 -0.5437944 0.2395819 -0.8042936 -0.5436689 0.2419236 -0.8036772 -0.5660349 0.1902729 -0.8021227 -0.566042 0.1970029 -0.8004913 -0.5874571 0.1395567 -0.7971312 -0.5880726 0.1502386 -0.794732 -0.6081073 0.08616667 -0.7891646 -0.6097313 0.100304 -0.7862359 -0.6276561 0.02914053 -0.7779453 -0.6306431 0.04621368 -0.7746958 -0.6452651 -0.03117036 -0.7633228 -0.6499024 -0.01174157 -0.7599271 -0.6602517 -0.09545481 -0.7449538 -0.6667391 -0.0742855 -0.7415799 -0.6716212 -0.1647453 -0.7223463 -0.6800963 -0.1425325 -0.7191338 -0.6780084 -0.2394353 -0.6949644 -0.6884706 -0.216987 -0.692044 -0.6779037 -0.3180425 -0.6627938 -0.6901941 -0.296185 -0.6602323 -0.6697659 -0.3999621 -0.6256549 -0.6835303 -0.3795497 -0.6234809 -0.6517899 -0.4846319 -0.5833541 -0.6664901 -0.4664866 -0.5815335 -0.6223078 -0.5704253 -0.5360485 -0.637152 -0.5552433 -0.5345486 -0.5809116 -0.6535912 -0.4851396 -0.5949468 -0.6417894 -0.4838852 -0.5273567 -0.7317509 -0.4317821 -0.5395801 -0.7234297 -0.4307006 -0.4615351 -0.8030081 -0.3770458 -0.4709819 -0.7979328 -0.3761373 -0.3897234 -0.8613785 -0.325796 0.8585212 -0.5127782 0 0.6448065 -0.7641109 -0.01894849 0.5098832 -0.8597093 -0.03031498 0.5352525 -0.8441113 -0.03132098 0.588297 -0.8084165 -0.01921993 0.6593595 -0.7513976 -0.02543586 0.8761483 -0.4817508 -0.0167424 0.8326569 -0.5537892 3.14805e-4 0.7659074 -0.6429169 -0.006622612 0.7821452 -0.6228618 -0.01709014 0.7251026 -0.6886218 -0.005144596 0.3305736 -0.9416356 -0.06359052 0.2602235 -0.9618674 -0.08423197 0.2591558 -0.9613943 -0.09251666 -0.1984114 -0.9550445 -0.2202793 -0.1911171 -0.9568136 -0.219048 -0.08973646 -0.979412 -0.1808302 0.1283016 -0.9852569 -0.1131712 0.04209059 -0.9889709 -0.1420032 0.04103744 -0.9878438 -0.1499357 0.3595909 -0.9310154 -0.06248873 0.3571124 -0.9303511 -0.08317154 0.3351108 -0.9387549 -0.08024924 0.3340869 -0.9385026 -0.08717215 0.3506833 -0.9323047 -0.08848208 0.3485664 -0.931766 -0.1015568 0.3486086 -0.9317501 -0.101557 0.3454389 -0.9305358 -0.121553 0.3139362 -0.9416386 -0.1214942 0.3102486 -0.9386417 -0.1506572 0.2159633 -0.9646796 -0.1508416 0.02060931 -0.9892573 -0.1447253 -0.07469677 -0.9810856 -0.1785818 -0.07567954 -0.9794881 -0.1867502 -0.1233284 -0.9699431 -0.2097633 -0.1227052 -0.9709546 -0.2054039 -0.3606973 -0.8916661 -0.2735493 -0.3603788 -0.892953 -0.2697447 -0.5728865 -0.7559795 -0.3166959 -0.5737128 -0.7637565 -0.2958544 -0.7479685 -0.5837512 -0.3158763 -0.717854 -0.6295107 -0.2973247 -0.837636 -0.4528977 -0.3053681 -0.8454285 -0.4616976 -0.2684885 -0.9069368 -0.3266475 -0.266021 -0.9177144 -0.3333854 -0.2159968 -0.9360734 -0.2775773 -0.2161425 0.2317447 -0.968945 -0.08625537 0.1543124 -0.9818176 -0.1105535 0.1525856 -0.9805642 -0.1233353 0.1184654 -0.9831541 -0.1391912 0.1182295 -0.9829796 -0.140616 -0.1137959 -0.9720411 -0.2053939 -0.115056 -0.9701972 -0.2132593 -0.3571853 -0.8942329 -0.2697523 -0.3569886 -0.8951289 -0.2670271 -0.5524856 -0.7786965 -0.2973072 -0.5536807 -0.7840844 -0.2804453 -0.6930744 -0.6599928 -0.289927 -0.6973735 -0.6666111 -0.2632488 -0.7346779 -0.6251585 -0.2634871 0.8611815 -0.5082976 0 0.8585364 -0.5127485 0.002105295 0.7751606 -0.6317263 -0.006920456 0.7660445 -0.6427845 -0.002008616 0.6612323 -0.7498995 -0.02055937 0.6450541 -0.7639948 -0.01473575 0.5166494 -0.8550837 -0.04365319 0.5338083 -0.8442628 -0.04763525 0.4513311 -0.8909325 -0.05039238 0.4519016 -0.8909379 -0.04488527 0.4240316 -0.904533 -0.04491502 -0.5684015 -0.7178928 -0.4019325 -0.5790917 -0.7096136 -0.4013743 -0.4911953 -0.7948659 -0.3562521 -0.4993504 -0.789924 -0.3559063 -0.5074265 -0.7878783 -0.3489502 -0.4999258 -0.7925531 -0.3491903 -0.5906047 -0.7058872 -0.3910363 -0.5807204 -0.7137941 -0.3914868 -0.6490826 -0.6305317 -0.4255841 -0.6444022 -0.6222568 -0.4444575 -0.6322551 -0.634003 -0.445302 -0.7714853 -0.2600621 -0.5806705 -0.7620992 -0.2805882 -0.5835025 -0.7763315 -0.1779791 -0.6046759 -0.7687361 -0.1987028 -0.6079162 -0.7734833 -0.1224343 -0.6218791 -0.758937 -0.06177878 -0.648227 -0.7015849 0.1775038 -0.690124 -0.7619151 -0.04867017 -0.6458457 -0.7558771 0.01798677 -0.6544663 -0.7355946 0.06656759 -0.6741435 -0.7369998 0.08123928 -0.6709929 -0.7233374 0.1410216 -0.6759408 -0.7011513 0.1957508 -0.6856154 -0.6823027 0.2479698 -0.6877312 -0.6623725 0.2734007 -0.6975061 -0.6590771 0.2969975 -0.6909486 -0.6352216 0.3450874 -0.6909474 -0.5679271 -0.7510333 -0.3367611 -0.5670756 -0.7456576 -0.349886 -0.5602809 -0.7494937 -0.3526253 -0.4643174 0.8551939 -0.2303321 -0.6430301 0.7329254 -0.2221099 -0.6382375 0.7241803 -0.2611817 -0.7573752 0.600152 -0.2572946 -0.7475694 0.5896482 -0.3057042 -0.8242488 0.4773641 -0.3045282 -0.8087134 0.467278 -0.357259 -0.860958 0.3620913 -0.3572695 -0.8405374 0.3546186 -0.4095639 -0.8794734 0.242623 -0.409464 -0.8564357 0.2392699 -0.457458 -0.8836652 0.1093257 -0.4551746 -0.8610298 0.1106999 -0.4963603 -0.8716164 -0.03905057 -0.4886307 -0.8524526 -0.03370958 -0.5217167 -0.8387645 -0.2072559 -0.5035068 -0.8253576 -0.1999734 -0.5280111 -0.7769895 -0.3910614 -0.4933137 -0.7591357 -0.3750687 -0.5320118 -0.7446635 -0.4485854 -0.4942139 -0.7331618 -0.4372183 -0.5208781 -0.7389902 0.3190112 -0.5934015 -0.7428991 0.2922132 -0.6022562 -0.7750526 0.2002457 -0.599329 -0.7763752 0.2092307 -0.5945284 -0.8052936 0.07955914 -0.5875141 -0.8089689 0.09275281 -0.5804879 -0.8214631 -0.05774813 -0.5673304 -0.7691818 0.3045616 -0.5617844 -0.7632611 0.3284215 -0.5563918 -0.8042993 0.2139913 -0.5543558 -0.8050079 0.2215548 -0.5503416 -0.8334153 0.09182631 -0.5449651 -0.8157197 -0.2159371 -0.5366309 -0.8281029 -0.04209798 -0.5589933 -0.8475068 -0.04721564 -0.5286805 -0.8359171 0.103074 -0.5390904 -0.8595291 0.1019368 -0.5008181 -0.8316643 0.2317312 -0.5046138 -0.8564618 0.2355958 -0.4593123 -0.8177736 0.3458206 -0.4600592 -0.8405965 0.3542873 -0.4097293 -0.7908177 0.4546684 -0.4097365 -0.8090574 0.4663657 -0.357672 -0.7393408 0.5701518 -0.3581929 -0.7516207 0.5828896 -0.3087168 -0.6474988 0.6958216 -0.3107695 -0.6539593 0.7072622 -0.2685471 -0.5014325 0.8209285 -0.2732066 -0.5037267 0.8290824 -0.2426562 -0.2890593 0.9239576 -0.2504939 0.8973392 0.4084671 -0.1671443 0.8139029 0.5475183 -0.1943863 0.8380145 0.5107139 -0.1921019 0.7518568 0.6210746 -0.2213096 0.6906357 0.6843138 -0.2339597 0.6334701 0.7307429 -0.2544219 0.4951483 0.827768 -0.263872 0.4772571 0.8366831 -0.268677 0.3113836 0.9082149 -0.2796174 0.3318495 0.9029266 -0.2731292 0.1079152 0.9559816 -0.2728617 0.150388 0.9531232 -0.2625642 -0.0966838 0.9607748 -0.2599308 -0.009576499 0.9710007 -0.2388848 -0.2892078 0.9254856 -0.2446129 -0.2364609 0.9441112 -0.2296528 -0.4667884 0.8632277 -0.1922155 -0.6157639 0.7598846 -0.2083517 -0.6153793 0.7592541 -0.2117581 -0.7566018 0.6207649 -0.2054383 -0.7491044 0.6125403 -0.2522635 -0.8360149 0.4883091 -0.2502667 -0.8231925 0.4798815 -0.3034272 -0.879077 0.3675947 -0.303476 -0.8611668 0.3611571 -0.3577113 -0.9005444 0.2463493 -0.3582345 -0.8794271 0.2435514 -0.4090119 -0.9058502 0.1132501 -0.4081788 -0.8843626 0.1148962 -0.4524397 -0.8937422 -0.03402024 -0.4472892 -0.8749645 -0.02842605 -0.4833518 -0.8599106 -0.2010411 -0.4691869 -0.8463264 -0.193304 -0.4963518 -0.7962301 -0.3843408 -0.4672256 -0.7887105 -0.3771715 -0.4854661 -0.7210601 -0.4548453 -0.5226741 -0.7577756 -0.346571 -0.5528696 -0.7698783 -0.3557467 -0.5298412 -0.7911157 -0.2714887 -0.5481149 -0.7898998 -0.202591 -0.578805 -0.7956961 -0.1863374 -0.5763213 -0.8019486 -0.0528441 -0.5950514 -0.7935222 -0.07007187 -0.6044937 -0.7801246 0.08033424 -0.620445 -0.7751461 0.06559032 -0.628368 -0.7457195 0.1951312 -0.637045 -0.7436498 0.1849573 -0.6424763 -0.7047027 0.2932981 -0.6460421 -0.7044085 0.2895177 -0.648065 -0.6583302 0.3826975 -0.6481851 -0.6581328 0.3866091 -0.6460608 -0.6028057 0.4722676 -0.6431086 -0.6006486 0.4834396 -0.6367947 -0.5314605 0.5663301 -0.6299365 -0.5253385 0.5833156 -0.6194857 -0.4393588 0.6618714 -0.6073633 -0.4277336 0.6821886 -0.5930116 -0.3330321 0.7462835 -0.5763251 -0.3264641 0.7198554 -0.6125597 -0.308263 0.7377674 -0.6005607 -0.5920884 -0.7102869 -0.3806887 -0.5576136 -0.7371435 -0.3816892 -0.5080534 -0.7916517 -0.339366 -0.4104061 -0.860737 -0.3011623 -0.4104152 -0.8586488 -0.3070531 -0.4124944 -0.857006 -0.3088514 -0.4014944 -0.8620439 -0.3093264 -0.401211 -0.8596743 -0.316212 -0.4904982 -0.7923632 -0.362729 -0.481822 -0.7974497 -0.3632103 -0.5666301 -0.7139182 -0.4114013 -0.5553281 -0.7223546 -0.4120857 -0.6287676 -0.6284001 -0.4580008 -0.6158756 -0.6403539 -0.4589601 -0.9711019 0.1865099 -0.148913 -0.9857726 0.02939862 -0.1654941 -0.9740268 0.03096604 -0.2243056 -0.9679677 -0.1018376 -0.2294945 -0.9541407 -0.09634029 -0.2834326 -0.9263128 -0.245248 -0.2860037 -0.9141556 -0.2366207 -0.3291357 -0.8548739 -0.4044334 -0.3249992 -0.8467991 -0.3948004 -0.3564605 -0.7375612 -0.5843826 -0.3383791 -0.752772 -0.5561042 -0.3522535 -0.5764908 -0.7533056 -0.3165268 -0.5756316 -0.7452634 -0.3364979 -0.3605911 -0.8917105 -0.2735444 -0.3608543 -0.8903427 -0.2776221 -0.3616307 -0.8897893 -0.2783852 -0.3058121 -0.9033122 -0.3008423 -0.3039397 -0.9158175 -0.2624866 -0.302998 -0.9161794 -0.2623119 -0.712108 -0.446457 -0.5418288 -0.6990489 -0.4645534 -0.5436183 -0.7343656 -0.3569889 -0.5772922 -0.7224065 -0.3770927 -0.5795947 -0.7458921 -0.2714853 -0.6082276 -0.7354984 -0.2927479 -0.6110163 -0.7486931 -0.1902993 -0.6350157 -0.740122 -0.2119044 -0.6382131 -0.74447 -0.1139075 -0.6578675 -0.7377902 -0.1350451 -0.6613838 -0.734782 -0.04379481 -0.676888 -0.7299286 -0.06374651 -0.6805443 -0.7210831 0.02058547 -0.6925427 -0.7178825 0.002447903 -0.69616 -0.704415 0.08034932 -0.7052259 -0.7026195 0.0645675 -0.7086303 -0.685528 0.1362087 -0.7151913 -0.6848286 0.1232552 -0.7182047 -0.6653498 0.1875997 -0.722576 -0.6653839 0.1778967 -0.7249945 -0.64433 0.2354332 -0.7276058 -0.6446992 0.2293593 -0.7292169 -0.6225191 0.2809808 -0.7304244 -0.6227744 0.2788767 -0.731013 -0.5997506 0.3253505 -0.7310584 -0.5993843 0.3274559 -0.7304186 -0.5756652 0.3694922 -0.7294417 -0.5741902 0.3756037 -0.7274802 -0.5494813 0.41425 -0.7255806 -0.546481 0.4240766 -0.7221618 -0.5202193 0.4604141 -0.7192988 -0.5152499 0.4735603 -0.7143237 -0.4868816 0.5082161 -0.7103962 -0.4795446 0.5241866 -0.7037509 -0.4493595 0.5566638 -0.6987143 -0.4393213 0.5748374 -0.6903323 -0.4066143 0.6056155 -0.6840284 -0.3936818 0.6252753 -0.673829 -0.3571404 0.6550251 -0.6658776 -0.3412001 0.6753022 -0.6538726 -0.2995669 0.7041637 -0.6437493 -0.2807776 0.7240287 -0.6300368 -0.234057 0.7509149 -0.6175307 -0.212861 0.7693224 -0.6023566 -0.1598739 0.7937049 -0.5869183 -0.1370249 0.8096657 -0.5706713 -0.07596796 0.830743 -0.5514482 -0.05256539 0.8433768 -0.5347453 0.004322469 0.8567392 -0.5157319 0.917298 -0.3982016 0 0.9271327 -0.3747273 0.002062737 0.9271538 -0.3746761 -0.001927733 0.9698718 -0.2433937 -0.01040446 0.969867 -0.2434638 -0.009132742 0.9958789 -0.08616483 -0.02829921 0.9958646 -0.08611619 -0.02894246 0.9991648 -0.02940636 -0.02837258 0.9994333 -0.0305972 -0.01403808 0.992546 0.1147123 -0.04115265 0.9934579 0.1132674 -0.01456159 0.9771479 0.2092217 -0.03752601 0.9700163 0.2395873 -0.0408225 0.9393075 0.3363344 -0.06768101 0.9406844 0.3360112 -0.04700446 0.8871268 0.4530293 -0.08815085 -0.9285188 0.3438963 -0.1399579 -0.9684686 0.2036294 -0.1435396 -0.9572052 0.2025902 -0.2066773 -0.975065 0.06814652 -0.2111971 -0.9603952 0.07035416 -0.2696134 -0.9594876 -0.06913709 -0.2731366 -0.9442256 -0.0631752 -0.3231827 -0.9201653 -0.22116 -0.3230856 -0.9073787 -0.2123076 -0.3627526 -0.8501623 -0.3894691 -0.3543134 -0.84199 -0.3800045 -0.3829487 -0.7370738 -0.5723825 -0.3593057 -0.7331215 -0.5638103 -0.3803301 -0.7391983 -0.550206 -0.3884061 -0.7188826 -0.5696597 -0.3983663 -0.7157735 -0.5637657 -0.4121125 -0.7061324 -0.5723018 -0.4169507 -0.7032026 -0.5671632 -0.4287565 -0.6916044 -0.5767191 -0.4348316 -0.6817616 -0.5610452 -0.4694992 -0.7012978 -0.5378962 -0.4678132 -0.6955827 -0.530502 -0.4844919 -0.6830102 -0.5454618 -0.4857659 -0.6771153 -0.5383033 -0.5017416 -0.6636748 -0.5535861 -0.5030689 0.8574739 -0.5145194 -0.002894759 0.8627684 -0.5055994 0 0.8627759 -0.5055863 6.31896e-4 0.8611791 -0.5083016 0 0.9113356 -0.4116643 0 0.9127056 -0.4086176 6.75405e-4 0.913749 -0.406279 0 0.9137462 -0.4062856 0 0.8763098 -0.4817481 0 0.8746 -0.4848445 9.39063e-4 0.8326442 -0.5538063 -0.00157243 0.8269196 -0.5623197 8.2626e-4 0.7824527 -0.6226982 -0.003866732 0.7722063 -0.6353716 -5.68306e-4 0.7250468 -0.6886609 -0.007299542 0.7100278 -0.7041643 -0.003647267 0.6599349 -0.7512206 -0.01239168 0.6402676 -0.7681006 -0.008885145 0.5882813 -0.8084223 -0.01946002 0.5644118 -0.8253281 -0.01651805 0.5099646 -0.8597036 -0.02908754 0.4827272 -0.8753529 -0.02705198 0.4242498 -0.9045658 -0.04210591 0.3948158 -0.9178364 -0.04119402 0.3309533 -0.9417818 -0.05930513 0.300915 -0.9517886 -0.05957055 0.232258 -0.9692875 -0.08085936 0.2034086 -0.9756383 -0.08218818 0.1288717 -0.9858359 -0.1073305 0.10313 -0.9886332 -0.1094008 0.02109873 -0.9900099 -0.1394112 4.44577e-4 -0.9899026 -0.1417495 -0.0894649 -0.9800822 -0.1772996 -0.1032606 -0.9783633 -0.179284 -0.1983965 -0.9551221 -0.2199562 -0.2042254 -0.9536622 -0.2209539 -0.303048 -0.9149098 -0.2666498 -0.30052 -0.9158871 -0.266155 -0.4018632 -0.8591036 -0.316934 -0.390437 -0.8640074 -0.3178839 -0.4810068 -0.7950683 -0.3694578 -0.4719107 -0.8001961 -0.370117 -0.5534254 -0.7185724 -0.4211581 -0.5416178 -0.7270195 -0.4220106 -0.6122369 -0.6349905 -0.471119 -0.5987346 -0.6469455 -0.472206 -0.6575911 -0.5466474 -0.5184118 -0.6434084 -0.5619803 -0.5198112 -0.6898556 -0.4563336 -0.5620133 -0.6759428 -0.4745596 -0.5638214 -0.7095986 -0.3681005 -0.6008094 -0.6967098 -0.3884916 -0.6030504 -0.7187801 -0.283642 -0.634746 -0.7074244 -0.3053387 -0.6374318 -0.7193995 -0.2034289 -0.6641394 -0.7098721 -0.22558 -0.6672295 -0.7131764 -0.1279767 -0.6892035 -0.7055948 -0.1497647 -0.6926085 -0.7017078 -0.05875861 -0.7100378 -0.6960382 -0.07943081 -0.7135976 -0.6864799 0.004741549 -0.7271333 -0.682577 -0.01414102 -0.7306768 -0.6685425 0.06363534 -0.7409464 -0.6661605 0.04712527 -0.7443181 -0.6486654 0.1186535 -0.7517678 -0.6475172 0.1050434 -0.7547765 -0.6277476 0.1693477 -0.7597725 -0.6274753 0.1591187 -0.7622046 -0.6062203 0.2166799 -0.7652103 -0.6064163 0.2102632 -0.7668433 -0.5841287 0.2619447 -0.768231 -0.5843198 0.2597195 -0.7688409 -0.5612802 0.3062356 -0.7688852 -0.5609542 0.3084813 -0.768225 -0.5374157 0.3503062 -0.7671179 -0.536065 0.3568595 -0.7650397 -0.5118184 0.3950202 -0.7628899 -0.5089668 0.4055775 -0.7592496 -0.4834547 0.4411891 -0.756058 -0.4786373 0.4553441 -0.7507117 -0.4513365 0.4890981 -0.7463769 -0.4441168 0.5063593 -0.7391621 -0.4152544 0.5378515 -0.7336755 -0.4052696 0.5575537 -0.7244933 -0.374176 0.5873435 -0.717649 -0.3611744 0.6087267 -0.7064028 -0.3265405 0.6375138 -0.6978163 -0.3104375 0.6596222 -0.6844905 -0.2710145 0.6875823 -0.6736332 -0.2519454 0.7093346 -0.6583068 -0.2076986 0.73545 -0.6449609 -0.1861163 0.7557243 -0.6278867 -0.1358758 0.7795167 -0.6114667 -0.1125655 0.7971831 -0.5931511 -0.05458331 0.8179061 -0.5727568 -0.03068399 0.8320098 -0.5539117 0.05820202 0.852302 -0.5198019 0.05538707 0.8359563 -0.5459939 0.07864034 0.8471193 -0.5255517 0.07519346 0.8232709 -0.5626464 0.09812772 0.835595 -0.540511 0.6410009 -0.7675402 4.93003e-5 -0.318971 -0.9477645 3.64422e-5 -0.9963284 -0.08561468 -3.50042e-6 0.1203318 0.9927337 -4.7645e-4 0.1974078 0.980319 -0.002191841 -0.4588832 0.8884966 -3.65255e-4 -0.3175416 0.9482429 -0.001684725 -0.3191934 0.9476883 -0.001641809 -0.1263834 0.9919816 3.13052e-6 -0.04041045 0.9991832 -1.84025e-6 -0.8417727 0.5398321 -1.77139e-4 -0.7336894 0.6794813 -0.002254545 -0.7502713 0.6611281 -0.001659929 -0.6079241 0.7939952 1.85324e-5 -0.5158336 0.8566889 -1.09969e-5 -0.9803214 0.1974089 4.22884e-5 -0.9997124 0.0232917 -0.00570935 -0.9926298 0.1211349 -0.003565609 -0.975705 0.2190828 -0.001564979 -0.9277849 0.3731158 -2.70103e-6 -0.889065 0.457781 6.22907e-7 -0.6611212 -0.7502791 -6.70023e-5 -0.5773859 -0.8164623 -0.003881275 -0.7716425 -0.6360564 1.83721e-4 -0.9476809 -0.319219 -3.94935e-4 -0.9082422 -0.4184272 -0.00386554 -0.9783336 -0.2070346 -3.38496e-4 0.3192004 -0.9476873 -1.14526e-4 0.5330281 -0.8460474 -0.009228408 0.4174782 -0.9086759 -0.004472613 0.2705435 -0.9627065 -0.00159955 0.1484854 -0.9889146 2.10739e-5 -0.1974064 -0.9803218 -6.21884e-5 0.008805871 -0.9999306 -0.007827877 -0.1094691 -0.9939815 -0.004156827 0.9991688 0.040766 4.08512e-6 0.9993597 -0.03578138 -2.69457e-4 0.9801007 -0.1984894 -0.002147555 0.980316 -0.1974238 -0.002116322 0.9262317 -0.3769547 -2.23083e-6 0.7502786 -0.6611218 5.80023e-6 0.8749551 -0.4841286 -0.008560597 0.7926369 -0.609683 -0.003674745 0.921809 0.3876439 -7.71881e-4 0.9476834 0.3192024 -0.002465605 0.9665342 0.2565339 -0.001435279 0.9882993 0.1525273 -1.53303e-5 0.3530766 0.9355944 0 0.5509455 0.8345413 0 0.6611209 0.7502755 -0.002424776 0.7395271 0.6731268 -2.55124e-4 0.8444823 0.5355834 6.24094e-5 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 0 4 0 5 0 6 0 7 0 8 0 9 0 10 0 11 0 12 0 13 0 14 0 15 0 16 0 17 0 18 0 19 0 20 0 21 0 22 0 23 0 24 0 25 0 23 0 26 0 27 0 28 0 29 0 30 0 31 0 32 0 33 0 34 0 35 0 36 0 37 0 36 0 38 0 37 0 37 0 38 0 39 0 37 0 39 0 40 0 40 0 39 0 41 0 40 0 41 0 42 0 42 0 41 0 43 0 42 0 43 0 44 0 45 0 46 0 47 0 47 0 46 0 48 0 48 0 46 0 49 0 48 0 49 0 50 0 51 0 52 0 53 0 53 0 52 0 54 0 53 0 54 0 55 0 55 0 54 0 56 0 55 0 56 0 57 0 58 0 59 0 60 0 26 0 28 0 61 0 61 0 28 0 62 0 61 0 62 0 63 0 64 0 65 0 63 0 66 0 67 0 68 0 65 0 64 0 69 0 69 0 64 0 66 0 69 0 66 0 70 0 70 0 66 0 68 0 70 0 68 0 71 0 72 0 23 0 73 0 73 0 23 0 25 0 73 0 25 0 74 0 72 0 75 0 23 0 23 0 75 0 76 0 23 0 76 0 77 0 77 0 76 0 78 0 77 0 78 0 66 0 66 0 78 0 79 0 66 0 79 0 67 0 71 0 80 0 70 0 70 0 80 0 81 0 70 0 81 0 82 0 82 0 81 0 83 0 82 0 83 0 25 0 25 0 83 0 84 0 25 0 84 0 74 0 22 0 85 0 23 0 23 0 85 0 86 0 23 0 86 0 24 0 18 0 20 0 87 0 88 0 89 0 90 0 90 0 89 0 91 0 92 0 93 0 94 0 94 0 93 0 95 0 94 0 95 0 96 0 97 0 98 0 99 0 99 0 98 0 100 0 99 0 100 0 101 0 101 0 100 0 102 0 101 0 102 0 103 0 15 0 17 0 104 0 104 0 17 0 105 0 104 0 105 0 106 0 106 0 105 0 107 0 106 0 107 0 13 0 108 0 109 0 110 0 110 0 109 0 111 0 110 0 111 0 14 0 14 0 111 0 112 0 14 0 112 0 12 0 113 0 114 0 115 0 115 0 114 0 116 0 115 0 116 0 117 0 118 0 119 0 120 0 120 0 119 0 121 0 110 0 122 0 108 0 108 0 122 0 120 0 108 0 120 0 123 0 123 0 120 0 121 0 121 0 124 0 123 0 123 0 124 0 125 0 123 0 125 0 126 0 126 0 125 0 127 0 126 0 127 0 128 0 128 0 127 0 129 0 129 0 127 0 130 0 129 0 130 0 131 0 132 0 133 0 129 0 134 0 133 0 135 0 135 0 133 0 132 0 135 0 132 0 136 0 137 0 138 0 139 0 139 0 138 0 140 0 140 0 141 0 8 0 8 0 141 0 142 0 8 0 142 0 143 0 142 0 144 0 143 0 143 0 144 0 145 0 143 0 145 0 146 0 146 0 145 0 147 0 146 0 147 0 148 0 148 0 147 0 149 0 148 0 149 0 150 0 150 0 149 0 151 0 150 0 151 0 152 0 152 0 151 0 153 0 152 0 153 0 154 0 154 0 153 0 155 0 154 0 155 0 156 0 64 0 157 0 158 0 159 0 160 0 11 0 11 0 160 0 161 0 11 0 161 0 162 0 63 0 62 0 64 0 64 0 62 0 163 0 64 0 163 0 157 0 161 0 164 0 162 0 162 0 164 0 165 0 162 0 165 0 166 0 167 0 168 0 28 0 28 0 168 0 169 0 28 0 169 0 62 0 62 0 169 0 170 0 62 0 170 0 163 0 171 0 172 0 173 0 173 0 174 0 171 0 171 0 174 0 175 0 171 0 175 0 176 0 177 0 178 0 179 0 179 0 178 0 180 0 179 0 180 0 172 0 172 0 180 0 181 0 172 0 181 0 173 0 182 0 183 0 184 0 184 0 183 0 185 0 184 0 185 0 186 0 187 0 188 0 189 0 189 0 188 0 190 0 191 0 192 0 136 0 136 0 192 0 193 0 192 0 194 0 193 0 193 0 194 0 195 0 193 0 195 0 196 0 196 0 195 0 197 0 198 0 199 0 200 0 158 0 159 0 64 0 64 0 159 0 11 0 64 0 11 0 201 0 201 0 11 0 10 0 140 0 8 0 139 0 139 0 8 0 7 0 139 0 7 0 202 0 202 0 203 0 139 0 139 0 203 0 204 0 139 0 204 0 205 0 205 0 204 0 206 0 205 0 206 0 207 0 207 0 206 0 208 0 207 0 208 0 209 0 201 0 210 0 64 0 64 0 210 0 211 0 64 0 211 0 66 0 66 0 211 0 212 0 66 0 212 0 77 0 77 0 212 0 213 0 77 0 213 0 214 0 215 0 216 0 217 0 217 0 216 0 218 0 219 0 115 0 120 0 120 0 115 0 117 0 120 0 117 0 118 0 220 0 221 0 222 0 222 0 221 0 223 0 222 0 223 0 224 0 224 0 223 0 225 0 224 0 225 0 226 0 226 0 225 0 227 0 226 0 227 0 228 0 229 0 179 0 230 0 230 0 179 0 231 0 231 0 179 0 232 0 232 0 179 0 172 0 232 0 172 0 233 0 131 0 113 0 129 0 129 0 113 0 115 0 129 0 115 0 132 0 132 0 115 0 189 0 132 0 189 0 136 0 136 0 189 0 190 0 136 0 190 0 191 0 219 0 218 0 115 0 115 0 218 0 216 0 115 0 216 0 189 0 189 0 216 0 215 0 189 0 215 0 187 0 187 0 215 0 234 0 187 0 234 0 235 0 235 0 234 0 2 0 235 0 2 0 236 0 236 0 2 0 1 0 236 0 1 0 233 0 233 0 1 0 0 0 233 0 0 0 232 0 13 0 107 0 14 0 14 0 107 0 225 0 14 0 225 0 110 0 110 0 225 0 223 0 110 0 223 0 122 0 122 0 223 0 221 0 122 0 221 0 120 0 120 0 221 0 220 0 120 0 220 0 219 0 237 0 238 0 227 0 237 0 227 0 239 0 239 0 227 0 225 0 239 0 225 0 240 0 241 0 242 0 105 0 105 0 242 0 243 0 105 0 243 0 107 0 107 0 243 0 244 0 107 0 244 0 245 0 245 0 246 0 107 0 107 0 246 0 247 0 107 0 247 0 225 0 225 0 247 0 248 0 225 0 248 0 240 0 26 0 58 0 27 0 27 0 58 0 60 0 27 0 60 0 28 0 28 0 60 0 166 0 28 0 166 0 167 0 167 0 166 0 165 0 249 0 134 0 250 0 250 0 134 0 135 0 250 0 135 0 251 0 251 0 135 0 136 0 251 0 136 0 252 0 252 0 136 0 193 0 252 0 193 0 253 0 253 0 193 0 196 0 253 0 196 0 49 0 49 0 196 0 34 0 49 0 34 0 50 0 50 0 34 0 33 0 197 0 199 0 196 0 196 0 199 0 198 0 196 0 198 0 34 0 34 0 198 0 42 0 34 0 42 0 32 0 32 0 42 0 44 0 230 0 3 0 229 0 229 0 3 0 5 0 229 0 5 0 179 0 179 0 5 0 186 0 179 0 186 0 177 0 177 0 186 0 185 0 238 0 241 0 227 0 227 0 241 0 105 0 227 0 105 0 254 0 254 0 105 0 17 0 254 0 17 0 102 0 102 0 17 0 16 0 102 0 16 0 103 0 103 0 16 0 15 0 59 0 57 0 60 0 60 0 57 0 56 0 60 0 56 0 166 0 166 0 56 0 255 0 166 0 255 0 162 0 162 0 255 0 256 0 162 0 256 0 11 0 11 0 256 0 207 0 11 0 207 0 9 0 9 0 207 0 209 0 176 0 257 0 171 0 171 0 257 0 258 0 171 0 258 0 95 0 95 0 258 0 259 0 95 0 259 0 96 0 257 0 182 0 258 0 258 0 182 0 184 0 258 0 184 0 259 0 259 0 184 0 260 0 259 0 260 0 96 0 96 0 260 0 261 0 3 0 228 0 4 0 4 0 228 0 227 0 4 0 227 0 5 0 5 0 227 0 254 0 5 0 254 0 186 0 186 0 254 0 102 0 186 0 102 0 184 0 184 0 102 0 100 0 184 0 100 0 260 0 260 0 100 0 98 0 260 0 98 0 261 0 261 0 98 0 97 0 51 0 249 0 52 0 52 0 249 0 250 0 52 0 250 0 54 0 54 0 250 0 251 0 54 0 251 0 56 0 56 0 251 0 252 0 56 0 252 0 255 0 255 0 252 0 253 0 255 0 253 0 256 0 256 0 253 0 49 0 256 0 49 0 207 0 207 0 49 0 46 0 207 0 46 0 205 0 205 0 46 0 45 0 205 0 45 0 139 0 139 0 45 0 156 0 139 0 156 0 137 0 137 0 156 0 155 0 200 0 236 0 198 0 198 0 236 0 233 0 198 0 233 0 42 0 42 0 233 0 172 0 42 0 172 0 40 0 40 0 172 0 171 0 40 0 171 0 37 0 37 0 171 0 95 0 37 0 95 0 88 0 88 0 95 0 93 0 88 0 93 0 89 0 89 0 93 0 92 0 214 0 6 0 77 0 77 0 6 0 8 0 77 0 8 0 23 0 23 0 8 0 143 0 23 0 143 0 21 0 21 0 143 0 146 0 47 0 29 0 45 0 45 0 29 0 31 0 45 0 31 0 156 0 156 0 31 0 262 0 156 0 262 0 154 0 154 0 262 0 20 0 154 0 20 0 152 0 152 0 20 0 19 0 30 0 35 0 31 0 31 0 35 0 37 0 31 0 37 0 262 0 262 0 37 0 88 0 262 0 88 0 20 0 20 0 88 0 90 0 20 0 90 0 87 0 87 0 90 0 91 0 55 1 263 1 264 1 55 2 264 2 53 2 53 3 264 3 265 3 53 3 265 3 51 3 51 4 265 4 266 4 51 5 266 5 249 5 249 6 266 6 267 6 249 7 267 7 134 7 134 8 267 8 268 8 134 9 268 9 133 9 133 10 268 10 269 10 133 11 269 11 129 11 129 12 269 12 270 12 129 13 270 13 128 13 128 14 270 14 271 14 128 15 271 15 126 15 126 16 271 16 123 16 123 16 271 16 272 16 123 17 272 17 108 17 272 17 273 17 108 17 108 18 273 18 274 18 108 19 274 19 109 19 109 20 274 20 275 20 109 20 275 20 111 20 111 21 275 21 276 21 111 21 276 21 112 21 112 22 276 22 277 22 112 22 277 22 12 22 12 23 277 23 278 23 12 24 278 24 13 24 13 25 278 25 279 25 13 25 279 25 106 25 106 26 279 26 280 26 106 27 280 27 104 27 104 28 280 28 281 28 104 29 281 29 15 29 15 30 281 30 282 30 15 31 282 31 103 31 103 32 282 32 283 32 103 33 283 33 101 33 101 34 283 34 284 34 101 34 284 34 99 34 99 35 284 35 285 35 99 36 285 36 97 36 97 37 285 37 286 37 97 38 286 38 261 38 261 39 286 39 287 39 261 40 287 40 96 40 96 41 287 41 288 41 96 42 288 42 94 42 94 43 288 43 289 43 94 43 289 43 92 43 92 44 289 44 290 44 92 45 290 45 89 45 89 46 290 46 291 46 89 47 291 47 91 47 91 48 291 48 292 48 91 49 292 49 87 49 87 50 292 50 293 50 87 51 293 51 18 51 18 52 293 52 19 52 19 52 293 52 294 52 19 53 294 53 152 53 152 53 294 53 295 53 152 54 295 54 150 54 150 55 295 55 296 55 150 56 296 56 148 56 296 56 297 56 148 56 148 57 297 57 298 57 148 58 298 58 146 58 146 59 298 59 299 59 146 60 299 60 21 60 21 61 299 61 300 61 21 62 300 62 22 62 22 63 300 63 301 63 22 64 301 64 85 64 85 65 301 65 302 65 85 66 302 66 86 66 86 67 302 67 303 67 86 68 303 68 24 68 24 69 303 69 304 69 24 70 304 70 25 70 25 71 304 71 305 71 25 71 305 71 82 71 82 72 305 72 306 72 82 72 306 72 70 72 70 73 306 73 307 73 70 74 307 74 69 74 69 75 307 75 308 75 69 75 308 75 65 75 65 76 308 76 309 76 65 77 309 77 63 77 63 78 309 78 310 78 63 78 310 78 61 78 61 79 310 79 311 79 61 79 311 79 26 79 26 80 311 80 312 80 26 81 312 81 58 81 58 82 312 82 313 82 58 83 313 83 59 83 59 84 313 84 314 84 59 85 314 85 57 85 57 86 314 86 263 86 57 87 263 87 55 87 315 88 316 88 317 88 318 88 319 88 320 88 321 88 322 88 323 88 324 88 325 88 326 88 327 88 328 88 329 88 330 88 331 88 332 88 274 88 273 88 333 88 265 88 334 88 335 88 313 88 312 88 336 88 288 88 287 88 337 88 338 88 339 88 289 88 340 88 292 88 291 88 292 88 340 88 293 88 293 88 340 88 341 88 293 88 341 88 294 88 294 88 341 88 342 88 294 88 342 88 295 88 302 88 301 88 343 88 343 88 301 88 300 88 343 89 300 89 299 89 344 88 345 88 343 88 345 88 304 88 343 88 343 88 304 88 303 88 343 88 303 88 302 88 346 88 347 88 348 88 346 88 348 88 349 88 347 88 350 88 348 88 348 88 350 88 351 88 348 88 351 88 352 88 352 88 351 88 353 88 352 88 353 88 343 88 343 88 353 88 354 88 343 88 354 88 344 88 345 88 355 88 304 88 304 88 355 88 356 88 304 88 356 88 305 88 305 88 356 88 357 88 305 88 357 88 306 88 306 88 357 88 358 88 306 88 358 88 359 88 312 88 311 88 336 88 336 88 311 88 310 88 336 88 310 88 360 88 360 88 310 88 309 88 360 88 309 88 361 88 361 88 309 88 308 88 361 88 308 88 362 88 362 88 308 88 307 88 362 88 307 88 348 88 348 88 307 88 306 88 348 88 306 88 349 88 349 88 306 88 359 88 263 88 314 88 363 88 363 88 314 88 313 88 364 88 264 88 365 88 365 88 264 88 263 88 265 88 335 88 266 88 266 88 335 88 366 88 266 88 366 88 267 88 267 88 366 88 367 88 267 88 367 88 268 88 268 88 367 88 368 88 268 88 368 88 269 88 369 88 370 88 368 88 269 88 371 88 270 88 270 88 371 88 372 88 270 88 372 88 271 88 271 88 372 88 373 88 271 88 373 88 272 88 272 88 373 88 374 88 272 88 374 88 375 88 376 88 377 88 378 88 378 88 377 88 369 88 370 88 379 88 368 88 368 88 379 88 380 88 368 88 380 88 269 88 269 88 380 88 381 88 269 88 381 88 371 88 333 88 273 88 382 88 382 88 273 88 272 88 382 88 272 88 378 88 378 88 272 88 375 88 378 88 375 88 376 88 278 88 277 88 383 88 383 88 277 88 276 88 383 88 276 88 333 88 333 88 276 88 275 88 333 88 275 88 274 88 281 88 280 88 384 88 384 88 280 88 385 88 384 88 385 88 386 88 315 88 286 88 316 88 316 88 286 88 285 88 316 88 285 88 317 88 317 88 285 88 284 88 317 88 284 88 283 88 387 88 388 88 389 88 389 88 388 88 390 88 389 88 390 88 391 88 330 88 332 88 391 88 331 88 392 88 393 88 393 88 392 88 394 88 395 88 396 88 362 88 397 88 398 88 399 88 399 88 398 88 400 88 399 88 400 88 401 88 395 88 362 88 401 88 396 88 402 88 362 88 362 88 402 88 403 88 362 88 403 88 361 88 361 88 403 88 404 88 361 88 404 88 360 88 360 88 404 88 405 88 360 88 405 88 406 88 407 88 408 88 397 88 397 88 408 88 409 88 397 88 409 88 398 88 410 88 411 88 412 88 412 88 411 88 413 88 414 88 415 88 416 88 416 88 415 88 417 88 416 88 417 88 418 88 419 88 420 88 421 88 421 88 420 88 418 88 421 88 418 88 422 88 422 88 418 88 417 88 423 88 424 88 425 88 425 88 424 88 426 88 427 88 428 88 429 88 427 88 429 88 430 88 429 88 431 88 430 88 430 88 431 88 432 88 430 88 432 88 433 88 433 88 432 88 434 88 433 88 434 88 435 88 428 88 427 88 436 88 436 88 427 88 437 88 436 88 437 88 438 88 438 88 439 88 440 88 440 88 439 88 328 88 329 88 328 88 441 88 442 88 443 88 444 88 444 88 443 88 445 88 446 88 447 88 352 88 448 88 449 88 332 88 391 88 332 88 389 88 389 88 332 88 449 88 389 88 449 88 446 88 450 88 451 88 452 88 452 88 451 88 453 88 452 88 453 88 454 88 454 88 453 88 455 88 454 88 455 88 332 88 332 88 455 88 456 88 332 88 456 88 448 88 457 88 458 88 362 88 401 88 362 88 399 88 399 88 362 88 458 88 399 88 458 88 459 88 447 88 460 88 352 88 352 88 460 88 461 88 352 88 461 88 348 88 348 88 461 88 462 88 348 88 462 88 362 88 362 88 462 88 463 88 362 88 463 88 457 88 464 88 465 88 466 88 369 88 368 88 378 88 378 88 368 88 467 88 378 88 467 88 468 88 435 88 444 88 433 88 433 88 444 88 445 88 433 88 445 88 469 88 469 88 445 88 470 88 471 88 472 88 473 88 473 88 472 88 474 88 475 88 476 88 477 88 477 88 476 88 478 88 477 88 478 88 479 88 471 88 480 88 481 88 481 88 480 88 482 88 481 88 482 88 483 88 483 88 482 88 484 88 321 88 323 88 485 88 486 88 320 88 487 88 487 88 320 88 479 88 487 88 479 88 488 88 488 88 479 88 478 88 446 88 352 88 389 88 389 88 352 88 343 88 389 88 343 88 387 88 387 90 343 90 299 90 387 88 299 88 298 88 291 88 290 88 340 88 340 88 290 88 319 88 340 88 319 88 341 88 341 88 319 88 318 88 341 88 318 88 342 88 393 88 323 88 484 88 484 88 323 88 322 88 484 88 322 88 483 88 486 88 485 88 320 88 320 88 485 88 323 88 320 88 323 88 318 88 318 88 323 88 393 88 318 88 393 88 342 88 342 88 393 88 394 88 342 88 394 88 295 88 295 88 394 88 489 88 295 88 489 88 296 88 296 88 489 88 490 88 296 88 490 88 297 88 297 88 490 88 491 88 297 88 491 88 298 88 298 88 491 88 492 88 298 91 492 91 387 91 387 88 492 88 493 88 387 88 493 88 388 88 338 88 412 88 416 88 416 88 412 88 413 88 416 88 413 88 414 88 289 88 288 88 338 88 338 88 288 88 337 88 338 88 337 88 412 88 412 88 337 88 494 88 412 88 494 88 410 88 287 88 286 88 337 88 337 88 286 88 315 88 337 88 315 88 494 88 494 88 315 88 317 88 494 88 317 88 386 88 386 88 317 88 283 88 386 88 283 88 384 88 384 88 283 88 282 88 384 88 282 88 281 88 438 88 437 88 439 88 439 88 437 88 473 88 439 88 473 88 477 88 477 88 473 88 474 88 477 88 474 88 475 88 328 88 439 88 441 88 441 88 439 88 477 88 441 88 477 88 418 88 418 88 477 88 479 88 418 88 479 88 416 88 416 88 479 88 320 88 416 88 320 88 338 88 338 88 320 88 319 88 338 88 319 88 339 88 339 88 319 88 290 88 339 88 290 88 289 88 495 88 496 88 420 88 279 88 497 88 280 88 280 88 497 88 498 88 280 88 498 88 385 88 385 88 498 88 499 88 385 88 499 88 386 88 386 88 499 88 425 88 386 88 425 88 494 88 494 88 425 88 426 88 494 88 426 88 410 88 313 88 336 88 363 88 363 88 336 88 360 88 363 88 360 88 407 88 407 88 360 88 406 88 407 88 406 88 408 88 263 88 363 88 365 88 365 88 363 88 407 88 365 88 407 88 500 88 500 88 407 88 397 88 500 88 397 88 501 88 501 88 397 88 399 88 501 88 399 88 452 88 452 88 399 88 459 88 452 88 459 88 450 88 444 88 327 88 442 88 442 88 327 88 329 88 442 88 329 88 502 88 502 88 329 88 441 88 502 88 441 88 503 88 503 88 441 88 418 88 503 88 418 88 504 88 504 88 418 88 420 88 504 88 420 88 505 88 505 88 420 88 496 88 505 88 496 88 324 88 324 88 496 88 495 88 324 88 495 88 325 88 325 88 495 88 466 88 325 88 466 88 326 88 326 88 466 88 465 88 331 88 393 88 332 88 332 88 393 88 484 88 332 88 484 88 454 88 454 88 484 88 482 88 454 88 482 88 452 88 452 88 482 88 480 88 452 88 480 88 501 88 501 88 480 88 506 88 501 88 506 88 500 88 500 88 506 88 507 88 500 88 507 88 365 88 365 88 507 88 508 88 365 88 508 88 364 88 471 88 473 88 480 88 480 88 473 88 437 88 480 88 437 88 506 88 506 88 437 88 427 88 506 88 427 88 507 88 507 88 427 88 430 88 507 88 430 88 508 88 509 88 510 88 511 88 512 88 497 88 513 88 513 88 497 88 511 88 513 88 511 88 514 88 514 88 511 88 510 88 512 88 515 88 497 88 497 88 515 88 516 88 497 88 516 88 498 88 498 88 516 88 517 88 498 88 517 88 518 88 519 88 520 88 466 88 466 88 520 88 521 88 419 88 423 88 420 88 420 88 423 88 425 88 420 88 425 88 495 88 495 88 425 88 499 88 495 88 499 88 466 88 466 88 499 88 498 88 466 88 498 88 519 88 519 88 498 88 518 88 521 88 509 88 466 88 466 88 509 88 511 88 466 88 511 88 464 88 464 88 511 88 522 88 464 88 522 88 523 88 523 88 522 88 524 88 523 88 524 88 525 88 470 88 467 88 469 88 469 88 467 88 368 88 469 88 368 88 433 88 433 88 368 88 367 88 433 88 367 88 430 88 430 88 367 88 366 88 430 88 366 88 508 88 508 88 366 88 335 88 508 88 335 88 364 88 364 88 335 88 334 88 364 88 334 88 264 88 264 88 334 88 265 88 279 88 278 88 497 88 497 88 278 88 383 88 497 88 383 88 511 88 511 88 383 88 333 88 511 88 333 88 522 88 522 88 333 88 382 88 522 88 382 88 524 88 524 88 382 88 378 88 524 88 378 88 525 88 525 88 378 88 468 88 388 92 144 92 390 92 390 93 144 93 142 93 390 94 142 94 391 94 391 94 142 94 141 94 391 95 141 95 330 95 330 96 141 96 140 96 330 97 140 97 331 97 331 97 140 97 138 97 331 98 138 98 392 98 392 98 138 98 137 98 392 99 137 99 394 99 394 99 137 99 155 99 394 100 155 100 489 100 489 100 155 100 153 100 489 101 153 101 490 101 490 101 153 101 151 101 490 102 151 102 491 102 491 103 151 103 149 103 491 104 149 104 492 104 492 105 149 105 147 105 492 106 147 106 493 106 493 107 147 107 145 107 493 108 145 108 388 108 388 109 145 109 144 109 403 110 163 110 404 110 404 110 163 110 170 110 404 111 170 111 405 111 405 111 170 111 169 111 405 112 169 112 406 112 406 112 169 112 168 112 406 113 168 113 408 113 408 113 168 113 167 113 408 114 167 114 409 114 409 115 167 115 165 115 409 116 165 116 398 116 398 117 165 117 164 117 398 100 164 100 400 100 400 118 164 118 161 118 400 101 161 101 401 101 401 101 161 101 160 101 401 102 160 102 395 102 395 102 160 102 159 102 395 105 159 105 396 105 396 105 159 105 158 105 396 119 158 119 402 119 402 106 158 106 157 106 402 120 157 120 403 120 403 121 157 121 163 121 417 93 174 93 422 93 422 92 174 92 173 92 422 94 173 94 421 94 421 94 173 94 181 94 421 96 181 96 419 96 419 95 181 95 180 95 419 97 180 97 423 97 423 97 180 97 178 97 423 122 178 122 424 122 424 123 178 123 177 123 424 99 177 99 426 99 426 124 177 124 185 124 426 125 185 125 410 125 410 126 185 126 183 126 410 127 183 127 411 127 411 127 183 127 182 127 411 128 182 128 413 128 413 129 182 129 257 129 413 130 257 130 414 130 414 131 257 131 176 131 414 132 176 132 415 132 415 107 176 107 175 107 415 121 175 121 417 121 417 121 175 121 174 121 429 110 194 110 431 110 431 110 194 110 192 110 431 94 192 94 432 94 432 133 192 133 191 133 432 95 191 95 434 95 434 96 191 96 190 96 434 97 190 97 435 97 435 134 190 134 188 134 435 98 188 98 444 98 444 135 188 135 187 135 444 136 187 136 327 136 327 136 187 136 235 136 327 100 235 100 328 100 328 137 235 137 236 137 328 101 236 101 440 101 440 138 236 138 200 138 440 103 200 103 438 103 438 139 200 139 199 139 438 140 199 140 436 140 436 104 199 104 197 104 436 106 197 106 428 106 428 106 197 106 195 106 428 141 195 141 429 141 429 109 195 109 194 109 380 142 113 142 381 142 381 110 113 110 131 110 381 111 131 111 371 111 371 111 131 111 130 111 371 143 130 143 372 143 372 144 130 144 127 144 372 145 127 145 373 145 373 146 127 146 125 146 373 123 125 123 374 123 374 122 125 122 124 122 374 99 124 99 375 99 375 99 124 99 121 99 375 100 121 100 376 100 376 147 121 147 119 147 376 101 119 101 377 101 377 101 119 101 118 101 377 102 118 102 369 102 369 103 118 103 117 103 369 105 117 105 370 105 370 105 117 105 116 105 370 107 116 107 379 107 379 132 116 132 114 132 379 121 114 121 380 121 380 148 114 148 113 148 509 110 239 110 510 110 510 142 239 142 240 142 510 94 240 94 514 94 514 94 240 94 248 94 514 96 248 96 513 96 513 95 248 95 247 95 513 134 247 134 512 134 512 97 247 97 246 97 512 114 246 114 515 114 515 122 246 122 245 122 515 136 245 136 516 136 516 149 245 149 244 149 516 125 244 125 517 125 517 150 244 150 243 150 517 101 243 101 518 101 518 101 243 101 242 101 518 102 242 102 519 102 519 103 242 103 241 103 519 131 241 131 520 131 520 131 241 131 238 131 520 107 238 107 521 107 521 132 238 132 237 132 521 121 237 121 509 121 509 121 237 121 239 121 462 151 212 151 463 151 463 151 212 151 211 151 463 152 211 152 457 152 457 152 211 152 210 152 457 153 210 153 458 153 458 154 210 154 201 154 458 155 201 155 459 155 459 155 201 155 10 155 459 156 10 156 450 156 450 157 10 157 9 157 450 158 9 158 451 158 451 158 9 158 209 158 451 159 209 159 453 159 453 159 209 159 208 159 453 160 208 160 455 160 455 160 208 160 206 160 455 161 206 161 456 161 456 162 206 162 204 162 456 163 204 163 448 163 448 164 204 164 203 164 448 165 203 165 449 165 449 166 203 166 202 166 449 167 202 167 446 167 446 167 202 167 7 167 446 168 7 168 447 168 447 168 7 168 6 168 447 169 6 169 460 169 460 169 6 169 214 169 460 170 214 170 461 170 461 171 214 171 213 171 461 172 213 172 462 172 462 172 213 172 212 172 443 173 234 173 445 173 445 174 234 174 215 174 445 175 215 175 470 175 470 176 215 176 217 176 470 153 217 153 467 153 467 153 217 153 218 153 467 177 218 177 468 177 468 178 218 178 219 178 468 179 219 179 525 179 525 180 219 180 220 180 525 181 220 181 523 181 523 158 220 158 222 158 523 182 222 182 464 182 464 183 222 183 224 183 464 184 224 184 465 184 465 185 224 185 226 185 465 161 226 161 326 161 326 186 226 186 228 186 326 187 228 187 324 187 324 188 228 188 3 188 324 189 3 189 505 189 505 189 3 189 230 189 505 190 230 190 504 190 504 191 230 191 231 191 504 192 231 192 503 192 503 193 231 193 232 193 503 194 232 194 502 194 502 195 232 195 0 195 502 170 0 170 442 170 442 196 0 196 2 196 442 197 2 197 443 197 443 198 2 198 234 198 344 199 72 199 345 199 345 199 72 199 73 199 345 200 73 200 355 200 355 201 73 201 74 201 355 202 74 202 356 202 356 202 74 202 84 202 356 203 84 203 357 203 357 203 84 203 83 203 357 204 83 204 358 204 358 204 83 204 81 204 358 205 81 205 359 205 359 205 81 205 80 205 349 206 71 206 346 206 346 207 71 207 68 207 346 208 68 208 347 208 347 209 68 209 67 209 347 210 67 210 350 210 350 211 67 211 79 211 350 212 79 212 351 212 351 212 79 212 78 212 351 213 78 213 353 213 353 213 78 213 76 213 353 214 76 214 354 214 354 215 76 215 75 215 71 216 349 216 80 216 80 217 349 217 359 217 354 218 75 218 344 218 344 218 75 218 72 218 474 219 33 219 475 219 475 219 33 219 32 219 475 208 32 208 476 208 476 208 32 208 44 208 476 220 44 220 478 220 478 221 44 221 43 221 478 222 43 222 488 222 488 212 43 212 41 212 488 223 41 223 487 223 487 213 41 213 39 213 487 224 39 224 486 224 486 225 39 225 38 225 485 226 36 226 321 226 321 226 36 226 35 226 321 201 35 201 322 201 322 201 35 201 30 201 322 202 30 202 483 202 483 227 30 227 29 227 483 203 29 203 481 203 481 203 29 203 47 203 481 228 47 228 471 228 471 204 47 204 48 204 471 205 48 205 472 205 472 205 48 205 50 205 36 229 485 229 38 229 38 229 485 229 486 229 472 217 50 217 474 217 474 230 50 230 33 230 526 88 527 88 528 88 529 88 530 88 531 88 532 88 533 88 534 88 535 231 536 231 537 231 535 232 537 232 538 232 538 233 537 233 539 233 538 233 539 233 540 233 540 234 539 234 541 234 540 234 541 234 542 234 543 235 544 235 545 235 545 236 544 236 546 236 546 237 544 237 547 237 547 237 544 237 548 237 547 238 548 238 549 238 548 238 550 238 549 238 549 239 550 239 551 239 549 240 551 240 552 240 552 241 551 241 553 241 552 242 553 242 554 242 554 243 553 243 555 243 554 243 555 243 556 243 556 244 555 244 557 244 556 245 557 245 558 245 558 246 557 246 559 246 559 246 557 246 560 246 559 247 560 247 561 247 560 247 562 247 561 247 561 248 562 248 563 248 561 249 563 249 564 249 564 250 563 250 565 250 564 251 565 251 566 251 566 252 565 252 567 252 567 252 565 252 568 252 567 253 568 253 569 253 568 254 570 254 569 254 569 255 570 255 571 255 569 256 571 256 572 256 573 257 574 257 575 257 575 258 574 258 576 258 575 258 576 258 577 258 578 259 579 259 580 259 580 259 579 259 581 259 580 260 581 260 573 260 573 261 581 261 582 261 573 262 582 262 574 262 535 0 583 0 584 0 542 0 585 0 586 0 587 0 588 0 535 0 586 0 545 0 542 0 542 0 545 0 546 0 542 0 546 0 547 0 579 0 587 0 589 0 589 0 587 0 535 0 589 0 535 0 590 0 590 0 535 0 584 0 579 0 589 0 581 0 581 0 589 0 591 0 581 0 591 0 592 0 593 0 535 0 594 0 594 0 535 0 538 0 594 0 538 0 595 0 595 0 538 0 540 0 595 0 540 0 596 0 596 0 540 0 542 0 597 0 598 0 599 0 600 0 601 0 547 0 547 0 601 0 602 0 547 0 602 0 542 0 542 0 602 0 603 0 542 0 603 0 596 0 599 0 604 0 597 0 597 0 604 0 605 0 597 0 605 0 547 0 593 0 606 0 535 0 535 0 606 0 607 0 535 0 607 0 583 0 583 0 607 0 608 0 608 0 609 0 583 0 583 0 609 0 600 0 583 0 600 0 610 0 610 0 600 0 547 0 610 0 547 0 611 0 611 0 547 0 605 0 612 0 613 0 572 0 572 0 613 0 576 0 614 0 567 0 576 0 576 0 567 0 569 0 576 0 569 0 572 0 597 0 615 0 616 0 614 0 617 0 567 0 567 0 617 0 618 0 567 0 618 0 597 0 597 0 618 0 619 0 597 0 619 0 615 0 592 0 598 0 581 0 581 0 598 0 597 0 581 0 597 0 620 0 620 0 597 0 616 0 620 0 621 0 581 0 581 0 621 0 622 0 581 0 622 0 582 0 582 0 622 0 623 0 582 0 623 0 574 0 574 0 623 0 624 0 574 0 624 0 576 0 576 0 624 0 625 0 576 0 625 0 614 0 597 0 626 0 627 0 627 0 628 0 597 0 597 0 628 0 629 0 597 0 629 0 567 0 629 0 630 0 567 0 567 0 630 0 631 0 567 0 631 0 566 0 566 0 631 0 632 0 566 0 632 0 564 0 632 0 633 0 564 0 564 0 633 0 634 0 564 0 634 0 561 0 561 0 634 0 635 0 561 0 635 0 559 0 559 0 635 0 636 0 559 0 636 0 637 0 597 0 638 0 639 0 637 0 626 0 559 0 559 0 626 0 597 0 559 0 597 0 558 0 558 0 597 0 639 0 558 0 639 0 556 0 640 0 547 0 641 0 641 0 547 0 549 0 641 0 549 0 642 0 642 0 549 0 552 0 640 0 643 0 547 0 547 0 643 0 644 0 547 0 644 0 597 0 597 0 644 0 645 0 597 0 645 0 638 0 639 0 646 0 556 0 556 0 646 0 647 0 556 0 647 0 554 0 554 0 647 0 648 0 554 0 648 0 552 0 552 0 648 0 649 0 552 0 649 0 642 0 650 88 651 88 577 88 577 88 651 88 571 88 652 88 653 88 568 88 568 88 653 88 654 88 655 88 656 88 652 88 652 88 656 88 657 88 652 88 657 88 653 88 654 88 658 88 568 88 568 88 658 88 577 88 568 88 577 88 570 88 570 88 577 88 571 88 658 88 659 88 577 88 577 88 659 88 660 88 577 88 660 88 575 88 575 88 660 88 661 88 575 88 661 88 573 88 573 88 661 88 662 88 573 88 662 88 580 88 580 88 662 88 663 88 580 88 663 88 664 88 537 88 536 88 548 88 665 88 666 88 543 88 543 88 666 88 541 88 543 88 541 88 544 88 544 88 541 88 548 88 548 88 541 88 539 88 548 88 539 88 537 88 667 88 668 88 536 88 536 88 668 88 578 88 669 88 670 88 578 88 548 88 671 88 652 88 652 88 671 88 672 88 652 88 672 88 673 88 673 88 674 88 652 88 652 88 674 88 580 88 652 88 580 88 655 88 655 88 580 88 664 88 675 88 676 88 677 88 669 88 578 88 678 88 679 88 548 88 680 88 680 88 548 88 536 88 680 88 536 88 681 88 681 88 536 88 578 88 681 88 578 88 682 88 682 88 578 88 670 88 679 88 683 88 548 88 548 88 683 88 684 88 548 88 684 88 676 88 675 88 677 88 685 88 675 88 686 88 676 88 676 88 686 88 687 88 676 88 687 88 548 88 548 88 687 88 688 88 548 88 688 88 671 88 674 88 689 88 580 88 580 88 689 88 690 88 580 88 690 88 578 88 578 88 690 88 691 88 578 88 691 88 678 88 678 88 691 88 685 88 678 88 685 88 692 88 692 88 685 88 677 88 693 88 694 88 652 88 652 88 694 88 695 88 548 88 696 88 550 88 550 88 696 88 697 88 550 88 697 88 551 88 695 88 698 88 652 88 652 88 698 88 699 88 652 88 699 88 548 88 548 88 699 88 700 88 548 88 700 88 696 88 568 88 701 88 702 88 568 88 702 88 652 88 652 88 702 88 703 88 652 88 703 88 704 88 705 88 706 88 560 88 560 88 706 88 707 88 560 88 707 88 562 88 562 88 707 88 708 88 562 88 708 88 563 88 708 88 709 88 563 88 563 88 709 88 710 88 563 88 710 88 565 88 565 88 710 88 711 88 565 88 711 88 568 88 568 88 711 88 712 88 568 88 712 88 701 88 704 88 705 88 652 88 652 88 705 88 560 88 652 88 560 88 693 88 693 88 560 88 557 88 693 88 557 88 713 88 713 88 557 88 555 88 713 88 555 88 714 88 714 88 555 88 553 88 714 88 553 88 715 88 715 88 553 88 551 88 715 88 551 88 716 88 716 88 551 88 697 88 702 263 629 263 703 263 703 264 629 264 628 264 703 265 628 265 704 265 704 266 628 266 627 266 704 267 627 267 705 267 705 267 627 267 626 267 705 268 626 268 706 268 706 268 626 268 637 268 706 269 637 269 707 269 707 269 637 269 636 269 707 270 636 270 708 270 708 270 636 270 635 270 708 271 635 271 709 271 709 272 635 272 634 272 709 273 634 273 710 273 710 274 634 274 633 274 710 275 633 275 711 275 711 275 633 275 632 275 711 276 632 276 712 276 712 276 632 276 631 276 712 277 631 277 701 277 701 277 631 277 630 277 701 278 630 278 702 278 702 278 630 278 629 278 662 279 623 279 663 279 663 264 623 264 622 264 663 266 622 266 664 266 664 280 622 280 621 280 664 281 621 281 655 281 655 281 621 281 620 281 655 268 620 268 656 268 656 268 620 268 616 268 656 282 616 282 657 282 657 282 616 282 615 282 657 283 615 283 653 283 653 284 615 284 619 284 653 271 619 271 654 271 654 285 619 285 618 285 654 273 618 273 658 273 658 274 618 274 617 274 658 286 617 286 659 286 659 275 617 275 614 275 659 276 614 276 660 276 660 276 614 276 625 276 660 287 625 287 661 287 661 288 625 288 624 288 661 289 624 289 662 289 662 290 624 290 623 290 682 263 594 263 681 263 681 264 594 264 595 264 681 266 595 266 680 266 680 265 595 265 596 265 680 267 596 267 679 267 679 267 596 267 603 267 679 268 603 268 683 268 683 268 603 268 602 268 683 291 602 291 684 291 684 291 602 291 601 291 684 292 601 292 676 292 676 284 601 284 600 284 676 271 600 271 677 271 677 272 600 272 609 272 677 293 609 293 692 293 692 274 609 274 608 274 692 275 608 275 678 275 678 286 608 286 607 286 678 276 607 276 669 276 669 276 607 276 606 276 669 288 606 288 670 288 670 294 606 294 593 294 670 295 593 295 682 295 682 296 593 296 594 296 699 264 644 264 700 264 700 279 644 279 643 279 700 265 643 265 696 265 696 266 643 266 640 266 696 281 640 281 697 281 697 267 640 267 641 267 697 268 641 268 716 268 716 268 641 268 642 268 716 269 642 269 715 269 715 297 642 297 649 297 715 298 649 298 714 298 714 270 649 270 648 270 714 285 648 285 713 285 713 271 648 271 647 271 713 274 647 274 693 274 693 293 647 293 646 293 693 286 646 286 694 286 694 286 646 286 639 286 694 276 639 276 695 276 695 276 639 276 638 276 695 299 638 299 698 299 698 299 638 299 645 299 698 300 645 300 699 300 699 301 645 301 644 301 691 302 589 302 685 302 685 302 589 302 590 302 685 303 590 303 675 303 675 303 590 303 584 303 675 304 584 304 686 304 686 305 584 305 583 305 686 306 583 306 687 306 687 306 583 306 610 306 687 307 610 307 688 307 688 308 610 308 611 308 688 309 611 309 671 309 671 309 611 309 605 309 671 310 605 310 672 310 672 310 605 310 604 310 672 311 604 311 673 311 673 311 604 311 599 311 673 312 599 312 674 312 674 313 599 313 598 313 674 314 598 314 689 314 689 314 598 314 592 314 689 315 592 315 690 315 690 316 592 316 591 316 690 317 591 317 691 317 691 317 591 317 589 317 579 318 578 318 587 318 587 319 578 319 668 319 587 320 668 320 717 320 717 321 668 321 718 321 717 322 718 322 719 322 719 323 718 323 720 323 719 324 720 324 721 324 721 325 720 325 527 325 722 326 528 326 723 326 723 327 528 327 724 327 723 328 724 328 725 328 725 329 724 329 726 329 725 330 726 330 588 330 588 331 726 331 667 331 588 328 667 328 535 328 535 332 667 332 536 332 724 333 720 333 726 333 726 334 720 334 718 334 528 335 527 335 724 335 724 336 527 336 720 336 723 337 719 337 722 337 722 338 719 338 721 338 725 339 717 339 723 339 723 339 717 339 719 339 588 340 587 340 725 340 725 341 587 341 717 341 726 342 718 342 667 342 667 343 718 343 668 343 572 344 571 344 612 344 612 345 571 345 651 345 612 346 651 346 727 346 727 347 651 347 728 347 727 348 728 348 729 348 729 349 728 349 730 349 729 350 730 350 731 350 731 351 730 351 530 351 731 350 530 350 732 350 732 352 530 352 733 352 734 353 531 353 735 353 735 354 531 354 736 354 735 355 736 355 737 355 737 356 736 356 738 356 737 357 738 357 613 357 613 358 738 358 650 358 613 359 650 359 576 359 576 360 650 360 577 360 736 361 730 361 738 361 738 362 730 362 728 362 531 363 530 363 736 363 736 363 530 363 730 363 735 364 729 364 734 364 734 364 729 364 731 364 737 365 727 365 735 365 735 366 727 366 729 366 613 367 612 367 737 367 737 368 612 368 727 368 738 369 728 369 650 369 650 370 728 370 651 370 542 371 541 371 585 371 585 372 541 372 666 372 585 373 666 373 739 373 739 374 666 374 740 374 739 375 740 375 741 375 741 376 740 376 742 376 741 377 742 377 743 377 743 378 742 378 533 378 744 379 745 379 746 379 746 379 745 379 534 379 746 380 534 380 747 380 747 381 534 381 748 381 747 382 748 382 749 382 749 383 748 383 750 383 749 384 750 384 586 384 586 385 750 385 665 385 586 386 665 386 545 386 545 387 665 387 543 387 748 388 742 388 750 388 750 389 742 389 740 389 534 390 533 390 748 390 748 391 533 391 742 391 747 392 741 392 746 392 746 393 741 393 743 393 749 394 739 394 747 394 747 395 739 395 741 395 586 396 585 396 749 396 749 397 585 397 739 397 750 398 740 398 665 398 665 399 740 399 666 399 528 0 722 0 751 0 751 0 722 0 752 0 751 0 752 0 753 0 753 0 752 0 754 0 753 0 754 0 755 0 755 0 754 0 756 0 755 0 756 0 757 0 757 0 756 0 758 0 757 0 758 0 759 0 759 0 758 0 760 0 759 0 760 0 761 0 761 0 760 0 762 0 761 0 762 0 763 0 763 0 762 0 764 0 763 0 764 0 765 0 765 0 764 0 766 0 765 0 766 0 533 0 533 0 766 0 743 0 531 0 734 0 767 0 767 0 734 0 768 0 767 0 768 0 769 0 769 0 768 0 770 0 769 0 770 0 771 0 771 0 770 0 772 0 771 0 772 0 773 0 773 0 772 0 774 0 773 0 774 0 775 0 775 0 774 0 776 0 775 0 776 0 777 0 777 0 776 0 778 0 777 0 778 0 779 0 779 0 778 0 780 0 779 0 780 0 781 0 781 0 780 0 782 0 781 0 782 0 527 0 527 0 782 0 721 0 721 0 783 0 722 0 731 0 784 0 734 0 784 400 731 400 732 400 746 401 785 401 744 401 744 402 785 402 743 402 744 403 743 403 786 403 743 404 766 404 786 404 786 405 766 405 764 405 786 406 764 406 787 406 787 407 764 407 762 407 787 407 762 407 788 407 788 408 762 408 760 408 788 409 760 409 789 409 789 410 760 410 758 410 789 411 758 411 790 411 790 412 758 412 756 412 790 412 756 412 791 412 791 413 756 413 754 413 791 413 754 413 792 413 792 414 754 414 752 414 792 415 752 415 793 415 752 416 722 416 793 416 793 417 722 417 783 417 793 418 783 418 794 418 794 419 783 419 721 419 721 420 782 420 794 420 794 421 782 421 780 421 794 422 780 422 795 422 795 423 780 423 778 423 795 424 778 424 796 424 796 425 778 425 776 425 796 426 776 426 797 426 797 427 776 427 774 427 797 427 774 427 798 427 798 428 774 428 772 428 798 428 772 428 799 428 799 429 772 429 770 429 799 430 770 430 800 430 800 431 770 431 768 431 800 432 768 432 801 432 801 433 768 433 732 433 732 434 768 434 734 434 732 435 734 435 784 435 532 436 534 436 745 436 530 437 529 437 733 437 733 438 529 438 531 438 733 439 531 439 802 439 802 440 531 440 767 440 802 441 767 441 803 441 803 441 767 441 769 441 803 442 769 442 804 442 804 442 769 442 771 442 804 443 771 443 805 443 805 443 771 443 773 443 805 444 773 444 806 444 806 445 773 445 775 445 806 446 775 446 807 446 807 446 775 446 777 446 807 447 777 447 808 447 808 448 777 448 779 448 808 449 779 449 809 449 809 450 779 450 781 450 781 451 527 451 809 451 809 452 527 452 526 452 809 453 526 453 810 453 526 454 528 454 810 454 810 455 528 455 751 455 810 456 751 456 811 456 811 457 751 457 753 457 811 458 753 458 812 458 812 459 753 459 755 459 812 460 755 460 813 460 813 461 755 461 757 461 813 462 757 462 814 462 814 463 757 463 759 463 814 464 759 464 815 464 815 465 759 465 761 465 815 466 761 466 816 466 816 467 761 467 763 467 816 468 763 468 817 468 817 469 763 469 765 469 817 470 765 470 745 470 745 471 765 471 533 471 745 472 533 472 532 472 745 88 744 88 817 88 817 88 744 88 786 88 817 88 786 88 816 88 816 88 786 88 787 88 816 88 787 88 815 88 815 88 787 88 788 88 815 473 788 473 814 473 814 474 788 474 789 474 814 88 789 88 813 88 813 88 789 88 790 88 813 88 790 88 812 88 812 88 790 88 791 88 812 88 791 88 811 88 811 88 791 88 792 88 811 475 792 475 810 475 810 88 792 88 793 88 810 88 793 88 809 88 809 88 793 88 794 88 809 88 794 88 808 88 808 88 794 88 795 88 808 88 795 88 807 88 807 88 795 88 796 88 807 88 796 88 806 88 806 88 796 88 797 88 806 88 797 88 805 88 805 88 797 88 798 88 805 88 798 88 804 88 804 88 798 88 799 88 804 88 799 88 803 88 803 88 799 88 800 88 803 88 800 88 802 88 802 88 800 88 801 88 802 88 801 88 733 88 733 88 801 88 732 88 743 476 785 476 746 476 818 88 819 88 820 88 821 88 822 88 823 88 824 88 825 88 826 88 827 477 828 477 829 477 827 478 829 478 830 478 830 479 829 479 831 479 830 480 831 480 832 480 832 481 831 481 833 481 832 481 833 481 834 481 835 482 836 482 837 482 837 483 836 483 838 483 838 484 836 484 839 484 839 485 836 485 840 485 839 486 840 486 841 486 840 486 842 486 841 486 841 487 842 487 843 487 841 488 843 488 844 488 844 489 843 489 845 489 844 490 845 490 846 490 846 491 845 491 847 491 846 491 847 491 848 491 848 492 847 492 849 492 848 493 849 493 850 493 850 494 849 494 851 494 851 494 849 494 852 494 851 495 852 495 853 495 852 495 854 495 853 495 853 496 854 496 855 496 853 497 855 497 856 497 856 498 855 498 857 498 856 499 857 499 858 499 858 500 857 500 859 500 859 500 857 500 860 500 859 501 860 501 861 501 860 501 862 501 861 501 861 502 862 502 863 502 861 503 863 503 864 503 865 504 866 504 867 504 867 505 866 505 868 505 867 505 868 505 869 505 870 506 871 506 872 506 872 506 871 506 873 506 872 507 873 507 865 507 865 507 873 507 874 507 865 504 874 504 866 504 827 0 875 0 876 0 834 0 877 0 878 0 879 0 880 0 827 0 878 0 837 0 834 0 834 0 837 0 838 0 834 0 838 0 839 0 871 0 879 0 881 0 881 0 879 0 827 0 881 0 827 0 882 0 882 0 827 0 876 0 871 0 881 0 873 0 873 0 881 0 883 0 873 0 883 0 884 0 885 0 827 0 886 0 886 0 827 0 830 0 886 0 830 0 887 0 887 0 830 0 832 0 887 0 832 0 888 0 888 0 832 0 834 0 889 0 890 0 891 0 892 0 893 0 839 0 839 0 893 0 894 0 839 0 894 0 834 0 834 0 894 0 895 0 834 0 895 0 888 0 891 0 896 0 889 0 889 0 896 0 897 0 889 0 897 0 839 0 885 0 898 0 827 0 827 0 898 0 899 0 827 0 899 0 875 0 875 0 899 0 900 0 900 0 901 0 875 0 875 0 901 0 892 0 875 0 892 0 902 0 902 0 892 0 839 0 902 0 839 0 903 0 903 0 839 0 897 0 904 0 905 0 864 0 864 0 905 0 868 0 906 0 859 0 868 0 868 0 859 0 861 0 868 0 861 0 864 0 889 0 907 0 908 0 906 0 909 0 859 0 859 0 909 0 910 0 859 0 910 0 889 0 889 0 910 0 911 0 889 0 911 0 907 0 884 0 890 0 873 0 873 0 890 0 889 0 873 0 889 0 912 0 912 0 889 0 908 0 912 0 913 0 873 0 873 0 913 0 914 0 873 0 914 0 874 0 874 0 914 0 915 0 874 0 915 0 866 0 866 0 915 0 916 0 866 0 916 0 868 0 868 0 916 0 917 0 868 0 917 0 906 0 889 0 918 0 919 0 919 0 920 0 889 0 889 0 920 0 921 0 889 0 921 0 859 0 921 0 922 0 859 0 859 0 922 0 923 0 859 0 923 0 858 0 858 0 923 0 924 0 858 0 924 0 856 0 924 0 925 0 856 0 856 0 925 0 926 0 856 0 926 0 853 0 853 0 926 0 927 0 853 0 927 0 851 0 851 0 927 0 928 0 851 0 928 0 929 0 889 0 930 0 931 0 929 0 918 0 851 0 851 0 918 0 889 0 851 0 889 0 850 0 850 0 889 0 931 0 850 0 931 0 848 0 932 0 839 0 933 0 933 0 839 0 841 0 933 0 841 0 934 0 934 0 841 0 844 0 932 0 935 0 839 0 839 0 935 0 936 0 839 0 936 0 889 0 889 0 936 0 937 0 889 0 937 0 930 0 931 0 938 0 848 0 848 0 938 0 939 0 848 0 939 0 846 0 846 0 939 0 940 0 846 0 940 0 844 0 844 0 940 0 941 0 844 0 941 0 934 0 942 88 943 88 869 88 869 88 943 88 863 88 944 88 945 88 860 88 860 88 945 88 946 88 947 88 948 88 944 88 944 88 948 88 949 88 944 88 949 88 945 88 946 88 950 88 860 88 860 88 950 88 869 88 860 88 869 88 862 88 862 88 869 88 863 88 950 88 951 88 869 88 869 88 951 88 952 88 869 88 952 88 867 88 867 88 952 88 953 88 867 88 953 88 865 88 865 88 953 88 954 88 865 88 954 88 872 88 872 88 954 88 955 88 872 88 955 88 956 88 829 88 828 88 840 88 957 88 958 88 835 88 835 88 958 88 833 88 835 88 833 88 836 88 836 88 833 88 840 88 840 88 833 88 831 88 840 88 831 88 829 88 959 88 960 88 828 88 828 88 960 88 870 88 961 88 962 88 870 88 840 88 963 88 944 88 944 88 963 88 964 88 944 88 964 88 965 88 965 88 966 88 944 88 944 88 966 88 872 88 944 88 872 88 947 88 947 88 872 88 956 88 967 88 968 88 969 88 961 88 870 88 970 88 971 88 840 88 972 88 972 88 840 88 828 88 972 88 828 88 973 88 973 88 828 88 870 88 973 88 870 88 974 88 974 88 870 88 962 88 971 88 975 88 840 88 840 88 975 88 976 88 840 88 976 88 968 88 967 88 969 88 977 88 967 88 978 88 968 88 968 88 978 88 979 88 968 88 979 88 840 88 840 88 979 88 980 88 840 88 980 88 963 88 966 88 981 88 872 88 872 88 981 88 982 88 872 88 982 88 870 88 870 88 982 88 983 88 870 88 983 88 970 88 970 88 983 88 977 88 970 88 977 88 984 88 984 88 977 88 969 88 985 88 986 88 944 88 944 88 986 88 987 88 840 88 988 88 842 88 842 88 988 88 989 88 842 88 989 88 843 88 987 88 990 88 944 88 944 88 990 88 991 88 944 88 991 88 840 88 840 88 991 88 992 88 840 88 992 88 988 88 860 88 993 88 994 88 860 88 994 88 944 88 944 88 994 88 995 88 944 88 995 88 996 88 997 88 998 88 852 88 852 88 998 88 999 88 852 88 999 88 854 88 854 88 999 88 1000 88 854 88 1000 88 855 88 1000 88 1001 88 855 88 855 88 1001 88 1002 88 855 88 1002 88 857 88 857 88 1002 88 1003 88 857 88 1003 88 860 88 860 88 1003 88 1004 88 860 88 1004 88 993 88 996 88 997 88 944 88 944 88 997 88 852 88 944 88 852 88 985 88 985 88 852 88 849 88 985 88 849 88 1005 88 1005 88 849 88 847 88 1005 88 847 88 1006 88 1006 88 847 88 845 88 1006 88 845 88 1007 88 1007 88 845 88 843 88 1007 88 843 88 1008 88 1008 88 843 88 989 88 994 508 921 508 995 508 995 509 921 509 920 509 995 510 920 510 996 510 996 510 920 510 919 510 996 511 919 511 997 511 997 511 919 511 918 511 997 512 918 512 998 512 998 512 918 512 929 512 998 513 929 513 999 513 999 514 929 514 928 514 999 515 928 515 1000 515 1000 516 928 516 927 516 1000 517 927 517 1001 517 1001 518 927 518 926 518 1001 519 926 519 1002 519 1002 520 926 520 925 520 1002 521 925 521 1003 521 1003 521 925 521 924 521 1003 522 924 522 1004 522 1004 523 924 523 923 523 1004 524 923 524 993 524 993 525 923 525 922 525 993 526 922 526 994 526 994 527 922 527 921 527 954 528 915 528 955 528 955 529 915 529 914 529 955 530 914 530 956 530 956 531 914 531 913 531 956 511 913 511 947 511 947 511 913 511 912 511 947 512 912 512 948 512 948 532 912 532 908 532 948 514 908 514 949 514 949 513 908 513 907 513 949 533 907 533 945 533 945 515 907 515 911 515 945 534 911 534 946 534 946 535 911 535 910 535 946 536 910 536 950 536 950 536 910 536 909 536 950 521 909 521 951 521 951 521 909 521 906 521 951 522 906 522 952 522 952 522 906 522 917 522 952 525 917 525 953 525 953 524 917 524 916 524 953 527 916 527 954 527 954 537 916 537 915 537 974 538 886 538 973 538 973 539 886 539 887 539 973 531 887 531 972 531 972 540 887 540 888 540 972 511 888 511 971 511 971 511 888 511 895 511 971 532 895 532 975 532 975 512 895 512 894 512 975 514 894 514 976 514 976 541 894 541 893 541 976 516 893 516 968 516 968 515 893 515 892 515 968 534 892 534 969 534 969 542 892 542 901 542 969 543 901 543 984 543 984 543 901 543 900 543 984 521 900 521 970 521 970 521 900 521 899 521 970 523 899 523 961 523 961 523 899 523 898 523 961 544 898 544 962 544 962 524 898 524 885 524 962 527 885 527 974 527 974 526 885 526 886 526 991 545 936 545 992 545 992 545 936 545 935 545 992 546 935 546 988 546 988 546 935 546 932 546 988 511 932 511 989 511 989 511 932 511 933 511 989 532 933 532 1008 532 1008 532 933 532 934 532 1008 514 934 514 1007 514 1007 541 934 541 941 541 1007 533 941 533 1006 533 1006 515 941 515 940 515 1006 517 940 517 1005 517 1005 517 940 517 939 517 1005 520 939 520 985 520 985 520 939 520 938 520 985 521 938 521 986 521 986 521 938 521 931 521 986 522 931 522 987 522 987 522 931 522 930 522 987 524 930 524 990 524 990 525 930 525 937 525 990 527 937 527 991 527 991 537 937 537 936 537 983 547 881 547 977 547 977 547 881 547 882 547 977 548 882 548 967 548 967 549 882 549 876 549 967 550 876 550 978 550 978 550 876 550 875 550 978 551 875 551 979 551 979 552 875 552 902 552 979 553 902 553 980 553 980 553 902 553 903 553 980 554 903 554 963 554 963 554 903 554 897 554 963 555 897 555 964 555 964 555 897 555 896 555 964 556 896 556 965 556 965 557 896 557 891 557 965 558 891 558 966 558 966 558 891 558 890 558 966 559 890 559 981 559 981 560 890 560 884 560 981 561 884 561 982 561 982 561 884 561 883 561 982 562 883 562 983 562 983 562 883 562 881 562 871 563 870 563 879 563 879 564 870 564 960 564 879 565 960 565 1009 565 1009 566 960 566 1010 566 1009 567 1010 567 1011 567 1011 568 1010 568 1012 568 1011 569 1012 569 1013 569 1013 570 1012 570 819 570 1014 571 820 571 1015 571 1015 572 820 572 1016 572 1015 573 1016 573 1017 573 1017 574 1016 574 1018 574 1017 575 1018 575 880 575 880 576 1018 576 959 576 880 577 959 577 827 577 827 578 959 578 828 578 1016 579 1012 579 1018 579 1018 580 1012 580 1010 580 820 581 819 581 1016 581 1016 582 819 582 1012 582 1015 583 1011 583 1014 583 1014 584 1011 584 1013 584 1017 585 1009 585 1015 585 1015 586 1009 586 1011 586 880 587 879 587 1017 587 1017 588 879 588 1009 588 1018 589 1010 589 959 589 959 590 1010 590 960 590 864 591 863 591 904 591 904 592 863 592 943 592 904 593 943 593 1019 593 1019 594 943 594 1020 594 1019 595 1020 595 1021 595 1021 596 1020 596 1022 596 1021 597 1022 597 1023 597 1023 598 1022 598 822 598 1023 599 822 599 1024 599 1024 599 822 599 1025 599 1026 600 823 600 1027 600 1027 601 823 601 1028 601 1027 602 1028 602 1029 602 1029 603 1028 603 1030 603 1029 604 1030 604 905 604 905 605 1030 605 942 605 905 606 942 606 868 606 868 607 942 607 869 607 1028 608 1022 608 1030 608 1030 609 1022 609 1020 609 823 610 822 610 1028 610 1028 611 822 611 1022 611 1027 612 1021 612 1026 612 1026 613 1021 613 1023 613 1029 614 1019 614 1027 614 1027 615 1019 615 1021 615 905 616 904 616 1029 616 1029 617 904 617 1019 617 1030 618 1020 618 942 618 942 619 1020 619 943 619 834 620 833 620 877 620 877 621 833 621 958 621 877 622 958 622 1031 622 1031 623 958 623 1032 623 1031 624 1032 624 1033 624 1033 625 1032 625 1034 625 1033 626 1034 626 1035 626 1035 627 1034 627 825 627 1036 628 1037 628 1038 628 1038 629 1037 629 826 629 1038 628 826 628 1039 628 1039 630 826 630 1040 630 1039 631 1040 631 1041 631 1041 632 1040 632 1042 632 1041 633 1042 633 878 633 878 634 1042 634 957 634 878 635 957 635 837 635 837 636 957 636 835 636 1040 637 1034 637 1042 637 1042 638 1034 638 1032 638 826 639 825 639 1040 639 1040 639 825 639 1034 639 1039 640 1033 640 1038 640 1038 640 1033 640 1035 640 1041 641 1031 641 1039 641 1039 642 1031 642 1033 642 878 643 877 643 1041 643 1041 644 877 644 1031 644 1042 645 1032 645 957 645 957 646 1032 646 958 646 820 0 1014 0 1043 0 1043 0 1014 0 1044 0 1043 0 1044 0 1045 0 1045 0 1044 0 1046 0 1045 0 1046 0 1047 0 1047 0 1046 0 1048 0 1047 0 1048 0 1049 0 1049 0 1048 0 1050 0 1049 0 1050 0 1051 0 1051 0 1050 0 1052 0 1051 0 1052 0 1053 0 1053 0 1052 0 1054 0 1053 0 1054 0 1055 0 1055 0 1054 0 1056 0 1055 0 1056 0 1057 0 1057 0 1056 0 1058 0 1057 0 1058 0 825 0 825 0 1058 0 1035 0 823 0 1026 0 1059 0 1059 0 1026 0 1060 0 1059 0 1060 0 1061 0 1061 0 1060 0 1062 0 1061 0 1062 0 1063 0 1063 0 1062 0 1064 0 1063 0 1064 0 1065 0 1065 0 1064 0 1066 0 1065 0 1066 0 1067 0 1067 0 1066 0 1068 0 1067 0 1068 0 1069 0 1069 647 1068 647 1070 647 1069 0 1070 0 1071 0 1071 0 1070 0 1072 0 1071 0 1072 0 1073 0 1073 0 1072 0 1074 0 1073 0 1074 0 819 0 819 0 1074 0 1013 0 1013 0 1075 0 1014 0 1023 476 1076 476 1026 476 1076 648 1023 648 1024 648 1038 649 1077 649 1036 649 1036 650 1077 650 1035 650 1036 651 1035 651 1078 651 1035 652 1058 652 1078 652 1078 653 1058 653 1056 653 1078 654 1056 654 1079 654 1079 655 1056 655 1054 655 1079 656 1054 656 1080 656 1080 657 1054 657 1052 657 1080 657 1052 657 1081 657 1081 658 1052 658 1050 658 1081 658 1050 658 1082 658 1082 659 1050 659 1048 659 1082 660 1048 660 1083 660 1083 661 1048 661 1046 661 1083 662 1046 662 1084 662 1084 663 1046 663 1044 663 1084 664 1044 664 1085 664 1044 665 1014 665 1085 665 1085 666 1014 666 1075 666 1085 667 1075 667 1086 667 1086 668 1075 668 1013 668 1013 669 1074 669 1086 669 1086 670 1074 670 1072 670 1086 671 1072 671 1087 671 1087 672 1072 672 1070 672 1087 672 1070 672 1088 672 1088 673 1070 673 1068 673 1088 673 1068 673 1089 673 1089 674 1068 674 1066 674 1089 675 1066 675 1090 675 1090 676 1066 676 1064 676 1090 677 1064 677 1091 677 1091 678 1064 678 1062 678 1091 678 1062 678 1092 678 1092 679 1062 679 1060 679 1092 680 1060 680 1093 680 1093 681 1060 681 1024 681 1024 682 1060 682 1026 682 1024 683 1026 683 1076 683 824 684 826 684 1037 684 822 685 821 685 1025 685 1025 686 821 686 823 686 1025 687 823 687 1094 687 1094 688 823 688 1059 688 1094 689 1059 689 1095 689 1095 690 1059 690 1061 690 1095 691 1061 691 1096 691 1096 692 1061 692 1063 692 1096 693 1063 693 1097 693 1097 694 1063 694 1065 694 1097 695 1065 695 1098 695 1098 696 1065 696 1067 696 1098 697 1067 697 1099 697 1099 698 1067 698 1069 698 1099 699 1069 699 1100 699 1100 700 1069 700 1071 700 1100 701 1071 701 1101 701 1101 702 1071 702 1073 702 1073 703 819 703 1101 703 1101 704 819 704 818 704 1101 705 818 705 1102 705 818 706 820 706 1102 706 1102 707 820 707 1043 707 1102 708 1043 708 1103 708 1103 709 1043 709 1045 709 1103 710 1045 710 1104 710 1104 711 1045 711 1047 711 1104 712 1047 712 1105 712 1105 712 1047 712 1049 712 1105 713 1049 713 1106 713 1106 714 1049 714 1051 714 1106 715 1051 715 1107 715 1107 715 1051 715 1053 715 1107 716 1053 716 1108 716 1108 716 1053 716 1055 716 1108 717 1055 717 1109 717 1109 717 1055 717 1057 717 1109 718 1057 718 1037 718 1037 719 1057 719 825 719 1037 720 825 720 824 720 1037 88 1036 88 1109 88 1109 88 1036 88 1078 88 1109 88 1078 88 1108 88 1108 88 1078 88 1079 88 1108 88 1079 88 1107 88 1107 88 1079 88 1080 88 1107 88 1080 88 1106 88 1106 88 1080 88 1081 88 1106 88 1081 88 1105 88 1105 88 1081 88 1082 88 1105 88 1082 88 1104 88 1104 88 1082 88 1083 88 1104 88 1083 88 1103 88 1103 88 1083 88 1084 88 1103 88 1084 88 1102 88 1102 721 1084 721 1085 721 1102 88 1085 88 1101 88 1101 88 1085 88 1086 88 1101 722 1086 722 1100 722 1100 88 1086 88 1087 88 1100 88 1087 88 1099 88 1099 88 1087 88 1088 88 1099 88 1088 88 1098 88 1098 723 1088 723 1089 723 1098 88 1089 88 1097 88 1097 88 1089 88 1090 88 1097 724 1090 724 1096 724 1096 725 1090 725 1091 725 1096 88 1091 88 1095 88 1095 88 1091 88 1092 88 1095 88 1092 88 1094 88 1094 88 1092 88 1093 88 1094 88 1093 88 1025 88 1025 88 1093 88 1024 88 1035 0 1077 0 1038 0 1110 88 1111 88 1112 88 1113 88 1114 88 1115 88 1116 88 1117 88 1118 88 1119 88 1120 88 1121 88 1122 88 1123 88 1124 88 1125 88 1126 88 1127 88 1128 88 1129 88 1130 88 1131 726 1132 726 1133 726 1134 88 1135 88 1133 88 1136 88 1137 88 1138 88 1139 88 1140 88 1141 88 1142 88 1143 88 1144 88 1145 88 1146 88 1147 88 1146 88 1148 88 1147 88 1147 88 1148 88 1149 88 1147 88 1149 88 1150 88 1150 88 1149 88 1151 88 1150 88 1151 88 1152 88 1152 88 1151 88 1153 88 1152 88 1153 88 1154 88 1155 88 1156 88 1157 88 1157 88 1156 88 1158 88 1158 88 1156 88 1159 88 1158 88 1159 88 1160 88 1161 88 1162 88 1163 88 1163 88 1162 88 1164 88 1163 88 1164 88 1165 88 1165 88 1164 88 1166 88 1165 88 1166 88 1167 88 1168 88 1169 88 1170 88 1136 88 1138 88 1171 88 1171 88 1138 88 1172 88 1171 88 1172 88 1173 88 1174 88 1175 88 1173 88 1176 88 1177 88 1178 88 1175 88 1174 88 1179 88 1179 88 1174 88 1176 88 1179 88 1176 88 1180 88 1180 88 1176 88 1178 88 1180 88 1178 88 1181 88 1182 88 1133 88 1183 88 1183 88 1133 88 1135 88 1183 88 1135 88 1184 88 1182 88 1185 88 1133 88 1133 88 1185 88 1186 88 1133 88 1186 88 1187 88 1187 88 1186 88 1188 88 1187 88 1188 88 1176 88 1176 88 1188 88 1189 88 1176 88 1189 88 1177 88 1181 88 1190 88 1180 88 1180 88 1190 88 1191 88 1180 88 1191 88 1192 88 1192 88 1191 88 1193 88 1192 88 1193 88 1135 88 1135 88 1193 88 1194 88 1135 88 1194 88 1184 88 1132 88 1195 88 1133 88 1133 88 1195 88 1196 88 1133 88 1196 88 1134 88 1128 88 1130 88 1197 88 1198 88 1199 88 1200 88 1200 88 1199 88 1201 88 1202 88 1203 88 1204 88 1204 88 1203 88 1205 88 1204 88 1205 88 1206 88 1207 88 1208 88 1209 88 1209 88 1208 88 1210 88 1209 88 1210 88 1211 88 1211 88 1210 88 1212 88 1211 88 1212 88 1213 88 1125 88 1127 88 1214 88 1214 88 1127 88 1215 88 1214 88 1215 88 1216 88 1216 88 1215 88 1217 88 1216 88 1217 88 1123 88 1218 88 1219 88 1220 88 1220 88 1219 88 1221 88 1220 88 1221 88 1124 88 1124 88 1221 88 1222 88 1124 88 1222 88 1122 88 1223 88 1224 88 1225 88 1225 88 1224 88 1226 88 1225 88 1226 88 1227 88 1228 88 1229 88 1230 88 1230 88 1229 88 1231 88 1220 88 1232 88 1218 88 1218 88 1232 88 1230 88 1218 88 1230 88 1233 88 1233 88 1230 88 1231 88 1231 88 1234 88 1233 88 1233 88 1234 88 1235 88 1233 88 1235 88 1236 88 1236 88 1235 88 1237 88 1236 88 1237 88 1238 88 1238 88 1237 88 1239 88 1239 88 1237 88 1240 88 1239 88 1240 88 1241 88 1242 88 1243 88 1239 88 1244 88 1243 88 1245 88 1245 88 1243 88 1242 88 1245 88 1242 88 1246 88 1247 88 1248 88 1249 88 1249 88 1248 88 1250 88 1250 88 1251 88 1118 88 1118 88 1251 88 1252 88 1118 88 1252 88 1253 88 1252 88 1254 88 1253 88 1253 88 1254 88 1255 88 1253 727 1255 727 1256 727 1256 88 1255 88 1257 88 1256 88 1257 88 1258 88 1258 88 1257 88 1259 88 1258 88 1259 88 1260 88 1260 88 1259 88 1261 88 1260 88 1261 88 1262 88 1262 88 1261 88 1263 88 1262 88 1263 88 1264 88 1264 88 1263 88 1265 88 1264 88 1265 88 1266 88 1174 88 1267 88 1268 88 1269 88 1270 88 1121 88 1121 88 1270 88 1271 88 1121 88 1271 88 1272 88 1173 88 1172 88 1174 88 1174 88 1172 88 1273 88 1174 88 1273 88 1267 88 1271 88 1274 88 1272 88 1272 88 1274 88 1275 88 1272 88 1275 88 1276 88 1277 88 1278 88 1138 88 1138 88 1278 88 1279 88 1138 88 1279 88 1172 88 1172 88 1279 88 1280 88 1172 88 1280 88 1273 88 1281 88 1282 88 1283 88 1283 88 1284 88 1281 88 1281 88 1284 88 1285 88 1281 88 1285 88 1286 88 1287 88 1288 88 1289 88 1289 88 1288 88 1290 88 1289 88 1290 88 1282 88 1282 88 1290 88 1291 88 1282 88 1291 88 1283 88 1292 88 1293 88 1294 88 1294 88 1293 88 1295 88 1294 88 1295 88 1296 88 1297 88 1298 88 1299 88 1299 88 1298 88 1300 88 1301 88 1302 88 1246 88 1246 88 1302 88 1303 88 1302 88 1304 88 1303 88 1303 88 1304 88 1305 88 1303 88 1305 88 1306 88 1306 88 1305 88 1307 88 1308 88 1309 88 1310 88 1268 88 1269 88 1174 88 1174 88 1269 88 1121 88 1174 88 1121 88 1311 88 1311 88 1121 88 1120 88 1250 88 1118 88 1249 88 1249 88 1118 88 1117 88 1249 88 1117 88 1312 88 1312 88 1313 88 1249 88 1249 88 1313 88 1314 88 1249 88 1314 88 1315 88 1315 88 1314 88 1316 88 1315 88 1316 88 1317 88 1317 88 1316 88 1318 88 1317 88 1318 88 1319 88 1311 88 1320 88 1174 88 1174 88 1320 88 1321 88 1174 88 1321 88 1176 88 1176 88 1321 88 1322 88 1176 88 1322 88 1187 88 1187 88 1322 88 1323 88 1187 88 1323 88 1324 88 1325 88 1326 88 1327 88 1327 88 1326 88 1328 88 1329 88 1225 88 1230 88 1230 88 1225 88 1227 88 1230 88 1227 88 1228 88 1330 88 1331 88 1332 88 1332 88 1331 88 1333 88 1332 88 1333 88 1334 88 1334 88 1333 88 1335 88 1334 88 1335 88 1336 88 1336 88 1335 88 1337 88 1336 88 1337 88 1338 88 1339 88 1289 88 1340 88 1340 88 1289 88 1341 88 1341 88 1289 88 1342 88 1342 88 1289 88 1282 88 1342 88 1282 88 1343 88 1241 88 1223 88 1239 88 1239 88 1223 88 1225 88 1239 88 1225 88 1242 88 1242 88 1225 88 1299 88 1242 88 1299 88 1246 88 1246 88 1299 88 1300 88 1246 88 1300 88 1301 88 1329 88 1328 88 1225 88 1225 88 1328 88 1326 88 1225 88 1326 88 1299 88 1299 88 1326 88 1325 88 1299 88 1325 88 1297 88 1297 88 1325 88 1344 88 1297 88 1344 88 1345 88 1345 88 1344 88 1112 88 1345 88 1112 88 1346 88 1346 88 1112 88 1111 88 1346 88 1111 88 1343 88 1343 88 1111 88 1110 88 1343 88 1110 88 1342 88 1123 88 1217 88 1124 88 1124 88 1217 88 1335 88 1124 88 1335 88 1220 88 1220 88 1335 88 1333 88 1220 88 1333 88 1232 88 1232 88 1333 88 1331 88 1232 88 1331 88 1230 88 1230 88 1331 88 1330 88 1230 88 1330 88 1329 88 1347 88 1348 88 1337 88 1347 88 1337 88 1349 88 1349 88 1337 88 1335 88 1349 88 1335 88 1350 88 1351 88 1352 88 1215 88 1215 88 1352 88 1353 88 1215 88 1353 88 1217 88 1217 88 1353 88 1354 88 1217 88 1354 88 1355 88 1355 88 1356 88 1217 88 1217 88 1356 88 1357 88 1217 88 1357 88 1335 88 1335 88 1357 88 1358 88 1335 88 1358 88 1350 88 1136 88 1168 88 1137 88 1137 88 1168 88 1170 88 1137 88 1170 88 1138 88 1138 88 1170 88 1276 88 1138 88 1276 88 1277 88 1277 88 1276 88 1275 88 1359 88 1244 88 1360 88 1360 88 1244 88 1245 88 1360 88 1245 88 1361 88 1361 88 1245 88 1246 88 1361 88 1246 88 1362 88 1362 88 1246 88 1303 88 1362 88 1303 88 1363 88 1363 88 1303 88 1306 88 1363 88 1306 88 1159 88 1159 88 1306 88 1144 88 1159 88 1144 88 1160 88 1160 88 1144 88 1143 88 1307 88 1309 88 1306 88 1306 88 1309 88 1308 88 1306 88 1308 88 1144 88 1144 88 1308 88 1152 88 1144 88 1152 88 1142 88 1142 88 1152 88 1154 88 1340 88 1113 88 1339 88 1339 88 1113 88 1115 88 1339 88 1115 88 1289 88 1289 88 1115 88 1296 88 1289 88 1296 88 1287 88 1287 88 1296 88 1295 88 1348 88 1351 88 1337 88 1337 88 1351 88 1215 88 1337 88 1215 88 1364 88 1364 88 1215 88 1127 88 1364 88 1127 88 1212 88 1212 88 1127 88 1126 88 1212 88 1126 88 1213 88 1213 88 1126 88 1125 88 1169 88 1167 88 1170 88 1170 88 1167 88 1166 88 1170 88 1166 88 1276 88 1276 88 1166 88 1365 88 1276 88 1365 88 1272 88 1272 88 1365 88 1366 88 1272 88 1366 88 1121 88 1121 88 1366 88 1317 88 1121 88 1317 88 1119 88 1119 88 1317 88 1319 88 1286 88 1367 88 1281 88 1281 88 1367 88 1368 88 1281 88 1368 88 1205 88 1205 88 1368 88 1369 88 1205 88 1369 88 1206 88 1367 88 1292 88 1368 88 1368 88 1292 88 1294 88 1368 88 1294 88 1369 88 1369 88 1294 88 1370 88 1369 88 1370 88 1206 88 1206 88 1370 88 1371 88 1113 88 1338 88 1114 88 1114 88 1338 88 1337 88 1114 88 1337 88 1115 88 1115 88 1337 88 1364 88 1115 88 1364 88 1296 88 1296 88 1364 88 1212 88 1296 88 1212 88 1294 88 1294 88 1212 88 1210 88 1294 88 1210 88 1370 88 1370 88 1210 88 1208 88 1370 88 1208 88 1371 88 1371 88 1208 88 1207 88 1161 88 1359 88 1162 88 1162 88 1359 88 1360 88 1162 88 1360 88 1164 88 1164 88 1360 88 1361 88 1164 88 1361 88 1166 88 1166 88 1361 88 1362 88 1166 88 1362 88 1365 88 1365 88 1362 88 1363 88 1365 88 1363 88 1366 88 1366 88 1363 88 1159 88 1366 88 1159 88 1317 88 1317 88 1159 88 1156 88 1317 88 1156 88 1315 88 1315 88 1156 88 1155 88 1315 88 1155 88 1249 88 1249 88 1155 88 1266 88 1249 88 1266 88 1247 88 1247 88 1266 88 1265 88 1310 88 1346 88 1308 88 1308 88 1346 88 1343 88 1308 88 1343 88 1152 88 1152 88 1343 88 1282 88 1152 88 1282 88 1150 88 1150 88 1282 88 1281 88 1150 88 1281 88 1147 88 1147 88 1281 88 1205 88 1147 88 1205 88 1198 88 1198 88 1205 88 1203 88 1198 88 1203 88 1199 88 1199 88 1203 88 1202 88 1324 88 1116 88 1187 88 1187 88 1116 88 1118 88 1187 88 1118 88 1133 88 1133 88 1118 88 1253 88 1133 728 1253 728 1131 728 1131 88 1253 88 1256 88 1157 88 1139 88 1155 88 1155 88 1139 88 1141 88 1155 88 1141 88 1266 88 1266 88 1141 88 1372 88 1266 88 1372 88 1264 88 1264 88 1372 88 1130 88 1264 88 1130 88 1262 88 1262 88 1130 88 1129 88 1140 88 1145 88 1141 88 1141 88 1145 88 1147 88 1141 88 1147 88 1372 88 1372 88 1147 88 1198 88 1372 88 1198 88 1130 88 1130 88 1198 88 1200 88 1130 88 1200 88 1197 88 1197 88 1200 88 1201 88 1165 729 1373 729 1374 729 1165 730 1374 730 1163 730 1163 731 1374 731 1375 731 1163 731 1375 731 1161 731 1161 732 1375 732 1376 732 1161 733 1376 733 1359 733 1359 734 1376 734 1377 734 1359 735 1377 735 1244 735 1244 736 1377 736 1378 736 1244 737 1378 737 1243 737 1243 738 1378 738 1379 738 1243 739 1379 739 1239 739 1239 740 1379 740 1380 740 1239 741 1380 741 1238 741 1238 742 1380 742 1381 742 1238 743 1381 743 1236 743 1236 744 1381 744 1233 744 1233 744 1381 744 1382 744 1233 745 1382 745 1218 745 1382 745 1383 745 1218 745 1218 746 1383 746 1384 746 1218 747 1384 747 1219 747 1219 748 1384 748 1385 748 1219 748 1385 748 1221 748 1221 749 1385 749 1386 749 1221 749 1386 749 1222 749 1222 750 1386 750 1387 750 1222 750 1387 750 1122 750 1122 751 1387 751 1388 751 1122 752 1388 752 1123 752 1123 753 1388 753 1389 753 1123 753 1389 753 1216 753 1216 754 1389 754 1390 754 1216 755 1390 755 1214 755 1214 756 1390 756 1391 756 1214 757 1391 757 1125 757 1125 758 1391 758 1392 758 1125 759 1392 759 1213 759 1213 760 1392 760 1393 760 1213 761 1393 761 1211 761 1211 762 1393 762 1394 762 1211 762 1394 762 1209 762 1209 763 1394 763 1395 763 1209 764 1395 764 1207 764 1207 765 1395 765 1396 765 1207 766 1396 766 1371 766 1371 767 1396 767 1397 767 1371 768 1397 768 1206 768 1206 769 1397 769 1398 769 1206 770 1398 770 1204 770 1204 771 1398 771 1399 771 1204 771 1399 771 1202 771 1202 772 1399 772 1400 772 1202 773 1400 773 1199 773 1199 774 1400 774 1401 774 1199 775 1401 775 1201 775 1201 776 1401 776 1402 776 1201 777 1402 777 1197 777 1197 778 1402 778 1403 778 1197 779 1403 779 1128 779 1128 780 1403 780 1129 780 1129 780 1403 780 1404 780 1129 781 1404 781 1262 781 1262 781 1404 781 1405 781 1262 782 1405 782 1260 782 1260 783 1405 783 1406 783 1260 784 1406 784 1258 784 1406 784 1407 784 1258 784 1258 785 1407 785 1408 785 1258 786 1408 786 1256 786 1256 787 1408 787 1409 787 1256 788 1409 788 1131 788 1131 789 1409 789 1410 789 1131 790 1410 790 1132 790 1132 791 1410 791 1411 791 1132 792 1411 792 1195 792 1195 793 1411 793 1412 793 1195 794 1412 794 1196 794 1196 795 1412 795 1413 795 1196 796 1413 796 1134 796 1134 797 1413 797 1414 797 1134 798 1414 798 1135 798 1135 799 1414 799 1415 799 1135 799 1415 799 1192 799 1192 800 1415 800 1416 800 1192 800 1416 800 1180 800 1180 801 1416 801 1417 801 1180 802 1417 802 1179 802 1179 803 1417 803 1418 803 1179 803 1418 803 1175 803 1175 804 1418 804 1419 804 1175 805 1419 805 1173 805 1173 806 1419 806 1420 806 1173 806 1420 806 1171 806 1171 807 1420 807 1421 807 1171 807 1421 807 1136 807 1136 808 1421 808 1422 808 1136 809 1422 809 1168 809 1168 810 1422 810 1423 810 1168 811 1423 811 1169 811 1169 812 1423 812 1424 812 1169 813 1424 813 1167 813 1167 814 1424 814 1373 814 1167 815 1373 815 1165 815 1425 0 1426 0 1427 0 1428 0 1429 0 1430 0 1431 0 1432 0 1433 0 1434 0 1435 0 1436 0 1437 0 1438 0 1439 0 1440 0 1441 0 1442 0 1384 0 1383 0 1443 0 1375 0 1444 0 1445 0 1423 0 1422 0 1446 0 1398 0 1397 0 1447 0 1448 0 1449 0 1399 0 1450 0 1402 0 1401 0 1402 0 1450 0 1403 0 1403 0 1450 0 1451 0 1403 0 1451 0 1404 0 1404 0 1451 0 1452 0 1404 0 1452 0 1405 0 1412 0 1411 0 1453 0 1453 0 1411 0 1410 0 1453 0 1410 0 1409 0 1454 0 1455 0 1453 0 1455 0 1414 0 1453 0 1453 0 1414 0 1413 0 1453 0 1413 0 1412 0 1456 0 1457 0 1458 0 1456 0 1458 0 1459 0 1457 0 1460 0 1458 0 1458 0 1460 0 1461 0 1458 0 1461 0 1462 0 1462 0 1461 0 1463 0 1462 0 1463 0 1453 0 1453 0 1463 0 1464 0 1453 0 1464 0 1454 0 1455 0 1465 0 1414 0 1414 0 1465 0 1466 0 1414 0 1466 0 1415 0 1415 0 1466 0 1467 0 1415 0 1467 0 1416 0 1416 0 1467 0 1468 0 1416 0 1468 0 1469 0 1422 0 1421 0 1446 0 1446 0 1421 0 1420 0 1446 0 1420 0 1470 0 1470 0 1420 0 1419 0 1470 0 1419 0 1471 0 1471 0 1419 0 1418 0 1471 0 1418 0 1472 0 1472 0 1418 0 1417 0 1472 0 1417 0 1458 0 1458 0 1417 0 1416 0 1458 0 1416 0 1459 0 1459 0 1416 0 1469 0 1373 0 1424 0 1473 0 1473 0 1424 0 1423 0 1474 0 1374 0 1475 0 1475 0 1374 0 1373 0 1375 0 1445 0 1376 0 1376 0 1445 0 1476 0 1376 0 1476 0 1377 0 1377 0 1476 0 1477 0 1377 0 1477 0 1378 0 1378 0 1477 0 1478 0 1378 0 1478 0 1379 0 1479 0 1480 0 1478 0 1379 0 1481 0 1380 0 1380 0 1481 0 1482 0 1380 0 1482 0 1381 0 1381 0 1482 0 1483 0 1381 0 1483 0 1382 0 1382 0 1483 0 1484 0 1382 0 1484 0 1485 0 1486 0 1487 0 1488 0 1488 0 1487 0 1479 0 1480 0 1489 0 1478 0 1478 0 1489 0 1490 0 1478 0 1490 0 1379 0 1379 0 1490 0 1491 0 1379 0 1491 0 1481 0 1443 0 1383 0 1492 0 1492 0 1383 0 1382 0 1492 0 1382 0 1488 0 1488 0 1382 0 1485 0 1488 0 1485 0 1486 0 1388 0 1387 0 1493 0 1493 0 1387 0 1386 0 1493 0 1386 0 1443 0 1443 0 1386 0 1385 0 1443 0 1385 0 1384 0 1391 0 1390 0 1494 0 1494 0 1390 0 1495 0 1494 0 1495 0 1496 0 1425 0 1396 0 1426 0 1426 0 1396 0 1395 0 1426 0 1395 0 1427 0 1427 0 1395 0 1394 0 1427 0 1394 0 1393 0 1497 0 1498 0 1499 0 1499 0 1498 0 1500 0 1499 0 1500 0 1501 0 1440 0 1442 0 1501 0 1441 0 1502 0 1503 0 1503 0 1502 0 1504 0 1505 0 1506 0 1472 0 1507 0 1508 0 1509 0 1509 0 1508 0 1510 0 1509 0 1510 0 1511 0 1505 0 1472 0 1511 0 1506 0 1512 0 1472 0 1472 0 1512 0 1513 0 1472 0 1513 0 1471 0 1471 0 1513 0 1514 0 1471 0 1514 0 1470 0 1470 0 1514 0 1515 0 1470 0 1515 0 1516 0 1517 0 1518 0 1507 0 1507 0 1518 0 1519 0 1507 0 1519 0 1508 0 1520 0 1521 0 1522 0 1522 0 1521 0 1523 0 1524 0 1525 0 1526 0 1526 0 1525 0 1527 0 1526 0 1527 0 1528 0 1529 0 1530 0 1531 0 1531 0 1530 0 1528 0 1531 0 1528 0 1532 0 1532 0 1528 0 1527 0 1533 0 1534 0 1535 0 1535 0 1534 0 1536 0 1537 0 1538 0 1539 0 1537 0 1539 0 1540 0 1539 0 1541 0 1540 0 1540 0 1541 0 1542 0 1540 0 1542 0 1543 0 1543 0 1542 0 1544 0 1543 0 1544 0 1545 0 1538 0 1537 0 1546 0 1546 0 1537 0 1547 0 1546 0 1547 0 1548 0 1548 0 1549 0 1550 0 1550 0 1549 0 1438 0 1439 0 1438 0 1551 0 1552 0 1553 0 1554 0 1554 0 1553 0 1555 0 1556 0 1557 0 1462 0 1558 0 1559 0 1442 0 1501 0 1442 0 1499 0 1499 0 1442 0 1559 0 1499 0 1559 0 1556 0 1560 0 1561 0 1562 0 1562 0 1561 0 1563 0 1562 0 1563 0 1564 0 1564 0 1563 0 1565 0 1564 0 1565 0 1442 0 1442 0 1565 0 1566 0 1442 0 1566 0 1558 0 1567 0 1568 0 1472 0 1511 0 1472 0 1509 0 1509 0 1472 0 1568 0 1509 0 1568 0 1569 0 1557 0 1570 0 1462 0 1462 0 1570 0 1571 0 1462 0 1571 0 1458 0 1458 0 1571 0 1572 0 1458 0 1572 0 1472 0 1472 0 1572 0 1573 0 1472 0 1573 0 1567 0 1574 0 1575 0 1576 0 1479 0 1478 0 1488 0 1488 0 1478 0 1577 0 1488 0 1577 0 1578 0 1545 0 1554 0 1543 0 1543 0 1554 0 1555 0 1543 0 1555 0 1579 0 1579 0 1555 0 1580 0 1581 0 1582 0 1583 0 1583 0 1582 0 1584 0 1585 0 1586 0 1587 0 1587 0 1586 0 1588 0 1587 0 1588 0 1589 0 1581 0 1590 0 1591 0 1591 0 1590 0 1592 0 1591 0 1592 0 1593 0 1593 0 1592 0 1594 0 1431 0 1433 0 1595 0 1596 0 1430 0 1597 0 1597 0 1430 0 1589 0 1597 0 1589 0 1598 0 1598 0 1589 0 1588 0 1556 0 1462 0 1499 0 1499 0 1462 0 1453 0 1499 0 1453 0 1497 0 1497 0 1453 0 1409 0 1497 0 1409 0 1408 0 1401 0 1400 0 1450 0 1450 0 1400 0 1429 0 1450 0 1429 0 1451 0 1451 0 1429 0 1428 0 1451 0 1428 0 1452 0 1503 0 1433 0 1594 0 1594 0 1433 0 1432 0 1594 0 1432 0 1593 0 1596 0 1595 0 1430 0 1430 0 1595 0 1433 0 1430 0 1433 0 1428 0 1428 0 1433 0 1503 0 1428 0 1503 0 1452 0 1452 0 1503 0 1504 0 1452 0 1504 0 1405 0 1405 0 1504 0 1599 0 1405 0 1599 0 1406 0 1406 0 1599 0 1600 0 1406 0 1600 0 1407 0 1407 0 1600 0 1601 0 1407 0 1601 0 1408 0 1408 0 1601 0 1602 0 1408 0 1602 0 1497 0 1497 0 1602 0 1603 0 1497 0 1603 0 1498 0 1448 0 1522 0 1526 0 1526 0 1522 0 1523 0 1526 0 1523 0 1524 0 1399 0 1398 0 1448 0 1448 0 1398 0 1447 0 1448 0 1447 0 1522 0 1522 0 1447 0 1604 0 1522 0 1604 0 1520 0 1397 0 1396 0 1447 0 1447 0 1396 0 1425 0 1447 0 1425 0 1604 0 1604 0 1425 0 1427 0 1604 0 1427 0 1496 0 1496 0 1427 0 1393 0 1496 0 1393 0 1494 0 1494 0 1393 0 1392 0 1494 0 1392 0 1391 0 1548 0 1547 0 1549 0 1549 0 1547 0 1583 0 1549 0 1583 0 1587 0 1587 0 1583 0 1584 0 1587 0 1584 0 1585 0 1438 0 1549 0 1551 0 1551 0 1549 0 1587 0 1551 0 1587 0 1528 0 1528 0 1587 0 1589 0 1528 0 1589 0 1526 0 1526 0 1589 0 1430 0 1526 0 1430 0 1448 0 1448 0 1430 0 1429 0 1448 0 1429 0 1449 0 1449 0 1429 0 1400 0 1449 0 1400 0 1399 0 1605 0 1606 0 1530 0 1389 0 1607 0 1390 0 1390 0 1607 0 1608 0 1390 0 1608 0 1495 0 1495 0 1608 0 1609 0 1495 0 1609 0 1496 0 1496 0 1609 0 1535 0 1496 0 1535 0 1604 0 1604 0 1535 0 1536 0 1604 0 1536 0 1520 0 1423 0 1446 0 1473 0 1473 0 1446 0 1470 0 1473 0 1470 0 1517 0 1517 0 1470 0 1516 0 1517 0 1516 0 1518 0 1373 0 1473 0 1475 0 1475 0 1473 0 1517 0 1475 0 1517 0 1610 0 1610 0 1517 0 1507 0 1610 0 1507 0 1611 0 1611 0 1507 0 1509 0 1611 0 1509 0 1562 0 1562 0 1509 0 1569 0 1562 0 1569 0 1560 0 1554 0 1437 0 1552 0 1552 0 1437 0 1439 0 1552 0 1439 0 1612 0 1612 0 1439 0 1551 0 1612 0 1551 0 1613 0 1613 0 1551 0 1528 0 1613 0 1528 0 1614 0 1614 0 1528 0 1530 0 1614 0 1530 0 1615 0 1615 0 1530 0 1606 0 1615 0 1606 0 1434 0 1434 0 1606 0 1605 0 1434 0 1605 0 1435 0 1435 0 1605 0 1576 0 1435 0 1576 0 1436 0 1436 0 1576 0 1575 0 1441 0 1503 0 1442 0 1442 0 1503 0 1594 0 1442 0 1594 0 1564 0 1564 0 1594 0 1592 0 1564 0 1592 0 1562 0 1562 0 1592 0 1590 0 1562 0 1590 0 1611 0 1611 0 1590 0 1616 0 1611 0 1616 0 1610 0 1610 0 1616 0 1617 0 1610 0 1617 0 1475 0 1475 0 1617 0 1618 0 1475 0 1618 0 1474 0 1581 0 1583 0 1590 0 1590 0 1583 0 1547 0 1590 0 1547 0 1616 0 1616 0 1547 0 1537 0 1616 0 1537 0 1617 0 1617 0 1537 0 1540 0 1617 0 1540 0 1618 0 1619 0 1620 0 1621 0 1622 0 1607 0 1623 0 1623 0 1607 0 1621 0 1623 0 1621 0 1624 0 1624 0 1621 0 1620 0 1622 0 1625 0 1607 0 1607 0 1625 0 1626 0 1607 0 1626 0 1608 0 1608 0 1626 0 1627 0 1608 0 1627 0 1628 0 1629 0 1630 0 1576 0 1576 0 1630 0 1631 0 1529 0 1533 0 1530 0 1530 0 1533 0 1535 0 1530 0 1535 0 1605 0 1605 0 1535 0 1609 0 1605 0 1609 0 1576 0 1576 0 1609 0 1608 0 1576 0 1608 0 1629 0 1629 0 1608 0 1628 0 1631 0 1619 0 1576 0 1576 0 1619 0 1621 0 1576 0 1621 0 1574 0 1574 0 1621 0 1632 0 1574 0 1632 0 1633 0 1633 0 1632 0 1634 0 1633 0 1634 0 1635 0 1580 0 1577 0 1579 0 1579 0 1577 0 1478 0 1579 0 1478 0 1543 0 1543 0 1478 0 1477 0 1543 0 1477 0 1540 0 1540 0 1477 0 1476 0 1540 0 1476 0 1618 0 1618 0 1476 0 1445 0 1618 0 1445 0 1474 0 1474 0 1445 0 1444 0 1474 0 1444 0 1374 0 1374 0 1444 0 1375 0 1389 0 1388 0 1607 0 1607 0 1388 0 1493 0 1607 0 1493 0 1621 0 1621 0 1493 0 1443 0 1621 0 1443 0 1632 0 1632 0 1443 0 1492 0 1632 0 1492 0 1634 0 1634 0 1492 0 1488 0 1634 0 1488 0 1635 0 1635 0 1488 0 1578 0 1498 816 1254 816 1500 816 1500 817 1254 817 1252 817 1500 818 1252 818 1501 818 1501 818 1252 818 1251 818 1501 819 1251 819 1440 819 1440 820 1251 820 1250 820 1440 821 1250 821 1441 821 1441 821 1250 821 1248 821 1441 822 1248 822 1502 822 1502 822 1248 822 1247 822 1502 823 1247 823 1504 823 1504 823 1247 823 1265 823 1504 824 1265 824 1599 824 1599 824 1265 824 1263 824 1599 825 1263 825 1600 825 1600 825 1263 825 1261 825 1600 826 1261 826 1601 826 1601 827 1261 827 1259 827 1601 828 1259 828 1602 828 1602 829 1259 829 1257 829 1602 830 1257 830 1603 830 1603 831 1257 831 1255 831 1603 832 1255 832 1498 832 1498 833 1255 833 1254 833 1513 834 1273 834 1514 834 1514 834 1273 834 1280 834 1514 835 1280 835 1515 835 1515 835 1280 835 1279 835 1515 836 1279 836 1516 836 1516 836 1279 836 1278 836 1516 837 1278 837 1518 837 1518 837 1278 837 1277 837 1518 838 1277 838 1519 838 1519 839 1277 839 1275 839 1519 840 1275 840 1508 840 1508 841 1275 841 1274 841 1508 824 1274 824 1510 824 1510 842 1274 842 1271 842 1510 825 1271 825 1511 825 1511 825 1271 825 1270 825 1511 826 1270 826 1505 826 1505 826 1270 826 1269 826 1505 829 1269 829 1506 829 1506 829 1269 829 1268 829 1506 843 1268 843 1512 843 1512 830 1268 830 1267 830 1512 844 1267 844 1513 844 1513 845 1267 845 1273 845 1527 817 1284 817 1532 817 1532 816 1284 816 1283 816 1532 818 1283 818 1531 818 1531 818 1283 818 1291 818 1531 820 1291 820 1529 820 1529 819 1291 819 1290 819 1529 821 1290 821 1533 821 1533 821 1290 821 1288 821 1533 846 1288 846 1534 846 1534 847 1288 847 1287 847 1534 823 1287 823 1536 823 1536 848 1287 848 1295 848 1536 849 1295 849 1520 849 1520 850 1295 850 1293 850 1520 851 1293 851 1521 851 1521 851 1293 851 1292 851 1521 852 1292 852 1523 852 1523 853 1292 853 1367 853 1523 854 1367 854 1524 854 1524 855 1367 855 1286 855 1524 856 1286 856 1525 856 1525 831 1286 831 1285 831 1525 845 1285 845 1527 845 1527 845 1285 845 1284 845 1539 834 1304 834 1541 834 1541 834 1304 834 1302 834 1541 818 1302 818 1542 818 1542 857 1302 857 1301 857 1542 819 1301 819 1544 819 1544 820 1301 820 1300 820 1544 821 1300 821 1545 821 1545 858 1300 858 1298 858 1545 822 1298 822 1554 822 1554 859 1298 859 1297 859 1554 860 1297 860 1437 860 1437 860 1297 860 1345 860 1437 824 1345 824 1438 824 1438 861 1345 861 1346 861 1438 825 1346 825 1550 825 1550 862 1346 862 1310 862 1550 827 1310 827 1548 827 1548 863 1310 863 1309 863 1548 864 1309 864 1546 864 1546 828 1309 828 1307 828 1546 830 1307 830 1538 830 1538 830 1307 830 1305 830 1538 865 1305 865 1539 865 1539 833 1305 833 1304 833 1490 866 1223 866 1491 866 1491 834 1223 834 1241 834 1491 835 1241 835 1481 835 1481 835 1241 835 1240 835 1481 867 1240 867 1482 867 1482 868 1240 868 1237 868 1482 869 1237 869 1483 869 1483 870 1237 870 1235 870 1483 847 1235 847 1484 847 1484 846 1235 846 1234 846 1484 823 1234 823 1485 823 1485 823 1234 823 1231 823 1485 824 1231 824 1486 824 1486 871 1231 871 1229 871 1486 825 1229 825 1487 825 1487 825 1229 825 1228 825 1487 826 1228 826 1479 826 1479 827 1228 827 1227 827 1479 829 1227 829 1480 829 1480 829 1227 829 1226 829 1480 831 1226 831 1489 831 1489 856 1226 856 1224 856 1489 845 1224 845 1490 845 1490 872 1224 872 1223 872 1619 834 1349 834 1620 834 1620 866 1349 866 1350 866 1620 818 1350 818 1624 818 1624 818 1350 818 1358 818 1624 820 1358 820 1623 820 1623 819 1358 819 1357 819 1623 858 1357 858 1622 858 1622 821 1357 821 1356 821 1622 838 1356 838 1625 838 1625 846 1356 846 1355 846 1625 860 1355 860 1626 860 1626 873 1355 873 1354 873 1626 849 1354 849 1627 849 1627 874 1354 874 1353 874 1627 825 1353 825 1628 825 1628 825 1353 825 1352 825 1628 826 1352 826 1629 826 1629 827 1352 827 1351 827 1629 855 1351 855 1630 855 1630 855 1351 855 1348 855 1630 831 1348 831 1631 831 1631 856 1348 856 1347 856 1631 845 1347 845 1619 845 1619 845 1347 845 1349 845 1572 875 1322 875 1573 875 1573 875 1322 875 1321 875 1573 876 1321 876 1567 876 1567 876 1321 876 1320 876 1567 877 1320 877 1568 877 1568 878 1320 878 1311 878 1568 879 1311 879 1569 879 1569 879 1311 879 1120 879 1569 880 1120 880 1560 880 1560 881 1120 881 1119 881 1560 882 1119 882 1561 882 1561 882 1119 882 1319 882 1561 883 1319 883 1563 883 1563 883 1319 883 1318 883 1563 884 1318 884 1565 884 1565 884 1318 884 1316 884 1565 885 1316 885 1566 885 1566 886 1316 886 1314 886 1566 887 1314 887 1558 887 1558 888 1314 888 1313 888 1558 889 1313 889 1559 889 1559 890 1313 890 1312 890 1559 891 1312 891 1556 891 1556 891 1312 891 1117 891 1556 892 1117 892 1557 892 1557 892 1117 892 1116 892 1557 893 1116 893 1570 893 1570 893 1116 893 1324 893 1570 894 1324 894 1571 894 1571 895 1324 895 1323 895 1571 896 1323 896 1572 896 1572 896 1323 896 1322 896 1553 897 1344 897 1555 897 1555 898 1344 898 1325 898 1555 899 1325 899 1580 899 1580 900 1325 900 1327 900 1580 877 1327 877 1577 877 1577 877 1327 877 1328 877 1577 901 1328 901 1578 901 1578 902 1328 902 1329 902 1578 903 1329 903 1635 903 1635 904 1329 904 1330 904 1635 905 1330 905 1633 905 1633 882 1330 882 1332 882 1633 906 1332 906 1574 906 1574 907 1332 907 1334 907 1574 908 1334 908 1575 908 1575 909 1334 909 1336 909 1575 885 1336 885 1436 885 1436 910 1336 910 1338 910 1436 911 1338 911 1434 911 1434 912 1338 912 1113 912 1434 913 1113 913 1615 913 1615 913 1113 913 1340 913 1615 914 1340 914 1614 914 1614 915 1340 915 1341 915 1614 916 1341 916 1613 916 1613 917 1341 917 1342 917 1613 918 1342 918 1612 918 1612 919 1342 919 1110 919 1612 894 1110 894 1552 894 1552 920 1110 920 1112 920 1552 921 1112 921 1553 921 1553 922 1112 922 1344 922 1454 923 1182 923 1455 923 1455 923 1182 923 1183 923 1455 924 1183 924 1465 924 1465 925 1183 925 1184 925 1465 926 1184 926 1466 926 1466 926 1184 926 1194 926 1466 927 1194 927 1467 927 1467 927 1194 927 1193 927 1467 928 1193 928 1468 928 1468 928 1193 928 1191 928 1468 929 1191 929 1469 929 1469 929 1191 929 1190 929 1459 930 1181 930 1456 930 1456 931 1181 931 1178 931 1456 932 1178 932 1457 932 1457 933 1178 933 1177 933 1457 934 1177 934 1460 934 1460 935 1177 935 1189 935 1460 936 1189 936 1461 936 1461 936 1189 936 1188 936 1461 937 1188 937 1463 937 1463 937 1188 937 1186 937 1463 938 1186 938 1464 938 1464 939 1186 939 1185 939 1181 940 1459 940 1190 940 1190 941 1459 941 1469 941 1464 942 1185 942 1454 942 1454 942 1185 942 1182 942 1584 943 1143 943 1585 943 1585 943 1143 943 1142 943 1585 932 1142 932 1586 932 1586 932 1142 932 1154 932 1586 944 1154 944 1588 944 1588 945 1154 945 1153 945 1588 946 1153 946 1598 946 1598 936 1153 936 1151 936 1598 947 1151 947 1597 947 1597 937 1151 937 1149 937 1597 948 1149 948 1596 948 1596 949 1149 949 1148 949 1595 950 1146 950 1431 950 1431 950 1146 950 1145 950 1431 925 1145 925 1432 925 1432 925 1145 925 1140 925 1432 926 1140 926 1593 926 1593 951 1140 951 1139 951 1593 927 1139 927 1591 927 1591 927 1139 927 1157 927 1591 952 1157 952 1581 952 1581 928 1157 928 1158 928 1581 929 1158 929 1582 929 1582 929 1158 929 1160 929 1146 953 1595 953 1148 953 1148 953 1595 953 1596 953 1582 941 1160 941 1584 941 1584 954 1160 954 1143 954 1636 0 1637 0 1638 0 1639 0 1640 0 1641 0 1642 0 1643 0 1644 0 1645 0 1646 0 1647 0 1648 0 1649 0 1650 0 1651 0 1652 0 1653 0 1654 0 1655 0 1656 0 1657 0 1658 0 1659 0 1660 0 1661 0 1659 0 1662 0 1663 0 1664 0 1665 0 1666 0 1667 0 1668 0 1669 0 1670 0 1671 0 1672 0 1673 0 1672 0 1674 0 1673 0 1673 0 1674 0 1675 0 1673 0 1675 0 1676 0 1676 0 1675 0 1677 0 1676 0 1677 0 1678 0 1678 0 1677 0 1679 0 1678 0 1679 0 1680 0 1681 0 1682 0 1683 0 1683 0 1682 0 1684 0 1684 0 1682 0 1685 0 1684 0 1685 0 1686 0 1687 0 1688 0 1689 0 1689 0 1688 0 1690 0 1689 0 1690 0 1691 0 1691 0 1690 0 1692 0 1691 0 1692 0 1693 0 1694 0 1695 0 1696 0 1662 0 1664 0 1697 0 1697 0 1664 0 1698 0 1697 0 1698 0 1699 0 1700 0 1701 0 1699 0 1702 0 1703 0 1704 0 1701 0 1700 0 1705 0 1705 0 1700 0 1702 0 1705 0 1702 0 1706 0 1706 0 1702 0 1704 0 1706 0 1704 0 1707 0 1708 0 1659 0 1709 0 1709 0 1659 0 1661 0 1709 0 1661 0 1710 0 1708 0 1711 0 1659 0 1659 0 1711 0 1712 0 1659 0 1712 0 1713 0 1713 0 1712 0 1714 0 1713 0 1714 0 1702 0 1702 0 1714 0 1715 0 1702 0 1715 0 1703 0 1707 0 1716 0 1706 0 1706 0 1716 0 1717 0 1706 0 1717 0 1718 0 1718 0 1717 0 1719 0 1718 0 1719 0 1661 0 1661 0 1719 0 1720 0 1661 0 1720 0 1710 0 1658 0 1721 0 1659 0 1659 0 1721 0 1722 0 1659 0 1722 0 1660 0 1654 0 1656 0 1723 0 1724 0 1725 0 1726 0 1726 0 1725 0 1727 0 1728 0 1729 0 1730 0 1730 0 1729 0 1731 0 1730 0 1731 0 1732 0 1733 0 1734 0 1735 0 1735 0 1734 0 1736 0 1735 0 1736 0 1737 0 1737 0 1736 0 1738 0 1737 0 1738 0 1739 0 1651 0 1653 0 1740 0 1740 0 1653 0 1741 0 1740 0 1741 0 1742 0 1742 0 1741 0 1743 0 1742 0 1743 0 1649 0 1744 0 1745 0 1746 0 1746 0 1745 0 1747 0 1746 0 1747 0 1650 0 1650 0 1747 0 1748 0 1650 0 1748 0 1648 0 1749 0 1750 0 1751 0 1751 0 1750 0 1752 0 1751 0 1752 0 1753 0 1754 0 1755 0 1756 0 1756 0 1755 0 1757 0 1746 0 1758 0 1744 0 1744 0 1758 0 1756 0 1744 0 1756 0 1759 0 1759 0 1756 0 1757 0 1757 0 1760 0 1759 0 1759 0 1760 0 1761 0 1759 0 1761 0 1762 0 1762 0 1761 0 1763 0 1762 0 1763 0 1764 0 1764 0 1763 0 1765 0 1765 0 1763 0 1766 0 1765 0 1766 0 1767 0 1768 0 1769 0 1765 0 1770 0 1769 0 1771 0 1771 0 1769 0 1768 0 1771 0 1768 0 1772 0 1773 0 1774 0 1775 0 1775 0 1774 0 1776 0 1776 0 1777 0 1644 0 1644 0 1777 0 1778 0 1644 0 1778 0 1779 0 1778 0 1780 0 1779 0 1779 0 1780 0 1781 0 1779 0 1781 0 1782 0 1782 0 1781 0 1783 0 1782 0 1783 0 1784 0 1784 0 1783 0 1785 0 1784 0 1785 0 1786 0 1786 0 1785 0 1787 0 1786 0 1787 0 1788 0 1788 0 1787 0 1789 0 1788 0 1789 0 1790 0 1790 0 1789 0 1791 0 1790 0 1791 0 1792 0 1700 0 1793 0 1794 0 1795 0 1796 0 1647 0 1647 0 1796 0 1797 0 1647 0 1797 0 1798 0 1699 0 1698 0 1700 0 1700 0 1698 0 1799 0 1700 0 1799 0 1793 0 1797 0 1800 0 1798 0 1798 0 1800 0 1801 0 1798 0 1801 0 1802 0 1803 0 1804 0 1664 0 1664 0 1804 0 1805 0 1664 0 1805 0 1698 0 1698 0 1805 0 1806 0 1698 0 1806 0 1799 0 1807 0 1808 0 1809 0 1809 0 1810 0 1807 0 1807 0 1810 0 1811 0 1807 0 1811 0 1812 0 1813 0 1814 0 1815 0 1815 0 1814 0 1816 0 1815 0 1816 0 1808 0 1808 0 1816 0 1817 0 1808 0 1817 0 1809 0 1818 0 1819 0 1820 0 1820 0 1819 0 1821 0 1820 0 1821 0 1822 0 1823 0 1824 0 1825 0 1825 0 1824 0 1826 0 1827 0 1828 0 1772 0 1772 0 1828 0 1829 0 1828 0 1830 0 1829 0 1829 0 1830 0 1831 0 1829 0 1831 0 1832 0 1832 0 1831 0 1833 0 1834 0 1835 0 1836 0 1794 0 1795 0 1700 0 1700 0 1795 0 1647 0 1700 0 1647 0 1837 0 1837 0 1647 0 1646 0 1776 0 1644 0 1775 0 1775 0 1644 0 1643 0 1775 0 1643 0 1838 0 1838 0 1839 0 1775 0 1775 0 1839 0 1840 0 1775 0 1840 0 1841 0 1841 0 1840 0 1842 0 1841 0 1842 0 1843 0 1843 0 1842 0 1844 0 1843 0 1844 0 1845 0 1837 0 1846 0 1700 0 1700 0 1846 0 1847 0 1700 0 1847 0 1702 0 1702 0 1847 0 1848 0 1702 0 1848 0 1713 0 1713 0 1848 0 1849 0 1713 0 1849 0 1850 0 1851 0 1852 0 1853 0 1853 0 1852 0 1854 0 1855 0 1751 0 1756 0 1756 0 1751 0 1753 0 1756 0 1753 0 1754 0 1856 0 1857 0 1858 0 1858 0 1857 0 1859 0 1858 0 1859 0 1860 0 1860 0 1859 0 1861 0 1860 0 1861 0 1862 0 1862 0 1861 0 1863 0 1862 0 1863 0 1864 0 1865 0 1815 0 1866 0 1866 0 1815 0 1867 0 1867 0 1815 0 1868 0 1868 0 1815 0 1808 0 1868 0 1808 0 1869 0 1767 0 1749 0 1765 0 1765 0 1749 0 1751 0 1765 0 1751 0 1768 0 1768 0 1751 0 1825 0 1768 0 1825 0 1772 0 1772 0 1825 0 1826 0 1772 0 1826 0 1827 0 1855 0 1854 0 1751 0 1751 0 1854 0 1852 0 1751 0 1852 0 1825 0 1825 0 1852 0 1851 0 1825 0 1851 0 1823 0 1823 0 1851 0 1870 0 1823 0 1870 0 1871 0 1871 0 1870 0 1638 0 1871 0 1638 0 1872 0 1872 0 1638 0 1637 0 1872 0 1637 0 1869 0 1869 0 1637 0 1636 0 1869 0 1636 0 1868 0 1649 0 1743 0 1650 0 1650 0 1743 0 1861 0 1650 0 1861 0 1746 0 1746 0 1861 0 1859 0 1746 0 1859 0 1758 0 1758 0 1859 0 1857 0 1758 0 1857 0 1756 0 1756 0 1857 0 1856 0 1756 0 1856 0 1855 0 1873 0 1874 0 1863 0 1873 0 1863 0 1875 0 1875 0 1863 0 1861 0 1875 0 1861 0 1876 0 1877 0 1878 0 1741 0 1741 0 1878 0 1879 0 1741 0 1879 0 1743 0 1743 0 1879 0 1880 0 1743 0 1880 0 1881 0 1881 0 1882 0 1743 0 1743 0 1882 0 1883 0 1743 0 1883 0 1861 0 1861 0 1883 0 1884 0 1861 0 1884 0 1876 0 1662 0 1694 0 1663 0 1663 0 1694 0 1696 0 1663 0 1696 0 1664 0 1664 0 1696 0 1802 0 1664 0 1802 0 1803 0 1803 0 1802 0 1801 0 1885 0 1770 0 1886 0 1886 0 1770 0 1771 0 1886 0 1771 0 1887 0 1887 0 1771 0 1772 0 1887 0 1772 0 1888 0 1888 0 1772 0 1829 0 1888 0 1829 0 1889 0 1889 0 1829 0 1832 0 1889 0 1832 0 1685 0 1685 0 1832 0 1670 0 1685 0 1670 0 1686 0 1686 0 1670 0 1669 0 1833 0 1835 0 1832 0 1832 0 1835 0 1834 0 1832 0 1834 0 1670 0 1670 0 1834 0 1678 0 1670 0 1678 0 1668 0 1668 0 1678 0 1680 0 1866 0 1639 0 1865 0 1865 0 1639 0 1641 0 1865 0 1641 0 1815 0 1815 0 1641 0 1822 0 1815 0 1822 0 1813 0 1813 0 1822 0 1821 0 1874 0 1877 0 1863 0 1863 0 1877 0 1741 0 1863 0 1741 0 1890 0 1890 0 1741 0 1653 0 1890 0 1653 0 1738 0 1738 0 1653 0 1652 0 1738 0 1652 0 1739 0 1739 0 1652 0 1651 0 1695 0 1693 0 1696 0 1696 0 1693 0 1692 0 1696 0 1692 0 1802 0 1802 0 1692 0 1891 0 1802 0 1891 0 1798 0 1798 0 1891 0 1892 0 1798 0 1892 0 1647 0 1647 0 1892 0 1843 0 1647 0 1843 0 1645 0 1645 0 1843 0 1845 0 1812 0 1893 0 1807 0 1807 0 1893 0 1894 0 1807 0 1894 0 1731 0 1731 0 1894 0 1895 0 1731 0 1895 0 1732 0 1893 0 1818 0 1894 0 1894 0 1818 0 1820 0 1894 0 1820 0 1895 0 1895 0 1820 0 1896 0 1895 0 1896 0 1732 0 1732 0 1896 0 1897 0 1639 0 1864 0 1640 0 1640 0 1864 0 1863 0 1640 0 1863 0 1641 0 1641 0 1863 0 1890 0 1641 0 1890 0 1822 0 1822 0 1890 0 1738 0 1822 0 1738 0 1820 0 1820 0 1738 0 1736 0 1820 0 1736 0 1896 0 1896 0 1736 0 1734 0 1896 0 1734 0 1897 0 1897 0 1734 0 1733 0 1687 0 1885 0 1688 0 1688 0 1885 0 1886 0 1688 0 1886 0 1690 0 1690 0 1886 0 1887 0 1690 0 1887 0 1692 0 1692 0 1887 0 1888 0 1692 0 1888 0 1891 0 1891 0 1888 0 1889 0 1891 0 1889 0 1892 0 1892 0 1889 0 1685 0 1892 0 1685 0 1843 0 1843 0 1685 0 1682 0 1843 0 1682 0 1841 0 1841 0 1682 0 1681 0 1841 0 1681 0 1775 0 1775 0 1681 0 1792 0 1775 0 1792 0 1773 0 1773 0 1792 0 1791 0 1836 0 1872 0 1834 0 1834 0 1872 0 1869 0 1834 0 1869 0 1678 0 1678 0 1869 0 1808 0 1678 0 1808 0 1676 0 1676 0 1808 0 1807 0 1676 0 1807 0 1673 0 1673 0 1807 0 1731 0 1673 0 1731 0 1724 0 1724 0 1731 0 1729 0 1724 0 1729 0 1725 0 1725 0 1729 0 1728 0 1850 0 1642 0 1713 0 1713 0 1642 0 1644 0 1713 0 1644 0 1659 0 1659 0 1644 0 1779 0 1659 0 1779 0 1657 0 1657 0 1779 0 1782 0 1683 0 1665 0 1681 0 1681 0 1665 0 1667 0 1681 0 1667 0 1792 0 1792 0 1667 0 1898 0 1792 0 1898 0 1790 0 1790 0 1898 0 1656 0 1790 0 1656 0 1788 0 1788 0 1656 0 1655 0 1666 0 1671 0 1667 0 1667 0 1671 0 1673 0 1667 0 1673 0 1898 0 1898 0 1673 0 1724 0 1898 0 1724 0 1656 0 1656 0 1724 0 1726 0 1656 0 1726 0 1723 0 1723 0 1726 0 1727 0 1691 43 1899 43 1900 43 1691 955 1900 955 1689 955 1689 45 1900 45 1901 45 1689 45 1901 45 1687 45 1687 956 1901 956 1902 956 1687 957 1902 957 1885 957 1885 958 1902 958 1903 958 1885 959 1903 959 1770 959 1770 960 1903 960 1904 960 1770 961 1904 961 1769 961 1769 962 1904 962 1905 962 1769 963 1905 963 1765 963 1765 964 1905 964 1906 964 1765 965 1906 965 1764 965 1764 59 1906 59 1907 59 1764 966 1907 966 1762 966 1762 967 1907 967 1759 967 1759 967 1907 967 1908 967 1759 968 1908 968 1744 968 1908 968 1909 968 1744 968 1744 969 1909 969 1910 969 1744 970 1910 970 1745 970 1745 971 1910 971 1911 971 1745 971 1911 971 1747 971 1747 972 1911 972 1912 972 1747 972 1912 972 1748 972 1748 973 1912 973 1913 973 1748 973 1913 973 1648 973 1648 974 1913 974 1914 974 1648 975 1914 975 1649 975 1649 72 1914 72 1915 72 1649 72 1915 72 1742 72 1742 976 1915 976 1916 976 1742 977 1916 977 1740 977 1740 978 1916 978 1917 978 1740 979 1917 979 1651 979 1651 77 1917 77 1918 77 1651 980 1918 980 1739 980 1739 981 1918 981 1919 981 1739 982 1919 982 1737 982 1737 79 1919 79 1920 79 1737 79 1920 79 1735 79 1735 983 1920 983 1921 983 1735 984 1921 984 1733 984 1733 985 1921 985 1922 985 1733 986 1922 986 1897 986 1897 987 1922 987 1923 987 1897 988 1923 988 1732 988 1732 86 1923 86 1924 86 1732 87 1924 87 1730 87 1730 1 1924 1 1925 1 1730 1 1925 1 1728 1 1728 989 1925 989 1926 989 1728 3 1926 3 1725 3 1725 990 1926 990 1927 990 1725 991 1927 991 1727 991 1727 992 1927 992 1928 992 1727 993 1928 993 1723 993 1723 994 1928 994 1929 994 1723 995 1929 995 1654 995 1654 996 1929 996 1655 996 1655 996 1929 996 1930 996 1655 997 1930 997 1788 997 1788 997 1930 997 1931 997 1788 998 1931 998 1786 998 1786 999 1931 999 1932 999 1786 1000 1932 1000 1784 1000 1932 1000 1933 1000 1784 1000 1784 1001 1933 1001 1934 1001 1784 1002 1934 1002 1782 1002 1782 14 1934 14 1935 14 1782 1003 1935 1003 1657 1003 1657 1004 1935 1004 1936 1004 1657 1005 1936 1005 1658 1005 1658 1006 1936 1006 1937 1006 1658 1007 1937 1007 1721 1007 1721 1008 1937 1008 1938 1008 1721 1009 1938 1009 1722 1009 1722 1010 1938 1010 1939 1010 1722 1011 1939 1011 1660 1011 1660 1012 1939 1012 1940 1012 1660 1013 1940 1013 1661 1013 1661 1014 1940 1014 1941 1014 1661 1014 1941 1014 1718 1014 1718 25 1941 25 1942 25 1718 25 1942 25 1706 25 1706 1015 1942 1015 1943 1015 1706 1016 1943 1016 1705 1016 1705 1017 1943 1017 1944 1017 1705 1017 1944 1017 1701 1017 1701 1018 1944 1018 1945 1018 1701 30 1945 30 1699 30 1699 1019 1945 1019 1946 1019 1699 1019 1946 1019 1697 1019 1697 34 1946 34 1947 34 1697 34 1947 34 1662 34 1662 1020 1947 1020 1948 1020 1662 1021 1948 1021 1694 1021 1694 1022 1948 1022 1949 1022 1694 1023 1949 1023 1695 1023 1695 1024 1949 1024 1950 1024 1695 1025 1950 1025 1693 1025 1693 41 1950 41 1899 41 1693 42 1899 42 1691 42 1951 88 1952 88 1953 88 1954 88 1955 88 1956 88 1957 88 1958 88 1959 88 1960 88 1961 88 1962 88 1963 88 1964 88 1965 88 1966 88 1967 88 1968 88 1910 88 1909 88 1969 88 1901 88 1970 88 1971 88 1949 88 1948 88 1972 88 1924 88 1923 88 1973 88 1974 88 1975 88 1925 88 1976 88 1928 88 1927 88 1928 88 1976 88 1929 88 1929 88 1976 88 1977 88 1929 88 1977 88 1930 88 1930 88 1977 88 1978 88 1930 88 1978 88 1931 88 1938 88 1937 88 1979 88 1979 88 1937 88 1936 88 1979 1026 1936 1026 1935 1026 1980 88 1981 88 1979 88 1981 88 1940 88 1979 88 1979 88 1940 88 1939 88 1979 88 1939 88 1938 88 1982 88 1983 88 1984 88 1982 88 1984 88 1985 88 1983 88 1986 88 1984 88 1984 88 1986 88 1987 88 1984 88 1987 88 1988 88 1988 88 1987 88 1989 88 1988 88 1989 88 1979 88 1979 88 1989 88 1990 88 1979 88 1990 88 1980 88 1981 88 1991 88 1940 88 1940 88 1991 88 1992 88 1940 88 1992 88 1941 88 1941 88 1992 88 1993 88 1941 88 1993 88 1942 88 1942 88 1993 88 1994 88 1942 88 1994 88 1995 88 1948 88 1947 88 1972 88 1972 88 1947 88 1946 88 1972 88 1946 88 1996 88 1996 88 1946 88 1945 88 1996 88 1945 88 1997 88 1997 88 1945 88 1944 88 1997 88 1944 88 1998 88 1998 88 1944 88 1943 88 1998 88 1943 88 1984 88 1984 88 1943 88 1942 88 1984 88 1942 88 1985 88 1985 88 1942 88 1995 88 1899 88 1950 88 1999 88 1999 88 1950 88 1949 88 2000 88 1900 88 2001 88 2001 88 1900 88 1899 88 1901 88 1971 88 1902 88 1902 88 1971 88 2002 88 1902 88 2002 88 1903 88 1903 88 2002 88 2003 88 1903 88 2003 88 1904 88 1904 88 2003 88 2004 88 1904 88 2004 88 1905 88 2005 88 2006 88 2004 88 1905 88 2007 88 1906 88 1906 88 2007 88 2008 88 1906 88 2008 88 1907 88 1907 88 2008 88 2009 88 1907 88 2009 88 1908 88 1908 88 2009 88 2010 88 1908 88 2010 88 2011 88 2012 88 2013 88 2014 88 2014 88 2013 88 2005 88 2006 88 2015 88 2004 88 2004 88 2015 88 2016 88 2004 88 2016 88 1905 88 1905 88 2016 88 2017 88 1905 88 2017 88 2007 88 1969 88 1909 88 2018 88 2018 88 1909 88 1908 88 2018 88 1908 88 2014 88 2014 88 1908 88 2011 88 2014 88 2011 88 2012 88 1914 88 1913 88 2019 88 2019 88 1913 88 1912 88 2019 88 1912 88 1969 88 1969 88 1912 88 1911 88 1969 88 1911 88 1910 88 1917 88 1916 88 2020 88 2020 88 1916 88 2021 88 2020 88 2021 88 2022 88 1951 88 1922 88 1952 88 1952 88 1922 88 1921 88 1952 88 1921 88 1953 88 1953 88 1921 88 1920 88 1953 88 1920 88 1919 88 2023 88 2024 88 2025 88 2025 88 2024 88 2026 88 2025 88 2026 88 2027 88 1966 88 1968 88 2027 88 1967 88 2028 88 2029 88 2029 88 2028 88 2030 88 2031 88 2032 88 1998 88 2033 88 2034 88 2035 88 2035 88 2034 88 2036 88 2035 88 2036 88 2037 88 2031 88 1998 88 2037 88 2032 88 2038 88 1998 88 1998 88 2038 88 2039 88 1998 88 2039 88 1997 88 1997 88 2039 88 2040 88 1997 88 2040 88 1996 88 1996 88 2040 88 2041 88 1996 88 2041 88 2042 88 2043 88 2044 88 2033 88 2033 88 2044 88 2045 88 2033 88 2045 88 2034 88 2046 88 2047 88 2048 88 2048 88 2047 88 2049 88 2050 88 2051 88 2052 88 2052 88 2051 88 2053 88 2052 88 2053 88 2054 88 2055 88 2056 88 2057 88 2057 88 2056 88 2054 88 2057 88 2054 88 2058 88 2058 88 2054 88 2053 88 2059 88 2060 88 2061 88 2061 88 2060 88 2062 88 2063 88 2064 88 2065 88 2063 88 2065 88 2066 88 2065 88 2067 88 2066 88 2066 88 2067 88 2068 88 2066 88 2068 88 2069 88 2069 88 2068 88 2070 88 2069 88 2070 88 2071 88 2064 88 2063 88 2072 88 2072 88 2063 88 2073 88 2072 88 2073 88 2074 88 2074 88 2075 88 2076 88 2076 88 2075 88 1964 88 1965 88 1964 88 2077 88 2078 88 2079 88 2080 88 2080 88 2079 88 2081 88 2082 88 2083 88 1988 88 2084 88 2085 88 1968 88 2027 88 1968 88 2025 88 2025 88 1968 88 2085 88 2025 88 2085 88 2082 88 2086 88 2087 88 2088 88 2088 88 2087 88 2089 88 2088 88 2089 88 2090 88 2090 88 2089 88 2091 88 2090 88 2091 88 1968 88 1968 88 2091 88 2092 88 1968 88 2092 88 2084 88 2093 88 2094 88 1998 88 2037 88 1998 88 2035 88 2035 88 1998 88 2094 88 2035 88 2094 88 2095 88 2083 88 2096 88 1988 88 1988 88 2096 88 2097 88 1988 88 2097 88 1984 88 1984 88 2097 88 2098 88 1984 88 2098 88 1998 88 1998 88 2098 88 2099 88 1998 88 2099 88 2093 88 2100 88 2101 88 2102 88 2005 88 2004 88 2014 88 2014 88 2004 88 2103 88 2014 88 2103 88 2104 88 2071 88 2080 88 2069 88 2069 88 2080 88 2081 88 2069 88 2081 88 2105 88 2105 88 2081 88 2106 88 2107 88 2108 88 2109 88 2109 88 2108 88 2110 88 2111 88 2112 88 2113 88 2113 88 2112 88 2114 88 2113 88 2114 88 2115 88 2107 88 2116 88 2117 88 2117 88 2116 88 2118 88 2117 88 2118 88 2119 88 2119 88 2118 88 2120 88 1957 88 1959 88 2121 88 2122 88 1956 88 2123 88 2123 88 1956 88 2115 88 2123 88 2115 88 2124 88 2124 88 2115 88 2114 88 2082 88 1988 88 2025 88 2025 88 1988 88 1979 88 2025 88 1979 88 2023 88 2023 728 1979 728 1935 728 2023 88 1935 88 1934 88 1927 88 1926 88 1976 88 1976 88 1926 88 1955 88 1976 88 1955 88 1977 88 1977 88 1955 88 1954 88 1977 88 1954 88 1978 88 2029 88 1959 88 2120 88 2120 88 1959 88 1958 88 2120 88 1958 88 2119 88 2122 88 2121 88 1956 88 1956 88 2121 88 1959 88 1956 88 1959 88 1954 88 1954 88 1959 88 2029 88 1954 88 2029 88 1978 88 1978 88 2029 88 2030 88 1978 88 2030 88 1931 88 1931 88 2030 88 2125 88 1931 88 2125 88 1932 88 1932 88 2125 88 2126 88 1932 88 2126 88 1933 88 1933 88 2126 88 2127 88 1933 88 2127 88 1934 88 1934 88 2127 88 2128 88 1934 1027 2128 1027 2023 1027 2023 88 2128 88 2129 88 2023 88 2129 88 2024 88 1974 88 2048 88 2052 88 2052 88 2048 88 2049 88 2052 88 2049 88 2050 88 1925 88 1924 88 1974 88 1974 88 1924 88 1973 88 1974 88 1973 88 2048 88 2048 88 1973 88 2130 88 2048 88 2130 88 2046 88 1923 88 1922 88 1973 88 1973 88 1922 88 1951 88 1973 88 1951 88 2130 88 2130 88 1951 88 1953 88 2130 88 1953 88 2022 88 2022 88 1953 88 1919 88 2022 88 1919 88 2020 88 2020 88 1919 88 1918 88 2020 88 1918 88 1917 88 2074 88 2073 88 2075 88 2075 88 2073 88 2109 88 2075 88 2109 88 2113 88 2113 88 2109 88 2110 88 2113 88 2110 88 2111 88 1964 88 2075 88 2077 88 2077 88 2075 88 2113 88 2077 88 2113 88 2054 88 2054 88 2113 88 2115 88 2054 88 2115 88 2052 88 2052 88 2115 88 1956 88 2052 88 1956 88 1974 88 1974 88 1956 88 1955 88 1974 88 1955 88 1975 88 1975 88 1955 88 1926 88 1975 88 1926 88 1925 88 2131 88 2132 88 2056 88 1915 88 2133 88 1916 88 1916 88 2133 88 2134 88 1916 88 2134 88 2021 88 2021 88 2134 88 2135 88 2021 88 2135 88 2022 88 2022 88 2135 88 2061 88 2022 88 2061 88 2130 88 2130 88 2061 88 2062 88 2130 88 2062 88 2046 88 1949 88 1972 88 1999 88 1999 88 1972 88 1996 88 1999 88 1996 88 2043 88 2043 88 1996 88 2042 88 2043 88 2042 88 2044 88 1899 88 1999 88 2001 88 2001 88 1999 88 2043 88 2001 88 2043 88 2136 88 2136 88 2043 88 2033 88 2136 88 2033 88 2137 88 2137 88 2033 88 2035 88 2137 88 2035 88 2088 88 2088 88 2035 88 2095 88 2088 88 2095 88 2086 88 2080 88 1963 88 2078 88 2078 88 1963 88 1965 88 2078 88 1965 88 2138 88 2138 88 1965 88 2077 88 2138 88 2077 88 2139 88 2139 88 2077 88 2054 88 2139 88 2054 88 2140 88 2140 88 2054 88 2056 88 2140 88 2056 88 2141 88 2141 88 2056 88 2132 88 2141 88 2132 88 1960 88 1960 88 2132 88 2131 88 1960 88 2131 88 1961 88 1961 88 2131 88 2102 88 1961 88 2102 88 1962 88 1962 88 2102 88 2101 88 1967 88 2029 88 1968 88 1968 88 2029 88 2120 88 1968 88 2120 88 2090 88 2090 88 2120 88 2118 88 2090 88 2118 88 2088 88 2088 88 2118 88 2116 88 2088 88 2116 88 2137 88 2137 88 2116 88 2142 88 2137 88 2142 88 2136 88 2136 88 2142 88 2143 88 2136 88 2143 88 2001 88 2001 88 2143 88 2144 88 2001 88 2144 88 2000 88 2107 88 2109 88 2116 88 2116 88 2109 88 2073 88 2116 88 2073 88 2142 88 2142 88 2073 88 2063 88 2142 88 2063 88 2143 88 2143 88 2063 88 2066 88 2143 88 2066 88 2144 88 2145 88 2146 88 2147 88 2148 88 2133 88 2149 88 2149 88 2133 88 2147 88 2149 88 2147 88 2150 88 2150 88 2147 88 2146 88 2148 88 2151 88 2133 88 2133 88 2151 88 2152 88 2133 88 2152 88 2134 88 2134 88 2152 88 2153 88 2134 88 2153 88 2154 88 2155 88 2156 88 2102 88 2102 88 2156 88 2157 88 2055 88 2059 88 2056 88 2056 88 2059 88 2061 88 2056 88 2061 88 2131 88 2131 88 2061 88 2135 88 2131 88 2135 88 2102 88 2102 88 2135 88 2134 88 2102 88 2134 88 2155 88 2155 88 2134 88 2154 88 2157 88 2145 88 2102 88 2102 88 2145 88 2147 88 2102 88 2147 88 2100 88 2100 88 2147 88 2158 88 2100 88 2158 88 2159 88 2159 88 2158 88 2160 88 2159 88 2160 88 2161 88 2106 88 2103 88 2105 88 2105 88 2103 88 2004 88 2105 88 2004 88 2069 88 2069 88 2004 88 2003 88 2069 88 2003 88 2066 88 2066 88 2003 88 2002 88 2066 88 2002 88 2144 88 2144 88 2002 88 1971 88 2144 88 1971 88 2000 88 2000 88 1971 88 1970 88 2000 88 1970 88 1900 88 1900 88 1970 88 1901 88 1915 88 1914 88 2133 88 2133 88 1914 88 2019 88 2133 88 2019 88 2147 88 2147 88 2019 88 1969 88 2147 88 1969 88 2158 88 2158 88 1969 88 2018 88 2158 88 2018 88 2160 88 2160 88 2018 88 2014 88 2160 88 2014 88 2161 88 2161 88 2014 88 2104 88 2024 147 1780 147 2026 147 2026 100 1780 100 1778 100 2026 101 1778 101 2027 101 2027 101 1778 101 1777 101 2027 103 1777 103 1966 103 1966 102 1777 102 1776 102 1966 105 1776 105 1967 105 1967 105 1776 105 1774 105 1967 1028 1774 1028 2028 1028 2028 1028 1774 1028 1773 1028 2028 121 1773 121 2030 121 2030 121 1773 121 1791 121 2030 93 1791 93 2125 93 2125 93 1791 93 1789 93 2125 94 1789 94 2126 94 2126 94 1789 94 1787 94 2126 96 1787 96 2127 96 2127 95 1787 95 1785 95 2127 134 1785 134 2128 134 2128 97 1785 97 1783 97 2128 114 1783 114 2129 114 2129 122 1783 122 1781 122 2129 136 1781 136 2024 136 2024 149 1781 149 1780 149 2039 126 1799 126 2040 126 2040 126 1799 126 1806 126 2040 127 1806 127 2041 127 2041 127 1806 127 1805 127 2041 1029 1805 1029 2042 1029 2042 1029 1805 1029 1804 1029 2042 1030 1804 1030 2044 1030 2044 1030 1804 1030 1803 1030 2044 106 1803 106 2045 106 2045 119 1803 119 1801 119 2045 1031 1801 1031 2034 1031 2034 120 1801 120 1800 120 2034 93 1800 93 2036 93 2036 1032 1800 1032 1797 1032 2036 94 1797 94 2037 94 2037 94 1797 94 1796 94 2037 96 1796 96 2031 96 2031 96 1796 96 1795 96 2031 97 1795 97 2032 97 2032 97 1795 97 1794 97 2032 115 1794 115 2038 115 2038 114 1794 114 1793 114 2038 117 1793 117 2039 117 2039 99 1793 99 1799 99 2053 100 1810 100 2058 100 2058 147 1810 147 1809 147 2058 101 1809 101 2057 101 2057 101 1809 101 1817 101 2057 102 1817 102 2055 102 2055 103 1817 103 1816 103 2055 105 1816 105 2059 105 2059 105 1816 105 1814 105 2059 107 1814 107 2060 107 2060 132 1814 132 1813 132 2060 121 1813 121 2062 121 2062 148 1813 148 1821 148 2062 142 1821 142 2046 142 2046 110 1821 110 1819 110 2046 111 1819 111 2047 111 2047 111 1819 111 1818 111 2047 143 1818 143 2049 143 2049 144 1818 144 1893 144 2049 145 1893 145 2050 145 2050 146 1893 146 1812 146 2050 123 1812 123 2051 123 2051 122 1812 122 1811 122 2051 99 1811 99 2053 99 2053 99 1811 99 1810 99 2065 126 1830 126 2067 126 2067 126 1830 126 1828 126 2067 101 1828 101 2068 101 2068 138 1828 138 1827 138 2068 103 1827 103 2070 103 2070 102 1827 102 1826 102 2070 105 1826 105 2071 105 2071 104 1826 104 1824 104 2071 1028 1824 1028 2080 1028 2080 1033 1824 1033 1823 1033 2080 108 1823 108 1963 108 1963 108 1823 108 1871 108 1963 93 1871 93 1964 93 1964 1034 1871 1034 1872 1034 1964 94 1872 94 2076 94 2076 133 1872 133 1836 133 2076 95 1836 95 2074 95 2074 1035 1836 1035 1835 1035 2074 1036 1835 1036 2072 1036 2072 134 1835 134 1833 134 2072 114 1833 114 2064 114 2064 114 1833 114 1831 114 2064 1037 1831 1037 2065 1037 2065 149 1831 149 1830 149 2016 125 1749 125 2017 125 2017 126 1749 126 1767 126 2017 127 1767 127 2007 127 2007 127 1767 127 1766 127 2007 128 1766 128 2008 128 2008 129 1766 129 1763 129 2008 130 1763 130 2009 130 2009 131 1763 131 1761 131 2009 132 1761 132 2010 132 2010 107 1761 107 1760 107 2010 121 1760 121 2011 121 2011 121 1760 121 1757 121 2011 93 1757 93 2012 93 2012 92 1757 92 1755 92 2012 94 1755 94 2013 94 2013 94 1755 94 1754 94 2013 96 1754 96 2005 96 2005 95 1754 95 1753 95 2005 97 1753 97 2006 97 2006 97 1753 97 1752 97 2006 122 1752 122 2015 122 2015 123 1752 123 1750 123 2015 99 1750 99 2016 99 2016 124 1750 124 1749 124 2145 126 1875 126 2146 126 2146 125 1875 125 1876 125 2146 101 1876 101 2150 101 2150 101 1876 101 1884 101 2150 102 1884 102 2149 102 2149 103 1884 103 1883 103 2149 104 1883 104 2148 104 2148 105 1883 105 1882 105 2148 106 1882 106 2151 106 2151 107 1882 107 1881 107 2151 108 1881 108 2152 108 2152 109 1881 109 1880 109 2152 142 1880 142 2153 142 2153 1038 1880 1038 1879 1038 2153 94 1879 94 2154 94 2154 94 1879 94 1878 94 2154 96 1878 96 2155 96 2155 95 1878 95 1877 95 2155 146 1877 146 2156 146 2156 146 1877 146 1874 146 2156 122 1874 122 2157 122 2157 123 1874 123 1873 123 2157 99 1873 99 2145 99 2145 99 1873 99 1875 99 2098 161 1848 161 2099 161 2099 161 1848 161 1847 161 2099 164 1847 164 2093 164 2093 164 1847 164 1846 164 2093 189 1846 189 2094 189 2094 1039 1846 1039 1837 1039 2094 1040 1837 1040 2095 1040 2095 1040 1837 1040 1646 1040 2095 1041 1646 1041 2086 1041 2086 1042 1646 1042 1645 1042 2086 195 1645 195 2087 195 2087 195 1645 195 1845 195 2087 1043 1845 1043 2089 1043 2089 1043 1845 1043 1844 1043 2089 197 1844 197 2091 197 2091 197 1844 197 1842 197 2091 151 1842 151 2092 151 2092 1044 1842 1044 1840 1044 2092 1045 1840 1045 2084 1045 2084 152 1840 152 1839 152 2084 1046 1839 1046 2085 1046 2085 1047 1839 1047 1838 1047 2085 1048 1838 1048 2082 1048 2082 1048 1838 1048 1643 1048 2082 1049 1643 1049 2083 1049 2083 1049 1643 1049 1642 1049 2083 1050 1642 1050 2096 1050 2096 1050 1642 1050 1850 1050 2096 182 1850 182 2097 182 2097 1051 1850 1051 1849 1051 2097 184 1849 184 2098 184 2098 184 1849 184 1848 184 2079 1052 1870 1052 2081 1052 2081 1053 1870 1053 1851 1053 2081 187 1851 187 2106 187 2106 188 1851 188 1853 188 2106 189 1853 189 2103 189 2103 189 1853 189 1854 189 2103 190 1854 190 2104 190 2104 191 1854 191 1855 191 2104 192 1855 192 2161 192 2161 193 1855 193 1856 193 2161 194 1856 194 2159 194 2159 195 1856 195 1858 195 2159 170 1858 170 2100 170 2100 196 1858 196 1860 196 2100 172 1860 172 2101 172 2101 1054 1860 1054 1862 1054 2101 151 1862 151 1962 151 1962 1055 1862 1055 1864 1055 1962 175 1864 175 1960 175 1960 176 1864 176 1639 176 1960 153 1639 153 2141 153 2141 153 1639 153 1866 153 2141 177 1866 177 2140 177 2140 178 1866 178 1867 178 2140 179 1867 179 2139 179 2139 180 1867 180 1868 180 2139 181 1868 181 2138 181 2138 158 1868 158 1636 158 2138 182 1636 182 2078 182 2078 183 1636 183 1638 183 2078 160 1638 160 2079 160 2079 1056 1638 1056 1870 1056 1980 1057 1708 1057 1981 1057 1981 1057 1708 1057 1709 1057 1981 209 1709 209 1991 209 1991 208 1709 208 1710 208 1991 1058 1710 1058 1992 1058 1992 1058 1710 1058 1720 1058 1992 1059 1720 1059 1993 1059 1993 1059 1720 1059 1719 1059 1993 1060 1719 1060 1994 1060 1994 1060 1719 1060 1717 1060 1994 224 1717 224 1995 224 1995 224 1717 224 1716 224 1985 1061 1707 1061 1982 1061 1982 226 1707 226 1704 226 1982 201 1704 201 1983 201 1983 200 1704 200 1703 200 1983 1062 1703 1062 1986 1062 1986 1063 1703 1063 1715 1063 1986 1064 1715 1064 1987 1064 1987 1064 1715 1064 1714 1064 1987 1065 1714 1065 1989 1065 1989 1065 1714 1065 1712 1065 1989 1066 1712 1066 1990 1066 1990 1067 1712 1067 1711 1067 1707 1068 1985 1068 1716 1068 1716 229 1985 229 1995 229 1990 1069 1711 1069 1980 1069 1980 1069 1711 1069 1708 1069 2110 1070 1669 1070 2111 1070 2111 1070 1669 1070 1668 1070 2111 201 1668 201 2112 201 2112 201 1668 201 1680 201 2112 1071 1680 1071 2114 1071 2114 1072 1680 1072 1679 1072 2114 1073 1679 1073 2124 1073 2124 1064 1679 1064 1677 1064 2124 1074 1677 1074 2123 1074 2123 1065 1677 1065 1675 1065 2123 205 1675 205 2122 205 2122 1075 1675 1075 1674 1075 2121 207 1672 207 1957 207 1957 207 1672 207 1671 207 1957 208 1671 208 1958 208 1958 208 1671 208 1666 208 1958 1058 1666 1058 2119 1058 2119 1076 1666 1076 1665 1076 2119 1059 1665 1059 2117 1059 2117 1059 1665 1059 1683 1059 2117 1077 1683 1077 2107 1077 2107 1060 1683 1060 1684 1060 2107 224 1684 224 2108 224 2108 224 1684 224 1686 224 1672 217 2121 217 1674 217 1674 217 2121 217 2122 217 2108 229 1686 229 2110 229 2110 1078 1686 1078 1669 1078 2162 1079 2163 1079 2164 1079 2165 1080 2166 1080 2167 1080 2168 1081 2169 1081 2170 1081 2171 1082 2172 1082 2173 1082 2174 1083 2175 1083 2176 1083 2174 1084 2177 1084 2175 1084 2175 1085 2177 1085 2178 1085 2175 1086 2178 1086 2179 1086 2178 1087 2180 1087 2179 1087 2179 1088 2180 1088 2181 1088 2179 1089 2181 1089 2182 1089 2182 1090 2181 1090 2183 1090 2182 1091 2183 1091 2184 1091 2185 1092 2186 1092 2187 1092 2187 1093 2188 1093 2185 1093 2185 1094 2188 1094 2189 1094 2185 1095 2189 1095 2190 1095 2189 1096 2191 1096 2190 1096 2190 1097 2191 1097 2192 1097 2190 1098 2192 1098 2193 1098 2193 1099 2192 1099 2194 1099 2193 1100 2194 1100 2195 1100 2196 1101 2197 1101 2198 1101 2196 1102 2199 1102 2197 1102 2197 1103 2199 1103 2200 1103 2197 1104 2200 1104 2201 1104 2200 1105 2202 1105 2201 1105 2201 1106 2202 1106 2203 1106 2201 1107 2203 1107 2204 1107 2204 1108 2203 1108 2205 1108 2204 1109 2205 1109 2206 1109 2207 1110 2208 1110 2209 1110 2209 1111 2210 1111 2207 1111 2207 1112 2210 1112 2211 1112 2207 1113 2211 1113 2212 1113 2211 1114 2213 1114 2212 1114 2212 1115 2213 1115 2214 1115 2212 1116 2214 1116 2215 1116 2215 1117 2214 1117 2216 1117 2215 1118 2216 1118 2217 1118 2184 1119 2183 1119 2218 1119 2218 1120 2183 1120 2219 1120 2218 1121 2219 1121 2220 1121 2219 1122 2221 1122 2220 1122 2220 1123 2221 1123 2222 1123 2220 1124 2222 1124 2223 1124 2222 1125 2224 1125 2223 1125 2223 1126 2224 1126 2225 1126 2223 1127 2225 1127 2226 1127 2225 1128 2227 1128 2226 1128 2226 1129 2227 1129 2228 1129 2226 1130 2228 1130 2170 1130 2170 1131 2228 1131 2229 1131 2170 1132 2229 1132 2168 1132 2168 1133 2229 1133 2230 1133 2168 1134 2230 1134 2186 1134 2186 1135 2230 1135 2231 1135 2186 1136 2231 1136 2187 1136 2195 1137 2194 1137 2232 1137 2232 1138 2194 1138 2233 1138 2232 1139 2233 1139 2234 1139 2233 1140 2235 1140 2234 1140 2234 1141 2235 1141 2236 1141 2234 1142 2236 1142 2237 1142 2236 1143 2238 1143 2237 1143 2237 1144 2238 1144 2239 1144 2237 1145 2239 1145 2240 1145 2239 1146 2241 1146 2240 1146 2240 1147 2241 1147 2242 1147 2240 1148 2242 1148 2167 1148 2167 1149 2242 1149 2243 1149 2167 1150 2243 1150 2165 1150 2165 1151 2243 1151 2244 1151 2165 1152 2244 1152 2198 1152 2198 1153 2244 1153 2245 1153 2198 1154 2245 1154 2196 1154 2206 1155 2205 1155 2246 1155 2246 1156 2205 1156 2247 1156 2246 1157 2247 1157 2248 1157 2247 1158 2249 1158 2248 1158 2248 1159 2249 1159 2250 1159 2248 1160 2250 1160 2251 1160 2250 1161 2252 1161 2251 1161 2251 1162 2252 1162 2253 1162 2251 1163 2253 1163 2254 1163 2253 1164 2255 1164 2254 1164 2254 1165 2255 1165 2256 1165 2254 1166 2256 1166 2164 1166 2164 1167 2256 1167 2257 1167 2164 1168 2257 1168 2162 1168 2162 1169 2257 1169 2258 1169 2162 1170 2258 1170 2208 1170 2208 1171 2258 1171 2259 1171 2208 1172 2259 1172 2209 1172 2217 1173 2216 1173 2260 1173 2260 1174 2216 1174 2261 1174 2260 1175 2261 1175 2262 1175 2261 1176 2263 1176 2262 1176 2262 1177 2263 1177 2264 1177 2262 1178 2264 1178 2265 1178 2264 1179 2266 1179 2265 1179 2265 1180 2266 1180 2267 1180 2265 1181 2267 1181 2268 1181 2267 1182 2269 1182 2268 1182 2268 1183 2269 1183 2270 1183 2268 1184 2270 1184 2173 1184 2173 1185 2270 1185 2271 1185 2173 1186 2271 1186 2171 1186 2171 1187 2271 1187 2272 1187 2171 1188 2272 1188 2176 1188 2176 1189 2272 1189 2273 1189 2176 1190 2273 1190 2174 1190 2166 1191 2274 1191 2167 1191 2167 1192 2274 1192 2240 1192 2275 88 2276 88 2277 88 2278 88 2279 88 2280 88 2280 88 2279 88 2281 88 2282 88 2283 88 2284 88 2240 1193 2285 1193 2237 1193 2237 1194 2285 1194 2279 1194 2237 1195 2279 1195 2234 1195 2234 1196 2279 1196 2278 1196 2286 1197 2226 1197 2287 1197 2287 1198 2226 1198 2170 1198 2287 1199 2170 1199 2169 1199 2278 88 2288 88 2234 88 2234 1200 2288 1200 2289 1200 2234 1201 2289 1201 2232 1201 2232 88 2289 88 2195 88 2281 88 2279 88 2290 88 2290 1202 2279 1202 2291 1202 2290 88 2291 88 2292 88 2292 1203 2291 1203 2293 1203 2292 88 2293 88 2294 88 2295 88 2296 88 2297 88 2297 88 2296 88 2298 88 2298 1204 2296 1204 2299 1204 2298 88 2299 88 2300 88 2277 88 2276 88 2301 88 2301 1205 2276 1205 2302 1205 2301 88 2302 88 2303 88 2304 88 2275 88 2254 88 2254 1206 2275 1206 2277 1206 2254 88 2277 88 2251 88 2251 1207 2277 1207 2284 1207 2251 88 2284 88 2248 88 2248 88 2284 88 2283 88 2297 88 2305 88 2295 88 2295 1208 2305 1208 2306 1208 2295 1209 2306 1209 2307 1209 2304 1210 2254 1210 2308 1210 2308 1211 2254 1211 2164 1211 2308 1212 2164 1212 2163 1212 2274 88 2309 88 2240 88 2240 1213 2309 1213 2310 1213 2240 1214 2310 1214 2285 1214 2285 1215 2310 1215 2311 1215 2285 88 2311 88 2312 88 2312 1216 2311 1216 2313 1216 2312 88 2313 88 2284 88 2284 1217 2313 1217 2314 1217 2284 1218 2314 1218 2282 1218 2283 88 2315 88 2248 88 2248 1219 2315 1219 2316 1219 2248 88 2316 88 2246 88 2246 88 2316 88 2206 88 2286 88 2294 88 2226 88 2226 1220 2294 1220 2293 1220 2226 1221 2293 1221 2223 1221 2223 1222 2293 1222 2295 1222 2223 88 2295 88 2220 88 2220 88 2295 88 2307 88 2307 88 2317 88 2220 88 2220 1223 2317 1223 2318 1223 2220 88 2318 88 2218 88 2218 88 2318 88 2184 88 2319 1224 2268 1224 2320 1224 2320 1225 2268 1225 2173 1225 2320 1226 2173 1226 2172 1226 2302 1227 2321 1227 2303 1227 2303 88 2321 88 2322 88 2303 88 2322 88 2323 88 2217 1228 2260 1228 2324 1228 2324 88 2260 88 2262 88 2324 88 2262 88 2325 88 2319 1229 2300 1229 2268 1229 2268 1230 2300 1230 2299 1230 2268 1231 2299 1231 2265 1231 2265 1232 2299 1232 2303 1232 2265 1233 2303 1233 2262 1233 2262 1234 2303 1234 2323 1234 2262 1235 2323 1235 2325 1235 2326 88 2171 88 2176 88 2327 88 2328 88 2329 88 2330 88 2331 88 2332 88 2332 88 2331 88 2333 88 2329 88 2326 88 2327 88 2327 88 2326 88 2176 88 2327 88 2176 88 2334 88 2334 88 2176 88 2175 88 2334 88 2175 88 2335 88 2335 88 2175 88 2179 88 2335 88 2179 88 2333 88 2333 88 2179 88 2182 88 2333 88 2182 88 2332 88 2320 1236 2172 1236 2326 1236 2326 1236 2172 1236 2171 1236 2318 1237 2332 1237 2184 1237 2184 1238 2332 1238 2182 1238 2332 1239 2318 1239 2330 1239 2330 1240 2318 1240 2317 1240 2330 1241 2317 1241 2331 1241 2331 1242 2317 1242 2307 1242 2331 1243 2307 1243 2333 1243 2333 1244 2307 1244 2306 1244 2333 1245 2306 1245 2335 1245 2335 1246 2306 1246 2305 1246 2335 1247 2305 1247 2334 1247 2334 1248 2305 1248 2297 1248 2334 1249 2297 1249 2327 1249 2327 1249 2297 1249 2298 1249 2327 1250 2298 1250 2328 1250 2328 1250 2298 1250 2300 1250 2328 1251 2300 1251 2329 1251 2329 1251 2300 1251 2319 1251 2329 1252 2319 1252 2326 1252 2326 1253 2319 1253 2320 1253 2336 88 2168 88 2186 88 2337 88 2338 88 2339 88 2339 88 2336 88 2337 88 2337 88 2336 88 2186 88 2337 88 2186 88 2340 88 2340 88 2186 88 2185 88 2340 88 2185 88 2341 88 2341 88 2185 88 2190 88 2341 88 2190 88 2342 88 2343 88 2344 88 2345 88 2345 88 2344 88 2342 88 2345 88 2342 88 2193 88 2193 88 2342 88 2190 88 2289 1254 2345 1254 2195 1254 2195 1255 2345 1255 2193 1255 2287 1256 2169 1256 2336 1256 2336 1257 2169 1257 2168 1257 2345 1258 2289 1258 2343 1258 2343 1259 2289 1259 2288 1259 2343 1260 2288 1260 2344 1260 2344 1261 2288 1261 2278 1261 2344 1262 2278 1262 2342 1262 2342 1263 2278 1263 2280 1263 2342 1264 2280 1264 2341 1264 2341 1264 2280 1264 2281 1264 2341 1265 2281 1265 2340 1265 2340 1265 2281 1265 2290 1265 2340 1266 2290 1266 2337 1266 2337 1267 2290 1267 2292 1267 2337 1268 2292 1268 2338 1268 2338 1269 2292 1269 2294 1269 2338 1270 2294 1270 2339 1270 2339 1271 2294 1271 2286 1271 2339 1272 2286 1272 2336 1272 2336 1272 2286 1272 2287 1272 2346 88 2165 88 2198 88 2347 88 2348 88 2349 88 2350 88 2351 88 2352 88 2352 88 2351 88 2353 88 2349 88 2346 88 2347 88 2347 88 2346 88 2198 88 2347 88 2198 88 2354 88 2354 88 2198 88 2197 88 2354 88 2197 88 2355 88 2355 88 2197 88 2201 88 2355 88 2201 88 2353 88 2353 88 2201 88 2204 88 2353 88 2204 88 2352 88 2316 1273 2352 1273 2206 1273 2206 1274 2352 1274 2204 1274 2274 1275 2166 1275 2346 1275 2346 1275 2166 1275 2165 1275 2352 1276 2316 1276 2350 1276 2350 1277 2316 1277 2315 1277 2350 1278 2315 1278 2351 1278 2351 1279 2315 1279 2283 1279 2351 1280 2283 1280 2353 1280 2353 1281 2283 1281 2282 1281 2353 1282 2282 1282 2355 1282 2355 1283 2282 1283 2314 1283 2355 1284 2314 1284 2354 1284 2354 1285 2314 1285 2313 1285 2354 1286 2313 1286 2347 1286 2347 1286 2313 1286 2311 1286 2347 1287 2311 1287 2348 1287 2348 1287 2311 1287 2310 1287 2348 1288 2310 1288 2349 1288 2349 1288 2310 1288 2309 1288 2349 1289 2309 1289 2346 1289 2346 1290 2309 1290 2274 1290 2356 88 2162 88 2208 88 2357 88 2358 88 2359 88 2359 88 2356 88 2357 88 2357 88 2356 88 2208 88 2357 88 2208 88 2360 88 2360 88 2208 88 2207 88 2360 88 2207 88 2361 88 2361 88 2207 88 2212 88 2361 88 2212 88 2362 88 2363 88 2364 88 2365 88 2365 88 2364 88 2362 88 2365 88 2362 88 2215 88 2215 88 2362 88 2212 88 2324 1256 2365 1256 2217 1256 2217 1256 2365 1256 2215 1256 2308 1291 2163 1291 2356 1291 2356 1292 2163 1292 2162 1292 2365 1293 2324 1293 2363 1293 2363 1294 2324 1294 2325 1294 2363 1295 2325 1295 2364 1295 2364 1296 2325 1296 2323 1296 2364 1297 2323 1297 2362 1297 2362 1298 2323 1298 2322 1298 2362 1299 2322 1299 2361 1299 2361 1299 2322 1299 2321 1299 2361 1300 2321 1300 2360 1300 2360 1300 2321 1300 2302 1300 2360 1301 2302 1301 2357 1301 2357 1302 2302 1302 2276 1302 2357 1303 2276 1303 2358 1303 2358 1304 2276 1304 2275 1304 2358 1305 2275 1305 2359 1305 2359 1306 2275 1306 2304 1306 2359 1307 2304 1307 2356 1307 2356 1307 2304 1307 2308 1307 2366 0 2367 0 2368 0 2366 0 2368 0 2369 0 2370 0 2371 0 2372 0 2372 0 2371 0 2373 0 2368 0 2374 0 2375 0 2376 0 2377 0 2368 0 2368 0 2377 0 2378 0 2368 0 2378 0 2379 0 2379 0 2380 0 2368 0 2368 0 2380 0 2381 0 2368 0 2381 0 2382 0 2383 0 2384 0 2368 0 2368 0 2384 0 2372 0 2368 0 2372 0 2385 0 2385 0 2372 0 2373 0 2368 0 2386 0 2387 0 2367 0 2388 0 2368 0 2368 0 2388 0 2389 0 2368 0 2389 0 2374 0 2387 0 2390 0 2368 0 2368 0 2390 0 2391 0 2368 0 2391 0 2369 0 2375 0 2392 0 2368 0 2368 0 2392 0 2393 0 2368 0 2393 0 2376 0 2382 0 2394 0 2368 0 2368 0 2394 0 2395 0 2368 0 2395 0 2396 0 2396 0 2397 0 2368 0 2368 0 2397 0 2398 0 2368 0 2398 0 2383 0 2372 0 2399 0 2370 0 2370 0 2399 0 2400 0 2370 0 2400 0 2401 0 2401 0 2400 0 2402 0 2401 0 2402 0 2403 0 2376 1308 2393 1308 2404 1308 2405 1309 2406 1309 2407 1309 2408 1310 2409 1310 2410 1310 2411 1311 2266 1311 2264 1311 2266 1312 2411 1312 2267 1312 2412 1313 2413 1313 2414 1313 2415 1314 2416 1314 2417 1314 2418 1315 2419 1315 2420 1315 2421 1316 2381 1316 2380 1316 2422 1317 2423 1317 2424 1317 2425 1318 2426 1318 2427 1318 2427 1319 2426 1319 2428 1319 2427 1320 2428 1320 2429 1320 2422 1321 2424 1321 2430 1321 2431 1322 2432 1322 2433 1322 2433 1323 2432 1323 2434 1323 2433 1324 2434 1324 2435 1324 2431 1325 2436 1325 2432 1325 2432 1326 2436 1326 2437 1326 2432 1327 2437 1327 2438 1327 2439 1328 2440 1328 2441 1328 2441 1329 2440 1329 2442 1329 2442 1330 2443 1330 2441 1330 2441 1331 2443 1331 2444 1331 2441 1332 2444 1332 2434 1332 2434 1333 2444 1333 2445 1333 2434 1334 2445 1334 2435 1334 2446 1335 2447 1335 2448 1335 2448 1336 2447 1336 2449 1336 2450 1337 2451 1337 2452 1337 2452 1338 2451 1338 2453 1338 2452 1339 2453 1339 2454 1339 2455 1340 2456 1340 2419 1340 2457 1341 2458 1341 2459 1341 2459 1342 2458 1342 2460 1342 2459 1343 2460 1343 2461 1343 2462 1344 2463 1344 2418 1344 2463 1345 2464 1345 2418 1345 2418 1346 2464 1346 2465 1346 2418 1347 2465 1347 2466 1347 2466 1348 2467 1348 2418 1348 2418 1349 2467 1349 2468 1349 2418 1350 2468 1350 2419 1350 2419 1351 2468 1351 2469 1351 2419 1352 2469 1352 2455 1352 2470 1353 2471 1353 2472 1353 2472 1354 2471 1354 2473 1354 2472 1355 2473 1355 2474 1355 2474 1356 2473 1356 2475 1356 2474 1357 2475 1357 2476 1357 2476 1358 2475 1358 2477 1358 2378 1359 2377 1359 2478 1359 2479 1360 2480 1360 2421 1360 2471 1361 2479 1361 2473 1361 2473 1362 2479 1362 2421 1362 2473 1363 2421 1363 2475 1363 2475 1364 2421 1364 2380 1364 2475 1365 2380 1365 2477 1365 2477 1366 2380 1366 2379 1366 2477 1367 2379 1367 2378 1367 2481 1368 2482 1368 2483 1368 2395 1369 2482 1369 2396 1369 2396 1370 2482 1370 2481 1370 2396 1371 2481 1371 2397 1371 2480 1372 2394 1372 2421 1372 2421 1373 2394 1373 2382 1373 2421 1374 2382 1374 2381 1374 2423 1375 2462 1375 2424 1375 2424 1376 2462 1376 2418 1376 2424 1377 2418 1377 2484 1377 2399 1378 2372 1378 2485 1378 2486 1379 2487 1379 2488 1379 2488 1380 2487 1380 2489 1380 2488 1381 2489 1381 2490 1381 2490 1382 2489 1382 2491 1382 2490 1383 2491 1383 2492 1383 2492 1384 2491 1384 2493 1384 2492 1385 2493 1385 2494 1385 2494 1386 2493 1386 2495 1386 2494 1387 2495 1387 2496 1387 2496 1388 2495 1388 2497 1388 2496 1389 2497 1389 2498 1389 2499 1390 2500 1390 2501 1390 2501 1391 2500 1391 2502 1391 2501 1392 2502 1392 2503 1392 2503 1393 2502 1393 2504 1393 2503 1394 2504 1394 2505 1394 2505 1395 2504 1395 2506 1395 2505 1396 2506 1396 2402 1396 2402 1397 2506 1397 2403 1397 2507 1398 2508 1398 2485 1398 2485 1399 2508 1399 2509 1399 2485 1400 2509 1400 2399 1400 2399 1401 2509 1401 2400 1401 2384 1402 2383 1402 2510 1402 2510 1403 2383 1403 2511 1403 2510 1404 2511 1404 2512 1404 2512 1405 2511 1405 2513 1405 2512 1406 2513 1406 2514 1406 2514 1407 2513 1407 2515 1407 2514 1408 2515 1408 2516 1408 2516 1409 2515 1409 2517 1409 2516 1410 2517 1410 2518 1410 2383 1411 2398 1411 2511 1411 2511 1412 2398 1412 2397 1412 2511 1413 2397 1413 2513 1413 2513 1414 2397 1414 2481 1414 2513 1415 2481 1415 2515 1415 2515 1416 2481 1416 2483 1416 2515 1417 2483 1417 2517 1417 2519 1418 2459 1418 2520 1418 2520 1419 2459 1419 2521 1419 2520 1420 2521 1420 2522 1420 2522 1421 2521 1421 2523 1421 2522 1422 2523 1422 2524 1422 2524 1423 2523 1423 2525 1423 2524 1424 2525 1424 2526 1424 2526 1425 2525 1425 2527 1425 2526 1426 2527 1426 2528 1426 2528 1427 2527 1427 2529 1427 2528 1428 2529 1428 2530 1428 2531 1429 2420 1429 2519 1429 2519 1430 2420 1430 2419 1430 2519 1431 2419 1431 2459 1431 2459 1432 2419 1432 2456 1432 2459 1433 2456 1433 2457 1433 2531 1434 2519 1434 2532 1434 2532 1435 2519 1435 2520 1435 2532 1436 2520 1436 2533 1436 2533 1437 2520 1437 2522 1437 2533 1438 2522 1438 2534 1438 2534 1439 2522 1439 2524 1439 2534 1440 2524 1440 2535 1440 2535 1441 2524 1441 2526 1441 2535 1442 2526 1442 2536 1442 2536 1443 2526 1443 2528 1443 2536 1444 2528 1444 2537 1444 2537 1445 2528 1445 2530 1445 2537 1446 2530 1446 2538 1446 2539 1447 2540 1447 2541 1447 2542 1448 2543 1448 2544 1448 2544 1449 2543 1449 2545 1449 2544 1450 2545 1450 2546 1450 2546 1451 2545 1451 2547 1451 2548 1452 2546 1452 2549 1452 2549 1453 2546 1453 2547 1453 2549 1454 2547 1454 2550 1454 2551 1455 2552 1455 2553 1455 2554 1456 2555 1456 2415 1456 2415 1457 2555 1457 2556 1457 2415 1458 2556 1458 2416 1458 2538 1459 2557 1459 2537 1459 2537 1460 2557 1460 2558 1460 2537 1461 2558 1461 2536 1461 2536 1462 2558 1462 2559 1462 2536 1463 2559 1463 2535 1463 2535 1464 2559 1464 2560 1464 2535 1465 2560 1465 2534 1465 2534 1466 2560 1466 2561 1466 2534 1467 2561 1467 2533 1467 2533 1468 2561 1468 2562 1468 2533 1469 2562 1469 2532 1469 2532 1470 2562 1470 2563 1470 2532 1471 2563 1471 2531 1471 2557 1472 2564 1472 2558 1472 2558 1473 2564 1473 2565 1473 2558 1474 2565 1474 2559 1474 2559 1475 2565 1475 2566 1475 2559 1476 2566 1476 2560 1476 2560 1477 2566 1477 2567 1477 2560 1478 2567 1478 2561 1478 2561 1479 2567 1479 2568 1479 2561 1480 2568 1480 2562 1480 2562 1481 2568 1481 2569 1481 2562 1482 2569 1482 2563 1482 2368 1483 2385 1483 2570 1483 2570 1484 2385 1484 2571 1484 2570 1485 2571 1485 2572 1485 2572 1486 2571 1486 2573 1486 2572 1487 2573 1487 2574 1487 2574 1488 2573 1488 2575 1488 2574 1489 2575 1489 2576 1489 2576 1490 2575 1490 2577 1490 2576 1491 2577 1491 2578 1491 2578 1492 2577 1492 2579 1492 2578 1493 2579 1493 2580 1493 2580 1494 2579 1494 2581 1494 2580 1495 2581 1495 2582 1495 2582 1496 2581 1496 2583 1496 2582 1497 2583 1497 2584 1497 2584 1498 2583 1498 2585 1498 2584 1499 2585 1499 2586 1499 2373 1500 2371 1500 2486 1500 2486 1501 2371 1501 2370 1501 2486 1502 2370 1502 2487 1502 2385 1503 2373 1503 2571 1503 2571 1504 2373 1504 2486 1504 2571 1505 2486 1505 2573 1505 2573 1506 2486 1506 2488 1506 2573 1507 2488 1507 2575 1507 2575 1508 2488 1508 2490 1508 2575 1509 2490 1509 2577 1509 2577 1510 2490 1510 2492 1510 2577 1511 2492 1511 2579 1511 2579 1512 2492 1512 2494 1512 2579 1513 2494 1513 2581 1513 2581 1514 2494 1514 2496 1514 2581 1515 2496 1515 2583 1515 2583 1516 2496 1516 2498 1516 2583 1517 2498 1517 2585 1517 2529 1518 2542 1518 2530 1518 2530 1519 2542 1519 2544 1519 2530 1520 2544 1520 2538 1520 2538 1521 2544 1521 2546 1521 2538 1522 2546 1522 2557 1522 2557 1523 2546 1523 2548 1523 2557 1524 2548 1524 2564 1524 2564 1525 2548 1525 2587 1525 2564 1526 2587 1526 2565 1526 2565 1527 2587 1527 2588 1527 2565 1528 2588 1528 2566 1528 2566 1529 2588 1529 2589 1529 2566 1530 2589 1530 2567 1530 2567 1531 2589 1531 2590 1531 2567 1532 2590 1532 2568 1532 2568 1533 2590 1533 2591 1533 2568 1534 2591 1534 2569 1534 2550 1535 2592 1535 2549 1535 2549 1536 2592 1536 2593 1536 2549 1537 2593 1537 2548 1537 2548 1538 2593 1538 2594 1538 2548 1539 2594 1539 2587 1539 2587 1540 2594 1540 2595 1540 2587 1541 2595 1541 2588 1541 2588 1542 2595 1542 2596 1542 2588 1543 2596 1543 2589 1543 2589 1544 2596 1544 2597 1544 2589 1545 2597 1545 2590 1545 2590 1546 2597 1546 2598 1546 2590 1547 2598 1547 2591 1547 2599 1548 2552 1548 2600 1548 2600 1549 2552 1549 2551 1549 2600 1550 2551 1550 2404 1550 2404 1551 2393 1551 2600 1551 2600 1552 2393 1552 2392 1552 2600 1553 2392 1553 2599 1553 2599 1554 2392 1554 2375 1554 2599 1555 2375 1555 2374 1555 2177 1556 2601 1556 2178 1556 2178 1557 2601 1557 2602 1557 2178 1558 2602 1558 2180 1558 2180 1559 2602 1559 2603 1559 2180 1560 2603 1560 2181 1560 2181 1561 2603 1561 2604 1561 2605 1562 2606 1562 2607 1562 2607 1563 2608 1563 2605 1563 2605 1564 2608 1564 2609 1564 2605 1565 2609 1565 2610 1565 2609 1566 2611 1566 2610 1566 2610 1567 2611 1567 2612 1567 2610 1568 2612 1568 2613 1568 2614 1569 2615 1569 2616 1569 2616 1570 2615 1570 2613 1570 2616 1571 2613 1571 2617 1571 2617 1572 2613 1572 2612 1572 2454 1573 2439 1573 2452 1573 2452 1574 2439 1574 2441 1574 2452 1575 2441 1575 2618 1575 2618 1576 2441 1576 2619 1576 2618 1577 2619 1577 2620 1577 2620 1578 2619 1578 2621 1578 2620 1579 2621 1579 2622 1579 2622 1580 2621 1580 2623 1580 2622 1581 2623 1581 2624 1581 2625 1582 2626 1582 2627 1582 2627 1583 2626 1583 2628 1583 2627 1584 2628 1584 2629 1584 2629 1585 2628 1585 2630 1585 2629 1586 2630 1586 2631 1586 2632 1587 2633 1587 2634 1587 2634 1588 2633 1588 2635 1588 2634 1589 2635 1589 2636 1589 2636 1590 2635 1590 2413 1590 2636 1591 2413 1591 2631 1591 2631 1592 2413 1592 2412 1592 2631 1593 2412 1593 2629 1593 2629 1594 2412 1594 2414 1594 2629 1595 2414 1595 2627 1595 2449 1596 2450 1596 2448 1596 2448 1597 2450 1597 2452 1597 2448 1598 2452 1598 2637 1598 2637 1599 2452 1599 2618 1599 2637 1600 2618 1600 2638 1600 2638 1601 2618 1601 2620 1601 2638 1602 2620 1602 2639 1602 2639 1603 2620 1603 2622 1603 2639 1604 2622 1604 2640 1604 2640 1605 2622 1605 2624 1605 2640 1606 2624 1606 2641 1606 2642 1607 2632 1607 2643 1607 2643 1608 2632 1608 2634 1608 2643 1609 2634 1609 2644 1609 2644 1610 2634 1610 2636 1610 2644 1611 2636 1611 2645 1611 2645 1612 2636 1612 2631 1612 2645 1613 2631 1613 2646 1613 2646 1614 2631 1614 2630 1614 2646 1615 2630 1615 2647 1615 2647 1616 2630 1616 2628 1616 2647 1617 2628 1617 2648 1617 2648 1618 2628 1618 2626 1618 2648 1619 2626 1619 2649 1619 2649 1620 2626 1620 2625 1620 2177 1621 2174 1621 2601 1621 2601 1622 2174 1622 2642 1622 2601 1623 2642 1623 2602 1623 2602 1624 2642 1624 2643 1624 2602 1625 2643 1625 2603 1625 2603 1626 2643 1626 2644 1626 2603 1627 2644 1627 2604 1627 2604 1628 2644 1628 2645 1628 2650 1629 2651 1629 2652 1629 2653 1630 2654 1630 2655 1630 2655 1631 2654 1631 2656 1631 2655 1632 2656 1632 2657 1632 2657 1633 2656 1633 2658 1633 2657 1634 2658 1634 2659 1634 2659 1635 2658 1635 2660 1635 2659 1636 2660 1636 2661 1636 2654 1637 2662 1637 2656 1637 2656 1638 2662 1638 2663 1638 2656 1639 2663 1639 2658 1639 2658 1640 2663 1640 2664 1640 2658 1641 2664 1641 2660 1641 2461 1642 2446 1642 2459 1642 2459 1643 2446 1643 2448 1643 2459 1644 2448 1644 2521 1644 2521 1645 2448 1645 2637 1645 2521 1646 2637 1646 2523 1646 2523 1647 2637 1647 2638 1647 2523 1648 2638 1648 2525 1648 2525 1649 2638 1649 2639 1649 2525 1650 2639 1650 2527 1650 2527 1651 2639 1651 2640 1651 2527 1652 2640 1652 2529 1652 2529 1653 2640 1653 2641 1653 2529 1654 2641 1654 2542 1654 2542 1655 2641 1655 2665 1655 2542 1656 2665 1656 2543 1656 2543 1657 2665 1657 2666 1657 2543 1658 2666 1658 2545 1658 2545 1659 2666 1659 2667 1659 2545 1660 2667 1660 2668 1660 2668 1661 2667 1661 2651 1661 2651 1662 2650 1662 2668 1662 2668 1663 2650 1663 2669 1663 2668 1664 2669 1664 2545 1664 2545 1665 2669 1665 2539 1665 2545 1666 2539 1666 2547 1666 2547 1667 2539 1667 2541 1667 2547 1668 2541 1668 2550 1668 2670 1669 2671 1669 2672 1669 2672 1670 2671 1670 2673 1670 2672 1671 2673 1671 2674 1671 2674 1672 2673 1672 2675 1672 2674 1673 2676 1673 2672 1673 2672 1674 2676 1674 2553 1674 2672 1675 2553 1675 2670 1675 2670 1676 2553 1676 2552 1676 2670 1677 2552 1677 2677 1677 2677 1678 2552 1678 2599 1678 2677 1679 2599 1679 2678 1679 2678 1680 2599 1680 2374 1680 2678 1681 2374 1681 2389 1681 2679 1682 2556 1682 2680 1682 2680 1683 2556 1683 2555 1683 2680 1684 2555 1684 2681 1684 2681 1685 2555 1685 2554 1685 2681 1686 2554 1686 2682 1686 2682 1687 2554 1687 2683 1687 2684 1688 2683 1688 2685 1688 2685 1689 2683 1689 2554 1689 2685 1690 2554 1690 2686 1690 2686 1691 2554 1691 2415 1691 2686 1692 2415 1692 2687 1692 2687 1693 2415 1693 2417 1693 2687 1694 2417 1694 2478 1694 2269 1695 2688 1695 2653 1695 2653 1696 2688 1696 2689 1696 2653 1697 2689 1697 2654 1697 2654 1698 2689 1698 2690 1698 2654 1699 2690 1699 2662 1699 2662 1700 2690 1700 2540 1700 2662 1701 2540 1701 2663 1701 2663 1702 2540 1702 2539 1702 2663 1703 2539 1703 2664 1703 2664 1704 2539 1704 2669 1704 2664 1705 2669 1705 2660 1705 2660 1706 2669 1706 2650 1706 2660 1707 2650 1707 2661 1707 2661 1708 2650 1708 2652 1708 2389 1709 2592 1709 2678 1709 2678 1710 2592 1710 2550 1710 2678 1711 2550 1711 2677 1711 2677 1712 2550 1712 2541 1712 2677 1713 2541 1713 2670 1713 2670 1714 2541 1714 2540 1714 2670 1715 2540 1715 2671 1715 2671 1716 2540 1716 2690 1716 2671 1717 2690 1717 2673 1717 2673 1718 2690 1718 2689 1718 2673 1719 2689 1719 2675 1719 2675 1720 2689 1720 2688 1720 2269 1721 2653 1721 2270 1721 2270 1722 2653 1722 2655 1722 2270 1723 2655 1723 2271 1723 2271 1724 2655 1724 2657 1724 2271 1725 2657 1725 2272 1725 2272 1726 2657 1726 2659 1726 2272 1727 2659 1727 2273 1727 2273 1728 2659 1728 2661 1728 2273 1729 2661 1729 2174 1729 2174 1730 2661 1730 2652 1730 2174 1731 2652 1731 2642 1731 2642 1732 2652 1732 2651 1732 2642 1733 2651 1733 2632 1733 2632 1734 2651 1734 2667 1734 2632 1735 2667 1735 2633 1735 2633 1736 2667 1736 2666 1736 2633 1737 2666 1737 2635 1737 2635 1738 2666 1738 2665 1738 2635 1739 2665 1739 2413 1739 2413 1740 2665 1740 2641 1740 2413 1741 2641 1741 2414 1741 2414 1742 2641 1742 2624 1742 2414 1743 2624 1743 2627 1743 2627 1744 2624 1744 2623 1744 2627 1745 2623 1745 2625 1745 2183 1746 2691 1746 2219 1746 2219 1747 2691 1747 2692 1747 2219 1748 2692 1748 2221 1748 2221 1749 2692 1749 2693 1749 2221 1750 2693 1750 2222 1750 2222 1751 2693 1751 2694 1751 2222 1752 2694 1752 2224 1752 2224 1753 2694 1753 2695 1753 2224 1754 2695 1754 2225 1754 2225 1755 2695 1755 2696 1755 2225 1756 2696 1756 2227 1756 2227 1757 2696 1757 2697 1757 2227 1758 2697 1758 2228 1758 2228 1759 2697 1759 2698 1759 2228 1760 2698 1760 2229 1760 2229 1761 2698 1761 2699 1761 2229 1762 2699 1762 2230 1762 2230 1763 2699 1763 2700 1763 2230 1764 2700 1764 2231 1764 2231 1765 2700 1765 2701 1765 2231 1766 2701 1766 2187 1766 2187 1767 2701 1767 2702 1767 2187 1768 2702 1768 2188 1768 2188 1769 2702 1769 2703 1769 2188 1770 2703 1770 2189 1770 2189 1771 2703 1771 2704 1771 2189 1772 2704 1772 2191 1772 2191 1773 2704 1773 2705 1773 2191 1774 2705 1774 2192 1774 2192 1775 2705 1775 2706 1775 2192 1776 2706 1776 2194 1776 2194 1777 2706 1777 2707 1777 2194 1778 2707 1778 2233 1778 2233 1779 2707 1779 2708 1779 2233 1780 2708 1780 2235 1780 2235 1781 2708 1781 2709 1781 2235 1782 2709 1782 2236 1782 2236 1783 2709 1783 2710 1783 2236 1784 2710 1784 2238 1784 2238 1785 2710 1785 2711 1785 2238 1786 2711 1786 2239 1786 2239 1787 2711 1787 2712 1787 2239 1788 2712 1788 2241 1788 2241 1789 2712 1789 2713 1789 2241 1790 2713 1790 2242 1790 2242 1791 2713 1791 2714 1791 2242 1792 2714 1792 2243 1792 2243 1793 2714 1793 2715 1793 2243 1794 2715 1794 2244 1794 2244 1795 2715 1795 2716 1795 2244 1796 2716 1796 2245 1796 2245 1797 2716 1797 2717 1797 2245 1798 2717 1798 2196 1798 2196 1799 2717 1799 2718 1799 2196 1800 2718 1800 2199 1800 2199 1801 2718 1801 2719 1801 2199 1802 2719 1802 2200 1802 2200 1803 2719 1803 2720 1803 2200 1804 2720 1804 2202 1804 2202 1805 2720 1805 2721 1805 2202 1806 2721 1806 2203 1806 2203 1807 2721 1807 2722 1807 2203 1808 2722 1808 2205 1808 2205 1809 2722 1809 2723 1809 2205 1810 2723 1810 2247 1810 2247 1811 2723 1811 2724 1811 2247 1812 2724 1812 2249 1812 2249 1813 2724 1813 2725 1813 2249 1814 2725 1814 2250 1814 2250 1815 2725 1815 2726 1815 2250 1816 2726 1816 2252 1816 2252 1817 2726 1817 2727 1817 2252 1818 2727 1818 2253 1818 2253 1819 2727 1819 2728 1819 2253 1820 2728 1820 2255 1820 2255 1821 2728 1821 2729 1821 2255 1822 2729 1822 2256 1822 2256 1823 2729 1823 2730 1823 2256 1824 2730 1824 2257 1824 2257 1825 2730 1825 2731 1825 2257 1826 2731 1826 2258 1826 2258 1827 2731 1827 2732 1827 2258 1828 2732 1828 2259 1828 2259 1829 2732 1829 2733 1829 2259 1830 2733 1830 2209 1830 2209 1831 2733 1831 2734 1831 2209 1832 2734 1832 2210 1832 2210 1833 2734 1833 2735 1833 2210 1834 2735 1834 2211 1834 2211 1835 2735 1835 2679 1835 2211 1836 2679 1836 2213 1836 2213 1837 2679 1837 2680 1837 2213 1838 2680 1838 2214 1838 2214 1839 2680 1839 2681 1839 2214 1840 2681 1840 2216 1840 2216 1841 2681 1841 2682 1841 2216 1842 2682 1842 2261 1842 2261 1843 2682 1843 2683 1843 2261 1844 2683 1844 2263 1844 2263 1845 2683 1845 2684 1845 2263 1846 2684 1846 2264 1846 2691 1847 2736 1847 2692 1847 2692 1848 2736 1848 2737 1848 2692 1849 2737 1849 2693 1849 2693 1850 2737 1850 2738 1850 2693 1851 2738 1851 2694 1851 2694 1852 2738 1852 2739 1852 2694 1853 2739 1853 2695 1853 2695 1854 2739 1854 2740 1854 2695 1855 2740 1855 2696 1855 2696 1856 2740 1856 2741 1856 2696 1857 2741 1857 2697 1857 2697 1858 2741 1858 2742 1858 2697 1859 2742 1859 2698 1859 2698 1860 2742 1860 2743 1860 2698 1861 2743 1861 2699 1861 2699 1862 2743 1862 2744 1862 2699 1863 2744 1863 2700 1863 2700 1864 2744 1864 2745 1864 2700 1865 2745 1865 2701 1865 2701 1866 2745 1866 2746 1866 2701 1867 2746 1867 2702 1867 2702 1868 2746 1868 2747 1868 2702 1869 2747 1869 2703 1869 2703 1870 2747 1870 2748 1870 2703 1871 2748 1871 2704 1871 2704 1872 2748 1872 2749 1872 2704 1873 2749 1873 2705 1873 2705 1874 2749 1874 2750 1874 2705 1875 2750 1875 2706 1875 2706 1876 2750 1876 2751 1876 2706 1877 2751 1877 2707 1877 2707 1878 2751 1878 2752 1878 2707 1879 2752 1879 2708 1879 2708 1880 2752 1880 2753 1880 2708 1881 2753 1881 2709 1881 2709 1882 2753 1882 2754 1882 2709 1883 2754 1883 2710 1883 2710 1884 2754 1884 2755 1884 2710 1885 2755 1885 2711 1885 2711 1886 2755 1886 2756 1886 2711 1887 2756 1887 2712 1887 2712 1888 2756 1888 2757 1888 2712 1889 2757 1889 2713 1889 2713 1890 2757 1890 2758 1890 2713 1891 2758 1891 2714 1891 2714 1892 2758 1892 2759 1892 2714 1893 2759 1893 2715 1893 2715 1894 2759 1894 2760 1894 2715 1895 2760 1895 2716 1895 2716 1896 2760 1896 2761 1896 2716 1897 2761 1897 2717 1897 2717 1898 2761 1898 2762 1898 2717 1899 2762 1899 2718 1899 2718 1900 2762 1900 2763 1900 2718 1901 2763 1901 2719 1901 2719 1902 2763 1902 2764 1902 2719 1903 2764 1903 2720 1903 2765 1904 2766 1904 2767 1904 2768 1905 2769 1905 2770 1905 2771 1906 2772 1906 2773 1906 2773 1907 2772 1907 2768 1907 2773 1908 2768 1908 2774 1908 2774 1909 2768 1909 2770 1909 2767 1910 2775 1910 2765 1910 2765 1911 2775 1911 2776 1911 2765 1912 2776 1912 2769 1912 2769 1913 2776 1913 2777 1913 2769 1914 2777 1914 2770 1914 2778 1915 2779 1915 2780 1915 2780 1916 2779 1916 2781 1916 2780 1917 2781 1917 2518 1917 2782 1918 2409 1918 2783 1918 2783 1919 2409 1919 2408 1919 2783 1920 2408 1920 2784 1920 2785 1921 2786 1921 2787 1921 2787 1922 2786 1922 2788 1922 2787 1923 2788 1923 2789 1923 2778 1924 2780 1924 2790 1924 2790 1925 2780 1925 2518 1925 2790 1926 2518 1926 2470 1926 2470 1927 2518 1927 2517 1927 2470 1928 2517 1928 2471 1928 2471 1929 2517 1929 2483 1929 2471 1930 2483 1930 2479 1930 2479 1931 2483 1931 2482 1931 2479 1932 2482 1932 2480 1932 2480 1933 2482 1933 2395 1933 2480 1934 2395 1934 2394 1934 2786 1935 2784 1935 2788 1935 2788 1936 2784 1936 2408 1936 2788 1937 2408 1937 2789 1937 2789 1938 2408 1938 2410 1938 2789 1939 2410 1939 2791 1939 2791 1940 2410 1940 2792 1940 2791 1941 2792 1941 2793 1941 2793 1942 2792 1942 2499 1942 2793 1943 2499 1943 2507 1943 2507 1944 2499 1944 2501 1944 2507 1945 2501 1945 2508 1945 2508 1946 2501 1946 2503 1946 2508 1947 2503 1947 2509 1947 2509 1948 2503 1948 2505 1948 2509 1949 2505 1949 2400 1949 2400 1950 2505 1950 2402 1950 2779 1951 2785 1951 2781 1951 2781 1952 2785 1952 2787 1952 2781 1953 2787 1953 2518 1953 2518 1954 2787 1954 2789 1954 2518 1955 2789 1955 2516 1955 2516 1956 2789 1956 2791 1956 2516 1957 2791 1957 2514 1957 2514 1958 2791 1958 2793 1958 2514 1959 2793 1959 2512 1959 2512 1960 2793 1960 2507 1960 2512 1961 2507 1961 2510 1961 2510 1962 2507 1962 2485 1962 2510 1963 2485 1963 2384 1963 2384 1964 2485 1964 2372 1964 2794 1965 2766 1965 2476 1965 2476 1966 2766 1966 2765 1966 2476 1967 2765 1967 2474 1967 2474 1968 2765 1968 2769 1968 2474 1969 2769 1969 2472 1969 2472 1970 2769 1970 2768 1970 2472 1971 2768 1971 2470 1971 2470 1972 2768 1972 2772 1972 2470 1973 2772 1973 2790 1973 2790 1974 2772 1974 2771 1974 2790 1975 2771 1975 2778 1975 2795 1976 2796 1976 2797 1976 2797 1977 2796 1977 2798 1977 2797 1978 2798 1978 2799 1978 2799 1979 2798 1979 2800 1979 2801 1980 2800 1980 2802 1980 2802 1981 2800 1981 2798 1981 2802 1982 2798 1982 2803 1982 2803 1983 2798 1983 2796 1983 2803 1984 2796 1984 2804 1984 2804 1985 2796 1985 2795 1985 2804 1986 2795 1986 2805 1986 2407 1987 2406 1987 2806 1987 2806 1988 2406 1988 2807 1988 2806 1989 2807 1989 2808 1989 2807 1990 2809 1990 2808 1990 2808 1991 2809 1991 2810 1991 2808 1992 2810 1992 2811 1992 2812 1993 2813 1993 2814 1993 2810 1994 2815 1994 2811 1994 2811 1995 2815 1995 2816 1995 2811 1996 2816 1996 2814 1996 2814 1997 2816 1997 2817 1997 2814 1998 2817 1998 2812 1998 2812 1999 2818 1999 2813 1999 2813 2000 2818 2000 2819 2000 2813 2001 2819 2001 2606 2001 2606 2002 2819 2002 2820 2002 2606 2003 2820 2003 2607 2003 2821 2004 2822 2004 2823 2004 2823 2005 2822 2005 2824 2005 2823 2006 2824 2006 2825 2006 2826 2007 2827 2007 2828 2007 2828 2008 2827 2008 2829 2008 2828 2009 2829 2009 2830 2009 2830 2010 2829 2010 2831 2010 2830 2011 2831 2011 2832 2011 2832 2012 2831 2012 2833 2012 2832 2013 2833 2013 2834 2013 2834 2014 2833 2014 2835 2014 2834 2015 2835 2015 2836 2015 2836 2016 2835 2016 2837 2016 2836 2017 2837 2017 2838 2017 2838 2018 2837 2018 2839 2018 2838 2019 2839 2019 2840 2019 2840 2020 2839 2020 2841 2020 2840 2021 2841 2021 2842 2021 2842 2022 2841 2022 2843 2022 2842 2023 2843 2023 2844 2023 2844 2024 2843 2024 2845 2024 2844 2025 2845 2025 2846 2025 2846 2026 2845 2026 2847 2026 2846 2027 2847 2027 2848 2027 2438 2028 2425 2028 2432 2028 2432 2029 2425 2029 2427 2029 2432 2030 2427 2030 2849 2030 2849 2031 2427 2031 2850 2031 2849 2032 2850 2032 2851 2032 2851 2033 2850 2033 2852 2033 2851 2034 2852 2034 2853 2034 2429 2035 2430 2035 2427 2035 2427 2036 2430 2036 2424 2036 2427 2037 2424 2037 2850 2037 2850 2038 2424 2038 2484 2038 2850 2039 2484 2039 2852 2039 2844 2040 2853 2040 2842 2040 2842 2041 2853 2041 2852 2041 2842 2042 2852 2042 2840 2042 2840 2043 2852 2043 2484 2043 2840 2044 2484 2044 2838 2044 2838 2045 2484 2045 2418 2045 2838 2046 2418 2046 2836 2046 2836 2047 2418 2047 2420 2047 2836 2048 2420 2048 2834 2048 2834 2049 2420 2049 2531 2049 2834 2050 2531 2050 2832 2050 2832 2051 2531 2051 2563 2051 2832 2052 2563 2052 2830 2052 2830 2053 2563 2053 2569 2053 2830 2054 2569 2054 2828 2054 2828 2055 2569 2055 2591 2055 2828 2056 2591 2056 2826 2056 2826 2057 2591 2057 2598 2057 2389 2058 2388 2058 2592 2058 2592 2059 2388 2059 2367 2059 2592 2060 2367 2060 2593 2060 2593 2061 2367 2061 2366 2061 2593 2062 2366 2062 2594 2062 2594 2063 2366 2063 2369 2063 2594 2064 2369 2064 2595 2064 2595 2065 2369 2065 2391 2065 2595 2066 2391 2066 2596 2066 2596 2067 2391 2067 2390 2067 2596 2068 2390 2068 2597 2068 2597 2069 2390 2069 2387 2069 2597 2070 2387 2070 2598 2070 2598 2071 2387 2071 2386 2071 2598 2072 2386 2072 2826 2072 2826 2073 2386 2073 2368 2073 2826 2074 2368 2074 2827 2074 2827 2075 2368 2075 2570 2075 2827 2076 2570 2076 2829 2076 2829 2077 2570 2077 2572 2077 2829 2078 2572 2078 2831 2078 2831 2079 2572 2079 2574 2079 2831 2080 2574 2080 2833 2080 2833 2081 2574 2081 2576 2081 2833 2082 2576 2082 2835 2082 2835 2083 2576 2083 2578 2083 2835 2084 2578 2084 2837 2084 2837 2085 2578 2085 2580 2085 2837 2086 2580 2086 2839 2086 2839 2087 2580 2087 2582 2087 2839 2088 2582 2088 2841 2088 2841 2089 2582 2089 2584 2089 2841 2090 2584 2090 2843 2090 2843 2091 2584 2091 2586 2091 2843 2092 2586 2092 2845 2092 2848 2093 2405 2093 2846 2093 2846 2094 2405 2094 2407 2094 2846 2095 2407 2095 2844 2095 2844 2096 2407 2096 2806 2096 2844 2097 2806 2097 2853 2097 2853 2098 2806 2098 2808 2098 2853 2099 2808 2099 2851 2099 2851 2100 2808 2100 2811 2100 2851 2101 2811 2101 2849 2101 2849 2102 2811 2102 2814 2102 2849 2103 2814 2103 2432 2103 2432 2104 2814 2104 2813 2104 2432 2105 2813 2105 2434 2105 2434 2106 2813 2106 2606 2106 2434 2107 2606 2107 2441 2107 2441 2108 2606 2108 2605 2108 2441 2109 2605 2109 2619 2109 2619 2110 2605 2110 2610 2110 2619 2111 2610 2111 2621 2111 2621 2112 2610 2112 2613 2112 2621 2113 2613 2113 2623 2113 2623 2114 2613 2114 2615 2114 2623 2115 2615 2115 2625 2115 2625 2116 2615 2116 2614 2116 2625 2117 2614 2117 2649 2117 2803 2118 2825 2118 2802 2118 2802 2119 2825 2119 2824 2119 2802 2120 2824 2120 2801 2120 2801 2121 2824 2121 2854 2121 2801 2122 2854 2122 2800 2122 2800 2123 2854 2123 2855 2123 2800 2124 2855 2124 2799 2124 2799 2125 2855 2125 2856 2125 2799 2126 2856 2126 2797 2126 2797 2127 2856 2127 2857 2127 2797 2128 2857 2128 2795 2128 2795 2129 2857 2129 2858 2129 2795 2130 2858 2130 2805 2130 2805 2131 2858 2131 2859 2131 2401 2132 2403 2132 2860 2132 2860 2133 2403 2133 2506 2133 2860 2134 2506 2134 2861 2134 2861 2135 2506 2135 2504 2135 2861 2136 2504 2136 2862 2136 2862 2137 2504 2137 2502 2137 2862 2138 2502 2138 2863 2138 2863 2139 2502 2139 2500 2139 2863 2140 2500 2140 2864 2140 2864 2141 2500 2141 2499 2141 2864 2142 2499 2142 2821 2142 2821 2143 2499 2143 2792 2143 2821 2144 2792 2144 2822 2144 2822 2145 2792 2145 2410 2145 2822 2146 2410 2146 2824 2146 2824 2147 2410 2147 2409 2147 2824 2148 2409 2148 2854 2148 2854 2149 2409 2149 2782 2149 2854 2150 2782 2150 2855 2150 2848 2151 2865 2151 2405 2151 2405 2152 2865 2152 2866 2152 2405 2153 2866 2153 2406 2153 2406 2154 2866 2154 2867 2154 2406 2155 2867 2155 2807 2155 2807 2156 2867 2156 2868 2156 2807 2157 2868 2157 2809 2157 2809 2158 2868 2158 2869 2158 2809 2159 2869 2159 2810 2159 2810 2160 2869 2160 2870 2160 2810 2161 2870 2161 2815 2161 2815 2162 2870 2162 2871 2162 2815 2163 2871 2163 2816 2163 2816 2164 2871 2164 2872 2164 2816 2165 2872 2165 2817 2165 2817 2166 2872 2166 2873 2166 2817 2167 2873 2167 2812 2167 2812 2168 2873 2168 2874 2168 2812 2169 2874 2169 2818 2169 2818 2170 2874 2170 2875 2170 2818 2171 2875 2171 2819 2171 2819 2172 2875 2172 2876 2172 2819 2173 2876 2173 2820 2173 2820 2174 2876 2174 2877 2174 2820 2175 2877 2175 2607 2175 2607 2176 2877 2176 2878 2176 2607 2177 2878 2177 2608 2177 2608 2178 2878 2178 2879 2178 2608 2179 2879 2179 2609 2179 2609 2180 2879 2180 2880 2180 2609 2181 2880 2181 2611 2181 2611 2182 2880 2182 2881 2182 2611 2183 2881 2183 2612 2183 2612 2184 2881 2184 2882 2184 2612 2185 2882 2185 2617 2185 2617 2186 2882 2186 2883 2186 2617 2187 2883 2187 2616 2187 2616 2188 2883 2188 2884 2188 2616 2189 2884 2189 2614 2189 2614 2190 2884 2190 2885 2190 2614 2191 2885 2191 2649 2191 2649 2192 2885 2192 2886 2192 2649 2193 2886 2193 2648 2193 2648 2194 2886 2194 2887 2194 2648 2195 2887 2195 2647 2195 2647 2196 2887 2196 2888 2196 2647 2197 2888 2197 2646 2197 2646 2198 2888 2198 2889 2198 2646 2199 2889 2199 2645 2199 2377 2200 2376 2200 2478 2200 2478 2201 2376 2201 2404 2201 2478 2202 2404 2202 2687 2202 2687 2203 2404 2203 2551 2203 2687 2204 2551 2204 2686 2204 2686 2205 2551 2205 2553 2205 2686 2206 2553 2206 2685 2206 2685 2207 2553 2207 2676 2207 2685 2208 2676 2208 2684 2208 2684 2209 2676 2209 2674 2209 2684 2210 2674 2210 2264 2210 2264 2211 2674 2211 2675 2211 2264 2212 2675 2212 2411 2212 2411 2213 2675 2213 2688 2213 2411 2214 2688 2214 2267 2214 2267 2215 2688 2215 2269 2215 2370 2216 2401 2216 2487 2216 2487 2217 2401 2217 2860 2217 2487 2218 2860 2218 2489 2218 2489 2219 2860 2219 2861 2219 2489 2220 2861 2220 2491 2220 2491 2221 2861 2221 2862 2221 2491 2222 2862 2222 2493 2222 2493 2223 2862 2223 2863 2223 2493 2224 2863 2224 2495 2224 2495 2225 2863 2225 2864 2225 2495 2226 2864 2226 2497 2226 2497 2227 2864 2227 2821 2227 2497 2228 2821 2228 2498 2228 2498 2229 2821 2229 2823 2229 2498 2230 2823 2230 2585 2230 2585 2231 2823 2231 2825 2231 2585 2232 2825 2232 2586 2232 2586 2233 2825 2233 2803 2233 2586 2234 2803 2234 2845 2234 2845 2235 2803 2235 2804 2235 2845 2236 2804 2236 2847 2236 2847 2237 2804 2237 2805 2237 2847 2238 2805 2238 2848 2238 2848 2239 2805 2239 2859 2239 2848 2240 2859 2240 2865 2240 2378 2241 2478 2241 2477 2241 2477 2242 2478 2242 2417 2242 2477 2243 2417 2243 2476 2243 2476 2244 2417 2244 2416 2244 2476 1965 2416 1965 2794 1965 2794 2245 2416 2245 2556 2245 2794 2245 2556 2245 2766 2245 2766 2246 2556 2246 2679 2246 2766 2247 2679 2247 2767 2247 2767 2248 2679 2248 2735 2248 2767 2249 2735 2249 2775 2249 2775 2250 2735 2250 2734 2250 2775 2251 2734 2251 2776 2251 2776 2252 2734 2252 2733 2252 2776 2253 2733 2253 2777 2253 2777 2254 2733 2254 2732 2254 2777 2255 2732 2255 2770 2255 2770 2256 2732 2256 2731 2256 2770 2257 2731 2257 2774 2257 2774 2258 2731 2258 2730 2258 2774 2259 2730 2259 2773 2259 2773 2260 2730 2260 2729 2260 2773 2261 2729 2261 2771 2261 2771 2262 2729 2262 2728 2262 2771 2263 2728 2263 2778 2263 2778 2264 2728 2264 2727 2264 2778 2265 2727 2265 2779 2265 2779 2266 2727 2266 2726 2266 2779 2267 2726 2267 2785 2267 2785 2268 2726 2268 2725 2268 2785 2269 2725 2269 2786 2269 2786 2270 2725 2270 2724 2270 2786 2271 2724 2271 2784 2271 2784 2272 2724 2272 2723 2272 2784 2273 2723 2273 2783 2273 2783 2274 2723 2274 2722 2274 2783 2275 2722 2275 2782 2275 2782 2276 2722 2276 2721 2276 2782 2277 2721 2277 2855 2277 2855 2278 2721 2278 2720 2278 2855 2279 2720 2279 2856 2279 2856 2280 2720 2280 2764 2280 2856 2281 2764 2281 2857 2281 2857 2282 2764 2282 2763 2282 2857 2283 2763 2283 2858 2283 2858 2284 2763 2284 2762 2284 2858 2285 2762 2285 2859 2285 2859 2286 2762 2286 2761 2286 2859 2287 2761 2287 2865 2287 2865 2288 2761 2288 2760 2288 2865 2289 2760 2289 2866 2289 2866 2290 2760 2290 2759 2290 2866 2291 2759 2291 2867 2291 2867 2292 2759 2292 2758 2292 2867 2293 2758 2293 2868 2293 2868 2294 2758 2294 2757 2294 2868 2295 2757 2295 2869 2295 2869 2296 2757 2296 2756 2296 2869 2297 2756 2297 2870 2297 2870 2298 2756 2298 2755 2298 2870 2299 2755 2299 2871 2299 2871 2300 2755 2300 2754 2300 2871 2301 2754 2301 2872 2301 2872 2302 2754 2302 2753 2302 2872 2303 2753 2303 2873 2303 2873 2304 2753 2304 2752 2304 2873 2305 2752 2305 2874 2305 2874 2306 2752 2306 2751 2306 2874 2307 2751 2307 2875 2307 2875 2308 2751 2308 2750 2308 2875 2309 2750 2309 2876 2309 2876 2310 2750 2310 2749 2310 2876 2311 2749 2311 2877 2311 2877 2312 2749 2312 2748 2312 2877 2313 2748 2313 2878 2313 2878 2314 2748 2314 2747 2314 2878 2315 2747 2315 2879 2315 2879 2316 2747 2316 2746 2316 2879 2317 2746 2317 2880 2317 2880 2318 2746 2318 2745 2318 2880 2319 2745 2319 2881 2319 2881 2320 2745 2320 2744 2320 2881 2321 2744 2321 2882 2321 2882 2322 2744 2322 2743 2322 2882 2323 2743 2323 2883 2323 2883 2324 2743 2324 2742 2324 2883 2325 2742 2325 2884 2325 2884 2326 2742 2326 2741 2326 2884 2327 2741 2327 2885 2327 2885 2328 2741 2328 2740 2328 2885 2329 2740 2329 2886 2329 2886 2330 2740 2330 2739 2330 2886 2331 2739 2331 2887 2331 2887 2332 2739 2332 2738 2332 2887 2333 2738 2333 2888 2333 2888 2334 2738 2334 2737 2334 2888 2335 2737 2335 2889 2335 2889 2336 2737 2336 2736 2336 2889 2337 2736 2337 2645 2337 2645 2338 2736 2338 2691 2338 2645 2339 2691 2339 2604 2339 2604 2340 2691 2340 2183 2340 2604 2341 2183 2341 2181 2341 2444 2342 2443 2342 2293 2342 2451 2343 2450 2343 2296 2343 2461 2344 2460 2344 2303 2344 2284 2345 2423 2345 2422 2345 2284 2346 2422 2346 2312 2346 2465 2347 2464 2347 2277 2347 2277 2348 2464 2348 2463 2348 2277 2349 2463 2349 2284 2349 2284 2350 2463 2350 2462 2350 2284 2351 2462 2351 2423 2351 2469 2352 2468 2352 2301 2352 2301 2353 2468 2353 2467 2353 2301 2354 2467 2354 2277 2354 2277 2355 2467 2355 2466 2355 2277 2356 2466 2356 2465 2356 2303 2357 2460 2357 2301 2357 2301 2358 2460 2358 2458 2358 2301 2359 2458 2359 2457 2359 2457 2360 2456 2360 2301 2360 2301 2361 2456 2361 2455 2361 2301 2362 2455 2362 2469 2362 2296 2363 2450 2363 2299 2363 2450 2364 2449 2364 2299 2364 2299 2365 2449 2365 2447 2365 2299 2366 2447 2366 2303 2366 2303 2367 2447 2367 2446 2367 2303 2368 2446 2368 2461 2368 2293 2369 2443 2369 2295 2369 2295 2370 2443 2370 2442 2370 2295 2371 2442 2371 2440 2371 2440 2372 2439 2372 2295 2372 2295 2373 2439 2373 2454 2373 2295 2374 2454 2374 2296 2374 2296 2375 2454 2375 2453 2375 2296 2376 2453 2376 2451 2376 2279 2377 2437 2377 2436 2377 2436 2378 2431 2378 2279 2378 2279 2379 2431 2379 2433 2379 2279 2380 2433 2380 2291 2380 2291 2381 2433 2381 2435 2381 2291 2382 2435 2382 2293 2382 2293 2383 2435 2383 2445 2383 2293 2384 2445 2384 2444 2384 2285 2385 2426 2385 2425 2385 2285 2386 2425 2386 2279 2386 2279 2387 2425 2387 2438 2387 2279 2388 2438 2388 2437 2388 2422 2389 2430 2389 2312 2389 2312 2390 2430 2390 2429 2390 2312 2391 2429 2391 2285 2391 2285 2392 2429 2392 2428 2392 2285 2393 2428 2393 2426 2393 2890 88 2891 88 2892 88 2893 88 2894 88 2895 88 2896 88 2897 88 2898 88 2899 2394 2900 2394 2901 2394 2899 2395 2901 2395 2902 2395 2902 2396 2901 2396 2903 2396 2902 2396 2903 2396 2904 2396 2904 2397 2903 2397 2905 2397 2904 2397 2905 2397 2906 2397 2907 2398 2908 2398 2909 2398 2909 2399 2908 2399 2910 2399 2910 2400 2908 2400 2911 2400 2911 2400 2908 2400 2912 2400 2911 2401 2912 2401 2913 2401 2912 2401 2914 2401 2913 2401 2913 2402 2914 2402 2915 2402 2913 2403 2915 2403 2916 2403 2916 2404 2915 2404 2917 2404 2916 2405 2917 2405 2918 2405 2918 2406 2917 2406 2919 2406 2918 2406 2919 2406 2920 2406 2920 2407 2919 2407 2921 2407 2920 2408 2921 2408 2922 2408 2922 2409 2921 2409 2923 2409 2923 2409 2921 2409 2924 2409 2923 2410 2924 2410 2925 2410 2924 2410 2926 2410 2925 2410 2925 2411 2926 2411 2927 2411 2925 2412 2927 2412 2928 2412 2928 2413 2927 2413 2929 2413 2928 2414 2929 2414 2930 2414 2930 2415 2929 2415 2931 2415 2931 2415 2929 2415 2932 2415 2931 2416 2932 2416 2933 2416 2932 2417 2934 2417 2933 2417 2933 2418 2934 2418 2935 2418 2933 2419 2935 2419 2936 2419 2937 2420 2938 2420 2939 2420 2939 2421 2938 2421 2940 2421 2939 2421 2940 2421 2941 2421 2942 2422 2943 2422 2944 2422 2944 2422 2943 2422 2945 2422 2944 2423 2945 2423 2937 2423 2937 2424 2945 2424 2946 2424 2937 2425 2946 2425 2938 2425 2899 0 2947 0 2948 0 2906 0 2949 0 2950 0 2951 0 2952 0 2899 0 2950 0 2909 0 2906 0 2906 0 2909 0 2910 0 2906 0 2910 0 2911 0 2943 0 2951 0 2953 0 2953 0 2951 0 2899 0 2953 0 2899 0 2954 0 2954 0 2899 0 2948 0 2943 0 2953 0 2945 0 2945 0 2953 0 2955 0 2945 0 2955 0 2956 0 2957 0 2899 0 2958 0 2958 0 2899 0 2902 0 2958 0 2902 0 2959 0 2959 0 2902 0 2904 0 2959 0 2904 0 2960 0 2960 0 2904 0 2906 0 2961 0 2962 0 2963 0 2964 0 2965 0 2911 0 2911 0 2965 0 2966 0 2911 0 2966 0 2906 0 2906 0 2966 0 2967 0 2906 0 2967 0 2960 0 2963 0 2968 0 2961 0 2961 0 2968 0 2969 0 2961 0 2969 0 2911 0 2957 0 2970 0 2899 0 2899 0 2970 0 2971 0 2899 0 2971 0 2947 0 2947 0 2971 0 2972 0 2972 0 2973 0 2947 0 2947 0 2973 0 2964 0 2947 0 2964 0 2974 0 2974 0 2964 0 2911 0 2974 0 2911 0 2975 0 2975 0 2911 0 2969 0 2976 0 2977 0 2936 0 2936 0 2977 0 2940 0 2978 0 2931 0 2940 0 2940 0 2931 0 2933 0 2940 0 2933 0 2936 0 2961 0 2979 0 2980 0 2978 0 2981 0 2931 0 2931 0 2981 0 2982 0 2931 0 2982 0 2961 0 2961 0 2982 0 2983 0 2961 0 2983 0 2979 0 2956 0 2962 0 2945 0 2945 0 2962 0 2961 0 2945 0 2961 0 2984 0 2984 0 2961 0 2980 0 2984 0 2985 0 2945 0 2945 0 2985 0 2986 0 2945 0 2986 0 2946 0 2946 0 2986 0 2987 0 2946 0 2987 0 2938 0 2938 0 2987 0 2988 0 2938 0 2988 0 2940 0 2940 0 2988 0 2989 0 2940 0 2989 0 2978 0 2961 0 2990 0 2991 0 2991 0 2992 0 2961 0 2961 0 2992 0 2993 0 2961 0 2993 0 2931 0 2993 0 2994 0 2931 0 2931 0 2994 0 2995 0 2931 0 2995 0 2930 0 2930 0 2995 0 2996 0 2930 0 2996 0 2928 0 2996 0 2997 0 2928 0 2928 0 2997 0 2998 0 2928 0 2998 0 2925 0 2925 0 2998 0 2999 0 2925 0 2999 0 2923 0 2923 0 2999 0 3000 0 2923 0 3000 0 3001 0 2961 0 3002 0 3003 0 3001 0 2990 0 2923 0 2923 0 2990 0 2961 0 2923 0 2961 0 2922 0 2922 0 2961 0 3003 0 2922 0 3003 0 2920 0 3004 0 2911 0 3005 0 3005 0 2911 0 2913 0 3005 0 2913 0 3006 0 3006 0 2913 0 2916 0 3004 0 3007 0 2911 0 2911 0 3007 0 3008 0 2911 0 3008 0 2961 0 2961 0 3008 0 3009 0 2961 0 3009 0 3002 0 3003 0 3010 0 2920 0 2920 0 3010 0 3011 0 2920 0 3011 0 2918 0 2918 0 3011 0 3012 0 2918 0 3012 0 2916 0 2916 0 3012 0 3013 0 2916 0 3013 0 3006 0 3014 88 3015 88 2941 88 2941 88 3015 88 2935 88 3016 88 3017 88 2932 88 2932 88 3017 88 3018 88 3019 88 3020 88 3016 88 3016 88 3020 88 3021 88 3016 88 3021 88 3017 88 3018 88 3022 88 2932 88 2932 88 3022 88 2941 88 2932 88 2941 88 2934 88 2934 88 2941 88 2935 88 3022 88 3023 88 2941 88 2941 88 3023 88 3024 88 2941 88 3024 88 2939 88 2939 88 3024 88 3025 88 2939 88 3025 88 2937 88 2937 88 3025 88 3026 88 2937 88 3026 88 2944 88 2944 88 3026 88 3027 88 2944 88 3027 88 3028 88 2901 88 2900 88 2912 88 3029 88 3030 88 2907 88 2907 88 3030 88 2905 88 2907 88 2905 88 2908 88 2908 88 2905 88 2912 88 2912 88 2905 88 2903 88 2912 88 2903 88 2901 88 3031 88 3032 88 2900 88 2900 88 3032 88 2942 88 3033 88 3034 88 2942 88 2912 88 3035 88 3016 88 3016 88 3035 88 3036 88 3016 88 3036 88 3037 88 3037 88 3038 88 3016 88 3016 88 3038 88 2944 88 3016 88 2944 88 3019 88 3019 88 2944 88 3028 88 3039 88 3040 88 3041 88 3033 88 2942 88 3042 88 3043 88 2912 88 3044 88 3044 88 2912 88 2900 88 3044 88 2900 88 3045 88 3045 88 2900 88 2942 88 3045 88 2942 88 3046 88 3046 88 2942 88 3034 88 3043 88 3047 88 2912 88 2912 88 3047 88 3048 88 2912 88 3048 88 3040 88 3039 88 3041 88 3049 88 3039 88 3050 88 3040 88 3040 88 3050 88 3051 88 3040 88 3051 88 2912 88 2912 88 3051 88 3052 88 2912 88 3052 88 3035 88 3038 88 3053 88 2944 88 2944 88 3053 88 3054 88 2944 88 3054 88 2942 88 2942 88 3054 88 3055 88 2942 88 3055 88 3042 88 3042 88 3055 88 3049 88 3042 88 3049 88 3056 88 3056 88 3049 88 3041 88 3057 88 3058 88 3016 88 3016 88 3058 88 3059 88 2912 88 3060 88 2914 88 2914 88 3060 88 3061 88 2914 88 3061 88 2915 88 3059 88 3062 88 3016 88 3016 88 3062 88 3063 88 3016 88 3063 88 2912 88 2912 88 3063 88 3064 88 2912 88 3064 88 3060 88 2932 88 3065 88 3066 88 2932 88 3066 88 3016 88 3016 88 3066 88 3067 88 3016 88 3067 88 3068 88 3069 88 3070 88 2924 88 2924 88 3070 88 3071 88 2924 88 3071 88 2926 88 2926 88 3071 88 3072 88 2926 88 3072 88 2927 88 3072 88 3073 88 2927 88 2927 88 3073 88 3074 88 2927 88 3074 88 2929 88 2929 88 3074 88 3075 88 2929 88 3075 88 2932 88 2932 88 3075 88 3076 88 2932 88 3076 88 3065 88 3068 88 3069 88 3016 88 3016 88 3069 88 2924 88 3016 88 2924 88 3057 88 3057 88 2924 88 2921 88 3057 88 2921 88 3077 88 3077 88 2921 88 2919 88 3077 88 2919 88 3078 88 3078 88 2919 88 2917 88 3078 88 2917 88 3079 88 3079 88 2917 88 2915 88 3079 88 2915 88 3080 88 3080 88 2915 88 3061 88 3066 272 2993 272 3067 272 3067 271 2993 271 2992 271 3067 273 2992 273 3068 273 3068 274 2992 274 2991 274 3068 275 2991 275 3069 275 3069 275 2991 275 2990 275 3069 276 2990 276 3070 276 3070 276 2990 276 3001 276 3070 294 3001 294 3071 294 3071 294 3001 294 3000 294 3071 289 3000 289 3072 289 3072 289 3000 289 2999 289 3072 264 2999 264 3073 264 3073 263 2999 263 2998 263 3073 265 2998 265 3074 265 3074 266 2998 266 2997 266 3074 267 2997 267 3075 267 3075 267 2997 267 2996 267 3075 268 2996 268 3076 268 3076 268 2996 268 2995 268 3076 291 2995 291 3065 291 3065 291 2995 291 2994 291 3065 292 2994 292 3066 292 3066 292 2994 292 2993 292 3026 285 2987 285 3027 285 3027 271 2987 271 2986 271 3027 274 2986 274 3028 274 3028 293 2986 293 2985 293 3028 286 2985 286 3019 286 3019 286 2985 286 2984 286 3019 276 2984 276 3020 276 3020 276 2984 276 2980 276 3020 299 2980 299 3021 299 3021 299 2980 299 2979 299 3021 300 2979 300 3017 300 3017 301 2979 301 2983 301 3017 264 2983 264 3018 264 3018 279 2983 279 2982 279 3018 265 2982 265 3022 265 3022 266 2982 266 2981 266 3022 281 2981 281 3023 281 3023 267 2981 267 2978 267 3023 268 2978 268 3024 268 3024 268 2978 268 2989 268 3024 2426 2989 2426 3025 2426 3025 297 2989 297 2988 297 3025 270 2988 270 3026 270 3026 2427 2988 2427 2987 2427 3046 272 2958 272 3045 272 3045 271 2958 271 2959 271 3045 274 2959 274 3044 274 3044 273 2959 273 2960 273 3044 275 2960 275 3043 275 3043 275 2960 275 2967 275 3043 276 2967 276 3047 276 3047 276 2967 276 2966 276 3047 277 2966 277 3048 277 3048 277 2966 277 2965 277 3048 278 2965 278 3040 278 3040 301 2965 301 2964 301 3040 264 2964 264 3041 264 3041 263 2964 263 2973 263 3041 280 2973 280 3056 280 3056 266 2973 266 2972 266 3056 267 2972 267 3042 267 3042 281 2972 281 2971 281 3042 268 2971 268 3033 268 3033 268 2971 268 2970 268 3033 297 2970 297 3034 297 3034 269 2970 269 2957 269 3034 298 2957 298 3046 298 3046 2428 2957 2428 2958 2428 3063 271 3008 271 3064 271 3064 285 3008 285 3007 285 3064 273 3007 273 3060 273 3060 274 3007 274 3004 274 3060 286 3004 286 3061 286 3061 275 3004 275 3005 275 3061 276 3005 276 3080 276 3080 276 3005 276 3006 276 3080 294 3006 294 3079 294 3079 288 3006 288 3013 288 3079 295 3013 295 3078 295 3078 289 3013 289 3012 289 3078 279 3012 279 3077 279 3077 264 3012 264 3011 264 3077 266 3011 266 3057 266 3057 280 3011 280 3010 280 3057 281 3010 281 3058 281 3058 281 3010 281 3003 281 3058 268 3003 268 3059 268 3059 268 3003 268 3002 268 3059 282 3002 282 3062 282 3062 282 3002 282 3009 282 3062 283 3009 283 3063 283 3063 284 3009 284 3008 284 3055 310 2953 310 3049 310 3049 310 2953 310 2954 310 3049 311 2954 311 3039 311 3039 311 2954 311 2948 311 3039 312 2948 312 3050 312 3050 313 2948 313 2947 313 3050 314 2947 314 3051 314 3051 314 2947 314 2974 314 3051 315 2974 315 3052 315 3052 316 2974 316 2975 316 3052 317 2975 317 3035 317 3035 317 2975 317 2969 317 3035 302 2969 302 3036 302 3036 302 2969 302 2968 302 3036 303 2968 303 3037 303 3037 303 2968 303 2963 303 3037 304 2963 304 3038 304 3038 305 2963 305 2962 305 3038 306 2962 306 3053 306 3053 306 2962 306 2956 306 3053 307 2956 307 3054 307 3054 308 2956 308 2955 308 3054 309 2955 309 3055 309 3055 309 2955 309 2953 309 2943 2429 2942 2429 2951 2429 2951 2430 2942 2430 3032 2430 2951 2431 3032 2431 3081 2431 3081 2432 3032 2432 3082 2432 3081 2433 3082 2433 3083 2433 3083 2434 3082 2434 3084 2434 3083 2435 3084 2435 3085 2435 3085 2436 3084 2436 2891 2436 3086 2437 2892 2437 3087 2437 3087 2438 2892 2438 3088 2438 3087 2439 3088 2439 3089 2439 3089 2440 3088 2440 3090 2440 3089 2441 3090 2441 2952 2441 2952 2442 3090 2442 3031 2442 2952 2439 3031 2439 2899 2439 2899 2443 3031 2443 2900 2443 3088 2444 3084 2444 3090 2444 3090 2445 3084 2445 3082 2445 2892 2446 2891 2446 3088 2446 3088 2447 2891 2447 3084 2447 3087 2448 3083 2448 3086 2448 3086 2449 3083 2449 3085 2449 3089 2450 3081 2450 3087 2450 3087 2450 3081 2450 3083 2450 2952 2451 2951 2451 3089 2451 3089 2452 2951 2452 3081 2452 3090 2453 3082 2453 3031 2453 3031 2454 3082 2454 3032 2454 2936 2455 2935 2455 2976 2455 2976 2456 2935 2456 3015 2456 2976 2457 3015 2457 3091 2457 3091 2458 3015 2458 3092 2458 3091 2459 3092 2459 3093 2459 3093 2460 3092 2460 3094 2460 3093 2461 3094 2461 3095 2461 3095 2462 3094 2462 2894 2462 3095 2461 2894 2461 3096 2461 3096 2463 2894 2463 3097 2463 3098 2464 2895 2464 3099 2464 3099 2465 2895 2465 3100 2465 3099 2466 3100 2466 3101 2466 3101 2467 3100 2467 3102 2467 3101 2468 3102 2468 2977 2468 2977 2469 3102 2469 3014 2469 2977 2470 3014 2470 2940 2470 2940 2471 3014 2471 2941 2471 3100 2472 3094 2472 3102 2472 3102 2473 3094 2473 3092 2473 2895 2474 2894 2474 3100 2474 3100 2474 2894 2474 3094 2474 3099 2475 3093 2475 3098 2475 3098 2475 3093 2475 3095 2475 3101 2476 3091 2476 3099 2476 3099 2477 3091 2477 3093 2477 2977 2478 2976 2478 3101 2478 3101 2479 2976 2479 3091 2479 3102 2480 3092 2480 3014 2480 3014 2481 3092 2481 3015 2481 2906 2482 2905 2482 2949 2482 2949 2483 2905 2483 3030 2483 2949 2484 3030 2484 3103 2484 3103 2485 3030 2485 3104 2485 3103 2486 3104 2486 3105 2486 3105 2487 3104 2487 3106 2487 3105 2488 3106 2488 3107 2488 3107 2489 3106 2489 2897 2489 3108 2490 3109 2490 3110 2490 3110 2490 3109 2490 2898 2490 3110 2491 2898 2491 3111 2491 3111 2492 2898 2492 3112 2492 3111 2493 3112 2493 3113 2493 3113 2494 3112 2494 3114 2494 3113 2495 3114 2495 2950 2495 2950 2496 3114 2496 3029 2496 2950 2497 3029 2497 2909 2497 2909 2498 3029 2498 2907 2498 3112 2499 3106 2499 3114 2499 3114 2500 3106 2500 3104 2500 2898 2501 2897 2501 3112 2501 3112 2502 2897 2502 3106 2502 3111 2503 3105 2503 3110 2503 3110 2504 3105 2504 3107 2504 3113 2505 3103 2505 3111 2505 3111 2506 3103 2506 3105 2506 2950 2507 2949 2507 3113 2507 3113 2508 2949 2508 3103 2508 3114 2509 3104 2509 3029 2509 3029 2510 3104 2510 3030 2510 2892 0 3086 0 3115 0 3115 0 3086 0 3116 0 3115 0 3116 0 3117 0 3117 0 3116 0 3118 0 3117 0 3118 0 3119 0 3119 0 3118 0 3120 0 3119 0 3120 0 3121 0 3121 0 3120 0 3122 0 3121 0 3122 0 3123 0 3123 0 3122 0 3124 0 3123 0 3124 0 3125 0 3125 0 3124 0 3126 0 3125 0 3126 0 3127 0 3127 0 3126 0 3128 0 3127 0 3128 0 3129 0 3129 0 3128 0 3130 0 3129 0 3130 0 2897 0 2897 0 3130 0 3107 0 2895 0 3098 0 3131 0 3131 0 3098 0 3132 0 3131 0 3132 0 3133 0 3133 0 3132 0 3134 0 3133 0 3134 0 3135 0 3135 0 3134 0 3136 0 3135 0 3136 0 3137 0 3137 0 3136 0 3138 0 3137 0 3138 0 3139 0 3139 0 3138 0 3140 0 3139 0 3140 0 3141 0 3141 0 3140 0 3142 0 3141 0 3142 0 3143 0 3143 0 3142 0 3144 0 3143 0 3144 0 3145 0 3145 0 3144 0 3146 0 3145 0 3146 0 2891 0 2891 0 3146 0 3085 0 3085 0 3147 0 3086 0 3095 0 3148 0 3098 0 3148 2511 3095 2511 3096 2511 3110 2512 3149 2512 3108 2512 3108 2513 3149 2513 3107 2513 3108 2514 3107 2514 3150 2514 3107 2515 3130 2515 3150 2515 3150 2516 3130 2516 3128 2516 3150 2517 3128 2517 3151 2517 3151 2518 3128 2518 3126 2518 3151 2518 3126 2518 3152 2518 3152 2519 3126 2519 3124 2519 3152 2520 3124 2520 3153 2520 3153 2521 3124 2521 3122 2521 3153 2522 3122 2522 3154 2522 3154 2523 3122 2523 3120 2523 3154 2523 3120 2523 3155 2523 3155 2524 3120 2524 3118 2524 3155 2524 3118 2524 3156 2524 3156 2525 3118 2525 3116 2525 3156 2526 3116 2526 3157 2526 3116 2527 3086 2527 3157 2527 3157 2528 3086 2528 3147 2528 3157 2529 3147 2529 3158 2529 3158 2530 3147 2530 3085 2530 3085 2531 3146 2531 3158 2531 3158 2532 3146 2532 3144 2532 3158 2533 3144 2533 3159 2533 3159 2534 3144 2534 3142 2534 3159 2535 3142 2535 3160 2535 3160 2536 3142 2536 3140 2536 3160 2537 3140 2537 3161 2537 3161 2538 3140 2538 3138 2538 3161 2538 3138 2538 3162 2538 3162 2539 3138 2539 3136 2539 3162 2539 3136 2539 3163 2539 3163 2540 3136 2540 3134 2540 3163 2541 3134 2541 3164 2541 3164 2542 3134 2542 3132 2542 3164 2543 3132 2543 3165 2543 3165 2544 3132 2544 3096 2544 3096 2545 3132 2545 3098 2545 3096 2546 3098 2546 3148 2546 2896 2547 2898 2547 3109 2547 2894 2548 2893 2548 3097 2548 3097 2549 2893 2549 2895 2549 3097 2550 2895 2550 3166 2550 3166 2551 2895 2551 3131 2551 3166 2552 3131 2552 3167 2552 3167 2552 3131 2552 3133 2552 3167 2553 3133 2553 3168 2553 3168 2553 3133 2553 3135 2553 3168 2554 3135 2554 3169 2554 3169 2554 3135 2554 3137 2554 3169 2555 3137 2555 3170 2555 3170 2556 3137 2556 3139 2556 3170 2557 3139 2557 3171 2557 3171 2557 3139 2557 3141 2557 3171 2558 3141 2558 3172 2558 3172 2559 3141 2559 3143 2559 3172 2560 3143 2560 3173 2560 3173 2561 3143 2561 3145 2561 3145 2562 2891 2562 3173 2562 3173 2563 2891 2563 2890 2563 3173 2564 2890 2564 3174 2564 2890 2565 2892 2565 3174 2565 3174 2566 2892 2566 3115 2566 3174 2567 3115 2567 3175 2567 3175 2568 3115 2568 3117 2568 3175 2569 3117 2569 3176 2569 3176 2570 3117 2570 3119 2570 3176 2571 3119 2571 3177 2571 3177 2572 3119 2572 3121 2572 3177 2573 3121 2573 3178 2573 3178 2574 3121 2574 3123 2574 3178 2575 3123 2575 3179 2575 3179 2576 3123 2576 3125 2576 3179 2577 3125 2577 3180 2577 3180 2578 3125 2578 3127 2578 3180 2579 3127 2579 3181 2579 3181 2580 3127 2580 3129 2580 3181 2581 3129 2581 3109 2581 3109 2582 3129 2582 2897 2582 3109 2583 2897 2583 2896 2583 3109 88 3108 88 3181 88 3181 88 3108 88 3150 88 3181 88 3150 88 3180 88 3180 88 3150 88 3151 88 3180 88 3151 88 3179 88 3179 88 3151 88 3152 88 3179 2584 3152 2584 3178 2584 3178 2585 3152 2585 3153 2585 3178 88 3153 88 3177 88 3177 88 3153 88 3154 88 3177 88 3154 88 3176 88 3176 88 3154 88 3155 88 3176 88 3155 88 3175 88 3175 88 3155 88 3156 88 3175 2586 3156 2586 3174 2586 3174 88 3156 88 3157 88 3174 88 3157 88 3173 88 3173 88 3157 88 3158 88 3173 88 3158 88 3172 88 3172 88 3158 88 3159 88 3172 88 3159 88 3171 88 3171 88 3159 88 3160 88 3171 88 3160 88 3170 88 3170 88 3160 88 3161 88 3170 88 3161 88 3169 88 3169 88 3161 88 3162 88 3169 88 3162 88 3168 88 3168 88 3162 88 3163 88 3168 88 3163 88 3167 88 3167 88 3163 88 3164 88 3167 88 3164 88 3166 88 3166 88 3164 88 3165 88 3166 88 3165 88 3097 88 3097 88 3165 88 3096 88 3107 2587 3149 2587 3110 2587 3182 88 3183 88 3184 88 3185 88 3186 88 3187 88 3188 88 3189 88 3190 88 3191 88 3192 88 3193 88 3194 88 3195 88 3196 88 3197 88 3198 88 3199 88 3200 88 3201 88 3202 88 3203 2588 3204 2588 3205 2588 3206 88 3207 88 3205 88 3208 88 3209 88 3210 88 3211 88 3212 88 3213 88 3214 88 3215 88 3216 88 3217 88 3218 88 3219 88 3218 88 3220 88 3219 88 3219 88 3220 88 3221 88 3219 88 3221 88 3222 88 3222 88 3221 88 3223 88 3222 88 3223 88 3224 88 3224 88 3223 88 3225 88 3224 88 3225 88 3226 88 3227 88 3228 88 3229 88 3229 88 3228 88 3230 88 3230 88 3228 88 3231 88 3230 88 3231 88 3232 88 3233 88 3234 88 3235 88 3235 88 3234 88 3236 88 3235 88 3236 88 3237 88 3237 88 3236 88 3238 88 3237 88 3238 88 3239 88 3240 88 3241 88 3242 88 3208 88 3210 88 3243 88 3243 88 3210 88 3244 88 3243 88 3244 88 3245 88 3246 88 3247 88 3245 88 3248 88 3249 88 3250 88 3247 88 3246 88 3251 88 3251 88 3246 88 3248 88 3251 88 3248 88 3252 88 3252 88 3248 88 3250 88 3252 88 3250 88 3253 88 3254 88 3205 88 3255 88 3255 88 3205 88 3207 88 3255 88 3207 88 3256 88 3254 88 3257 88 3205 88 3205 88 3257 88 3258 88 3205 88 3258 88 3259 88 3259 88 3258 88 3260 88 3259 88 3260 88 3248 88 3248 88 3260 88 3261 88 3248 88 3261 88 3249 88 3253 88 3262 88 3252 88 3252 88 3262 88 3263 88 3252 88 3263 88 3264 88 3264 88 3263 88 3265 88 3264 88 3265 88 3207 88 3207 88 3265 88 3266 88 3207 88 3266 88 3256 88 3204 88 3267 88 3205 88 3205 88 3267 88 3268 88 3205 88 3268 88 3206 88 3200 88 3202 88 3269 88 3270 88 3271 88 3272 88 3272 88 3271 88 3273 88 3274 88 3275 88 3276 88 3276 88 3275 88 3277 88 3276 88 3277 88 3278 88 3279 88 3280 88 3281 88 3281 88 3280 88 3282 88 3281 88 3282 88 3283 88 3283 88 3282 88 3284 88 3283 88 3284 88 3285 88 3197 88 3199 88 3286 88 3286 88 3199 88 3287 88 3286 88 3287 88 3288 88 3288 88 3287 88 3289 88 3288 88 3289 88 3195 88 3290 88 3291 88 3292 88 3292 88 3291 88 3293 88 3292 88 3293 88 3196 88 3196 88 3293 88 3294 88 3196 88 3294 88 3194 88 3295 88 3296 88 3297 88 3297 88 3296 88 3298 88 3297 88 3298 88 3299 88 3300 88 3301 88 3302 88 3302 88 3301 88 3303 88 3292 88 3304 88 3290 88 3290 88 3304 88 3302 88 3290 88 3302 88 3305 88 3305 88 3302 88 3303 88 3303 88 3306 88 3305 88 3305 88 3306 88 3307 88 3305 88 3307 88 3308 88 3308 88 3307 88 3309 88 3308 88 3309 88 3310 88 3310 88 3309 88 3311 88 3311 88 3309 88 3312 88 3311 88 3312 88 3313 88 3314 88 3315 88 3311 88 3316 88 3315 88 3317 88 3317 88 3315 88 3314 88 3317 88 3314 88 3318 88 3319 88 3320 88 3321 88 3321 88 3320 88 3322 88 3322 88 3323 88 3190 88 3190 88 3323 88 3324 88 3190 88 3324 88 3325 88 3324 88 3326 88 3325 88 3325 88 3326 88 3327 88 3325 2589 3327 2589 3328 2589 3328 88 3327 88 3329 88 3328 88 3329 88 3330 88 3330 88 3329 88 3331 88 3330 88 3331 88 3332 88 3332 88 3331 88 3333 88 3332 88 3333 88 3334 88 3334 88 3333 88 3335 88 3334 88 3335 88 3336 88 3336 88 3335 88 3337 88 3336 88 3337 88 3338 88 3246 88 3339 88 3340 88 3341 88 3342 88 3193 88 3193 88 3342 88 3343 88 3193 88 3343 88 3344 88 3245 88 3244 88 3246 88 3246 88 3244 88 3345 88 3246 88 3345 88 3339 88 3343 88 3346 88 3344 88 3344 88 3346 88 3347 88 3344 88 3347 88 3348 88 3349 88 3350 88 3210 88 3210 88 3350 88 3351 88 3210 88 3351 88 3244 88 3244 88 3351 88 3352 88 3244 88 3352 88 3345 88 3353 88 3354 88 3355 88 3355 88 3356 88 3353 88 3353 88 3356 88 3357 88 3353 88 3357 88 3358 88 3359 88 3360 88 3361 88 3361 88 3360 88 3362 88 3361 88 3362 88 3354 88 3354 88 3362 88 3363 88 3354 88 3363 88 3355 88 3364 88 3365 88 3366 88 3366 88 3365 88 3367 88 3366 88 3367 88 3368 88 3369 88 3370 88 3371 88 3371 88 3370 88 3372 88 3373 88 3374 88 3318 88 3318 88 3374 88 3375 88 3374 88 3376 88 3375 88 3375 88 3376 88 3377 88 3375 88 3377 88 3378 88 3378 88 3377 88 3379 88 3380 88 3381 88 3382 88 3340 88 3341 88 3246 88 3246 88 3341 88 3193 88 3246 88 3193 88 3383 88 3383 88 3193 88 3192 88 3322 88 3190 88 3321 88 3321 88 3190 88 3189 88 3321 88 3189 88 3384 88 3384 88 3385 88 3321 88 3321 88 3385 88 3386 88 3321 88 3386 88 3387 88 3387 88 3386 88 3388 88 3387 88 3388 88 3389 88 3389 88 3388 88 3390 88 3389 88 3390 88 3391 88 3383 88 3392 88 3246 88 3246 88 3392 88 3393 88 3246 88 3393 88 3248 88 3248 88 3393 88 3394 88 3248 88 3394 88 3259 88 3259 88 3394 88 3395 88 3259 88 3395 88 3396 88 3397 88 3398 88 3399 88 3399 88 3398 88 3400 88 3401 88 3297 88 3302 88 3302 88 3297 88 3299 88 3302 88 3299 88 3300 88 3402 88 3403 88 3404 88 3404 88 3403 88 3405 88 3404 88 3405 88 3406 88 3406 88 3405 88 3407 88 3406 88 3407 88 3408 88 3408 88 3407 88 3409 88 3408 88 3409 88 3410 88 3411 88 3361 88 3412 88 3412 88 3361 88 3413 88 3413 88 3361 88 3414 88 3414 88 3361 88 3354 88 3414 88 3354 88 3415 88 3313 88 3295 88 3311 88 3311 88 3295 88 3297 88 3311 88 3297 88 3314 88 3314 88 3297 88 3371 88 3314 88 3371 88 3318 88 3318 88 3371 88 3372 88 3318 88 3372 88 3373 88 3401 88 3400 88 3297 88 3297 88 3400 88 3398 88 3297 88 3398 88 3371 88 3371 88 3398 88 3397 88 3371 88 3397 88 3369 88 3369 88 3397 88 3416 88 3369 88 3416 88 3417 88 3417 88 3416 88 3184 88 3417 88 3184 88 3418 88 3418 88 3184 88 3183 88 3418 88 3183 88 3415 88 3415 88 3183 88 3182 88 3415 88 3182 88 3414 88 3195 88 3289 88 3196 88 3196 88 3289 88 3407 88 3196 88 3407 88 3292 88 3292 88 3407 88 3405 88 3292 88 3405 88 3304 88 3304 88 3405 88 3403 88 3304 88 3403 88 3302 88 3302 88 3403 88 3402 88 3302 88 3402 88 3401 88 3419 88 3420 88 3409 88 3419 88 3409 88 3421 88 3421 88 3409 88 3407 88 3421 88 3407 88 3422 88 3423 88 3424 88 3287 88 3287 88 3424 88 3425 88 3287 88 3425 88 3289 88 3289 88 3425 88 3426 88 3289 88 3426 88 3427 88 3427 88 3428 88 3289 88 3289 88 3428 88 3429 88 3289 88 3429 88 3407 88 3407 88 3429 88 3430 88 3407 88 3430 88 3422 88 3208 88 3240 88 3209 88 3209 88 3240 88 3242 88 3209 88 3242 88 3210 88 3210 88 3242 88 3348 88 3210 88 3348 88 3349 88 3349 88 3348 88 3347 88 3431 88 3316 88 3432 88 3432 88 3316 88 3317 88 3432 88 3317 88 3433 88 3433 88 3317 88 3318 88 3433 88 3318 88 3434 88 3434 88 3318 88 3375 88 3434 88 3375 88 3435 88 3435 88 3375 88 3378 88 3435 88 3378 88 3231 88 3231 88 3378 88 3216 88 3231 88 3216 88 3232 88 3232 88 3216 88 3215 88 3379 88 3381 88 3378 88 3378 88 3381 88 3380 88 3378 88 3380 88 3216 88 3216 88 3380 88 3224 88 3216 88 3224 88 3214 88 3214 88 3224 88 3226 88 3412 88 3185 88 3411 88 3411 88 3185 88 3187 88 3411 88 3187 88 3361 88 3361 88 3187 88 3368 88 3361 88 3368 88 3359 88 3359 88 3368 88 3367 88 3420 88 3423 88 3409 88 3409 88 3423 88 3287 88 3409 88 3287 88 3436 88 3436 88 3287 88 3199 88 3436 88 3199 88 3284 88 3284 88 3199 88 3198 88 3284 88 3198 88 3285 88 3285 88 3198 88 3197 88 3241 88 3239 88 3242 88 3242 88 3239 88 3238 88 3242 88 3238 88 3348 88 3348 88 3238 88 3437 88 3348 88 3437 88 3344 88 3344 88 3437 88 3438 88 3344 88 3438 88 3193 88 3193 88 3438 88 3389 88 3193 88 3389 88 3191 88 3191 88 3389 88 3391 88 3358 88 3439 88 3353 88 3353 88 3439 88 3440 88 3353 88 3440 88 3277 88 3277 88 3440 88 3441 88 3277 88 3441 88 3278 88 3439 88 3364 88 3440 88 3440 88 3364 88 3366 88 3440 88 3366 88 3441 88 3441 88 3366 88 3442 88 3441 88 3442 88 3278 88 3278 88 3442 88 3443 88 3185 88 3410 88 3186 88 3186 88 3410 88 3409 88 3186 88 3409 88 3187 88 3187 88 3409 88 3436 88 3187 88 3436 88 3368 88 3368 88 3436 88 3284 88 3368 88 3284 88 3366 88 3366 88 3284 88 3282 88 3366 88 3282 88 3442 88 3442 88 3282 88 3280 88 3442 88 3280 88 3443 88 3443 88 3280 88 3279 88 3233 88 3431 88 3234 88 3234 88 3431 88 3432 88 3234 88 3432 88 3236 88 3236 88 3432 88 3433 88 3236 88 3433 88 3238 88 3238 88 3433 88 3434 88 3238 88 3434 88 3437 88 3437 88 3434 88 3435 88 3437 88 3435 88 3438 88 3438 88 3435 88 3231 88 3438 88 3231 88 3389 88 3389 88 3231 88 3228 88 3389 88 3228 88 3387 88 3387 88 3228 88 3227 88 3387 88 3227 88 3321 88 3321 88 3227 88 3338 88 3321 88 3338 88 3319 88 3319 88 3338 88 3337 88 3382 88 3418 88 3380 88 3380 88 3418 88 3415 88 3380 88 3415 88 3224 88 3224 88 3415 88 3354 88 3224 88 3354 88 3222 88 3222 88 3354 88 3353 88 3222 88 3353 88 3219 88 3219 88 3353 88 3277 88 3219 88 3277 88 3270 88 3270 88 3277 88 3275 88 3270 88 3275 88 3271 88 3271 88 3275 88 3274 88 3396 88 3188 88 3259 88 3259 88 3188 88 3190 88 3259 88 3190 88 3205 88 3205 88 3190 88 3325 88 3205 90 3325 90 3203 90 3203 88 3325 88 3328 88 3229 88 3211 88 3227 88 3227 88 3211 88 3213 88 3227 88 3213 88 3338 88 3338 88 3213 88 3444 88 3338 88 3444 88 3336 88 3336 88 3444 88 3202 88 3336 88 3202 88 3334 88 3334 88 3202 88 3201 88 3212 88 3217 88 3213 88 3213 88 3217 88 3219 88 3213 88 3219 88 3444 88 3444 88 3219 88 3270 88 3444 88 3270 88 3202 88 3202 88 3270 88 3272 88 3202 88 3272 88 3269 88 3269 88 3272 88 3273 88 3237 771 3445 771 3446 771 3237 2590 3446 2590 3235 2590 3235 773 3446 773 3447 773 3235 773 3447 773 3233 773 3233 2591 3447 2591 3448 2591 3233 2592 3448 2592 3431 2592 3431 2593 3448 2593 3449 2593 3431 2594 3449 2594 3316 2594 3316 2595 3449 2595 3450 2595 3316 2596 3450 2596 3315 2596 3315 2597 3450 2597 3451 2597 3315 2598 3451 2598 3311 2598 3311 2599 3451 2599 3452 2599 3311 2600 3452 2600 3310 2600 3310 787 3452 787 3453 787 3310 2601 3453 2601 3308 2601 3308 2602 3453 2602 3305 2602 3305 2602 3453 2602 3454 2602 3305 2603 3454 2603 3290 2603 3454 2603 3455 2603 3290 2603 3290 2604 3455 2604 3456 2604 3290 2605 3456 2605 3291 2605 3291 2606 3456 2606 3457 2606 3291 2606 3457 2606 3293 2606 3293 2607 3457 2607 3458 2607 3293 2607 3458 2607 3294 2607 3294 2608 3458 2608 3459 2608 3294 2608 3459 2608 3194 2608 3194 2609 3459 2609 3460 2609 3194 2610 3460 2610 3195 2610 3195 800 3460 800 3461 800 3195 800 3461 800 3288 800 3288 2611 3461 2611 3462 2611 3288 2612 3462 2612 3286 2612 3286 2613 3462 2613 3463 2613 3286 2614 3463 2614 3197 2614 3197 805 3463 805 3464 805 3197 2615 3464 2615 3285 2615 3285 2616 3464 2616 3465 2616 3285 2617 3465 2617 3283 2617 3283 807 3465 807 3466 807 3283 807 3466 807 3281 807 3281 2618 3466 2618 3467 2618 3281 2619 3467 2619 3279 2619 3279 2620 3467 2620 3468 2620 3279 2621 3468 2621 3443 2621 3443 2622 3468 2622 3469 2622 3443 2623 3469 2623 3278 2623 3278 814 3469 814 3470 814 3278 815 3470 815 3276 815 3276 729 3470 729 3471 729 3276 729 3471 729 3274 729 3274 2624 3471 2624 3472 2624 3274 731 3472 731 3271 731 3271 2625 3472 2625 3473 2625 3271 2626 3473 2626 3273 2626 3273 2627 3473 2627 3474 2627 3273 2628 3474 2628 3269 2628 3269 2629 3474 2629 3475 2629 3269 2630 3475 2630 3200 2630 3200 2631 3475 2631 3201 2631 3201 2631 3475 2631 3476 2631 3201 2632 3476 2632 3334 2632 3334 2632 3476 2632 3477 2632 3334 2633 3477 2633 3332 2633 3332 2634 3477 2634 3478 2634 3332 2635 3478 2635 3330 2635 3478 2635 3479 2635 3330 2635 3330 2636 3479 2636 3480 2636 3330 2637 3480 2637 3328 2637 3328 742 3480 742 3481 742 3328 2638 3481 2638 3203 2638 3203 2639 3481 2639 3482 2639 3203 2640 3482 2640 3204 2640 3204 2641 3482 2641 3483 2641 3204 2642 3483 2642 3267 2642 3267 2643 3483 2643 3484 2643 3267 2644 3484 2644 3268 2644 3268 2645 3484 2645 3485 2645 3268 2646 3485 2646 3206 2646 3206 2647 3485 2647 3486 2647 3206 2648 3486 2648 3207 2648 3207 2649 3486 2649 3487 2649 3207 2649 3487 2649 3264 2649 3264 753 3487 753 3488 753 3264 753 3488 753 3252 753 3252 2650 3488 2650 3489 2650 3252 2651 3489 2651 3251 2651 3251 2652 3489 2652 3490 2652 3251 2652 3490 2652 3247 2652 3247 2653 3490 2653 3491 2653 3247 758 3491 758 3245 758 3245 2654 3491 2654 3492 2654 3245 2654 3492 2654 3243 2654 3243 762 3492 762 3493 762 3243 762 3493 762 3208 762 3208 2655 3493 2655 3494 2655 3208 2656 3494 2656 3240 2656 3240 2657 3494 2657 3495 2657 3240 2658 3495 2658 3241 2658 3241 2659 3495 2659 3496 2659 3241 2660 3496 2660 3239 2660 3239 769 3496 769 3445 769 3239 770 3445 770 3237 770 3497 0 3498 0 3499 0 3500 0 3501 0 3502 0 3503 0 3504 0 3505 0 3506 0 3507 0 3508 0 3509 0 3510 0 3511 0 3512 0 3513 0 3514 0 3456 0 3455 0 3515 0 3447 0 3516 0 3517 0 3495 0 3494 0 3518 0 3470 0 3469 0 3519 0 3520 0 3521 0 3471 0 3522 0 3474 0 3473 0 3474 0 3522 0 3475 0 3475 0 3522 0 3523 0 3475 0 3523 0 3476 0 3476 0 3523 0 3524 0 3476 0 3524 0 3477 0 3484 0 3483 0 3525 0 3525 0 3483 0 3482 0 3525 0 3482 0 3481 0 3526 0 3527 0 3525 0 3527 0 3486 0 3525 0 3525 0 3486 0 3485 0 3525 0 3485 0 3484 0 3528 0 3529 0 3530 0 3528 0 3530 0 3531 0 3529 0 3532 0 3530 0 3530 0 3532 0 3533 0 3530 0 3533 0 3534 0 3534 0 3533 0 3535 0 3534 0 3535 0 3525 0 3525 0 3535 0 3536 0 3525 0 3536 0 3526 0 3527 0 3537 0 3486 0 3486 0 3537 0 3538 0 3486 0 3538 0 3487 0 3487 0 3538 0 3539 0 3487 0 3539 0 3488 0 3488 0 3539 0 3540 0 3488 0 3540 0 3541 0 3494 0 3493 0 3518 0 3518 0 3493 0 3492 0 3518 0 3492 0 3542 0 3542 0 3492 0 3491 0 3542 0 3491 0 3543 0 3543 0 3491 0 3490 0 3543 0 3490 0 3544 0 3544 0 3490 0 3489 0 3544 0 3489 0 3530 0 3530 0 3489 0 3488 0 3530 0 3488 0 3531 0 3531 0 3488 0 3541 0 3445 0 3496 0 3545 0 3545 0 3496 0 3495 0 3546 0 3446 0 3547 0 3547 0 3446 0 3445 0 3447 0 3517 0 3448 0 3448 0 3517 0 3548 0 3448 0 3548 0 3449 0 3449 0 3548 0 3549 0 3449 0 3549 0 3450 0 3450 0 3549 0 3550 0 3450 0 3550 0 3451 0 3551 0 3552 0 3550 0 3451 0 3553 0 3452 0 3452 0 3553 0 3554 0 3452 0 3554 0 3453 0 3453 0 3554 0 3555 0 3453 0 3555 0 3454 0 3454 0 3555 0 3556 0 3454 0 3556 0 3557 0 3558 0 3559 0 3560 0 3560 0 3559 0 3551 0 3552 0 3561 0 3550 0 3550 0 3561 0 3562 0 3550 0 3562 0 3451 0 3451 0 3562 0 3563 0 3451 0 3563 0 3553 0 3515 0 3455 0 3564 0 3564 0 3455 0 3454 0 3564 0 3454 0 3560 0 3560 0 3454 0 3557 0 3560 0 3557 0 3558 0 3460 0 3459 0 3565 0 3565 0 3459 0 3458 0 3565 0 3458 0 3515 0 3515 0 3458 0 3457 0 3515 0 3457 0 3456 0 3463 0 3462 0 3566 0 3566 0 3462 0 3567 0 3566 0 3567 0 3568 0 3497 0 3468 0 3498 0 3498 0 3468 0 3467 0 3498 0 3467 0 3499 0 3499 0 3467 0 3466 0 3499 0 3466 0 3465 0 3569 0 3570 0 3571 0 3571 0 3570 0 3572 0 3571 0 3572 0 3573 0 3512 0 3514 0 3573 0 3513 0 3574 0 3575 0 3575 0 3574 0 3576 0 3577 0 3578 0 3544 0 3579 0 3580 0 3581 0 3581 0 3580 0 3582 0 3581 0 3582 0 3583 0 3577 0 3544 0 3583 0 3578 0 3584 0 3544 0 3544 0 3584 0 3585 0 3544 0 3585 0 3543 0 3543 0 3585 0 3586 0 3543 0 3586 0 3542 0 3542 0 3586 0 3587 0 3542 0 3587 0 3588 0 3589 0 3590 0 3579 0 3579 0 3590 0 3591 0 3579 0 3591 0 3580 0 3592 0 3593 0 3594 0 3594 0 3593 0 3595 0 3596 0 3597 0 3598 0 3598 0 3597 0 3599 0 3598 0 3599 0 3600 0 3601 0 3602 0 3603 0 3603 0 3602 0 3600 0 3603 0 3600 0 3604 0 3604 0 3600 0 3599 0 3605 0 3606 0 3607 0 3607 0 3606 0 3608 0 3609 0 3610 0 3611 0 3609 0 3611 0 3612 0 3611 0 3613 0 3612 0 3612 0 3613 0 3614 0 3612 0 3614 0 3615 0 3615 0 3614 0 3616 0 3615 0 3616 0 3617 0 3610 0 3609 0 3618 0 3618 0 3609 0 3619 0 3618 0 3619 0 3620 0 3620 0 3621 0 3622 0 3622 0 3621 0 3510 0 3511 0 3510 0 3623 0 3624 0 3625 0 3626 0 3626 0 3625 0 3627 0 3628 0 3629 0 3534 0 3630 0 3631 0 3514 0 3573 0 3514 0 3571 0 3571 0 3514 0 3631 0 3571 0 3631 0 3628 0 3632 0 3633 0 3634 0 3634 0 3633 0 3635 0 3634 0 3635 0 3636 0 3636 0 3635 0 3637 0 3636 0 3637 0 3514 0 3514 0 3637 0 3638 0 3514 0 3638 0 3630 0 3639 0 3640 0 3544 0 3583 0 3544 0 3581 0 3581 0 3544 0 3640 0 3581 0 3640 0 3641 0 3629 0 3642 0 3534 0 3534 0 3642 0 3643 0 3534 0 3643 0 3530 0 3530 0 3643 0 3644 0 3530 0 3644 0 3544 0 3544 0 3644 0 3645 0 3544 0 3645 0 3639 0 3646 0 3647 0 3648 0 3551 0 3550 0 3560 0 3560 0 3550 0 3649 0 3560 0 3649 0 3650 0 3617 0 3626 0 3615 0 3615 0 3626 0 3627 0 3615 0 3627 0 3651 0 3651 0 3627 0 3652 0 3653 0 3654 0 3655 0 3655 0 3654 0 3656 0 3657 0 3658 0 3659 0 3659 0 3658 0 3660 0 3659 0 3660 0 3661 0 3653 0 3662 0 3663 0 3663 0 3662 0 3664 0 3663 0 3664 0 3665 0 3665 0 3664 0 3666 0 3503 0 3505 0 3667 0 3668 0 3502 0 3669 0 3669 0 3502 0 3661 0 3669 0 3661 0 3670 0 3670 0 3661 0 3660 0 3628 0 3534 0 3571 0 3571 0 3534 0 3525 0 3571 0 3525 0 3569 0 3569 0 3525 0 3481 0 3569 0 3481 0 3480 0 3473 0 3472 0 3522 0 3522 0 3472 0 3501 0 3522 0 3501 0 3523 0 3523 0 3501 0 3500 0 3523 0 3500 0 3524 0 3575 0 3505 0 3666 0 3666 0 3505 0 3504 0 3666 0 3504 0 3665 0 3668 0 3667 0 3502 0 3502 0 3667 0 3505 0 3502 0 3505 0 3500 0 3500 0 3505 0 3575 0 3500 0 3575 0 3524 0 3524 0 3575 0 3576 0 3524 0 3576 0 3477 0 3477 0 3576 0 3671 0 3477 0 3671 0 3478 0 3478 0 3671 0 3672 0 3478 0 3672 0 3479 0 3479 0 3672 0 3673 0 3479 0 3673 0 3480 0 3480 0 3673 0 3674 0 3480 0 3674 0 3569 0 3569 0 3674 0 3675 0 3569 0 3675 0 3570 0 3520 0 3594 0 3598 0 3598 0 3594 0 3595 0 3598 0 3595 0 3596 0 3471 0 3470 0 3520 0 3520 0 3470 0 3519 0 3520 0 3519 0 3594 0 3594 0 3519 0 3676 0 3594 0 3676 0 3592 0 3469 0 3468 0 3519 0 3519 0 3468 0 3497 0 3519 0 3497 0 3676 0 3676 0 3497 0 3499 0 3676 0 3499 0 3568 0 3568 0 3499 0 3465 0 3568 0 3465 0 3566 0 3566 0 3465 0 3464 0 3566 0 3464 0 3463 0 3620 0 3619 0 3621 0 3621 0 3619 0 3655 0 3621 0 3655 0 3659 0 3659 0 3655 0 3656 0 3659 0 3656 0 3657 0 3510 0 3621 0 3623 0 3623 0 3621 0 3659 0 3623 0 3659 0 3600 0 3600 0 3659 0 3661 0 3600 0 3661 0 3598 0 3598 0 3661 0 3502 0 3598 0 3502 0 3520 0 3520 0 3502 0 3501 0 3520 0 3501 0 3521 0 3521 0 3501 0 3472 0 3521 0 3472 0 3471 0 3677 0 3678 0 3602 0 3461 0 3679 0 3462 0 3462 0 3679 0 3680 0 3462 0 3680 0 3567 0 3567 0 3680 0 3681 0 3567 0 3681 0 3568 0 3568 0 3681 0 3607 0 3568 0 3607 0 3676 0 3676 0 3607 0 3608 0 3676 0 3608 0 3592 0 3495 0 3518 0 3545 0 3545 0 3518 0 3542 0 3545 0 3542 0 3589 0 3589 0 3542 0 3588 0 3589 0 3588 0 3590 0 3445 0 3545 0 3547 0 3547 0 3545 0 3589 0 3547 0 3589 0 3682 0 3682 0 3589 0 3579 0 3682 0 3579 0 3683 0 3683 0 3579 0 3581 0 3683 0 3581 0 3634 0 3634 0 3581 0 3641 0 3634 0 3641 0 3632 0 3626 0 3509 0 3624 0 3624 0 3509 0 3511 0 3624 0 3511 0 3684 0 3684 0 3511 0 3623 0 3684 0 3623 0 3685 0 3685 0 3623 0 3600 0 3685 0 3600 0 3686 0 3686 0 3600 0 3602 0 3686 0 3602 0 3687 0 3687 0 3602 0 3678 0 3687 0 3678 0 3506 0 3506 0 3678 0 3677 0 3506 0 3677 0 3507 0 3507 0 3677 0 3648 0 3507 0 3648 0 3508 0 3508 0 3648 0 3647 0 3513 0 3575 0 3514 0 3514 0 3575 0 3666 0 3514 0 3666 0 3636 0 3636 0 3666 0 3664 0 3636 0 3664 0 3634 0 3634 0 3664 0 3662 0 3634 0 3662 0 3683 0 3683 0 3662 0 3688 0 3683 0 3688 0 3682 0 3682 0 3688 0 3689 0 3682 0 3689 0 3547 0 3547 0 3689 0 3690 0 3547 0 3690 0 3546 0 3653 0 3655 0 3662 0 3662 0 3655 0 3619 0 3662 0 3619 0 3688 0 3688 0 3619 0 3609 0 3688 0 3609 0 3689 0 3689 0 3609 0 3612 0 3689 0 3612 0 3690 0 3691 0 3692 0 3693 0 3694 0 3679 0 3695 0 3695 0 3679 0 3693 0 3695 0 3693 0 3696 0 3696 0 3693 0 3692 0 3694 0 3697 0 3679 0 3679 0 3697 0 3698 0 3679 0 3698 0 3680 0 3680 0 3698 0 3699 0 3680 0 3699 0 3700 0 3701 0 3702 0 3648 0 3648 0 3702 0 3703 0 3601 0 3605 0 3602 0 3602 0 3605 0 3607 0 3602 0 3607 0 3677 0 3677 0 3607 0 3681 0 3677 0 3681 0 3648 0 3648 0 3681 0 3680 0 3648 0 3680 0 3701 0 3701 0 3680 0 3700 0 3703 0 3691 0 3648 0 3648 0 3691 0 3693 0 3648 0 3693 0 3646 0 3646 0 3693 0 3704 0 3646 0 3704 0 3705 0 3705 0 3704 0 3706 0 3705 0 3706 0 3707 0 3652 0 3649 0 3651 0 3651 0 3649 0 3550 0 3651 0 3550 0 3615 0 3615 0 3550 0 3549 0 3615 0 3549 0 3612 0 3612 0 3549 0 3548 0 3612 0 3548 0 3690 0 3690 0 3548 0 3517 0 3690 0 3517 0 3546 0 3546 0 3517 0 3516 0 3546 0 3516 0 3446 0 3446 0 3516 0 3447 0 3461 0 3460 0 3679 0 3679 0 3460 0 3565 0 3679 0 3565 0 3693 0 3693 0 3565 0 3515 0 3693 0 3515 0 3704 0 3704 0 3515 0 3564 0 3704 0 3564 0 3706 0 3706 0 3564 0 3560 0 3706 0 3560 0 3707 0 3707 0 3560 0 3650 0 3570 871 3326 871 3572 871 3572 824 3326 824 3324 824 3572 825 3324 825 3573 825 3573 825 3324 825 3323 825 3573 827 3323 827 3512 827 3512 826 3323 826 3322 826 3512 829 3322 829 3513 829 3513 829 3322 829 3320 829 3513 2661 3320 2661 3574 2661 3574 2661 3320 2661 3319 2661 3574 845 3319 845 3576 845 3576 845 3319 845 3337 845 3576 817 3337 817 3671 817 3671 817 3337 817 3335 817 3671 818 3335 818 3672 818 3672 818 3335 818 3333 818 3672 820 3333 820 3673 820 3673 819 3333 819 3331 819 3673 858 3331 858 3674 858 3674 821 3331 821 3329 821 3674 838 3329 838 3675 838 3675 846 3329 846 3327 846 3675 860 3327 860 3570 860 3570 873 3327 873 3326 873 3585 850 3345 850 3586 850 3586 850 3345 850 3352 850 3586 851 3352 851 3587 851 3587 851 3352 851 3351 851 3587 2662 3351 2662 3588 2662 3588 2662 3351 2662 3350 2662 3588 2663 3350 2663 3590 2663 3590 2663 3350 2663 3349 2663 3590 830 3349 830 3591 830 3591 843 3349 843 3347 843 3591 2664 3347 2664 3580 2664 3580 844 3347 844 3346 844 3580 817 3346 817 3582 817 3582 2665 3346 2665 3343 2665 3582 818 3343 818 3583 818 3583 818 3343 818 3342 818 3583 820 3342 820 3577 820 3577 820 3342 820 3341 820 3577 821 3341 821 3578 821 3578 821 3341 821 3340 821 3578 839 3340 839 3584 839 3584 838 3340 838 3339 838 3584 841 3339 841 3585 841 3585 823 3339 823 3345 823 3599 824 3356 824 3604 824 3604 871 3356 871 3355 871 3604 825 3355 825 3603 825 3603 825 3355 825 3363 825 3603 826 3363 826 3601 826 3601 827 3363 827 3362 827 3601 829 3362 829 3605 829 3605 829 3362 829 3360 829 3605 831 3360 831 3606 831 3606 856 3360 856 3359 856 3606 845 3359 845 3608 845 3608 872 3359 872 3367 872 3608 866 3367 866 3592 866 3592 834 3367 834 3365 834 3592 835 3365 835 3593 835 3593 835 3365 835 3364 835 3593 867 3364 867 3595 867 3595 868 3364 868 3439 868 3595 869 3439 869 3596 869 3596 870 3439 870 3358 870 3596 847 3358 847 3597 847 3597 846 3358 846 3357 846 3597 823 3357 823 3599 823 3599 823 3357 823 3356 823 3611 850 3376 850 3613 850 3613 850 3376 850 3374 850 3613 825 3374 825 3614 825 3614 862 3374 862 3373 862 3614 827 3373 827 3616 827 3616 826 3373 826 3372 826 3616 829 3372 829 3617 829 3617 828 3372 828 3370 828 3617 2661 3370 2661 3626 2661 3626 2666 3370 2666 3369 2666 3626 832 3369 832 3509 832 3509 832 3369 832 3417 832 3509 817 3417 817 3510 817 3510 2667 3417 2667 3418 2667 3510 818 3418 818 3622 818 3622 857 3418 857 3382 857 3622 819 3382 819 3620 819 3620 2668 3382 2668 3381 2668 3620 2669 3381 2669 3618 2669 3618 858 3381 858 3379 858 3618 838 3379 838 3610 838 3610 838 3379 838 3377 838 3610 2670 3377 2670 3611 2670 3611 873 3377 873 3376 873 3562 849 3295 849 3563 849 3563 850 3295 850 3313 850 3563 851 3313 851 3553 851 3553 851 3313 851 3312 851 3553 852 3312 852 3554 852 3554 853 3312 853 3309 853 3554 854 3309 854 3555 854 3555 855 3309 855 3307 855 3555 856 3307 856 3556 856 3556 831 3307 831 3306 831 3556 845 3306 845 3557 845 3557 845 3306 845 3303 845 3557 817 3303 817 3558 817 3558 816 3303 816 3301 816 3558 818 3301 818 3559 818 3559 818 3301 818 3300 818 3559 820 3300 820 3551 820 3551 819 3300 819 3299 819 3551 821 3299 821 3552 821 3552 821 3299 821 3298 821 3552 846 3298 846 3561 846 3561 847 3298 847 3296 847 3561 823 3296 823 3562 823 3562 848 3296 848 3295 848 3691 850 3421 850 3692 850 3692 849 3421 849 3422 849 3692 825 3422 825 3696 825 3696 825 3422 825 3430 825 3696 826 3430 826 3695 826 3695 827 3430 827 3429 827 3695 828 3429 828 3694 828 3694 829 3429 829 3428 829 3694 830 3428 830 3697 830 3697 831 3428 831 3427 831 3697 832 3427 832 3698 832 3698 833 3427 833 3426 833 3698 866 3426 866 3699 866 3699 2671 3426 2671 3425 2671 3699 818 3425 818 3700 818 3700 818 3425 818 3424 818 3700 820 3424 820 3701 820 3701 819 3424 819 3423 819 3701 870 3423 870 3702 870 3702 870 3423 870 3420 870 3702 846 3420 846 3703 846 3703 847 3420 847 3419 847 3703 823 3419 823 3691 823 3691 823 3419 823 3421 823 3644 885 3394 885 3645 885 3645 885 3394 885 3393 885 3645 888 3393 888 3639 888 3639 888 3393 888 3392 888 3639 913 3392 913 3640 913 3640 2672 3392 2672 3383 2672 3640 2673 3383 2673 3641 2673 3641 2673 3383 2673 3192 2673 3641 2674 3192 2674 3632 2674 3632 2675 3192 2675 3191 2675 3632 919 3191 919 3633 919 3633 919 3191 919 3391 919 3633 2676 3391 2676 3635 2676 3635 2676 3391 2676 3390 2676 3635 921 3390 921 3637 921 3637 921 3390 921 3388 921 3637 875 3388 875 3638 875 3638 2677 3388 2677 3386 2677 3638 2678 3386 2678 3630 2678 3630 876 3386 876 3385 876 3630 2679 3385 2679 3631 2679 3631 2680 3385 2680 3384 2680 3631 2681 3384 2681 3628 2681 3628 2681 3384 2681 3189 2681 3628 2682 3189 2682 3629 2682 3629 2682 3189 2682 3188 2682 3629 2683 3188 2683 3642 2683 3642 2683 3188 2683 3396 2683 3642 906 3396 906 3643 906 3643 2684 3396 2684 3395 2684 3643 908 3395 908 3644 908 3644 908 3395 908 3394 908 3625 2685 3416 2685 3627 2685 3627 2686 3416 2686 3397 2686 3627 911 3397 911 3652 911 3652 912 3397 912 3399 912 3652 913 3399 913 3649 913 3649 913 3399 913 3400 913 3649 914 3400 914 3650 914 3650 915 3400 915 3401 915 3650 916 3401 916 3707 916 3707 917 3401 917 3402 917 3707 918 3402 918 3705 918 3705 919 3402 919 3404 919 3705 894 3404 894 3646 894 3646 920 3404 920 3406 920 3646 896 3406 896 3647 896 3647 2687 3406 2687 3408 2687 3647 875 3408 875 3508 875 3508 2688 3408 2688 3410 2688 3508 899 3410 899 3506 899 3506 900 3410 900 3185 900 3506 877 3185 877 3687 877 3687 877 3185 877 3412 877 3687 901 3412 901 3686 901 3686 902 3412 902 3413 902 3686 903 3413 903 3685 903 3685 904 3413 904 3414 904 3685 905 3414 905 3684 905 3684 882 3414 882 3182 882 3684 906 3182 906 3624 906 3624 907 3182 907 3184 907 3624 884 3184 884 3625 884 3625 2689 3184 2689 3416 2689 3526 2690 3254 2690 3527 2690 3527 2690 3254 2690 3255 2690 3527 933 3255 933 3537 933 3537 932 3255 932 3256 932 3537 2691 3256 2691 3538 2691 3538 2691 3256 2691 3266 2691 3538 2692 3266 2692 3539 2692 3539 2692 3266 2692 3265 2692 3539 2693 3265 2693 3540 2693 3540 2693 3265 2693 3263 2693 3540 948 3263 948 3541 948 3541 948 3263 948 3262 948 3531 2694 3253 2694 3528 2694 3528 950 3253 950 3250 950 3528 925 3250 925 3529 925 3529 924 3250 924 3249 924 3529 2695 3249 2695 3532 2695 3532 2696 3249 2696 3261 2696 3532 2697 3261 2697 3533 2697 3533 2697 3261 2697 3260 2697 3533 2698 3260 2698 3535 2698 3535 2698 3260 2698 3258 2698 3535 2699 3258 2699 3536 2699 3536 2700 3258 2700 3257 2700 3253 2701 3531 2701 3262 2701 3262 953 3531 953 3541 953 3536 2702 3257 2702 3526 2702 3526 2702 3257 2702 3254 2702 3656 2703 3215 2703 3657 2703 3657 2703 3215 2703 3214 2703 3657 925 3214 925 3658 925 3658 925 3214 925 3226 925 3658 2704 3226 2704 3660 2704 3660 2705 3226 2705 3225 2705 3660 2706 3225 2706 3670 2706 3670 2697 3225 2697 3223 2697 3670 2707 3223 2707 3669 2707 3669 2698 3223 2698 3221 2698 3669 929 3221 929 3668 929 3668 2708 3221 2708 3220 2708 3667 931 3218 931 3503 931 3503 931 3218 931 3217 931 3503 932 3217 932 3504 932 3504 932 3217 932 3212 932 3504 2691 3212 2691 3665 2691 3665 2709 3212 2709 3211 2709 3665 2692 3211 2692 3663 2692 3663 2692 3211 2692 3229 2692 3663 2710 3229 2710 3653 2710 3653 2693 3229 2693 3230 2693 3653 948 3230 948 3654 948 3654 948 3230 948 3232 948 3218 941 3667 941 3220 941 3220 941 3667 941 3668 941 3654 953 3232 953 3656 953 3656 2711 3232 2711 3215 2711 3708 88 3709 88 3710 88 3711 88 3712 88 3713 88 3714 88 3715 88 3716 88 3717 2712 3718 2712 3719 2712 3717 2713 3719 2713 3720 2713 3720 2714 3719 2714 3721 2714 3720 2715 3721 2715 3722 2715 3722 2716 3721 2716 3723 2716 3722 2716 3723 2716 3724 2716 3725 2717 3726 2717 3727 2717 3727 2718 3726 2718 3728 2718 3728 2719 3726 2719 3729 2719 3729 2720 3726 2720 3730 2720 3729 2721 3730 2721 3731 2721 3730 2721 3732 2721 3731 2721 3731 2722 3732 2722 3733 2722 3731 2723 3733 2723 3734 2723 3734 2724 3733 2724 3735 2724 3734 2725 3735 2725 3736 2725 3736 2726 3735 2726 3737 2726 3736 2726 3737 2726 3738 2726 3738 2727 3737 2727 3739 2727 3738 2728 3739 2728 3740 2728 3740 2729 3739 2729 3741 2729 3741 2729 3739 2729 3742 2729 3741 2730 3742 2730 3743 2730 3742 2730 3744 2730 3743 2730 3743 2731 3744 2731 3745 2731 3743 2732 3745 2732 3746 2732 3746 2733 3745 2733 3747 2733 3746 2734 3747 2734 3748 2734 3748 2735 3747 2735 3749 2735 3749 2735 3747 2735 3750 2735 3749 2736 3750 2736 3751 2736 3750 2736 3752 2736 3751 2736 3751 2737 3752 2737 3753 2737 3751 2738 3753 2738 3754 2738 3755 2739 3756 2739 3757 2739 3757 2740 3756 2740 3758 2740 3757 2740 3758 2740 3759 2740 3760 2741 3761 2741 3762 2741 3762 2741 3761 2741 3763 2741 3762 2742 3763 2742 3755 2742 3755 2742 3763 2742 3764 2742 3755 2739 3764 2739 3756 2739 3717 0 3765 0 3766 0 3724 0 3767 0 3768 0 3769 0 3770 0 3717 0 3768 0 3727 0 3724 0 3724 0 3727 0 3728 0 3724 0 3728 0 3729 0 3761 0 3769 0 3771 0 3771 0 3769 0 3717 0 3771 0 3717 0 3772 0 3772 0 3717 0 3766 0 3761 0 3771 0 3763 0 3763 0 3771 0 3773 0 3763 0 3773 0 3774 0 3775 0 3717 0 3776 0 3776 0 3717 0 3720 0 3776 0 3720 0 3777 0 3777 0 3720 0 3722 0 3777 0 3722 0 3778 0 3778 0 3722 0 3724 0 3779 0 3780 0 3781 0 3782 0 3783 0 3729 0 3729 0 3783 0 3784 0 3729 0 3784 0 3724 0 3724 0 3784 0 3785 0 3724 0 3785 0 3778 0 3781 0 3786 0 3779 0 3779 0 3786 0 3787 0 3779 0 3787 0 3729 0 3775 0 3788 0 3717 0 3717 0 3788 0 3789 0 3717 0 3789 0 3765 0 3765 0 3789 0 3790 0 3790 0 3791 0 3765 0 3765 0 3791 0 3782 0 3765 0 3782 0 3792 0 3792 0 3782 0 3729 0 3792 0 3729 0 3793 0 3793 0 3729 0 3787 0 3794 0 3795 0 3754 0 3754 0 3795 0 3758 0 3796 0 3749 0 3758 0 3758 0 3749 0 3751 0 3758 0 3751 0 3754 0 3779 0 3797 0 3798 0 3796 0 3799 0 3749 0 3749 0 3799 0 3800 0 3749 0 3800 0 3779 0 3779 0 3800 0 3801 0 3779 0 3801 0 3797 0 3774 0 3780 0 3763 0 3763 0 3780 0 3779 0 3763 0 3779 0 3802 0 3802 0 3779 0 3798 0 3802 0 3803 0 3763 0 3763 0 3803 0 3804 0 3763 0 3804 0 3764 0 3764 0 3804 0 3805 0 3764 0 3805 0 3756 0 3756 0 3805 0 3806 0 3756 0 3806 0 3758 0 3758 0 3806 0 3807 0 3758 0 3807 0 3796 0 3779 0 3808 0 3809 0 3809 0 3810 0 3779 0 3779 0 3810 0 3811 0 3779 0 3811 0 3749 0 3811 0 3812 0 3749 0 3749 0 3812 0 3813 0 3749 0 3813 0 3748 0 3748 0 3813 0 3814 0 3748 0 3814 0 3746 0 3814 0 3815 0 3746 0 3746 0 3815 0 3816 0 3746 0 3816 0 3743 0 3743 0 3816 0 3817 0 3743 0 3817 0 3741 0 3741 0 3817 0 3818 0 3741 0 3818 0 3819 0 3779 0 3820 0 3821 0 3819 0 3808 0 3741 0 3741 0 3808 0 3779 0 3741 0 3779 0 3740 0 3740 0 3779 0 3821 0 3740 0 3821 0 3738 0 3822 0 3729 0 3823 0 3823 0 3729 0 3731 0 3823 0 3731 0 3824 0 3824 0 3731 0 3734 0 3822 0 3825 0 3729 0 3729 0 3825 0 3826 0 3729 0 3826 0 3779 0 3779 0 3826 0 3827 0 3779 0 3827 0 3820 0 3821 0 3828 0 3738 0 3738 0 3828 0 3829 0 3738 0 3829 0 3736 0 3736 0 3829 0 3830 0 3736 0 3830 0 3734 0 3734 0 3830 0 3831 0 3734 0 3831 0 3824 0 3832 88 3833 88 3759 88 3759 88 3833 88 3753 88 3834 88 3835 88 3750 88 3750 88 3835 88 3836 88 3837 88 3838 88 3834 88 3834 88 3838 88 3839 88 3834 88 3839 88 3835 88 3836 88 3840 88 3750 88 3750 88 3840 88 3759 88 3750 88 3759 88 3752 88 3752 88 3759 88 3753 88 3840 88 3841 88 3759 88 3759 88 3841 88 3842 88 3759 88 3842 88 3757 88 3757 88 3842 88 3843 88 3757 88 3843 88 3755 88 3755 88 3843 88 3844 88 3755 88 3844 88 3762 88 3762 88 3844 88 3845 88 3762 88 3845 88 3846 88 3719 88 3718 88 3730 88 3847 88 3848 88 3725 88 3725 88 3848 88 3723 88 3725 88 3723 88 3726 88 3726 88 3723 88 3730 88 3730 88 3723 88 3721 88 3730 88 3721 88 3719 88 3849 88 3850 88 3718 88 3718 88 3850 88 3760 88 3851 88 3852 88 3760 88 3730 88 3853 88 3834 88 3834 88 3853 88 3854 88 3834 88 3854 88 3855 88 3855 88 3856 88 3834 88 3834 88 3856 88 3762 88 3834 88 3762 88 3837 88 3837 88 3762 88 3846 88 3857 88 3858 88 3859 88 3851 88 3760 88 3860 88 3861 88 3730 88 3862 88 3862 88 3730 88 3718 88 3862 88 3718 88 3863 88 3863 88 3718 88 3760 88 3863 88 3760 88 3864 88 3864 88 3760 88 3852 88 3861 88 3865 88 3730 88 3730 88 3865 88 3866 88 3730 88 3866 88 3858 88 3857 88 3859 88 3867 88 3857 88 3868 88 3858 88 3858 88 3868 88 3869 88 3858 88 3869 88 3730 88 3730 88 3869 88 3870 88 3730 88 3870 88 3853 88 3856 88 3871 88 3762 88 3762 88 3871 88 3872 88 3762 88 3872 88 3760 88 3760 88 3872 88 3873 88 3760 88 3873 88 3860 88 3860 88 3873 88 3867 88 3860 88 3867 88 3874 88 3874 88 3867 88 3859 88 3875 88 3876 88 3834 88 3834 88 3876 88 3877 88 3730 88 3878 88 3732 88 3732 88 3878 88 3879 88 3732 88 3879 88 3733 88 3877 88 3880 88 3834 88 3834 88 3880 88 3881 88 3834 88 3881 88 3730 88 3730 88 3881 88 3882 88 3730 88 3882 88 3878 88 3750 88 3883 88 3884 88 3750 88 3884 88 3834 88 3834 88 3884 88 3885 88 3834 88 3885 88 3886 88 3887 88 3888 88 3742 88 3742 88 3888 88 3889 88 3742 88 3889 88 3744 88 3744 88 3889 88 3890 88 3744 88 3890 88 3745 88 3890 88 3891 88 3745 88 3745 88 3891 88 3892 88 3745 88 3892 88 3747 88 3747 88 3892 88 3893 88 3747 88 3893 88 3750 88 3750 88 3893 88 3894 88 3750 88 3894 88 3883 88 3886 88 3887 88 3834 88 3834 88 3887 88 3742 88 3834 88 3742 88 3875 88 3875 88 3742 88 3739 88 3875 88 3739 88 3895 88 3895 88 3739 88 3737 88 3895 88 3737 88 3896 88 3896 88 3737 88 3735 88 3896 88 3735 88 3897 88 3897 88 3735 88 3733 88 3897 88 3733 88 3898 88 3898 88 3733 88 3879 88 3884 534 3811 534 3885 534 3885 542 3811 542 3810 542 3885 543 3810 543 3886 543 3886 543 3810 543 3809 543 3886 521 3809 521 3887 521 3887 521 3809 521 3808 521 3887 523 3808 523 3888 523 3888 523 3808 523 3819 523 3888 544 3819 544 3889 544 3889 524 3819 524 3818 524 3889 527 3818 527 3890 527 3890 526 3818 526 3817 526 3890 539 3817 539 3891 539 3891 529 3817 529 3816 529 3891 531 3816 531 3892 531 3892 530 3816 530 3815 530 3892 511 3815 511 3893 511 3893 511 3815 511 3814 511 3893 532 3814 532 3894 532 3894 512 3814 512 3813 512 3894 514 3813 514 3883 514 3883 541 3813 541 3812 541 3883 516 3812 516 3884 516 3884 515 3812 515 3811 515 3844 2743 3805 2743 3845 2743 3845 518 3805 518 3804 518 3845 520 3804 520 3846 520 3846 519 3804 519 3803 519 3846 521 3803 521 3837 521 3837 521 3803 521 3802 521 3837 523 3802 523 3838 523 3838 522 3802 522 3798 522 3838 524 3798 524 3839 524 3839 544 3798 544 3797 544 3839 537 3797 537 3835 537 3835 527 3797 527 3801 527 3835 508 3801 508 3836 508 3836 545 3801 545 3800 545 3836 546 3800 546 3840 546 3840 546 3800 546 3799 546 3840 511 3799 511 3841 511 3841 511 3799 511 3796 511 3841 532 3796 532 3842 532 3842 532 3796 532 3807 532 3842 541 3807 541 3843 541 3843 514 3807 514 3806 514 3843 515 3806 515 3844 515 3844 533 3806 533 3805 533 3864 2744 3776 2744 3863 2744 3863 517 3776 517 3777 517 3863 519 3777 519 3862 519 3862 2745 3777 2745 3778 2745 3862 521 3778 521 3861 521 3861 521 3778 521 3785 521 3861 522 3785 522 3865 522 3865 523 3785 523 3784 523 3865 524 3784 524 3866 524 3866 525 3784 525 3783 525 3866 526 3783 526 3858 526 3858 527 3783 527 3782 527 3858 508 3782 508 3859 508 3859 509 3782 509 3791 509 3859 510 3791 510 3874 510 3874 510 3791 510 3790 510 3874 511 3790 511 3860 511 3860 511 3790 511 3789 511 3860 512 3789 512 3851 512 3851 512 3789 512 3788 512 3851 513 3788 513 3852 513 3852 514 3788 514 3775 514 3852 515 3775 515 3864 515 3864 516 3775 516 3776 516 3881 535 3826 535 3882 535 3882 535 3826 535 3825 535 3882 536 3825 536 3878 536 3878 536 3825 536 3822 536 3878 521 3822 521 3879 521 3879 521 3822 521 3823 521 3879 522 3823 522 3898 522 3898 522 3823 522 3824 522 3898 524 3824 524 3897 524 3897 525 3824 525 3831 525 3897 537 3831 537 3896 537 3896 527 3831 527 3830 527 3896 539 3830 539 3895 539 3895 539 3830 539 3829 539 3895 530 3829 530 3875 530 3875 530 3829 530 3828 530 3875 511 3828 511 3876 511 3876 511 3828 511 3821 511 3876 532 3821 532 3877 532 3877 532 3821 532 3820 532 3877 514 3820 514 3880 514 3880 541 3820 541 3827 541 3880 515 3827 515 3881 515 3881 533 3827 533 3826 533 3873 555 3771 555 3867 555 3867 555 3771 555 3772 555 3867 556 3772 556 3857 556 3857 557 3772 557 3766 557 3857 558 3766 558 3868 558 3868 558 3766 558 3765 558 3868 559 3765 559 3869 559 3869 560 3765 560 3792 560 3869 561 3792 561 3870 561 3870 561 3792 561 3793 561 3870 562 3793 562 3853 562 3853 562 3793 562 3787 562 3853 547 3787 547 3854 547 3854 547 3787 547 3786 547 3854 548 3786 548 3855 548 3855 549 3786 549 3781 549 3855 550 3781 550 3856 550 3856 550 3781 550 3780 550 3856 551 3780 551 3871 551 3871 552 3780 552 3774 552 3871 553 3774 553 3872 553 3872 553 3774 553 3773 553 3872 554 3773 554 3873 554 3873 554 3773 554 3771 554 3761 2746 3760 2746 3769 2746 3769 574 3760 574 3850 574 3769 2747 3850 2747 3899 2747 3899 2748 3850 2748 3900 2748 3899 2749 3900 2749 3901 2749 3901 2750 3900 2750 3902 2750 3901 2751 3902 2751 3903 2751 3903 2752 3902 2752 3709 2752 3904 2753 3710 2753 3905 2753 3905 2754 3710 2754 3906 2754 3905 2755 3906 2755 3907 2755 3907 564 3906 564 3908 564 3907 2756 3908 2756 3770 2756 3770 2757 3908 2757 3849 2757 3770 2758 3849 2758 3717 2758 3717 2759 3849 2759 3718 2759 3906 2760 3902 2760 3908 2760 3908 2761 3902 2761 3900 2761 3710 2762 3709 2762 3906 2762 3906 2763 3709 2763 3902 2763 3905 2764 3901 2764 3904 2764 3904 2765 3901 2765 3903 2765 3907 2766 3899 2766 3905 2766 3905 2767 3899 2767 3901 2767 3770 2768 3769 2768 3907 2768 3907 2769 3769 2769 3899 2769 3908 2770 3900 2770 3849 2770 3849 2771 3900 2771 3850 2771 3754 2772 3753 2772 3794 2772 3794 2773 3753 2773 3833 2773 3794 2774 3833 2774 3909 2774 3909 2775 3833 2775 3910 2775 3909 2776 3910 2776 3911 2776 3911 2777 3910 2777 3912 2777 3911 2778 3912 2778 3913 2778 3913 2779 3912 2779 3712 2779 3913 2780 3712 2780 3914 2780 3914 2780 3712 2780 3915 2780 3916 2781 3713 2781 3917 2781 3917 2782 3713 2782 3918 2782 3917 2783 3918 2783 3919 2783 3919 2784 3918 2784 3920 2784 3919 2785 3920 2785 3795 2785 3795 2786 3920 2786 3832 2786 3795 2787 3832 2787 3758 2787 3758 2788 3832 2788 3759 2788 3918 2789 3912 2789 3920 2789 3920 2790 3912 2790 3910 2790 3713 2791 3712 2791 3918 2791 3918 2792 3712 2792 3912 2792 3917 2793 3911 2793 3916 2793 3916 2794 3911 2794 3913 2794 3919 2795 3909 2795 3917 2795 3917 2796 3909 2796 3911 2796 3795 2797 3794 2797 3919 2797 3919 2798 3794 2798 3909 2798 3920 2799 3910 2799 3832 2799 3832 2800 3910 2800 3833 2800 3724 2801 3723 2801 3767 2801 3767 2802 3723 2802 3848 2802 3767 2803 3848 2803 3921 2803 3921 2804 3848 2804 3922 2804 3921 2805 3922 2805 3923 2805 3923 2806 3922 2806 3924 2806 3923 2807 3924 2807 3925 2807 3925 2808 3924 2808 3715 2808 3926 2809 3927 2809 3928 2809 3928 2810 3927 2810 3716 2810 3928 2809 3716 2809 3929 2809 3929 2811 3716 2811 3930 2811 3929 2812 3930 2812 3931 2812 3931 2813 3930 2813 3932 2813 3931 2814 3932 2814 3768 2814 3768 2815 3932 2815 3847 2815 3768 2816 3847 2816 3727 2816 3727 2817 3847 2817 3725 2817 3930 2818 3924 2818 3932 2818 3932 2819 3924 2819 3922 2819 3716 2820 3715 2820 3930 2820 3930 2820 3715 2820 3924 2820 3929 2821 3923 2821 3928 2821 3928 2821 3923 2821 3925 2821 3931 2822 3921 2822 3929 2822 3929 2823 3921 2823 3923 2823 3768 2824 3767 2824 3931 2824 3931 2825 3767 2825 3921 2825 3932 2826 3922 2826 3847 2826 3847 2827 3922 2827 3848 2827 3710 0 3904 0 3933 0 3933 0 3904 0 3934 0 3933 0 3934 0 3935 0 3935 0 3934 0 3936 0 3935 0 3936 0 3937 0 3937 0 3936 0 3938 0 3937 0 3938 0 3939 0 3939 0 3938 0 3940 0 3939 0 3940 0 3941 0 3941 0 3940 0 3942 0 3941 0 3942 0 3943 0 3943 0 3942 0 3944 0 3943 0 3944 0 3945 0 3945 0 3944 0 3946 0 3945 0 3946 0 3947 0 3947 0 3946 0 3948 0 3947 0 3948 0 3715 0 3715 0 3948 0 3925 0 3713 0 3916 0 3949 0 3949 0 3916 0 3950 0 3949 0 3950 0 3951 0 3951 0 3950 0 3952 0 3951 0 3952 0 3953 0 3953 0 3952 0 3954 0 3953 0 3954 0 3955 0 3955 0 3954 0 3956 0 3955 0 3956 0 3957 0 3957 0 3956 0 3958 0 3957 0 3958 0 3959 0 3959 2828 3958 2828 3960 2828 3959 0 3960 0 3961 0 3961 0 3960 0 3962 0 3961 0 3962 0 3963 0 3963 0 3962 0 3964 0 3963 0 3964 0 3709 0 3709 0 3964 0 3903 0 3903 0 3965 0 3904 0 3913 2587 3966 2587 3916 2587 3966 2829 3913 2829 3914 2829 3928 2830 3967 2830 3926 2830 3926 2831 3967 2831 3925 2831 3926 2832 3925 2832 3968 2832 3925 2833 3948 2833 3968 2833 3968 2834 3948 2834 3946 2834 3968 2835 3946 2835 3969 2835 3969 2836 3946 2836 3944 2836 3969 2837 3944 2837 3970 2837 3970 2838 3944 2838 3942 2838 3970 2838 3942 2838 3971 2838 3971 2839 3942 2839 3940 2839 3971 2839 3940 2839 3972 2839 3972 2840 3940 2840 3938 2840 3972 2841 3938 2841 3973 2841 3973 2842 3938 2842 3936 2842 3973 2843 3936 2843 3974 2843 3974 2844 3936 2844 3934 2844 3974 2845 3934 2845 3975 2845 3934 2846 3904 2846 3975 2846 3975 2847 3904 2847 3965 2847 3975 2848 3965 2848 3976 2848 3976 2849 3965 2849 3903 2849 3903 2850 3964 2850 3976 2850 3976 2851 3964 2851 3962 2851 3976 2852 3962 2852 3977 2852 3977 2853 3962 2853 3960 2853 3977 2853 3960 2853 3978 2853 3978 2854 3960 2854 3958 2854 3978 2854 3958 2854 3979 2854 3979 2855 3958 2855 3956 2855 3979 2856 3956 2856 3980 2856 3980 2857 3956 2857 3954 2857 3980 2858 3954 2858 3981 2858 3981 2859 3954 2859 3952 2859 3981 2859 3952 2859 3982 2859 3982 2860 3952 2860 3950 2860 3982 2861 3950 2861 3983 2861 3983 2862 3950 2862 3914 2862 3914 2863 3950 2863 3916 2863 3914 2864 3916 2864 3966 2864 3714 2865 3716 2865 3927 2865 3712 2866 3711 2866 3915 2866 3915 2867 3711 2867 3713 2867 3915 2868 3713 2868 3984 2868 3984 2869 3713 2869 3949 2869 3984 2870 3949 2870 3985 2870 3985 2871 3949 2871 3951 2871 3985 2872 3951 2872 3986 2872 3986 2873 3951 2873 3953 2873 3986 2874 3953 2874 3987 2874 3987 2875 3953 2875 3955 2875 3987 2876 3955 2876 3988 2876 3988 2877 3955 2877 3957 2877 3988 2878 3957 2878 3989 2878 3989 2879 3957 2879 3959 2879 3989 2880 3959 2880 3990 2880 3990 2881 3959 2881 3961 2881 3990 2882 3961 2882 3991 2882 3991 2883 3961 2883 3963 2883 3963 2884 3709 2884 3991 2884 3991 2885 3709 2885 3708 2885 3991 2886 3708 2886 3992 2886 3708 2887 3710 2887 3992 2887 3992 2888 3710 2888 3933 2888 3992 2889 3933 2889 3993 2889 3993 2890 3933 2890 3935 2890 3993 2891 3935 2891 3994 2891 3994 2892 3935 2892 3937 2892 3994 2893 3937 2893 3995 2893 3995 2893 3937 2893 3939 2893 3995 2894 3939 2894 3996 2894 3996 2895 3939 2895 3941 2895 3996 2896 3941 2896 3997 2896 3997 2896 3941 2896 3943 2896 3997 2897 3943 2897 3998 2897 3998 2897 3943 2897 3945 2897 3998 2898 3945 2898 3999 2898 3999 2898 3945 2898 3947 2898 3999 2899 3947 2899 3927 2899 3927 2900 3947 2900 3715 2900 3927 2901 3715 2901 3714 2901 3927 88 3926 88 3999 88 3999 88 3926 88 3968 88 3999 88 3968 88 3998 88 3998 88 3968 88 3969 88 3998 88 3969 88 3997 88 3997 88 3969 88 3970 88 3997 88 3970 88 3996 88 3996 88 3970 88 3971 88 3996 88 3971 88 3995 88 3995 88 3971 88 3972 88 3995 88 3972 88 3994 88 3994 88 3972 88 3973 88 3994 88 3973 88 3993 88 3993 88 3973 88 3974 88 3993 88 3974 88 3992 88 3992 2902 3974 2902 3975 2902 3992 88 3975 88 3991 88 3991 88 3975 88 3976 88 3991 2903 3976 2903 3990 2903 3990 88 3976 88 3977 88 3990 88 3977 88 3989 88 3989 88 3977 88 3978 88 3989 88 3978 88 3988 88 3988 2904 3978 2904 3979 2904 3988 88 3979 88 3987 88 3987 88 3979 88 3980 88 3987 2905 3980 2905 3986 2905 3986 2906 3980 2906 3981 2906 3986 88 3981 88 3985 88 3985 88 3981 88 3982 88 3985 88 3982 88 3984 88 3984 88 3982 88 3983 88 3984 88 3983 88 3915 88 3915 88 3983 88 3914 88 3925 0 3967 0 3928 0 4000 88 4001 88 4002 88 4003 88 4004 88 4005 88 4006 2907 4007 2907 4008 2907 4009 88 4010 88 4007 88 4011 88 4012 88 4013 88 4014 88 4015 88 4016 88 4017 88 4018 88 4001 88 4001 2908 4018 2908 4019 2908 4001 88 4019 88 4002 88 4019 2909 4020 2909 4002 2909 4002 2910 4020 2910 4021 2910 4002 88 4021 88 4022 88 4022 2911 4021 2911 4023 2911 4022 88 4023 88 4024 88 4024 88 4023 88 4025 88 4025 88 4023 88 4026 88 4025 2912 4026 2912 4027 2912 4027 2913 4026 2913 4028 2913 4027 88 4028 88 4029 88 4029 88 4028 88 4030 88 4029 88 4030 88 4031 88 4031 88 4030 88 4032 88 4032 2914 4030 2914 4033 2914 4032 2915 4033 2915 4034 2915 4034 2916 4033 2916 4035 2916 4034 88 4035 88 4036 88 4036 88 4035 88 4037 88 4036 88 4037 88 4038 88 4039 88 4040 88 4041 88 4041 88 4040 88 4042 88 4041 2917 4042 2917 4043 2917 4000 88 4044 88 4045 88 4037 88 4017 88 4038 88 4038 2918 4017 2918 4001 2918 4038 88 4001 88 4042 88 4042 88 4001 88 4046 88 4042 2919 4046 2919 4043 2919 4047 88 4048 88 4049 88 4049 2920 4048 2920 4050 2920 4049 88 4050 88 4044 88 4044 2921 4050 2921 4051 2921 4044 2922 4051 2922 4045 2922 4045 88 4052 88 4000 88 4000 88 4052 88 4053 88 4000 88 4053 88 4001 88 4001 2923 4053 2923 4054 2923 4001 2924 4054 2924 4046 2924 4039 88 4047 88 4040 88 4040 88 4047 88 4049 88 4040 2925 4049 2925 4055 2925 4055 2926 4049 2926 4056 2926 4057 2927 4058 2927 4059 2927 4059 2928 4058 2928 4060 2928 4059 2929 4060 2929 4061 2929 4061 2930 4060 2930 4062 2930 4061 88 4062 88 4063 88 4064 2931 4065 2931 4066 2931 4066 88 4065 88 4067 88 4066 88 4067 88 4068 88 4068 88 4067 88 4069 88 4068 88 4069 88 4070 88 4071 2932 4072 2932 4073 2932 4073 2933 4072 2933 4056 2933 4073 2934 4056 2934 4074 2934 4074 2935 4056 2935 4049 2935 4074 88 4049 88 4075 88 4076 2936 4077 2936 4078 2936 4078 88 4077 88 4079 88 4078 88 4079 88 4080 88 4080 88 4079 88 4081 88 4080 88 4081 88 4082 88 4073 2929 4082 2929 4071 2929 4071 88 4082 88 4081 88 4071 2937 4081 2937 4083 2937 4083 88 4081 88 4084 88 4085 88 4086 88 4087 88 4087 88 4086 88 4016 88 4088 88 4089 88 4090 88 4090 88 4089 88 4084 88 4091 88 4092 88 4015 88 4015 2938 4092 2938 4093 2938 4015 2939 4093 2939 4016 2939 4016 2940 4093 2940 4094 2940 4016 88 4094 88 4087 88 4095 88 4096 88 4081 88 4081 2941 4096 2941 4097 2941 4081 2942 4097 2942 4084 2942 4084 2943 4097 2943 4098 2943 4084 2944 4098 2944 4090 2944 4099 2945 4100 2945 4014 2945 4014 88 4100 88 4015 88 4015 2946 4100 2946 4101 2946 4015 2947 4101 2947 4102 2947 4099 2948 4014 2948 4103 2948 4103 2949 4014 2949 4104 2949 4103 88 4104 88 4105 88 4088 2950 4091 2950 4089 2950 4089 88 4091 88 4015 88 4089 88 4015 88 4106 88 4106 2951 4015 2951 4102 2951 4102 88 4107 88 4106 88 4106 2952 4107 2952 4108 2952 4106 88 4108 88 4109 88 4109 88 4108 88 4110 88 4109 88 4110 88 4111 88 4111 88 4110 88 4112 88 4112 2953 4110 2953 4113 2953 4112 2954 4113 2954 4114 2954 4114 2955 4113 2955 4115 2955 4114 88 4115 88 4116 88 4116 88 4115 88 4117 88 4116 2956 4117 2956 4105 2956 4118 2957 4119 2957 4120 2957 4105 88 4104 88 4116 88 4116 2958 4104 2958 4121 2958 4116 88 4121 88 4120 88 4120 2959 4121 2959 4122 2959 4120 2960 4122 2960 4118 2960 4085 88 4095 88 4086 88 4086 88 4095 88 4081 88 4086 88 4081 88 4123 88 4123 88 4081 88 4079 88 4078 88 4063 88 4076 88 4076 88 4063 88 4062 88 4076 88 4062 88 4124 88 4124 88 4062 88 4125 88 4011 88 4125 88 4126 88 4126 88 4127 88 4011 88 4011 88 4127 88 4128 88 4011 88 4128 88 4012 88 4012 2961 4128 2961 4129 2961 4012 2938 4129 2938 4130 2938 4131 88 4132 88 4062 88 4062 2941 4132 2941 4133 2941 4062 88 4133 88 4125 88 4125 2962 4133 2962 4134 2962 4125 2963 4134 2963 4126 2963 4130 2964 4135 2964 4136 2964 4136 2965 4135 2965 4137 2965 4136 88 4137 88 4138 88 4138 2966 4137 2966 4139 2966 4140 2967 4141 2967 4007 2967 4130 88 4136 88 4012 88 4012 88 4136 88 4142 88 4012 2968 4142 2968 4143 2968 4010 2969 4013 2969 4144 2969 4145 88 4146 88 4142 88 4142 88 4146 88 4147 88 4142 2952 4147 2952 4143 2952 4143 88 4148 88 4012 88 4012 2947 4148 2947 4149 2947 4012 88 4149 88 4013 88 4013 2970 4149 2970 4150 2970 4013 2971 4150 2971 4144 2971 4144 2972 4151 2972 4010 2972 4010 88 4151 88 4152 88 4010 2973 4152 2973 4007 2973 4007 88 4152 88 4153 88 4007 2974 4153 2974 4140 2974 4006 88 4154 88 4007 88 4007 2975 4154 2975 4155 2975 4007 2976 4155 2976 4009 2976 4156 88 4007 88 4145 88 4145 88 4007 88 4141 88 4145 2977 4141 2977 4146 2977 4157 88 4008 88 4158 88 4158 2978 4008 2978 4007 2978 4158 88 4007 88 4159 88 4159 88 4007 88 4156 88 4139 88 4131 88 4138 88 4138 88 4131 88 4062 88 4138 2979 4062 2979 4160 2979 4160 2980 4062 2980 4060 2980 4059 2934 4070 2934 4057 2934 4057 88 4070 88 4069 88 4057 2981 4069 2981 4161 2981 4161 88 4069 88 4162 88 4163 88 4164 88 4004 88 4004 88 4164 88 4165 88 4162 88 4166 88 4164 88 4164 2982 4166 2982 4167 2982 4164 2983 4167 2983 4165 2983 4165 88 4168 88 4004 88 4004 2924 4168 2924 4169 2924 4004 2984 4169 2984 4005 2984 4169 88 4170 88 4005 88 4005 88 4170 88 4171 88 4005 88 4171 88 4172 88 4172 2985 4171 2985 4173 2985 4174 88 4175 88 4069 88 4069 2920 4175 2920 4176 2920 4069 2986 4176 2986 4162 2986 4162 2987 4176 2987 4177 2987 4162 2988 4177 2988 4166 2988 4178 88 4179 88 4180 88 4181 2989 4182 2989 4183 2989 4183 2990 4182 2990 4163 2990 4180 2991 4179 2991 4184 2991 4184 88 4179 88 4185 88 4184 2992 4185 2992 4186 2992 4186 88 4185 88 4187 88 4186 88 4187 88 4188 88 4188 88 4187 88 4189 88 4188 88 4189 88 4190 88 4190 2911 4189 2911 4191 2911 4190 2993 4191 2993 4003 2993 4003 2910 4191 2910 4192 2910 4003 88 4192 88 4004 88 4192 2994 4193 2994 4004 2994 4004 2908 4193 2908 4194 2908 4004 2995 4194 2995 4163 2995 4163 88 4194 88 4195 88 4163 2996 4195 2996 4183 2996 4196 2997 4197 2997 4198 2997 4181 2998 4178 2998 4182 2998 4182 88 4178 88 4180 88 4182 88 4180 88 4199 88 4199 88 4180 88 4196 88 4199 88 4196 88 4200 88 4200 88 4196 88 4198 88 4173 88 4174 88 4172 88 4172 88 4174 88 4069 88 4172 88 4069 88 4201 88 4201 88 4069 88 4067 88 4066 88 4075 88 4064 88 4064 88 4075 88 4049 88 4064 88 4049 88 4202 88 4202 88 4049 88 4044 88 4203 0 4204 0 4205 0 4206 0 4207 0 4208 0 4209 0 4210 0 4211 0 4212 0 4213 0 4214 0 4215 2999 4216 2999 4217 2999 4217 0 4216 0 4218 0 4219 0 4220 0 4221 0 4222 0 4223 0 4224 0 4224 0 4223 0 4225 0 4224 0 4225 0 4226 0 4226 0 4225 0 4219 0 4226 0 4219 0 4215 0 4215 0 4219 0 4221 0 4215 3000 4221 3000 4216 3000 4227 0 4228 0 4204 0 4204 3001 4228 3001 4229 3001 4204 0 4229 0 4205 0 4229 3002 4230 3002 4205 3002 4205 3003 4230 3003 4231 3003 4205 3004 4231 3004 4232 3004 4232 3005 4231 3005 4233 3005 4220 0 4219 0 4234 0 4234 0 4219 0 4235 0 4234 0 4235 0 4236 0 4236 3006 4235 3006 4237 3006 4236 0 4237 0 4233 0 4233 0 4237 0 4238 0 4233 0 4238 0 4232 0 4203 0 4239 0 4204 0 4204 3007 4239 3007 4240 3007 4204 3008 4240 3008 4241 3008 4218 0 4227 0 4217 0 4217 0 4227 0 4204 0 4217 0 4204 0 4242 0 4242 0 4204 0 4241 0 4243 0 4244 0 4245 0 4245 0 4244 0 4242 0 4245 3009 4242 3009 4246 3009 4246 0 4242 0 4241 0 4247 0 4248 0 4249 0 4249 3010 4248 3010 4250 3010 4249 0 4250 0 4251 0 4250 0 4252 0 4251 0 4251 3011 4252 3011 4253 3011 4251 3012 4253 3012 4203 3012 4203 3013 4253 3013 4254 3013 4203 0 4254 0 4239 0 4243 0 4247 0 4244 0 4244 0 4247 0 4249 0 4244 3014 4249 3014 4255 3014 4255 3015 4249 3015 4256 3015 4257 0 4258 0 4259 0 4259 3016 4258 3016 4256 3016 4259 0 4256 0 4260 0 4260 3017 4256 3017 4249 3017 4260 0 4249 0 4261 0 4262 3018 4263 3018 4264 3018 4264 0 4263 0 4265 0 4264 3019 4265 3019 4266 3019 4266 3020 4265 3020 4267 3020 4266 0 4267 0 4268 0 4269 0 4270 0 4271 0 4271 3021 4270 3021 4272 3021 4271 0 4272 0 4273 0 4273 3022 4272 3022 4274 3022 4273 0 4274 0 4275 0 4276 3023 4277 3023 4278 3023 4278 0 4277 0 4279 0 4278 3024 4279 3024 4280 3024 4280 3025 4279 3025 4281 3025 4280 0 4281 0 4282 0 4259 0 4268 0 4257 0 4257 0 4268 0 4267 0 4257 0 4267 0 4283 0 4283 0 4267 0 4284 0 4212 0 4285 0 4213 0 4213 3026 4285 3026 4286 3026 4213 3027 4286 3027 4287 3027 4284 0 4288 0 4212 0 4212 3028 4288 3028 4289 3028 4212 3029 4289 3029 4285 3029 4290 0 4291 0 4267 0 4267 3030 4291 3030 4292 3030 4267 0 4292 0 4284 0 4284 3031 4292 3031 4293 3031 4284 3032 4293 3032 4288 3032 4294 0 4295 0 4296 0 4296 0 4295 0 4297 0 4296 0 4297 0 4298 0 4298 0 4297 0 4287 0 4287 0 4297 0 4213 0 4213 0 4297 0 4299 0 4213 0 4299 0 4300 0 4301 3033 4302 3033 4303 3033 4303 3034 4302 3034 4304 3034 4303 0 4304 0 4305 0 4214 0 4306 0 4307 0 4307 3005 4306 3005 4308 3005 4309 0 4310 0 4299 0 4299 3035 4310 3035 4311 3035 4299 3036 4311 3036 4300 3036 4300 0 4312 0 4213 0 4213 3037 4312 3037 4313 3037 4213 0 4313 0 4214 0 4214 3038 4313 3038 4314 3038 4214 0 4314 0 4306 0 4303 0 4315 0 4316 0 4308 3039 4301 3039 4307 3039 4307 0 4301 0 4303 0 4307 0 4303 0 4317 0 4317 0 4303 0 4316 0 4317 0 4316 0 4318 0 4319 0 4303 0 4309 0 4309 0 4303 0 4305 0 4309 0 4305 0 4310 0 4320 3040 4321 3040 4319 3040 4319 0 4321 0 4322 0 4319 3041 4322 3041 4303 3041 4303 0 4322 0 4323 0 4303 0 4323 0 4315 0 4294 0 4290 0 4295 0 4295 0 4290 0 4267 0 4295 0 4267 0 4324 0 4324 0 4267 0 4265 0 4264 3019 4275 3019 4262 3019 4262 3020 4275 3020 4274 3020 4262 0 4274 0 4325 0 4325 0 4274 0 4326 0 4327 0 4328 0 4274 0 4274 3030 4328 3030 4329 3030 4274 0 4329 0 4326 0 4329 0 4330 0 4326 0 4326 3042 4330 3042 4331 3042 4326 3043 4331 3043 4332 3043 4332 3044 4331 3044 4333 3044 4334 0 4335 0 4210 0 4210 3027 4335 3027 4336 3027 4210 0 4336 0 4211 0 4336 3045 4337 3045 4211 3045 4211 3029 4337 3029 4338 3029 4211 0 4338 0 4339 0 4339 3046 4338 3046 4340 3046 4341 3047 4342 3047 4343 3047 4333 0 4334 0 4332 0 4332 0 4334 0 4210 0 4332 0 4210 0 4344 0 4344 0 4210 0 4345 0 4345 3048 4346 3048 4344 3048 4344 3036 4346 3036 4347 3036 4344 3049 4347 3049 4348 3049 4348 0 4347 0 4349 0 4341 0 4343 0 4350 0 4350 3050 4343 3050 4351 3050 4350 0 4351 0 4352 0 4352 3051 4351 3051 4353 3051 4352 3052 4353 3052 4354 3052 4354 0 4353 0 4355 0 4354 0 4355 0 4356 0 4356 0 4355 0 4357 0 4356 0 4357 0 4209 0 4209 0 4357 0 4358 0 4209 0 4358 0 4210 0 4210 0 4358 0 4359 0 4210 3037 4359 3037 4345 3037 4349 0 4342 0 4348 0 4348 3053 4342 3053 4341 3053 4348 3054 4341 3054 4360 3054 4360 3055 4341 3055 4361 3055 4361 0 4362 0 4360 0 4360 0 4362 0 4363 0 4360 3056 4363 3056 4364 3056 4340 0 4327 0 4339 0 4339 0 4327 0 4274 0 4339 3057 4274 3057 4365 3057 4365 3058 4274 3058 4272 3058 4271 0 4282 0 4269 0 4269 0 4282 0 4281 0 4269 0 4281 0 4366 0 4366 0 4281 0 4367 0 4368 0 4369 0 4207 0 4207 3008 4369 3008 4370 3008 4207 0 4370 0 4208 0 4371 0 4372 0 4373 0 4373 0 4372 0 4208 0 4373 0 4208 0 4374 0 4374 0 4208 0 4370 0 4375 0 4376 0 4281 0 4281 3010 4376 3010 4377 3010 4281 0 4377 0 4367 0 4377 3059 4378 3059 4367 3059 4367 3060 4378 3060 4379 3060 4367 0 4379 0 4380 0 4380 3061 4379 3061 4381 3061 4207 3001 4382 3001 4383 3001 4384 0 4385 0 4386 0 4386 3062 4385 3062 4387 3062 4386 0 4387 0 4388 0 4381 3009 4368 3009 4380 3009 4380 0 4368 0 4207 0 4380 0 4207 0 4389 0 4389 0 4207 0 4383 0 4383 3002 4390 3002 4389 3002 4389 0 4390 0 4391 0 4389 0 4391 0 4392 0 4392 0 4391 0 4388 0 4392 0 4388 0 4393 0 4393 0 4388 0 4387 0 4382 3063 4207 3063 4394 3063 4394 0 4207 0 4206 0 4394 0 4206 0 4395 0 4395 3064 4206 3064 4396 3064 4395 0 4396 0 4397 0 4397 0 4396 0 4398 0 4397 0 4398 0 4399 0 4399 0 4398 0 4400 0 4399 0 4400 0 4401 0 4401 0 4400 0 4402 0 4401 0 4402 0 4384 0 4384 0 4402 0 4403 0 4384 0 4403 0 4385 0 4371 0 4375 0 4372 0 4372 0 4375 0 4281 0 4372 0 4281 0 4404 0 4404 0 4281 0 4279 0 4278 3024 4261 3024 4276 3024 4276 3025 4261 3025 4249 3025 4276 0 4249 0 4405 0 4405 0 4249 0 4251 0 4360 3065 4121 3065 4348 3065 4348 3066 4121 3066 4104 3066 4348 3067 4104 3067 4344 3067 4344 3068 4104 3068 4014 3068 4344 3069 4014 3069 4332 3069 4332 3069 4014 3069 4016 3069 4332 3069 4016 3069 4326 3069 4326 3069 4016 3069 4086 3069 4326 3069 4086 3069 4325 3069 4325 3070 4086 3070 4123 3070 4109 3071 4356 3071 4106 3071 4106 3071 4356 3071 4209 3071 4106 3072 4209 3072 4089 3072 4089 3073 4209 3073 4211 3073 4089 3074 4211 3074 4084 3074 4084 3074 4211 3074 4339 3074 4084 3072 4339 3072 4083 3072 4083 3075 4339 3075 4365 3075 4199 3066 4226 3066 4182 3066 4182 3065 4226 3065 4215 3065 4182 3067 4215 3067 4163 3067 4163 3068 4215 3068 4217 3068 4163 3076 4217 3076 4164 3076 4164 3077 4217 3077 4242 3077 4164 3069 4242 3069 4162 3069 4162 3069 4242 3069 4244 3069 4162 3076 4244 3076 4161 3076 4161 3078 4244 3078 4255 3078 4232 3071 4190 3071 4205 3071 4205 3071 4190 3071 4003 3071 4205 3074 4003 3074 4203 3074 4203 3074 4003 3074 4005 3074 4203 3074 4005 3074 4251 3074 4251 3074 4005 3074 4172 3074 4251 3074 4172 3074 4405 3074 4405 3079 4172 3079 4201 3079 4022 3080 4396 3080 4002 3080 4002 3080 4396 3080 4206 3080 4002 3081 4206 3081 4000 3081 4000 3081 4206 3081 4208 3081 4000 3081 4208 3081 4044 3081 4044 3081 4208 3081 4372 3081 4044 3082 4372 3082 4202 3082 4202 3083 4372 3083 4404 3083 4392 3084 4036 3084 4389 3084 4389 3084 4036 3084 4038 3084 4389 3085 4038 3085 4380 3085 4380 3086 4038 3086 4042 3086 4380 3087 4042 3087 4367 3087 4367 3087 4042 3087 4040 3087 4367 3088 4040 3088 4366 3088 4366 3089 4040 3089 4055 3089 4009 3090 4319 3090 4010 3090 4010 3091 4319 3091 4309 3091 4010 3092 4309 3092 4013 3092 4013 3093 4309 3093 4299 3093 4013 3087 4299 3087 4011 3087 4011 3087 4299 3087 4297 3087 4011 3087 4297 3087 4125 3087 4125 3087 4297 3087 4295 3087 4125 3094 4295 3094 4124 3094 4124 3095 4295 3095 4324 3095 4317 3096 4156 3096 4307 3096 4307 3097 4156 3097 4145 3097 4307 3098 4145 3098 4214 3098 4214 3099 4145 3099 4142 3099 4214 3100 4142 3100 4212 3100 4212 3101 4142 3101 4136 3101 4212 3081 4136 3081 4284 3081 4284 3081 4136 3081 4138 3081 4284 3102 4138 3102 4283 3102 4283 3103 4138 3103 4160 3103 4196 3104 4225 3104 4223 3104 4196 3105 4223 3105 4197 3105 4197 3106 4223 3106 4222 3106 4197 3106 4222 3106 4198 3106 4198 3107 4222 3107 4224 3107 4198 3107 4224 3107 4200 3107 4200 3108 4224 3108 4226 3108 4200 3109 4226 3109 4199 3109 4235 3110 4186 3110 4237 3110 4237 3111 4186 3111 4188 3111 4237 3112 4188 3112 4238 3112 4238 3113 4188 3113 4190 3113 4238 3113 4190 3113 4232 3113 4225 3114 4196 3114 4219 3114 4219 3114 4196 3114 4180 3114 4219 3115 4180 3115 4235 3115 4235 3115 4180 3115 4184 3115 4235 3116 4184 3116 4186 3116 4008 3117 4323 3117 4322 3117 4008 3117 4322 3117 4006 3117 4006 3118 4322 3118 4321 3118 4006 3119 4321 3119 4154 3119 4154 3120 4321 3120 4320 3120 4154 3121 4320 3121 4155 3121 4155 3122 4320 3122 4319 3122 4155 3122 4319 3122 4009 3122 4156 3123 4317 3123 4318 3123 4156 3124 4318 3124 4159 3124 4159 3125 4318 3125 4316 3125 4159 3125 4316 3125 4158 3125 4158 3126 4316 3126 4315 3126 4158 3126 4315 3126 4157 3126 4157 3127 4315 3127 4323 3127 4157 3128 4323 3128 4008 3128 4120 3129 4361 3129 4116 3129 4116 3129 4361 3129 4341 3129 4116 3130 4341 3130 4114 3130 4341 3130 4350 3130 4114 3130 4114 3131 4350 3131 4352 3131 4114 3131 4352 3131 4112 3131 4112 3132 4352 3132 4354 3132 4112 3132 4354 3132 4111 3132 4111 3133 4354 3133 4356 3133 4111 3134 4356 3134 4109 3134 4121 3117 4360 3117 4364 3117 4121 3117 4364 3117 4122 3117 4122 3135 4364 3135 4363 3135 4122 3136 4363 3136 4118 3136 4118 3137 4363 3137 4362 3137 4118 3138 4362 3138 4119 3138 4119 3122 4362 3122 4361 3122 4119 3122 4361 3122 4120 3122 4029 3113 4403 3113 4402 3113 4029 3113 4402 3113 4027 3113 4027 3139 4402 3139 4400 3139 4027 3140 4400 3140 4025 3140 4025 3141 4400 3141 4398 3141 4025 3142 4398 3142 4024 3142 4024 3143 4398 3143 4396 3143 4024 3143 4396 3143 4022 3143 4036 3144 4392 3144 4393 3144 4036 3145 4393 3145 4034 3145 4034 3146 4393 3146 4387 3146 4034 3146 4387 3146 4032 3146 4032 3147 4387 3147 4385 3147 4032 3147 4385 3147 4031 3147 4031 3148 4385 3148 4403 3148 4031 3149 4403 3149 4029 3149 4124 3150 4324 3150 4076 3150 4076 3151 4324 3151 4265 3151 4076 3152 4265 3152 4077 3152 4077 3153 4265 3153 4263 3153 4077 3154 4263 3154 4079 3154 4079 3155 4263 3155 4262 3155 4079 3156 4262 3156 4123 3156 4123 3157 4262 3157 4325 3157 4283 3158 4160 3158 4257 3158 4257 3159 4160 3159 4060 3159 4257 3160 4060 3160 4258 3160 4258 3160 4060 3160 4058 3160 4258 3161 4058 3161 4256 3161 4256 3161 4058 3161 4057 3161 4256 3162 4057 3162 4255 3162 4255 3163 4057 3163 4161 3163 4202 3164 4404 3164 4064 3164 4064 3165 4404 3165 4279 3165 4064 3166 4279 3166 4065 3166 4065 3167 4279 3167 4277 3167 4065 3168 4277 3168 4067 3168 4067 3169 4277 3169 4276 3169 4067 3170 4276 3170 4201 3170 4201 3171 4276 3171 4405 3171 4366 3172 4055 3172 4269 3172 4269 3173 4055 3173 4056 3173 4269 3174 4056 3174 4270 3174 4270 3174 4056 3174 4072 3174 4270 3175 4072 3175 4272 3175 4272 3175 4072 3175 4071 3175 4272 3176 4071 3176 4365 3176 4365 3177 4071 3177 4083 3177 4378 3178 4047 3178 4379 3178 4379 3179 4047 3179 4039 3179 4379 3180 4039 3180 4381 3180 4381 3180 4039 3180 4041 3180 4381 3181 4041 3181 4368 3181 4368 3182 4041 3182 4043 3182 4368 3183 4043 3183 4369 3183 4369 3183 4043 3183 4046 3183 4369 3184 4046 3184 4370 3184 4370 3184 4046 3184 4054 3184 4370 3185 4054 3185 4374 3185 4374 3185 4054 3185 4053 3185 4374 3186 4053 3186 4373 3186 4373 3186 4053 3186 4052 3186 4373 3187 4052 3187 4371 3187 4371 3187 4052 3187 4045 3187 4371 3188 4045 3188 4375 3188 4375 3188 4045 3188 4051 3188 4375 3189 4051 3189 4376 3189 4376 3190 4051 3190 4050 3190 4376 3191 4050 3191 4377 3191 4377 3191 4050 3191 4048 3191 4377 3192 4048 3192 4378 3192 4378 3193 4048 3193 4047 3193 4264 3194 4406 3194 4275 3194 4275 3195 4406 3195 4080 3195 4275 3083 4080 3083 4273 3083 4273 3083 4080 3083 4082 3083 4273 3196 4082 3196 4271 3196 4271 3197 4082 3197 4073 3197 4271 3198 4073 3198 4282 3198 4282 3199 4073 3199 4074 3199 4282 3078 4074 3078 4280 3078 4280 3078 4074 3078 4075 3078 4280 3200 4075 3200 4278 3200 4278 3201 4075 3201 4066 3201 4278 3202 4066 3202 4261 3202 4261 3203 4066 3203 4068 3203 4261 3095 4068 3095 4260 3095 4260 3095 4068 3095 4070 3095 4260 3204 4070 3204 4259 3204 4259 3205 4070 3205 4059 3205 4259 3206 4059 3206 4268 3206 4268 3207 4059 3207 4061 3207 4268 3075 4061 3075 4266 3075 4266 3075 4061 3075 4063 3075 4266 3208 4063 3208 4264 3208 4264 3209 4063 3209 4406 3209 4390 3210 4017 3210 4391 3210 4391 3210 4017 3210 4037 3210 4391 3211 4037 3211 4388 3211 4388 3211 4037 3211 4035 3211 4388 3212 4035 3212 4386 3212 4386 3212 4035 3212 4033 3212 4386 3213 4033 3213 4384 3213 4384 3213 4033 3213 4030 3213 4384 3214 4030 3214 4401 3214 4401 3214 4030 3214 4028 3214 4401 3215 4028 3215 4399 3215 4399 3215 4028 3215 4026 3215 4399 3216 4026 3216 4397 3216 4397 3216 4026 3216 4023 3216 4397 3217 4023 3217 4395 3217 4395 3217 4023 3217 4021 3217 4395 3218 4021 3218 4394 3218 4394 3218 4021 3218 4020 3218 4394 3219 4020 3219 4382 3219 4382 3219 4020 3219 4019 3219 4382 3220 4019 3220 4383 3220 4383 3220 4019 3220 4018 3220 4383 3221 4018 3221 4390 3221 4390 3221 4018 3221 4017 3221 4247 3222 4177 3222 4248 3222 4248 3223 4177 3223 4176 3223 4248 3224 4176 3224 4250 3224 4250 3224 4176 3224 4175 3224 4250 3181 4175 3181 4252 3181 4252 3182 4175 3182 4174 3182 4252 3183 4174 3183 4253 3183 4253 3183 4174 3183 4173 3183 4253 3225 4173 3225 4254 3225 4254 3225 4173 3225 4171 3225 4254 3226 4171 3226 4239 3226 4239 3226 4171 3226 4170 3226 4239 3227 4170 3227 4240 3227 4240 3227 4170 3227 4169 3227 4240 3228 4169 3228 4241 3228 4241 3228 4169 3228 4168 3228 4241 3188 4168 3188 4246 3188 4246 3188 4168 3188 4165 3188 4246 3189 4165 3189 4245 3189 4245 3190 4165 3190 4167 3190 4245 3229 4167 3229 4243 3229 4243 3229 4167 3229 4166 3229 4243 3230 4166 3230 4247 3230 4247 3231 4166 3231 4177 3231 4298 3223 4128 3223 4296 3223 4296 3223 4128 3223 4127 3223 4296 3232 4127 3232 4294 3232 4294 3232 4127 3232 4126 3232 4294 3181 4126 3181 4290 3181 4290 3181 4126 3181 4134 3181 4290 3233 4134 3233 4291 3233 4291 3183 4134 3183 4133 3183 4291 3234 4133 3234 4292 3234 4292 3234 4133 3234 4132 3234 4292 3226 4132 3226 4293 3226 4293 3235 4132 3235 4131 3235 4293 3236 4131 3236 4288 3236 4288 3227 4131 3227 4139 3227 4288 3237 4139 3237 4289 3237 4289 3237 4139 3237 4137 3237 4289 3188 4137 3188 4285 3188 4285 3238 4137 3238 4135 3238 4285 3190 4135 3190 4286 3190 4286 3190 4135 3190 4130 3190 4286 3239 4130 3239 4287 3239 4287 3239 4130 3239 4129 3239 4287 3230 4129 3230 4298 3230 4298 3230 4129 3230 4128 3230 4334 3179 4094 3179 4335 3179 4335 3179 4094 3179 4093 3179 4335 3240 4093 3240 4336 3240 4336 3240 4093 3240 4092 3240 4336 3181 4092 3181 4337 3181 4337 3181 4092 3181 4091 3181 4337 3233 4091 3233 4338 3233 4338 3183 4091 3183 4088 3183 4338 3241 4088 3241 4340 3241 4340 3241 4088 3241 4090 3241 4340 3185 4090 3185 4327 3185 4327 3242 4090 3242 4098 3242 4327 3243 4098 3243 4328 3243 4328 3186 4098 3186 4097 3186 4328 3244 4097 3244 4329 3244 4329 3244 4097 3244 4096 3244 4329 3188 4096 3188 4330 3188 4330 3238 4096 3238 4095 3238 4330 3190 4095 3190 4331 3190 4331 3190 4095 3190 4085 3190 4331 3245 4085 3245 4333 3245 4333 3245 4085 3245 4087 3245 4333 3192 4087 3192 4334 3192 4334 3192 4087 3192 4094 3192 4227 3210 4195 3210 4228 3210 4228 3210 4195 3210 4194 3210 4228 3211 4194 3211 4229 3211 4229 3211 4194 3211 4193 3211 4229 3212 4193 3212 4230 3212 4230 3212 4193 3212 4192 3212 4230 3213 4192 3213 4231 3213 4231 3213 4192 3213 4191 3213 4231 3214 4191 3214 4233 3214 4233 3214 4191 3214 4189 3214 4233 3215 4189 3215 4236 3215 4236 3215 4189 3215 4187 3215 4236 3216 4187 3216 4234 3216 4234 3216 4187 3216 4185 3216 4234 3217 4185 3217 4220 3217 4220 3217 4185 3217 4179 3217 4220 3218 4179 3218 4221 3218 4221 3218 4179 3218 4178 3218 4221 3219 4178 3219 4216 3219 4216 3219 4178 3219 4181 3219 4216 3220 4181 3220 4218 3220 4218 3220 4181 3220 4183 3220 4218 3221 4183 3221 4227 3221 4227 3221 4183 3221 4195 3221 4305 3210 4152 3210 4310 3210 4310 3210 4152 3210 4151 3210 4310 3211 4151 3211 4311 3211 4311 3211 4151 3211 4144 3211 4311 3212 4144 3212 4300 3212 4300 3212 4144 3212 4150 3212 4300 3213 4150 3213 4312 3213 4312 3213 4150 3213 4149 3213 4312 3214 4149 3214 4313 3214 4313 3214 4149 3214 4148 3214 4313 3215 4148 3215 4314 3215 4314 3215 4148 3215 4143 3215 4314 3216 4143 3216 4306 3216 4306 3216 4143 3216 4147 3216 4306 3217 4147 3217 4308 3217 4308 3217 4147 3217 4146 3217 4308 3218 4146 3218 4301 3218 4301 3218 4146 3218 4141 3218 4301 3219 4141 3219 4302 3219 4302 3219 4141 3219 4140 3219 4302 3220 4140 3220 4304 3220 4304 3220 4140 3220 4153 3220 4304 3221 4153 3221 4305 3221 4305 3221 4153 3221 4152 3221 4342 3210 4105 3210 4343 3210 4343 3210 4105 3210 4117 3210 4343 3211 4117 3211 4351 3211 4351 3211 4117 3211 4115 3211 4351 3212 4115 3212 4353 3212 4353 3212 4115 3212 4113 3212 4353 3213 4113 3213 4355 3213 4355 3213 4113 3213 4110 3213 4355 3214 4110 3214 4357 3214 4357 3214 4110 3214 4108 3214 4357 3215 4108 3215 4358 3215 4358 3215 4108 3215 4107 3215 4358 3216 4107 3216 4359 3216 4359 3216 4107 3216 4102 3216 4359 3217 4102 3217 4345 3217 4345 3217 4102 3217 4101 3217 4345 3218 4101 3218 4346 3218 4346 3218 4101 3218 4100 3218 4346 3219 4100 3219 4347 3219 4347 3219 4100 3219 4099 3219 4347 3220 4099 3220 4349 3220 4349 3220 4099 3220 4103 3220 4349 3221 4103 3221 4342 3221 4342 3221 4103 3221 4105 3221 4407 3246 4408 3246 4409 3246 4410 3247 4411 3247 4412 3247 4413 3248 4414 3248 4415 3248 4416 3249 4417 3249 4418 3249 4419 3250 4420 3250 4421 3250 4419 3251 4422 3251 4420 3251 4420 3252 4422 3252 4423 3252 4420 3253 4423 3253 4424 3253 4423 3254 4425 3254 4424 3254 4424 3255 4425 3255 4426 3255 4424 3256 4426 3256 4427 3256 4427 3257 4426 3257 4428 3257 4427 3258 4428 3258 4429 3258 4430 3259 4431 3259 4432 3259 4432 3260 4433 3260 4430 3260 4430 3261 4433 3261 4434 3261 4430 3262 4434 3262 4435 3262 4434 3263 4436 3263 4435 3263 4435 3264 4436 3264 4437 3264 4435 3265 4437 3265 4438 3265 4438 3266 4437 3266 4439 3266 4438 3267 4439 3267 4440 3267 4441 3268 4442 3268 4443 3268 4441 3269 4444 3269 4442 3269 4442 3270 4444 3270 4445 3270 4442 3271 4445 3271 4446 3271 4445 3272 4447 3272 4446 3272 4446 3273 4447 3273 4448 3273 4446 3274 4448 3274 4449 3274 4449 3275 4448 3275 4450 3275 4449 3276 4450 3276 4451 3276 4452 3277 4453 3277 4454 3277 4454 3278 4455 3278 4452 3278 4452 3279 4455 3279 4456 3279 4452 3280 4456 3280 4457 3280 4456 3281 4458 3281 4457 3281 4457 3282 4458 3282 4459 3282 4457 3283 4459 3283 4460 3283 4460 3284 4459 3284 4461 3284 4460 3285 4461 3285 4462 3285 4429 3286 4428 3286 4463 3286 4463 3287 4428 3287 4464 3287 4463 3288 4464 3288 4465 3288 4464 3289 4466 3289 4465 3289 4465 3290 4466 3290 4467 3290 4465 3291 4467 3291 4468 3291 4467 3292 4469 3292 4468 3292 4468 3293 4469 3293 4470 3293 4468 3294 4470 3294 4471 3294 4470 3295 4472 3295 4471 3295 4471 3296 4472 3296 4473 3296 4471 3297 4473 3297 4415 3297 4415 3298 4473 3298 4474 3298 4415 3248 4474 3248 4413 3248 4413 3299 4474 3299 4475 3299 4413 3300 4475 3300 4431 3300 4431 3301 4475 3301 4476 3301 4431 3302 4476 3302 4432 3302 4440 3303 4439 3303 4477 3303 4477 3304 4439 3304 4478 3304 4477 3305 4478 3305 4479 3305 4478 3306 4480 3306 4479 3306 4479 3307 4480 3307 4481 3307 4479 3308 4481 3308 4482 3308 4481 3309 4483 3309 4482 3309 4482 3310 4483 3310 4484 3310 4482 3311 4484 3311 4485 3311 4484 3312 4486 3312 4485 3312 4485 3313 4486 3313 4487 3313 4485 3314 4487 3314 4412 3314 4412 3315 4487 3315 4488 3315 4412 3316 4488 3316 4410 3316 4410 3317 4488 3317 4489 3317 4410 3318 4489 3318 4443 3318 4443 3319 4489 3319 4490 3319 4443 3320 4490 3320 4441 3320 4451 3321 4450 3321 4491 3321 4491 3322 4450 3322 4492 3322 4491 3323 4492 3323 4493 3323 4492 3324 4494 3324 4493 3324 4493 3325 4494 3325 4495 3325 4493 3326 4495 3326 4496 3326 4495 3327 4497 3327 4496 3327 4496 3328 4497 3328 4498 3328 4496 3329 4498 3329 4499 3329 4498 3330 4500 3330 4499 3330 4499 3331 4500 3331 4501 3331 4499 3332 4501 3332 4409 3332 4409 3333 4501 3333 4502 3333 4409 3334 4502 3334 4407 3334 4407 3335 4502 3335 4503 3335 4407 3336 4503 3336 4453 3336 4453 3337 4503 3337 4504 3337 4453 3338 4504 3338 4454 3338 4462 3339 4461 3339 4505 3339 4505 3340 4461 3340 4506 3340 4505 3341 4506 3341 4507 3341 4506 3342 4508 3342 4507 3342 4507 3343 4508 3343 4509 3343 4507 3344 4509 3344 4510 3344 4509 3345 4511 3345 4510 3345 4510 3346 4511 3346 4512 3346 4510 3347 4512 3347 4513 3347 4512 3348 4514 3348 4513 3348 4513 3349 4514 3349 4515 3349 4513 3350 4515 3350 4418 3350 4418 3351 4515 3351 4516 3351 4418 3352 4516 3352 4416 3352 4416 3353 4516 3353 4517 3353 4416 3354 4517 3354 4421 3354 4421 3355 4517 3355 4518 3355 4421 3356 4518 3356 4419 3356 4411 88 4519 88 4412 88 4412 88 4519 88 4485 88 4520 88 4521 88 4522 88 4523 88 4524 88 4525 88 4525 88 4524 88 4526 88 4527 88 4528 88 4529 88 4485 88 4530 88 4482 88 4482 3357 4530 3357 4524 3357 4482 88 4524 88 4479 88 4479 88 4524 88 4523 88 4531 88 4471 88 4532 88 4532 88 4471 88 4415 88 4532 88 4415 88 4414 88 4523 88 4533 88 4479 88 4479 88 4533 88 4534 88 4479 88 4534 88 4477 88 4477 88 4534 88 4440 88 4526 88 4524 88 4535 88 4535 88 4524 88 4536 88 4535 88 4536 88 4537 88 4537 88 4536 88 4538 88 4537 88 4538 88 4539 88 4540 88 4541 88 4542 88 4542 88 4541 88 4543 88 4543 88 4541 88 4544 88 4543 88 4544 88 4545 88 4522 88 4521 88 4546 88 4546 88 4521 88 4547 88 4546 88 4547 88 4548 88 4549 88 4520 88 4499 88 4499 88 4520 88 4522 88 4499 88 4522 88 4496 88 4496 88 4522 88 4529 88 4496 88 4529 88 4493 88 4493 88 4529 88 4528 88 4542 88 4550 88 4540 88 4540 88 4550 88 4551 88 4540 88 4551 88 4552 88 4549 88 4499 88 4553 88 4553 88 4499 88 4409 88 4553 88 4409 88 4408 88 4519 88 4554 88 4485 88 4485 88 4554 88 4555 88 4485 88 4555 88 4530 88 4530 88 4555 88 4556 88 4530 88 4556 88 4557 88 4557 88 4556 88 4558 88 4557 88 4558 88 4529 88 4529 88 4558 88 4559 88 4529 88 4559 88 4527 88 4528 88 4560 88 4493 88 4493 88 4560 88 4561 88 4493 88 4561 88 4491 88 4491 88 4561 88 4451 88 4531 88 4539 88 4471 88 4471 88 4539 88 4538 88 4471 88 4538 88 4468 88 4468 88 4538 88 4540 88 4468 88 4540 88 4465 88 4465 88 4540 88 4552 88 4552 88 4562 88 4465 88 4465 88 4562 88 4563 88 4465 88 4563 88 4463 88 4463 88 4563 88 4429 88 4564 88 4513 88 4565 88 4565 88 4513 88 4418 88 4565 88 4418 88 4417 88 4547 88 4566 88 4548 88 4548 88 4566 88 4567 88 4548 88 4567 88 4568 88 4462 88 4505 88 4569 88 4569 88 4505 88 4507 88 4569 88 4507 88 4570 88 4564 88 4545 88 4513 88 4513 88 4545 88 4544 88 4513 88 4544 88 4510 88 4510 88 4544 88 4548 88 4510 88 4548 88 4507 88 4507 88 4548 88 4568 88 4507 88 4568 88 4570 88 4571 88 4416 88 4421 88 4572 88 4573 88 4574 88 4575 88 4576 88 4577 88 4577 88 4576 88 4578 88 4574 88 4571 88 4572 88 4572 88 4571 88 4421 88 4572 88 4421 88 4579 88 4579 88 4421 88 4420 88 4579 88 4420 88 4580 88 4580 88 4420 88 4424 88 4580 88 4424 88 4578 88 4578 88 4424 88 4427 88 4578 88 4427 88 4577 88 4565 3358 4417 3358 4571 3358 4571 3359 4417 3359 4416 3359 4563 3360 4577 3360 4429 3360 4429 3360 4577 3360 4427 3360 4577 3361 4563 3361 4575 3361 4575 3362 4563 3362 4562 3362 4575 3363 4562 3363 4576 3363 4576 3363 4562 3363 4552 3363 4576 3364 4552 3364 4578 3364 4578 3364 4552 3364 4551 3364 4578 3365 4551 3365 4580 3365 4580 3365 4551 3365 4550 3365 4580 3366 4550 3366 4579 3366 4579 3367 4550 3367 4542 3367 4579 3368 4542 3368 4572 3368 4572 3369 4542 3369 4543 3369 4572 3370 4543 3370 4573 3370 4573 3371 4543 3371 4545 3371 4573 3372 4545 3372 4574 3372 4574 3373 4545 3373 4564 3373 4574 3374 4564 3374 4571 3374 4571 3375 4564 3375 4565 3375 4581 88 4413 88 4431 88 4582 88 4583 88 4584 88 4584 88 4581 88 4582 88 4582 88 4581 88 4431 88 4582 88 4431 88 4585 88 4585 88 4431 88 4430 88 4585 88 4430 88 4586 88 4586 88 4430 88 4435 88 4586 88 4435 88 4587 88 4588 88 4589 88 4590 88 4590 88 4589 88 4587 88 4590 88 4587 88 4438 88 4438 88 4587 88 4435 88 4534 3376 4590 3376 4440 3376 4440 3377 4590 3377 4438 3377 4532 3378 4414 3378 4581 3378 4581 3379 4414 3379 4413 3379 4590 3380 4534 3380 4588 3380 4588 3380 4534 3380 4533 3380 4588 3381 4533 3381 4589 3381 4589 3382 4533 3382 4523 3382 4589 3383 4523 3383 4587 3383 4587 3384 4523 3384 4525 3384 4587 3385 4525 3385 4586 3385 4586 3386 4525 3386 4526 3386 4586 3387 4526 3387 4585 3387 4585 3387 4526 3387 4535 3387 4585 3388 4535 3388 4582 3388 4582 3388 4535 3388 4537 3388 4582 3389 4537 3389 4583 3389 4583 3390 4537 3390 4539 3390 4583 3391 4539 3391 4584 3391 4584 3392 4539 3392 4531 3392 4584 3393 4531 3393 4581 3393 4581 3394 4531 3394 4532 3394 4591 88 4410 88 4443 88 4592 88 4593 88 4594 88 4595 88 4596 88 4597 88 4597 88 4596 88 4598 88 4594 88 4591 88 4592 88 4592 88 4591 88 4443 88 4592 88 4443 88 4599 88 4599 88 4443 88 4442 88 4599 88 4442 88 4600 88 4600 88 4442 88 4446 88 4600 88 4446 88 4598 88 4598 88 4446 88 4449 88 4598 88 4449 88 4597 88 4561 3395 4597 3395 4451 3395 4451 3395 4597 3395 4449 3395 4519 3396 4411 3396 4591 3396 4591 3397 4411 3397 4410 3397 4597 3398 4561 3398 4595 3398 4595 3399 4561 3399 4560 3399 4595 3400 4560 3400 4596 3400 4596 3400 4560 3400 4528 3400 4596 3401 4528 3401 4598 3401 4598 3401 4528 3401 4527 3401 4598 3402 4527 3402 4600 3402 4600 3402 4527 3402 4559 3402 4600 3403 4559 3403 4599 3403 4599 3404 4559 3404 4558 3404 4599 3405 4558 3405 4592 3405 4592 3406 4558 3406 4556 3406 4592 3407 4556 3407 4593 3407 4593 3408 4556 3408 4555 3408 4593 3409 4555 3409 4594 3409 4594 3410 4555 3410 4554 3410 4594 3411 4554 3411 4591 3411 4591 3412 4554 3412 4519 3412 4601 88 4407 88 4453 88 4602 88 4603 88 4604 88 4604 88 4601 88 4602 88 4602 88 4601 88 4453 88 4602 88 4453 88 4605 88 4605 88 4453 88 4452 88 4605 88 4452 88 4606 88 4606 88 4452 88 4457 88 4606 88 4457 88 4607 88 4608 88 4609 88 4610 88 4610 88 4609 88 4607 88 4610 88 4607 88 4460 88 4460 88 4607 88 4457 88 4569 3413 4610 3413 4462 3413 4462 3414 4610 3414 4460 3414 4553 3376 4408 3376 4601 3376 4601 3376 4408 3376 4407 3376 4610 3415 4569 3415 4608 3415 4608 3415 4569 3415 4570 3415 4608 3416 4570 3416 4609 3416 4609 3417 4570 3417 4568 3417 4609 3418 4568 3418 4607 3418 4607 3419 4568 3419 4567 3419 4607 3420 4567 3420 4606 3420 4606 3421 4567 3421 4566 3421 4606 3422 4566 3422 4605 3422 4605 3422 4566 3422 4547 3422 4605 3423 4547 3423 4602 3423 4602 3423 4547 3423 4521 3423 4602 3424 4521 3424 4603 3424 4603 3425 4521 3425 4520 3425 4603 3426 4520 3426 4604 3426 4604 3427 4520 3427 4549 3427 4604 3428 4549 3428 4601 3428 4601 3429 4549 3429 4553 3429 4611 0 4612 0 4613 0 4611 0 4613 0 4614 0 4615 0 4616 0 4617 0 4617 0 4616 0 4618 0 4613 0 4619 0 4620 0 4621 0 4622 0 4613 0 4613 0 4622 0 4623 0 4613 0 4623 0 4624 0 4624 0 4625 0 4613 0 4613 0 4625 0 4626 0 4613 0 4626 0 4627 0 4628 0 4629 0 4613 0 4613 0 4629 0 4617 0 4613 0 4617 0 4630 0 4630 0 4617 0 4618 0 4613 0 4631 0 4632 0 4612 0 4633 0 4613 0 4613 0 4633 0 4634 0 4613 0 4634 0 4619 0 4632 0 4635 0 4613 0 4613 0 4635 0 4636 0 4613 0 4636 0 4614 0 4620 0 4637 0 4613 0 4613 0 4637 0 4638 0 4613 0 4638 0 4621 0 4627 0 4639 0 4613 0 4613 0 4639 0 4640 0 4613 0 4640 0 4641 0 4641 0 4642 0 4613 0 4613 0 4642 0 4643 0 4613 0 4643 0 4628 0 4617 0 4644 0 4615 0 4615 0 4644 0 4645 0 4615 0 4645 0 4646 0 4646 0 4645 0 4647 0 4646 0 4647 0 4648 0 4621 3430 4638 3430 4649 3430 4650 3431 4651 3431 4652 3431 4653 3432 4654 3432 4655 3432 4656 3433 4511 3433 4509 3433 4511 3434 4656 3434 4512 3434 4657 3435 4658 3435 4659 3435 4660 3436 4661 3436 4662 3436 4663 3437 4664 3437 4665 3437 4666 3438 4626 3438 4625 3438 4667 3439 4668 3439 4669 3439 4670 3440 4671 3440 4672 3440 4672 3441 4671 3441 4673 3441 4672 3442 4673 3442 4674 3442 4667 3443 4669 3443 4675 3443 4676 3444 4677 3444 4678 3444 4678 3445 4677 3445 4679 3445 4678 3446 4679 3446 4680 3446 4676 3447 4681 3447 4677 3447 4677 3448 4681 3448 4682 3448 4677 3449 4682 3449 4683 3449 4684 3450 4685 3450 4686 3450 4686 3451 4685 3451 4687 3451 4687 3452 4688 3452 4686 3452 4686 3453 4688 3453 4689 3453 4686 3454 4689 3454 4679 3454 4679 3455 4689 3455 4690 3455 4679 3456 4690 3456 4680 3456 4691 3457 4692 3457 4693 3457 4693 3458 4692 3458 4694 3458 4695 3459 4696 3459 4697 3459 4697 3460 4696 3460 4698 3460 4697 3461 4698 3461 4699 3461 4700 3462 4701 3462 4664 3462 4702 3463 4703 3463 4704 3463 4704 3464 4703 3464 4705 3464 4704 3465 4705 3465 4706 3465 4707 3466 4708 3466 4663 3466 4708 3467 4709 3467 4663 3467 4663 3468 4709 3468 4710 3468 4663 3469 4710 3469 4711 3469 4711 3470 4712 3470 4663 3470 4663 3471 4712 3471 4713 3471 4663 3472 4713 3472 4664 3472 4664 3473 4713 3473 4714 3473 4664 3474 4714 3474 4700 3474 4715 3475 4716 3475 4717 3475 4717 3476 4716 3476 4718 3476 4717 3477 4718 3477 4719 3477 4719 3478 4718 3478 4720 3478 4719 3479 4720 3479 4721 3479 4721 3480 4720 3480 4722 3480 4623 3481 4622 3481 4723 3481 4724 3482 4725 3482 4666 3482 4716 3483 4724 3483 4718 3483 4718 3484 4724 3484 4666 3484 4718 3485 4666 3485 4720 3485 4720 3486 4666 3486 4625 3486 4720 3487 4625 3487 4722 3487 4722 3488 4625 3488 4624 3488 4722 3489 4624 3489 4623 3489 4726 3490 4727 3490 4728 3490 4640 3491 4727 3491 4641 3491 4641 3492 4727 3492 4726 3492 4641 3493 4726 3493 4642 3493 4725 3494 4639 3494 4666 3494 4666 3495 4639 3495 4627 3495 4666 3496 4627 3496 4626 3496 4668 3497 4707 3497 4669 3497 4669 3498 4707 3498 4663 3498 4669 3499 4663 3499 4729 3499 4644 3500 4617 3500 4730 3500 4731 3501 4732 3501 4733 3501 4733 3502 4732 3502 4734 3502 4733 3503 4734 3503 4735 3503 4735 3504 4734 3504 4736 3504 4735 3505 4736 3505 4737 3505 4737 3506 4736 3506 4738 3506 4737 3507 4738 3507 4739 3507 4739 3508 4738 3508 4740 3508 4739 3509 4740 3509 4741 3509 4741 3510 4740 3510 4742 3510 4741 3511 4742 3511 4743 3511 4744 3512 4745 3512 4746 3512 4746 3513 4745 3513 4747 3513 4746 3514 4747 3514 4748 3514 4748 3515 4747 3515 4749 3515 4748 3516 4749 3516 4750 3516 4750 3517 4749 3517 4751 3517 4750 3518 4751 3518 4647 3518 4647 3519 4751 3519 4648 3519 4752 3520 4753 3520 4730 3520 4730 3521 4753 3521 4754 3521 4730 3522 4754 3522 4644 3522 4644 3523 4754 3523 4645 3523 4629 3524 4628 3524 4755 3524 4755 3525 4628 3525 4756 3525 4755 3526 4756 3526 4757 3526 4757 3527 4756 3527 4758 3527 4757 3528 4758 3528 4759 3528 4759 3529 4758 3529 4760 3529 4759 3530 4760 3530 4761 3530 4761 3531 4760 3531 4762 3531 4761 3532 4762 3532 4763 3532 4628 3533 4643 3533 4756 3533 4756 3534 4643 3534 4642 3534 4756 3535 4642 3535 4758 3535 4758 3536 4642 3536 4726 3536 4758 3537 4726 3537 4760 3537 4760 3538 4726 3538 4728 3538 4760 3539 4728 3539 4762 3539 4764 3540 4704 3540 4765 3540 4765 3541 4704 3541 4766 3541 4765 3542 4766 3542 4767 3542 4767 3543 4766 3543 4768 3543 4767 3544 4768 3544 4769 3544 4769 3545 4768 3545 4770 3545 4769 3546 4770 3546 4771 3546 4771 3547 4770 3547 4772 3547 4771 3548 4772 3548 4773 3548 4773 3549 4772 3549 4774 3549 4773 3550 4774 3550 4775 3550 4776 3551 4665 3551 4764 3551 4764 3552 4665 3552 4664 3552 4764 3553 4664 3553 4704 3553 4704 3554 4664 3554 4701 3554 4704 3555 4701 3555 4702 3555 4776 3556 4764 3556 4777 3556 4777 3557 4764 3557 4765 3557 4777 3558 4765 3558 4778 3558 4778 3559 4765 3559 4767 3559 4778 3560 4767 3560 4779 3560 4779 3561 4767 3561 4769 3561 4779 3562 4769 3562 4780 3562 4780 3563 4769 3563 4771 3563 4780 3564 4771 3564 4781 3564 4781 3565 4771 3565 4773 3565 4781 3566 4773 3566 4782 3566 4782 3567 4773 3567 4775 3567 4782 3568 4775 3568 4783 3568 4784 3569 4785 3569 4786 3569 4787 3570 4788 3570 4789 3570 4789 3571 4788 3571 4790 3571 4789 3572 4790 3572 4791 3572 4791 3573 4790 3573 4792 3573 4793 3574 4791 3574 4794 3574 4794 3575 4791 3575 4792 3575 4794 3576 4792 3576 4795 3576 4796 3577 4797 3577 4798 3577 4799 3578 4800 3578 4660 3578 4660 3579 4800 3579 4801 3579 4660 3580 4801 3580 4661 3580 4783 3581 4802 3581 4782 3581 4782 3582 4802 3582 4803 3582 4782 3583 4803 3583 4781 3583 4781 3584 4803 3584 4804 3584 4781 3585 4804 3585 4780 3585 4780 3586 4804 3586 4805 3586 4780 3587 4805 3587 4779 3587 4779 3588 4805 3588 4806 3588 4779 3589 4806 3589 4778 3589 4778 3590 4806 3590 4807 3590 4778 3591 4807 3591 4777 3591 4777 3592 4807 3592 4808 3592 4777 3593 4808 3593 4776 3593 4802 3594 4809 3594 4803 3594 4803 3595 4809 3595 4810 3595 4803 3596 4810 3596 4804 3596 4804 3597 4810 3597 4811 3597 4804 3598 4811 3598 4805 3598 4805 3599 4811 3599 4812 3599 4805 3600 4812 3600 4806 3600 4806 3601 4812 3601 4813 3601 4806 3602 4813 3602 4807 3602 4807 3603 4813 3603 4814 3603 4807 3604 4814 3604 4808 3604 4613 3605 4630 3605 4815 3605 4815 3606 4630 3606 4816 3606 4815 3607 4816 3607 4817 3607 4817 3608 4816 3608 4818 3608 4817 3609 4818 3609 4819 3609 4819 3610 4818 3610 4820 3610 4819 3611 4820 3611 4821 3611 4821 3612 4820 3612 4822 3612 4821 3613 4822 3613 4823 3613 4823 3614 4822 3614 4824 3614 4823 3615 4824 3615 4825 3615 4825 3616 4824 3616 4826 3616 4825 3617 4826 3617 4827 3617 4827 3618 4826 3618 4828 3618 4827 3619 4828 3619 4829 3619 4829 3620 4828 3620 4830 3620 4829 3621 4830 3621 4831 3621 4618 3622 4616 3622 4731 3622 4731 3623 4616 3623 4615 3623 4731 3624 4615 3624 4732 3624 4630 3625 4618 3625 4816 3625 4816 3626 4618 3626 4731 3626 4816 3627 4731 3627 4818 3627 4818 3628 4731 3628 4733 3628 4818 3629 4733 3629 4820 3629 4820 3630 4733 3630 4735 3630 4820 3631 4735 3631 4822 3631 4822 3632 4735 3632 4737 3632 4822 3633 4737 3633 4824 3633 4824 3634 4737 3634 4739 3634 4824 3635 4739 3635 4826 3635 4826 3636 4739 3636 4741 3636 4826 3637 4741 3637 4828 3637 4828 3638 4741 3638 4743 3638 4828 3639 4743 3639 4830 3639 4774 3640 4787 3640 4775 3640 4775 3641 4787 3641 4789 3641 4775 3642 4789 3642 4783 3642 4783 3643 4789 3643 4791 3643 4783 3644 4791 3644 4802 3644 4802 3645 4791 3645 4793 3645 4802 3646 4793 3646 4809 3646 4809 3647 4793 3647 4832 3647 4809 3648 4832 3648 4810 3648 4810 3649 4832 3649 4833 3649 4810 3650 4833 3650 4811 3650 4811 3651 4833 3651 4834 3651 4811 3652 4834 3652 4812 3652 4812 3653 4834 3653 4835 3653 4812 3654 4835 3654 4813 3654 4813 3655 4835 3655 4836 3655 4813 3656 4836 3656 4814 3656 4795 3657 4837 3657 4794 3657 4794 3658 4837 3658 4838 3658 4794 3659 4838 3659 4793 3659 4793 3660 4838 3660 4839 3660 4793 3661 4839 3661 4832 3661 4832 3662 4839 3662 4840 3662 4832 3663 4840 3663 4833 3663 4833 3664 4840 3664 4841 3664 4833 3665 4841 3665 4834 3665 4834 3666 4841 3666 4842 3666 4834 3667 4842 3667 4835 3667 4835 3668 4842 3668 4843 3668 4835 3669 4843 3669 4836 3669 4844 3670 4797 3670 4845 3670 4845 3671 4797 3671 4796 3671 4845 3672 4796 3672 4649 3672 4649 3673 4638 3673 4845 3673 4845 3674 4638 3674 4637 3674 4845 3675 4637 3675 4844 3675 4844 3676 4637 3676 4620 3676 4844 3677 4620 3677 4619 3677 4422 3678 4846 3678 4423 3678 4423 3679 4846 3679 4847 3679 4423 3680 4847 3680 4425 3680 4425 3681 4847 3681 4848 3681 4425 3682 4848 3682 4426 3682 4426 3683 4848 3683 4849 3683 4850 3684 4851 3684 4852 3684 4852 3685 4853 3685 4850 3685 4850 3686 4853 3686 4854 3686 4850 3687 4854 3687 4855 3687 4854 3688 4856 3688 4855 3688 4855 3689 4856 3689 4857 3689 4855 3690 4857 3690 4858 3690 4859 3691 4860 3691 4861 3691 4861 3692 4860 3692 4858 3692 4861 3693 4858 3693 4862 3693 4862 3694 4858 3694 4857 3694 4699 3695 4684 3695 4697 3695 4697 3696 4684 3696 4686 3696 4697 3697 4686 3697 4863 3697 4863 3698 4686 3698 4864 3698 4863 3699 4864 3699 4865 3699 4865 3700 4864 3700 4866 3700 4865 3701 4866 3701 4867 3701 4867 3702 4866 3702 4868 3702 4867 3703 4868 3703 4869 3703 4870 3704 4871 3704 4872 3704 4872 3705 4871 3705 4873 3705 4872 3706 4873 3706 4874 3706 4874 3707 4873 3707 4875 3707 4874 3708 4875 3708 4876 3708 4877 3709 4878 3709 4879 3709 4879 3710 4878 3710 4880 3710 4879 3711 4880 3711 4881 3711 4881 3712 4880 3712 4658 3712 4881 3713 4658 3713 4876 3713 4876 3714 4658 3714 4657 3714 4876 3715 4657 3715 4874 3715 4874 3716 4657 3716 4659 3716 4874 3717 4659 3717 4872 3717 4694 3718 4695 3718 4693 3718 4693 3719 4695 3719 4697 3719 4693 3720 4697 3720 4882 3720 4882 3721 4697 3721 4863 3721 4882 3722 4863 3722 4883 3722 4883 3723 4863 3723 4865 3723 4883 3724 4865 3724 4884 3724 4884 3725 4865 3725 4867 3725 4884 3726 4867 3726 4885 3726 4885 3727 4867 3727 4869 3727 4885 3728 4869 3728 4886 3728 4887 3729 4877 3729 4888 3729 4888 3730 4877 3730 4879 3730 4888 3731 4879 3731 4889 3731 4889 3732 4879 3732 4881 3732 4889 3733 4881 3733 4890 3733 4890 3734 4881 3734 4876 3734 4890 3735 4876 3735 4891 3735 4891 3736 4876 3736 4875 3736 4891 3737 4875 3737 4892 3737 4892 3738 4875 3738 4873 3738 4892 3739 4873 3739 4893 3739 4893 3740 4873 3740 4871 3740 4893 3741 4871 3741 4894 3741 4894 3742 4871 3742 4870 3742 4422 3743 4419 3743 4846 3743 4846 3744 4419 3744 4887 3744 4846 3745 4887 3745 4847 3745 4847 3746 4887 3746 4888 3746 4847 3747 4888 3747 4848 3747 4848 3748 4888 3748 4889 3748 4848 3749 4889 3749 4849 3749 4849 3750 4889 3750 4890 3750 4895 3751 4896 3751 4897 3751 4898 3752 4899 3752 4900 3752 4900 3753 4899 3753 4901 3753 4900 3754 4901 3754 4902 3754 4902 3755 4901 3755 4903 3755 4902 3756 4903 3756 4904 3756 4904 3757 4903 3757 4905 3757 4904 3758 4905 3758 4906 3758 4899 3759 4907 3759 4901 3759 4901 3760 4907 3760 4908 3760 4901 3761 4908 3761 4903 3761 4903 3762 4908 3762 4909 3762 4903 3763 4909 3763 4905 3763 4706 3764 4691 3764 4704 3764 4704 3765 4691 3765 4693 3765 4704 3766 4693 3766 4766 3766 4766 3767 4693 3767 4882 3767 4766 3768 4882 3768 4768 3768 4768 3769 4882 3769 4883 3769 4768 3770 4883 3770 4770 3770 4770 3771 4883 3771 4884 3771 4770 3772 4884 3772 4772 3772 4772 3773 4884 3773 4885 3773 4772 3774 4885 3774 4774 3774 4774 3775 4885 3775 4886 3775 4774 3776 4886 3776 4787 3776 4787 3777 4886 3777 4910 3777 4787 3778 4910 3778 4788 3778 4788 3779 4910 3779 4911 3779 4788 3780 4911 3780 4790 3780 4790 3781 4911 3781 4912 3781 4790 3782 4912 3782 4913 3782 4913 3783 4912 3783 4896 3783 4896 3784 4895 3784 4913 3784 4913 3785 4895 3785 4914 3785 4913 3786 4914 3786 4790 3786 4790 3787 4914 3787 4784 3787 4790 3788 4784 3788 4792 3788 4792 3789 4784 3789 4786 3789 4792 3790 4786 3790 4795 3790 4915 3791 4916 3791 4917 3791 4917 3792 4916 3792 4918 3792 4917 3793 4918 3793 4919 3793 4919 3794 4918 3794 4920 3794 4919 3795 4921 3795 4917 3795 4917 3796 4921 3796 4798 3796 4917 3797 4798 3797 4915 3797 4915 3798 4798 3798 4797 3798 4915 3799 4797 3799 4922 3799 4922 3800 4797 3800 4844 3800 4922 3801 4844 3801 4923 3801 4923 3802 4844 3802 4619 3802 4923 3803 4619 3803 4634 3803 4924 3804 4801 3804 4925 3804 4925 3805 4801 3805 4800 3805 4925 3806 4800 3806 4926 3806 4926 3807 4800 3807 4799 3807 4926 3808 4799 3808 4927 3808 4927 3809 4799 3809 4928 3809 4929 3810 4928 3810 4930 3810 4930 3811 4928 3811 4799 3811 4930 3812 4799 3812 4931 3812 4931 3813 4799 3813 4660 3813 4931 3814 4660 3814 4932 3814 4932 3815 4660 3815 4662 3815 4932 3816 4662 3816 4723 3816 4514 3817 4933 3817 4898 3817 4898 3818 4933 3818 4934 3818 4898 3819 4934 3819 4899 3819 4899 3820 4934 3820 4935 3820 4899 3821 4935 3821 4907 3821 4907 3822 4935 3822 4785 3822 4907 3823 4785 3823 4908 3823 4908 3824 4785 3824 4784 3824 4908 3825 4784 3825 4909 3825 4909 3826 4784 3826 4914 3826 4909 3827 4914 3827 4905 3827 4905 3828 4914 3828 4895 3828 4905 3829 4895 3829 4906 3829 4906 3830 4895 3830 4897 3830 4634 3831 4837 3831 4923 3831 4923 3832 4837 3832 4795 3832 4923 3833 4795 3833 4922 3833 4922 3834 4795 3834 4786 3834 4922 3835 4786 3835 4915 3835 4915 3836 4786 3836 4785 3836 4915 3837 4785 3837 4916 3837 4916 3838 4785 3838 4935 3838 4916 3839 4935 3839 4918 3839 4918 3840 4935 3840 4934 3840 4918 3841 4934 3841 4920 3841 4920 3842 4934 3842 4933 3842 4514 3843 4898 3843 4515 3843 4515 3844 4898 3844 4900 3844 4515 3845 4900 3845 4516 3845 4516 3846 4900 3846 4902 3846 4516 3847 4902 3847 4517 3847 4517 3848 4902 3848 4904 3848 4517 3849 4904 3849 4518 3849 4518 3850 4904 3850 4906 3850 4518 3851 4906 3851 4419 3851 4419 3852 4906 3852 4897 3852 4419 3853 4897 3853 4887 3853 4887 3854 4897 3854 4896 3854 4887 3855 4896 3855 4877 3855 4877 3856 4896 3856 4912 3856 4877 3857 4912 3857 4878 3857 4878 3858 4912 3858 4911 3858 4878 3859 4911 3859 4880 3859 4880 3860 4911 3860 4910 3860 4880 3861 4910 3861 4658 3861 4658 3862 4910 3862 4886 3862 4658 3863 4886 3863 4659 3863 4659 3864 4886 3864 4869 3864 4659 3865 4869 3865 4872 3865 4872 3866 4869 3866 4868 3866 4872 3867 4868 3867 4870 3867 4428 3868 4936 3868 4464 3868 4464 3869 4936 3869 4937 3869 4464 3870 4937 3870 4466 3870 4466 3871 4937 3871 4938 3871 4466 3872 4938 3872 4467 3872 4467 3873 4938 3873 4939 3873 4467 3874 4939 3874 4469 3874 4469 3875 4939 3875 4940 3875 4469 3876 4940 3876 4470 3876 4470 3877 4940 3877 4941 3877 4470 3878 4941 3878 4472 3878 4472 3879 4941 3879 4942 3879 4472 3880 4942 3880 4473 3880 4473 3881 4942 3881 4943 3881 4473 3882 4943 3882 4474 3882 4474 3883 4943 3883 4944 3883 4474 3884 4944 3884 4475 3884 4475 3885 4944 3885 4945 3885 4475 3886 4945 3886 4476 3886 4476 3887 4945 3887 4946 3887 4476 3888 4946 3888 4432 3888 4432 3889 4946 3889 4947 3889 4432 3890 4947 3890 4433 3890 4433 3891 4947 3891 4948 3891 4433 3892 4948 3892 4434 3892 4434 3893 4948 3893 4949 3893 4434 3894 4949 3894 4436 3894 4436 3895 4949 3895 4950 3895 4436 3896 4950 3896 4437 3896 4437 3897 4950 3897 4951 3897 4437 3898 4951 3898 4439 3898 4439 3899 4951 3899 4952 3899 4439 3900 4952 3900 4478 3900 4478 3901 4952 3901 4953 3901 4478 3902 4953 3902 4480 3902 4480 3903 4953 3903 4954 3903 4480 3904 4954 3904 4481 3904 4481 3905 4954 3905 4955 3905 4481 3906 4955 3906 4483 3906 4483 3907 4955 3907 4956 3907 4483 3908 4956 3908 4484 3908 4484 3909 4956 3909 4957 3909 4484 3910 4957 3910 4486 3910 4486 3911 4957 3911 4958 3911 4486 3912 4958 3912 4487 3912 4487 3913 4958 3913 4959 3913 4487 3914 4959 3914 4488 3914 4488 3915 4959 3915 4960 3915 4488 3916 4960 3916 4489 3916 4489 3917 4960 3917 4961 3917 4489 3918 4961 3918 4490 3918 4490 3919 4961 3919 4962 3919 4490 3920 4962 3920 4441 3920 4441 3921 4962 3921 4963 3921 4441 3922 4963 3922 4444 3922 4444 3923 4963 3923 4964 3923 4444 3924 4964 3924 4445 3924 4445 3925 4964 3925 4965 3925 4445 3926 4965 3926 4447 3926 4447 3927 4965 3927 4966 3927 4447 3928 4966 3928 4448 3928 4448 3929 4966 3929 4967 3929 4448 3930 4967 3930 4450 3930 4450 3931 4967 3931 4968 3931 4450 3932 4968 3932 4492 3932 4492 3933 4968 3933 4969 3933 4492 3934 4969 3934 4494 3934 4494 3935 4969 3935 4970 3935 4494 3936 4970 3936 4495 3936 4495 3937 4970 3937 4971 3937 4495 3938 4971 3938 4497 3938 4497 3939 4971 3939 4972 3939 4497 3940 4972 3940 4498 3940 4498 3941 4972 3941 4973 3941 4498 3942 4973 3942 4500 3942 4500 3943 4973 3943 4974 3943 4500 3944 4974 3944 4501 3944 4501 3945 4974 3945 4975 3945 4501 3946 4975 3946 4502 3946 4502 3947 4975 3947 4976 3947 4502 3948 4976 3948 4503 3948 4503 3949 4976 3949 4977 3949 4503 3950 4977 3950 4504 3950 4504 3951 4977 3951 4978 3951 4504 3952 4978 3952 4454 3952 4454 3953 4978 3953 4979 3953 4454 3954 4979 3954 4455 3954 4455 3955 4979 3955 4980 3955 4455 3956 4980 3956 4456 3956 4456 3957 4980 3957 4924 3957 4456 3958 4924 3958 4458 3958 4458 3959 4924 3959 4925 3959 4458 3960 4925 3960 4459 3960 4459 3961 4925 3961 4926 3961 4459 3962 4926 3962 4461 3962 4461 3963 4926 3963 4927 3963 4461 3964 4927 3964 4506 3964 4506 3965 4927 3965 4928 3965 4506 3966 4928 3966 4508 3966 4508 3967 4928 3967 4929 3967 4508 3968 4929 3968 4509 3968 4936 3969 4981 3969 4937 3969 4937 3970 4981 3970 4982 3970 4937 3971 4982 3971 4938 3971 4938 3972 4982 3972 4983 3972 4938 3973 4983 3973 4939 3973 4939 3974 4983 3974 4984 3974 4939 3975 4984 3975 4940 3975 4940 3976 4984 3976 4985 3976 4940 3977 4985 3977 4941 3977 4941 3978 4985 3978 4986 3978 4941 3979 4986 3979 4942 3979 4942 3980 4986 3980 4987 3980 4942 3981 4987 3981 4943 3981 4943 3982 4987 3982 4988 3982 4943 3983 4988 3983 4944 3983 4944 3984 4988 3984 4989 3984 4944 3985 4989 3985 4945 3985 4945 3986 4989 3986 4990 3986 4945 3987 4990 3987 4946 3987 4946 3988 4990 3988 4991 3988 4946 3989 4991 3989 4947 3989 4947 3990 4991 3990 4992 3990 4947 3991 4992 3991 4948 3991 4948 3992 4992 3992 4993 3992 4948 3993 4993 3993 4949 3993 4949 3994 4993 3994 4994 3994 4949 3995 4994 3995 4950 3995 4950 3996 4994 3996 4995 3996 4950 3997 4995 3997 4951 3997 4951 3998 4995 3998 4996 3998 4951 3999 4996 3999 4952 3999 4952 4000 4996 4000 4997 4000 4952 4001 4997 4001 4953 4001 4953 4002 4997 4002 4998 4002 4953 4003 4998 4003 4954 4003 4954 4004 4998 4004 4999 4004 4954 4005 4999 4005 4955 4005 4955 4006 4999 4006 5000 4006 4955 4007 5000 4007 4956 4007 4956 4008 5000 4008 5001 4008 4956 4009 5001 4009 4957 4009 4957 4010 5001 4010 5002 4010 4957 4011 5002 4011 4958 4011 4958 4012 5002 4012 5003 4012 4958 4013 5003 4013 4959 4013 4959 4014 5003 4014 5004 4014 4959 4015 5004 4015 4960 4015 4960 4016 5004 4016 5005 4016 4960 4017 5005 4017 4961 4017 4961 4018 5005 4018 5006 4018 4961 4019 5006 4019 4962 4019 4962 4020 5006 4020 5007 4020 4962 4021 5007 4021 4963 4021 4963 4022 5007 4022 5008 4022 4963 4023 5008 4023 4964 4023 4964 4024 5008 4024 5009 4024 4964 4025 5009 4025 4965 4025 5010 4026 5011 4026 5012 4026 5013 4027 5014 4027 5015 4027 5016 4028 5017 4028 5018 4028 5018 4029 5017 4029 5013 4029 5018 4030 5013 4030 5019 4030 5019 4031 5013 4031 5015 4031 5012 4032 5020 4032 5010 4032 5010 4033 5020 4033 5021 4033 5010 4034 5021 4034 5014 4034 5014 4035 5021 4035 5022 4035 5014 4036 5022 4036 5015 4036 5023 4037 5024 4037 5025 4037 5025 4038 5024 4038 5026 4038 5025 4039 5026 4039 4763 4039 5027 4040 4654 4040 5028 4040 5028 4041 4654 4041 4653 4041 5028 4042 4653 4042 5029 4042 5030 4043 5031 4043 5032 4043 5032 4044 5031 4044 5033 4044 5032 4045 5033 4045 5034 4045 5023 4046 5025 4046 5035 4046 5035 4047 5025 4047 4763 4047 5035 4048 4763 4048 4715 4048 4715 4049 4763 4049 4762 4049 4715 4050 4762 4050 4716 4050 4716 4051 4762 4051 4728 4051 4716 4052 4728 4052 4724 4052 4724 4053 4728 4053 4727 4053 4724 4054 4727 4054 4725 4054 4725 4055 4727 4055 4640 4055 4725 4056 4640 4056 4639 4056 5031 4057 5029 4057 5033 4057 5033 4058 5029 4058 4653 4058 5033 4059 4653 4059 5034 4059 5034 4060 4653 4060 4655 4060 5034 4061 4655 4061 5036 4061 5036 4062 4655 4062 5037 4062 5036 4063 5037 4063 5038 4063 5038 4064 5037 4064 4744 4064 5038 4065 4744 4065 4752 4065 4752 4066 4744 4066 4746 4066 4752 4067 4746 4067 4753 4067 4753 4068 4746 4068 4748 4068 4753 4069 4748 4069 4754 4069 4754 4070 4748 4070 4750 4070 4754 4071 4750 4071 4645 4071 4645 4072 4750 4072 4647 4072 5024 4073 5030 4073 5026 4073 5026 4074 5030 4074 5032 4074 5026 4075 5032 4075 4763 4075 4763 4076 5032 4076 5034 4076 4763 4077 5034 4077 4761 4077 4761 4078 5034 4078 5036 4078 4761 4079 5036 4079 4759 4079 4759 4080 5036 4080 5038 4080 4759 4081 5038 4081 4757 4081 4757 4082 5038 4082 4752 4082 4757 4083 4752 4083 4755 4083 4755 4084 4752 4084 4730 4084 4755 4085 4730 4085 4629 4085 4629 4086 4730 4086 4617 4086 5039 4087 5011 4087 4721 4087 4721 4088 5011 4088 5010 4088 4721 4089 5010 4089 4719 4089 4719 4090 5010 4090 5014 4090 4719 4091 5014 4091 4717 4091 4717 4092 5014 4092 5013 4092 4717 4093 5013 4093 4715 4093 4715 4094 5013 4094 5017 4094 4715 4095 5017 4095 5035 4095 5035 4096 5017 4096 5016 4096 5035 4097 5016 4097 5023 4097 5040 4098 5041 4098 5042 4098 5042 4099 5041 4099 5043 4099 5042 4100 5043 4100 5044 4100 5044 4101 5043 4101 5045 4101 5046 4102 5045 4102 5047 4102 5047 4103 5045 4103 5043 4103 5047 4104 5043 4104 5048 4104 5048 4105 5043 4105 5041 4105 5048 4106 5041 4106 5049 4106 5049 4107 5041 4107 5040 4107 5049 4108 5040 4108 5050 4108 4652 4109 4651 4109 5051 4109 5051 4110 4651 4110 5052 4110 5051 4111 5052 4111 5053 4111 5052 4112 5054 4112 5053 4112 5053 4113 5054 4113 5055 4113 5053 4114 5055 4114 5056 4114 5057 4115 5058 4115 5059 4115 5055 4116 5060 4116 5056 4116 5056 4117 5060 4117 5061 4117 5056 4118 5061 4118 5059 4118 5059 4119 5061 4119 5062 4119 5059 4120 5062 4120 5057 4120 5057 4121 5063 4121 5058 4121 5058 4122 5063 4122 5064 4122 5058 4123 5064 4123 4851 4123 4851 4124 5064 4124 5065 4124 4851 4125 5065 4125 4852 4125 5066 4126 5067 4126 5068 4126 5068 4127 5067 4127 5069 4127 5068 4128 5069 4128 5070 4128 5071 4129 5072 4129 5073 4129 5073 4130 5072 4130 5074 4130 5073 4131 5074 4131 5075 4131 5075 4132 5074 4132 5076 4132 5075 4133 5076 4133 5077 4133 5077 4134 5076 4134 5078 4134 5077 4135 5078 4135 5079 4135 5079 4136 5078 4136 5080 4136 5079 4137 5080 4137 5081 4137 5081 4138 5080 4138 5082 4138 5081 4139 5082 4139 5083 4139 5083 4140 5082 4140 5084 4140 5083 4141 5084 4141 5085 4141 5085 4142 5084 4142 5086 4142 5085 4143 5086 4143 5087 4143 5087 4144 5086 4144 5088 4144 5087 4145 5088 4145 5089 4145 5089 4146 5088 4146 5090 4146 5089 4147 5090 4147 5091 4147 5091 4148 5090 4148 5092 4148 5091 4149 5092 4149 5093 4149 4683 4150 4670 4150 4677 4150 4677 4151 4670 4151 4672 4151 4677 4152 4672 4152 5094 4152 5094 4153 4672 4153 5095 4153 5094 4154 5095 4154 5096 4154 5096 4155 5095 4155 5097 4155 5096 4156 5097 4156 5098 4156 4674 4157 4675 4157 4672 4157 4672 4158 4675 4158 4669 4158 4672 4159 4669 4159 5095 4159 5095 4160 4669 4160 4729 4160 5095 4161 4729 4161 5097 4161 5089 4162 5098 4162 5087 4162 5087 4163 5098 4163 5097 4163 5087 4164 5097 4164 5085 4164 5085 4165 5097 4165 4729 4165 5085 4166 4729 4166 5083 4166 5083 4167 4729 4167 4663 4167 5083 4168 4663 4168 5081 4168 5081 4169 4663 4169 4665 4169 5081 4170 4665 4170 5079 4170 5079 4171 4665 4171 4776 4171 5079 4172 4776 4172 5077 4172 5077 4173 4776 4173 4808 4173 5077 4174 4808 4174 5075 4174 5075 4175 4808 4175 4814 4175 5075 4176 4814 4176 5073 4176 5073 4177 4814 4177 4836 4177 5073 4178 4836 4178 5071 4178 5071 4179 4836 4179 4843 4179 4634 4180 4633 4180 4837 4180 4837 4181 4633 4181 4612 4181 4837 4182 4612 4182 4838 4182 4838 4183 4612 4183 4611 4183 4838 4184 4611 4184 4839 4184 4839 4185 4611 4185 4614 4185 4839 4186 4614 4186 4840 4186 4840 4187 4614 4187 4636 4187 4840 4188 4636 4188 4841 4188 4841 4189 4636 4189 4635 4189 4841 4190 4635 4190 4842 4190 4842 4191 4635 4191 4632 4191 4842 4192 4632 4192 4843 4192 4843 4193 4632 4193 4631 4193 4843 4194 4631 4194 5071 4194 5071 4195 4631 4195 4613 4195 5071 4196 4613 4196 5072 4196 5072 4197 4613 4197 4815 4197 5072 4198 4815 4198 5074 4198 5074 4199 4815 4199 4817 4199 5074 4200 4817 4200 5076 4200 5076 4201 4817 4201 4819 4201 5076 4202 4819 4202 5078 4202 5078 4203 4819 4203 4821 4203 5078 4204 4821 4204 5080 4204 5080 4205 4821 4205 4823 4205 5080 4206 4823 4206 5082 4206 5082 4207 4823 4207 4825 4207 5082 4208 4825 4208 5084 4208 5084 4209 4825 4209 4827 4209 5084 4210 4827 4210 5086 4210 5086 4211 4827 4211 4829 4211 5086 4212 4829 4212 5088 4212 5088 4213 4829 4213 4831 4213 5088 4214 4831 4214 5090 4214 5093 4215 4650 4215 5091 4215 5091 4216 4650 4216 4652 4216 5091 4217 4652 4217 5089 4217 5089 4218 4652 4218 5051 4218 5089 4219 5051 4219 5098 4219 5098 4220 5051 4220 5053 4220 5098 4221 5053 4221 5096 4221 5096 4222 5053 4222 5056 4222 5096 4223 5056 4223 5094 4223 5094 4224 5056 4224 5059 4224 5094 4225 5059 4225 4677 4225 4677 4226 5059 4226 5058 4226 4677 4227 5058 4227 4679 4227 4679 4228 5058 4228 4851 4228 4679 4229 4851 4229 4686 4229 4686 4230 4851 4230 4850 4230 4686 4231 4850 4231 4864 4231 4864 4232 4850 4232 4855 4232 4864 4233 4855 4233 4866 4233 4866 4234 4855 4234 4858 4234 4866 4235 4858 4235 4868 4235 4868 4236 4858 4236 4860 4236 4868 4237 4860 4237 4870 4237 4870 4238 4860 4238 4859 4238 4870 4239 4859 4239 4894 4239 5048 4240 5070 4240 5047 4240 5047 4241 5070 4241 5069 4241 5047 4242 5069 4242 5046 4242 5046 4243 5069 4243 5099 4243 5046 4244 5099 4244 5045 4244 5045 4245 5099 4245 5100 4245 5045 4246 5100 4246 5044 4246 5044 4247 5100 4247 5101 4247 5044 4248 5101 4248 5042 4248 5042 4249 5101 4249 5102 4249 5042 4250 5102 4250 5040 4250 5040 4251 5102 4251 5103 4251 5040 4252 5103 4252 5050 4252 5050 4253 5103 4253 5104 4253 4646 4254 4648 4254 5105 4254 5105 4255 4648 4255 4751 4255 5105 4256 4751 4256 5106 4256 5106 4257 4751 4257 4749 4257 5106 4258 4749 4258 5107 4258 5107 4259 4749 4259 4747 4259 5107 4260 4747 4260 5108 4260 5108 4261 4747 4261 4745 4261 5108 4262 4745 4262 5109 4262 5109 4263 4745 4263 4744 4263 5109 4264 4744 4264 5066 4264 5066 4265 4744 4265 5037 4265 5066 4266 5037 4266 5067 4266 5067 4267 5037 4267 4655 4267 5067 4268 4655 4268 5069 4268 5069 4269 4655 4269 4654 4269 5069 4270 4654 4270 5099 4270 5099 4271 4654 4271 5027 4271 5099 4272 5027 4272 5100 4272 5093 4273 5110 4273 4650 4273 4650 4274 5110 4274 5111 4274 4650 4275 5111 4275 4651 4275 4651 4276 5111 4276 5112 4276 4651 4277 5112 4277 5052 4277 5052 4278 5112 4278 5113 4278 5052 4279 5113 4279 5054 4279 5054 4280 5113 4280 5114 4280 5054 4281 5114 4281 5055 4281 5055 4282 5114 4282 5115 4282 5055 4283 5115 4283 5060 4283 5060 4284 5115 4284 5116 4284 5060 4285 5116 4285 5061 4285 5061 4286 5116 4286 5117 4286 5061 4287 5117 4287 5062 4287 5062 4288 5117 4288 5118 4288 5062 4289 5118 4289 5057 4289 5057 4290 5118 4290 5119 4290 5057 4291 5119 4291 5063 4291 5063 4292 5119 4292 5120 4292 5063 4293 5120 4293 5064 4293 5064 4294 5120 4294 5121 4294 5064 4295 5121 4295 5065 4295 5065 4296 5121 4296 5122 4296 5065 4297 5122 4297 4852 4297 4852 4298 5122 4298 5123 4298 4852 4299 5123 4299 4853 4299 4853 4300 5123 4300 5124 4300 4853 4301 5124 4301 4854 4301 4854 4302 5124 4302 5125 4302 4854 4303 5125 4303 4856 4303 4856 4304 5125 4304 5126 4304 4856 4305 5126 4305 4857 4305 4857 4306 5126 4306 5127 4306 4857 4307 5127 4307 4862 4307 4862 4308 5127 4308 5128 4308 4862 4309 5128 4309 4861 4309 4861 4310 5128 4310 5129 4310 4861 4311 5129 4311 4859 4311 4859 4312 5129 4312 5130 4312 4859 4313 5130 4313 4894 4313 4894 4314 5130 4314 5131 4314 4894 4315 5131 4315 4893 4315 4893 4316 5131 4316 5132 4316 4893 4317 5132 4317 4892 4317 4892 4318 5132 4318 5133 4318 4892 4319 5133 4319 4891 4319 4891 4320 5133 4320 5134 4320 4891 4321 5134 4321 4890 4321 4622 4322 4621 4322 4723 4322 4723 4323 4621 4323 4649 4323 4723 4324 4649 4324 4932 4324 4932 4325 4649 4325 4796 4325 4932 4326 4796 4326 4931 4326 4931 4327 4796 4327 4798 4327 4931 4328 4798 4328 4930 4328 4930 4329 4798 4329 4921 4329 4930 4330 4921 4330 4929 4330 4929 4331 4921 4331 4919 4331 4929 4332 4919 4332 4509 4332 4509 4333 4919 4333 4920 4333 4509 4334 4920 4334 4656 4334 4656 4335 4920 4335 4933 4335 4656 4336 4933 4336 4512 4336 4512 4337 4933 4337 4514 4337 4615 4338 4646 4338 4732 4338 4732 4339 4646 4339 5105 4339 4732 4340 5105 4340 4734 4340 4734 4341 5105 4341 5106 4341 4734 4342 5106 4342 4736 4342 4736 4343 5106 4343 5107 4343 4736 4344 5107 4344 4738 4344 4738 4345 5107 4345 5108 4345 4738 4346 5108 4346 4740 4346 4740 4347 5108 4347 5109 4347 4740 4348 5109 4348 4742 4348 4742 4349 5109 4349 5066 4349 4742 4350 5066 4350 4743 4350 4743 4351 5066 4351 5068 4351 4743 4352 5068 4352 4830 4352 4830 4353 5068 4353 5070 4353 4830 4354 5070 4354 4831 4354 4831 4355 5070 4355 5048 4355 4831 4356 5048 4356 5090 4356 5090 4357 5048 4357 5049 4357 5090 4358 5049 4358 5092 4358 5092 4359 5049 4359 5050 4359 5092 4360 5050 4360 5093 4360 5093 4361 5050 4361 5104 4361 5093 4362 5104 4362 5110 4362 4623 4363 4723 4363 4722 4363 4722 4364 4723 4364 4662 4364 4722 4365 4662 4365 4721 4365 4721 4087 4662 4087 4661 4087 4721 4087 4661 4087 5039 4087 5039 4366 4661 4366 4801 4366 5039 4366 4801 4366 5011 4366 5011 4367 4801 4367 4924 4367 5011 4368 4924 4368 5012 4368 5012 4369 4924 4369 4980 4369 5012 4370 4980 4370 5020 4370 5020 4371 4980 4371 4979 4371 5020 4372 4979 4372 5021 4372 5021 4373 4979 4373 4978 4373 5021 4374 4978 4374 5022 4374 5022 4375 4978 4375 4977 4375 5022 4376 4977 4376 5015 4376 5015 4377 4977 4377 4976 4377 5015 4378 4976 4378 5019 4378 5019 4379 4976 4379 4975 4379 5019 4380 4975 4380 5018 4380 5018 4381 4975 4381 4974 4381 5018 4382 4974 4382 5016 4382 5016 4383 4974 4383 4973 4383 5016 4384 4973 4384 5023 4384 5023 4385 4973 4385 4972 4385 5023 4386 4972 4386 5024 4386 5024 4387 4972 4387 4971 4387 5024 4388 4971 4388 5030 4388 5030 4389 4971 4389 4970 4389 5030 4390 4970 4390 5031 4390 5031 4391 4970 4391 4969 4391 5031 4392 4969 4392 5029 4392 5029 4393 4969 4393 4968 4393 5029 4394 4968 4394 5028 4394 5028 4395 4968 4395 4967 4395 5028 4396 4967 4396 5027 4396 5027 4397 4967 4397 4966 4397 5027 4398 4966 4398 5100 4398 5100 4399 4966 4399 4965 4399 5100 4400 4965 4400 5101 4400 5101 4401 4965 4401 5009 4401 5101 4402 5009 4402 5102 4402 5102 4403 5009 4403 5008 4403 5102 4404 5008 4404 5103 4404 5103 4405 5008 4405 5007 4405 5103 4406 5007 4406 5104 4406 5104 4407 5007 4407 5006 4407 5104 4408 5006 4408 5110 4408 5110 4409 5006 4409 5005 4409 5110 4410 5005 4410 5111 4410 5111 4411 5005 4411 5004 4411 5111 4412 5004 4412 5112 4412 5112 4413 5004 4413 5003 4413 5112 4414 5003 4414 5113 4414 5113 4415 5003 4415 5002 4415 5113 4416 5002 4416 5114 4416 5114 4417 5002 4417 5001 4417 5114 4418 5001 4418 5115 4418 5115 4419 5001 4419 5000 4419 5115 4420 5000 4420 5116 4420 5116 4421 5000 4421 4999 4421 5116 4422 4999 4422 5117 4422 5117 4423 4999 4423 4998 4423 5117 4424 4998 4424 5118 4424 5118 4425 4998 4425 4997 4425 5118 4426 4997 4426 5119 4426 5119 4427 4997 4427 4996 4427 5119 4428 4996 4428 5120 4428 5120 4429 4996 4429 4995 4429 5120 4430 4995 4430 5121 4430 5121 4431 4995 4431 4994 4431 5121 4432 4994 4432 5122 4432 5122 4433 4994 4433 4993 4433 5122 4434 4993 4434 5123 4434 5123 4435 4993 4435 4992 4435 5123 4436 4992 4436 5124 4436 5124 4437 4992 4437 4991 4437 5124 4438 4991 4438 5125 4438 5125 4439 4991 4439 4990 4439 5125 4440 4990 4440 5126 4440 5126 4441 4990 4441 4989 4441 5126 4442 4989 4442 5127 4442 5127 4443 4989 4443 4988 4443 5127 4444 4988 4444 5128 4444 5128 4445 4988 4445 4987 4445 5128 4446 4987 4446 5129 4446 5129 4447 4987 4447 4986 4447 5129 4448 4986 4448 5130 4448 5130 4449 4986 4449 4985 4449 5130 4450 4985 4450 5131 4450 5131 4451 4985 4451 4984 4451 5131 4452 4984 4452 5132 4452 5132 4453 4984 4453 4983 4453 5132 4454 4983 4454 5133 4454 5133 4455 4983 4455 4982 4455 5133 4456 4982 4456 5134 4456 5134 4457 4982 4457 4981 4457 5134 4458 4981 4458 4890 4458 4890 4459 4981 4459 4936 4459 4890 4460 4936 4460 4849 4460 4849 4461 4936 4461 4428 4461 4849 4462 4428 4462 4426 4462 4689 4463 4688 4463 4538 4463 4696 4464 4695 4464 4541 4464 4706 4465 4705 4465 4548 4465 4529 4466 4668 4466 4667 4466 4529 4467 4667 4467 4557 4467 4710 4468 4709 4468 4522 4468 4522 4469 4709 4469 4708 4469 4522 4470 4708 4470 4529 4470 4529 4471 4708 4471 4707 4471 4529 4472 4707 4472 4668 4472 4714 4473 4713 4473 4546 4473 4546 4474 4713 4474 4712 4474 4546 4475 4712 4475 4522 4475 4522 4476 4712 4476 4711 4476 4522 4477 4711 4477 4710 4477 4548 4478 4705 4478 4546 4478 4546 4479 4705 4479 4703 4479 4546 4480 4703 4480 4702 4480 4702 4481 4701 4481 4546 4481 4546 4482 4701 4482 4700 4482 4546 4483 4700 4483 4714 4483 4541 4484 4695 4484 4544 4484 4695 4485 4694 4485 4544 4485 4544 4486 4694 4486 4692 4486 4544 4487 4692 4487 4548 4487 4548 4488 4692 4488 4691 4488 4548 4489 4691 4489 4706 4489 4538 4490 4688 4490 4540 4490 4540 4491 4688 4491 4687 4491 4540 4492 4687 4492 4685 4492 4685 4493 4684 4493 4540 4493 4540 4494 4684 4494 4699 4494 4540 4495 4699 4495 4541 4495 4541 4496 4699 4496 4698 4496 4541 4497 4698 4497 4696 4497 4524 4498 4682 4498 4681 4498 4681 4499 4676 4499 4524 4499 4524 4500 4676 4500 4678 4500 4524 4501 4678 4501 4536 4501 4536 4502 4678 4502 4680 4502 4536 4503 4680 4503 4538 4503 4538 4504 4680 4504 4690 4504 4538 4505 4690 4505 4689 4505 4530 4506 4671 4506 4670 4506 4530 4507 4670 4507 4524 4507 4524 4508 4670 4508 4683 4508 4524 4509 4683 4509 4682 4509 4667 4510 4675 4510 4557 4510 4557 4511 4675 4511 4674 4511 4557 4512 4674 4512 4530 4512 4530 4513 4674 4513 4673 4513 4530 4514 4673 4514 4671 4514 5135 4515 5136 4515 5137 4515 5138 3249 5139 3249 5140 3249 5141 4516 5142 4516 5143 4516 5144 3247 5145 3247 5146 3247 5147 3268 5148 3268 5149 3268 5147 3269 5150 3269 5148 3269 5148 3270 5150 3270 5151 3270 5148 4517 5151 4517 5152 4517 5151 3272 5153 3272 5152 3272 5152 4518 5153 4518 5154 4518 5152 4519 5154 4519 5155 4519 5155 4520 5154 4520 5156 4520 5155 3276 5156 3276 5157 3276 5158 4521 5159 4521 5160 4521 5160 4522 5161 4522 5158 4522 5158 4523 5161 4523 5162 4523 5158 3280 5162 3280 5163 3280 5162 3281 5164 3281 5163 3281 5163 3282 5164 3282 5165 3282 5163 4524 5165 4524 5166 4524 5166 4525 5165 4525 5167 4525 5166 4526 5167 4526 5168 4526 5169 3250 5170 3250 5171 3250 5169 3251 5172 3251 5170 3251 5170 3252 5172 3252 5173 3252 5170 4527 5173 4527 5174 4527 5173 3254 5175 3254 5174 3254 5174 4528 5175 4528 5176 4528 5174 4529 5176 4529 5177 4529 5177 4530 5176 4530 5178 4530 5177 3258 5178 3258 5179 3258 5180 4531 5181 4531 5182 4531 5182 4532 5183 4532 5180 4532 5180 4533 5183 4533 5184 4533 5180 3262 5184 3262 5185 3262 5184 3263 5186 3263 5185 3263 5185 3264 5186 3264 5187 3264 5185 4534 5187 4534 5188 4534 5188 4535 5187 4535 5189 4535 5188 4536 5189 4536 5190 4536 5157 3321 5156 3321 5191 3321 5191 3322 5156 3322 5192 3322 5191 4537 5192 4537 5193 4537 5192 3324 5194 3324 5193 3324 5193 4538 5194 4538 5195 4538 5193 4539 5195 4539 5196 4539 5195 4540 5197 4540 5196 4540 5196 4541 5197 4541 5198 4541 5196 4542 5198 4542 5199 4542 5198 4543 5200 4543 5199 4543 5199 4544 5200 4544 5201 4544 5199 4545 5201 4545 5143 4545 5143 3333 5201 3333 5202 3333 5143 4516 5202 4516 5141 4516 5141 4546 5202 4546 5203 4546 5141 4547 5203 4547 5159 4547 5159 4548 5203 4548 5204 4548 5159 4549 5204 4549 5160 4549 5168 4550 5167 4550 5205 4550 5205 3340 5167 3340 5206 3340 5205 4551 5206 4551 5207 4551 5206 4552 5208 4552 5207 4552 5207 3343 5208 3343 5209 3343 5207 4553 5209 4553 5210 4553 5209 4554 5211 4554 5210 4554 5210 3346 5211 3346 5212 3346 5210 4555 5212 4555 5213 4555 5212 4556 5214 4556 5213 4556 5213 4557 5214 4557 5215 4557 5213 4558 5215 4558 5140 4558 5140 4559 5215 4559 5216 4559 5140 3352 5216 3352 5138 3352 5138 4560 5216 4560 5217 4560 5138 4561 5217 4561 5171 4561 5171 3355 5217 3355 5218 3355 5171 3356 5218 3356 5169 3356 5179 3286 5178 3286 5219 3286 5219 3287 5178 3287 5220 3287 5219 4562 5220 4562 5221 4562 5220 3289 5222 3289 5221 3289 5221 4563 5222 4563 5223 4563 5221 4564 5223 4564 5224 4564 5223 4565 5225 4565 5224 4565 5224 4566 5225 4566 5226 4566 5224 4567 5226 4567 5227 4567 5226 4568 5228 4568 5227 4568 5227 4569 5228 4569 5229 4569 5227 4570 5229 4570 5137 4570 5137 3298 5229 3298 5230 3298 5137 4571 5230 4571 5135 4571 5135 4572 5230 4572 5231 4572 5135 4573 5231 4573 5181 4573 5181 4574 5231 4574 5232 4574 5181 4575 5232 4575 5182 4575 5190 4576 5189 4576 5233 4576 5233 3304 5189 3304 5234 3304 5233 4577 5234 4577 5235 4577 5234 4578 5236 4578 5235 4578 5235 3307 5236 3307 5237 3307 5235 4579 5237 4579 5238 4579 5237 4580 5239 4580 5238 4580 5238 3310 5239 3310 5240 3310 5238 4581 5240 4581 5241 4581 5240 4582 5242 4582 5241 4582 5241 4583 5242 4583 5243 4583 5241 4584 5243 4584 5146 4584 5146 4585 5243 4585 5244 4585 5146 3316 5244 3316 5144 3316 5144 4586 5244 4586 5245 4586 5144 4587 5245 4587 5149 4587 5149 3319 5245 3319 5246 3319 5149 3320 5246 3320 5147 3320 5139 88 5247 88 5140 88 5140 88 5247 88 5213 88 5248 88 5249 88 5250 88 5251 88 5252 88 5253 88 5253 88 5252 88 5254 88 5255 88 5256 88 5257 88 5213 88 5258 88 5210 88 5210 4588 5258 4588 5252 4588 5210 88 5252 88 5207 88 5207 88 5252 88 5251 88 5259 88 5199 88 5260 88 5260 88 5199 88 5143 88 5260 88 5143 88 5142 88 5251 88 5261 88 5207 88 5207 88 5261 88 5262 88 5207 88 5262 88 5205 88 5205 88 5262 88 5168 88 5254 88 5252 88 5263 88 5263 88 5252 88 5264 88 5263 88 5264 88 5265 88 5265 88 5264 88 5266 88 5265 88 5266 88 5267 88 5268 88 5269 88 5270 88 5270 88 5269 88 5271 88 5271 88 5269 88 5272 88 5271 88 5272 88 5273 88 5250 88 5249 88 5274 88 5274 88 5249 88 5275 88 5274 88 5275 88 5276 88 5277 88 5248 88 5227 88 5227 88 5248 88 5250 88 5227 88 5250 88 5224 88 5224 88 5250 88 5257 88 5224 88 5257 88 5221 88 5221 88 5257 88 5256 88 5270 88 5278 88 5268 88 5268 88 5278 88 5279 88 5268 88 5279 88 5280 88 5277 88 5227 88 5281 88 5281 88 5227 88 5137 88 5281 88 5137 88 5136 88 5247 88 5282 88 5213 88 5213 88 5282 88 5283 88 5213 88 5283 88 5258 88 5258 88 5283 88 5284 88 5258 88 5284 88 5285 88 5285 88 5284 88 5286 88 5285 88 5286 88 5257 88 5257 88 5286 88 5287 88 5257 88 5287 88 5255 88 5256 88 5288 88 5221 88 5221 88 5288 88 5289 88 5221 88 5289 88 5219 88 5219 88 5289 88 5179 88 5259 88 5267 88 5199 88 5199 88 5267 88 5266 88 5199 88 5266 88 5196 88 5196 88 5266 88 5268 88 5196 88 5268 88 5193 88 5193 88 5268 88 5280 88 5280 88 5290 88 5193 88 5193 88 5290 88 5291 88 5193 88 5291 88 5191 88 5191 88 5291 88 5157 88 5292 88 5241 88 5293 88 5293 88 5241 88 5146 88 5293 88 5146 88 5145 88 5275 88 5294 88 5276 88 5276 88 5294 88 5295 88 5276 88 5295 88 5296 88 5190 88 5233 88 5297 88 5297 88 5233 88 5235 88 5297 88 5235 88 5298 88 5292 88 5273 88 5241 88 5241 88 5273 88 5272 88 5241 88 5272 88 5238 88 5238 88 5272 88 5276 88 5238 88 5276 88 5235 88 5235 88 5276 88 5296 88 5235 88 5296 88 5298 88 5299 88 5144 88 5149 88 5300 88 5301 88 5302 88 5303 88 5304 88 5305 88 5305 88 5304 88 5306 88 5302 88 5299 88 5300 88 5300 88 5299 88 5149 88 5300 88 5149 88 5307 88 5307 88 5149 88 5148 88 5307 88 5148 88 5308 88 5308 88 5148 88 5152 88 5308 88 5152 88 5306 88 5306 88 5152 88 5155 88 5306 88 5155 88 5305 88 5293 3396 5145 3396 5299 3396 5299 3397 5145 3397 5144 3397 5291 3395 5305 3395 5157 3395 5157 3395 5305 3395 5155 3395 5305 3398 5291 3398 5303 3398 5303 3399 5291 3399 5290 3399 5303 3400 5290 3400 5304 3400 5304 3400 5290 3400 5280 3400 5304 3401 5280 3401 5306 3401 5306 3401 5280 3401 5279 3401 5306 3402 5279 3402 5308 3402 5308 3402 5279 3402 5278 3402 5308 3403 5278 3403 5307 3403 5307 3404 5278 3404 5270 3404 5307 3405 5270 3405 5300 3405 5300 3406 5270 3406 5271 3406 5300 3407 5271 3407 5301 3407 5301 3408 5271 3408 5273 3408 5301 3409 5273 3409 5302 3409 5302 3410 5273 3410 5292 3410 5302 3411 5292 3411 5299 3411 5299 3412 5292 3412 5293 3412 5309 88 5141 88 5159 88 5310 88 5311 88 5312 88 5312 88 5309 88 5310 88 5310 88 5309 88 5159 88 5310 88 5159 88 5313 88 5313 88 5159 88 5158 88 5313 88 5158 88 5314 88 5314 88 5158 88 5163 88 5314 88 5163 88 5315 88 5316 88 5317 88 5318 88 5318 88 5317 88 5315 88 5318 88 5315 88 5166 88 5166 88 5315 88 5163 88 5262 3413 5318 3413 5168 3413 5168 3414 5318 3414 5166 3414 5260 4589 5142 4589 5309 4589 5309 4590 5142 4590 5141 4590 5318 3415 5262 3415 5316 3415 5316 3415 5262 3415 5261 3415 5316 3416 5261 3416 5317 3416 5317 3417 5261 3417 5251 3417 5317 3418 5251 3418 5315 3418 5315 3419 5251 3419 5253 3419 5315 3420 5253 3420 5314 3420 5314 3421 5253 3421 5254 3421 5314 3422 5254 3422 5313 3422 5313 3422 5254 3422 5263 3422 5313 3423 5263 3423 5310 3423 5310 3423 5263 3423 5265 3423 5310 3424 5265 3424 5311 3424 5311 3425 5265 3425 5267 3425 5311 3426 5267 3426 5312 3426 5312 3427 5267 3427 5259 3427 5312 3428 5259 3428 5309 3428 5309 3429 5259 3429 5260 3429 5319 88 5138 88 5171 88 5320 88 5321 88 5322 88 5323 88 5324 88 5325 88 5325 88 5324 88 5326 88 5322 88 5319 88 5320 88 5320 88 5319 88 5171 88 5320 88 5171 88 5327 88 5327 88 5171 88 5170 88 5327 88 5170 88 5328 88 5328 88 5170 88 5174 88 5328 88 5174 88 5326 88 5326 88 5174 88 5177 88 5326 88 5177 88 5325 88 5289 3360 5325 3360 5179 3360 5179 3360 5325 3360 5177 3360 5247 3358 5139 3358 5319 3358 5319 3359 5139 3359 5138 3359 5325 3361 5289 3361 5323 3361 5323 3362 5289 3362 5288 3362 5323 3363 5288 3363 5324 3363 5324 3363 5288 3363 5256 3363 5324 3364 5256 3364 5326 3364 5326 3364 5256 3364 5255 3364 5326 3365 5255 3365 5328 3365 5328 3365 5255 3365 5287 3365 5328 3366 5287 3366 5327 3366 5327 3367 5287 3367 5286 3367 5327 3368 5286 3368 5320 3368 5320 3369 5286 3369 5284 3369 5320 3370 5284 3370 5321 3370 5321 3371 5284 3371 5283 3371 5321 3372 5283 3372 5322 3372 5322 3373 5283 3373 5282 3373 5322 3374 5282 3374 5319 3374 5319 3375 5282 3375 5247 3375 5329 88 5135 88 5181 88 5330 88 5331 88 5332 88 5332 88 5329 88 5330 88 5330 88 5329 88 5181 88 5330 88 5181 88 5333 88 5333 88 5181 88 5180 88 5333 88 5180 88 5334 88 5334 88 5180 88 5185 88 5334 88 5185 88 5335 88 5336 88 5337 88 5338 88 5338 88 5337 88 5335 88 5338 88 5335 88 5188 88 5188 88 5335 88 5185 88 5297 3376 5338 3376 5190 3376 5190 3377 5338 3377 5188 3377 5281 3413 5136 3413 5329 3413 5329 3413 5136 3413 5135 3413 5338 3380 5297 3380 5336 3380 5336 3380 5297 3380 5298 3380 5336 3381 5298 3381 5337 3381 5337 3382 5298 3382 5296 3382 5337 3383 5296 3383 5335 3383 5335 3384 5296 3384 5295 3384 5335 3385 5295 3385 5334 3385 5334 3386 5295 3386 5294 3386 5334 3387 5294 3387 5333 3387 5333 3387 5294 3387 5275 3387 5333 3388 5275 3388 5330 3388 5330 3388 5275 3388 5249 3388 5330 3389 5249 3389 5331 3389 5331 3390 5249 3390 5248 3390 5331 3391 5248 3391 5332 3391 5332 3392 5248 3392 5277 3392 5332 3393 5277 3393 5329 3393 5329 3394 5277 3394 5281 3394 5339 0 5340 0 5341 0 5339 0 5341 0 5342 0 5343 0 5344 0 5345 0 5345 0 5344 0 5346 0 5341 0 5347 0 5348 0 5349 0 5350 0 5341 0 5341 0 5350 0 5351 0 5341 0 5351 0 5352 0 5352 0 5353 0 5341 0 5341 0 5353 0 5354 0 5341 0 5354 0 5355 0 5356 0 5357 0 5341 0 5341 0 5357 0 5345 0 5341 0 5345 0 5358 0 5358 0 5345 0 5346 0 5341 0 5359 0 5360 0 5340 0 5361 0 5341 0 5341 0 5361 0 5362 0 5341 0 5362 0 5347 0 5360 0 5363 0 5341 0 5341 0 5363 0 5364 0 5341 0 5364 0 5342 0 5348 0 5365 0 5341 0 5341 0 5365 0 5366 0 5341 0 5366 0 5349 0 5355 0 5367 0 5341 0 5341 0 5367 0 5368 0 5341 0 5368 0 5369 0 5369 0 5370 0 5341 0 5341 0 5370 0 5371 0 5341 0 5371 0 5356 0 5345 0 5372 0 5343 0 5343 0 5372 0 5373 0 5343 0 5373 0 5374 0 5374 0 5373 0 5375 0 5374 0 5375 0 5376 0 5349 4591 5366 4591 5377 4591 5378 4592 5379 4592 5380 4592 5381 4593 5382 4593 5383 4593 5384 4594 5239 4594 5237 4594 5239 4595 5384 4595 5240 4595 5385 4596 5386 4596 5387 4596 5388 4597 5389 4597 5390 4597 5391 4598 5392 4598 5393 4598 5394 4599 5354 4599 5353 4599 5395 4600 5396 4600 5397 4600 5398 4601 5399 4601 5400 4601 5400 4602 5399 4602 5401 4602 5400 4603 5401 4603 5402 4603 5395 4604 5397 4604 5403 4604 5404 4605 5405 4605 5406 4605 5406 4606 5405 4606 5407 4606 5406 4607 5407 4607 5408 4607 5404 4608 5409 4608 5405 4608 5405 4609 5409 4609 5410 4609 5405 4610 5410 4610 5411 4610 5412 4611 5413 4611 5414 4611 5414 4612 5413 4612 5415 4612 5415 4613 5416 4613 5414 4613 5414 4614 5416 4614 5417 4614 5414 4615 5417 4615 5407 4615 5407 4616 5417 4616 5418 4616 5407 4617 5418 4617 5408 4617 5419 4618 5420 4618 5421 4618 5421 4619 5420 4619 5422 4619 5423 4620 5424 4620 5425 4620 5425 4621 5424 4621 5426 4621 5425 4622 5426 4622 5427 4622 5428 4623 5429 4623 5392 4623 5430 4624 5431 4624 5432 4624 5432 4625 5431 4625 5433 4625 5432 4626 5433 4626 5434 4626 5435 4627 5436 4627 5391 4627 5436 4628 5437 4628 5391 4628 5391 4629 5437 4629 5438 4629 5391 4630 5438 4630 5439 4630 5439 4631 5440 4631 5391 4631 5391 4632 5440 4632 5441 4632 5391 4633 5441 4633 5392 4633 5392 4634 5441 4634 5442 4634 5392 4635 5442 4635 5428 4635 5443 4636 5444 4636 5445 4636 5445 4637 5444 4637 5446 4637 5445 4638 5446 4638 5447 4638 5447 4639 5446 4639 5448 4639 5447 4640 5448 4640 5449 4640 5449 4641 5448 4641 5450 4641 5351 4642 5350 4642 5451 4642 5452 4643 5453 4643 5394 4643 5444 4644 5452 4644 5446 4644 5446 4645 5452 4645 5394 4645 5446 4646 5394 4646 5448 4646 5448 4647 5394 4647 5353 4647 5448 4648 5353 4648 5450 4648 5450 4649 5353 4649 5352 4649 5450 4650 5352 4650 5351 4650 5454 4651 5455 4651 5456 4651 5368 4652 5455 4652 5369 4652 5369 4653 5455 4653 5454 4653 5369 4654 5454 4654 5370 4654 5453 4655 5367 4655 5394 4655 5394 4656 5367 4656 5355 4656 5394 4657 5355 4657 5354 4657 5396 4658 5435 4658 5397 4658 5397 4659 5435 4659 5391 4659 5397 4660 5391 4660 5457 4660 5372 4661 5345 4661 5458 4661 5459 4662 5460 4662 5461 4662 5461 4663 5460 4663 5462 4663 5461 4664 5462 4664 5463 4664 5463 4665 5462 4665 5464 4665 5463 4666 5464 4666 5465 4666 5465 4667 5464 4667 5466 4667 5465 4668 5466 4668 5467 4668 5467 4669 5466 4669 5468 4669 5467 4670 5468 4670 5469 4670 5469 4671 5468 4671 5470 4671 5469 4672 5470 4672 5471 4672 5472 4673 5473 4673 5474 4673 5474 4674 5473 4674 5475 4674 5474 4675 5475 4675 5476 4675 5476 4676 5475 4676 5477 4676 5476 4677 5477 4677 5478 4677 5478 4678 5477 4678 5479 4678 5478 4679 5479 4679 5375 4679 5375 4680 5479 4680 5376 4680 5480 4681 5481 4681 5458 4681 5458 4682 5481 4682 5482 4682 5458 4683 5482 4683 5372 4683 5372 4684 5482 4684 5373 4684 5357 4685 5356 4685 5483 4685 5483 4686 5356 4686 5484 4686 5483 4687 5484 4687 5485 4687 5485 4688 5484 4688 5486 4688 5485 4689 5486 4689 5487 4689 5487 4690 5486 4690 5488 4690 5487 4691 5488 4691 5489 4691 5489 4692 5488 4692 5490 4692 5489 4693 5490 4693 5491 4693 5356 4694 5371 4694 5484 4694 5484 4695 5371 4695 5370 4695 5484 4696 5370 4696 5486 4696 5486 4697 5370 4697 5454 4697 5486 4698 5454 4698 5488 4698 5488 4699 5454 4699 5456 4699 5488 4700 5456 4700 5490 4700 5492 4701 5432 4701 5493 4701 5493 4702 5432 4702 5494 4702 5493 4703 5494 4703 5495 4703 5495 4704 5494 4704 5496 4704 5495 4705 5496 4705 5497 4705 5497 4706 5496 4706 5498 4706 5497 4707 5498 4707 5499 4707 5499 4708 5498 4708 5500 4708 5499 4709 5500 4709 5501 4709 5501 4710 5500 4710 5502 4710 5501 4711 5502 4711 5503 4711 5504 4712 5393 4712 5492 4712 5492 4713 5393 4713 5392 4713 5492 4714 5392 4714 5432 4714 5432 4715 5392 4715 5429 4715 5432 4716 5429 4716 5430 4716 5504 4717 5492 4717 5505 4717 5505 4718 5492 4718 5493 4718 5505 4719 5493 4719 5506 4719 5506 4720 5493 4720 5495 4720 5506 4721 5495 4721 5507 4721 5507 4722 5495 4722 5497 4722 5507 4723 5497 4723 5508 4723 5508 4724 5497 4724 5499 4724 5508 4725 5499 4725 5509 4725 5509 4726 5499 4726 5501 4726 5509 4727 5501 4727 5510 4727 5510 4728 5501 4728 5503 4728 5510 4729 5503 4729 5511 4729 5512 4730 5513 4730 5514 4730 5515 4731 5516 4731 5517 4731 5517 4732 5516 4732 5518 4732 5517 4733 5518 4733 5519 4733 5519 4734 5518 4734 5520 4734 5521 4735 5519 4735 5522 4735 5522 4736 5519 4736 5520 4736 5522 4737 5520 4737 5523 4737 5524 4738 5525 4738 5526 4738 5527 4739 5528 4739 5388 4739 5388 4740 5528 4740 5529 4740 5388 4741 5529 4741 5389 4741 5511 4742 5530 4742 5510 4742 5510 4743 5530 4743 5531 4743 5510 4744 5531 4744 5509 4744 5509 4745 5531 4745 5532 4745 5509 4746 5532 4746 5508 4746 5508 4747 5532 4747 5533 4747 5508 4748 5533 4748 5507 4748 5507 4749 5533 4749 5534 4749 5507 4750 5534 4750 5506 4750 5506 4751 5534 4751 5535 4751 5506 4752 5535 4752 5505 4752 5505 4753 5535 4753 5536 4753 5505 4754 5536 4754 5504 4754 5530 4755 5537 4755 5531 4755 5531 4756 5537 4756 5538 4756 5531 4757 5538 4757 5532 4757 5532 4758 5538 4758 5539 4758 5532 4759 5539 4759 5533 4759 5533 4760 5539 4760 5540 4760 5533 4761 5540 4761 5534 4761 5534 4762 5540 4762 5541 4762 5534 4763 5541 4763 5535 4763 5535 4764 5541 4764 5542 4764 5535 4765 5542 4765 5536 4765 5341 4766 5358 4766 5543 4766 5543 4767 5358 4767 5544 4767 5543 4768 5544 4768 5545 4768 5545 4769 5544 4769 5546 4769 5545 4770 5546 4770 5547 4770 5547 4771 5546 4771 5548 4771 5547 4772 5548 4772 5549 4772 5549 4773 5548 4773 5550 4773 5549 4774 5550 4774 5551 4774 5551 4775 5550 4775 5552 4775 5551 4776 5552 4776 5553 4776 5553 4777 5552 4777 5554 4777 5553 4778 5554 4778 5555 4778 5555 4779 5554 4779 5556 4779 5555 4780 5556 4780 5557 4780 5557 4781 5556 4781 5558 4781 5557 4782 5558 4782 5559 4782 5346 4783 5344 4783 5459 4783 5459 4784 5344 4784 5343 4784 5459 4785 5343 4785 5460 4785 5358 4786 5346 4786 5544 4786 5544 4787 5346 4787 5459 4787 5544 4788 5459 4788 5546 4788 5546 4789 5459 4789 5461 4789 5546 4790 5461 4790 5548 4790 5548 4791 5461 4791 5463 4791 5548 4792 5463 4792 5550 4792 5550 4793 5463 4793 5465 4793 5550 4794 5465 4794 5552 4794 5552 4795 5465 4795 5467 4795 5552 4796 5467 4796 5554 4796 5554 4797 5467 4797 5469 4797 5554 4798 5469 4798 5556 4798 5556 4799 5469 4799 5471 4799 5556 4800 5471 4800 5558 4800 5502 4801 5515 4801 5503 4801 5503 4802 5515 4802 5517 4802 5503 4803 5517 4803 5511 4803 5511 4804 5517 4804 5519 4804 5511 4805 5519 4805 5530 4805 5530 4806 5519 4806 5521 4806 5530 4807 5521 4807 5537 4807 5537 4808 5521 4808 5560 4808 5537 4809 5560 4809 5538 4809 5538 4810 5560 4810 5561 4810 5538 4811 5561 4811 5539 4811 5539 4812 5561 4812 5562 4812 5539 4813 5562 4813 5540 4813 5540 4814 5562 4814 5563 4814 5540 4815 5563 4815 5541 4815 5541 4816 5563 4816 5564 4816 5541 4817 5564 4817 5542 4817 5523 4818 5565 4818 5522 4818 5522 4819 5565 4819 5566 4819 5522 4820 5566 4820 5521 4820 5521 4821 5566 4821 5567 4821 5521 4822 5567 4822 5560 4822 5560 4823 5567 4823 5568 4823 5560 4824 5568 4824 5561 4824 5561 4825 5568 4825 5569 4825 5561 4826 5569 4826 5562 4826 5562 4827 5569 4827 5570 4827 5562 4828 5570 4828 5563 4828 5563 4829 5570 4829 5571 4829 5563 4830 5571 4830 5564 4830 5572 4831 5525 4831 5573 4831 5573 4832 5525 4832 5524 4832 5573 4833 5524 4833 5377 4833 5377 4834 5366 4834 5573 4834 5573 4835 5366 4835 5365 4835 5573 4836 5365 4836 5572 4836 5572 4837 5365 4837 5348 4837 5572 4838 5348 4838 5347 4838 5150 4839 5574 4839 5151 4839 5151 4840 5574 4840 5575 4840 5151 4841 5575 4841 5153 4841 5153 4842 5575 4842 5576 4842 5153 4843 5576 4843 5154 4843 5154 4844 5576 4844 5577 4844 5578 4845 5579 4845 5580 4845 5580 4846 5581 4846 5578 4846 5578 4847 5581 4847 5582 4847 5578 4848 5582 4848 5583 4848 5582 4849 5584 4849 5583 4849 5583 4850 5584 4850 5585 4850 5583 4851 5585 4851 5586 4851 5587 4852 5588 4852 5589 4852 5589 4853 5588 4853 5586 4853 5589 4854 5586 4854 5590 4854 5590 4855 5586 4855 5585 4855 5427 4856 5412 4856 5425 4856 5425 4857 5412 4857 5414 4857 5425 4858 5414 4858 5591 4858 5591 4859 5414 4859 5592 4859 5591 4860 5592 4860 5593 4860 5593 4861 5592 4861 5594 4861 5593 4862 5594 4862 5595 4862 5595 4863 5594 4863 5596 4863 5595 4864 5596 4864 5597 4864 5598 4865 5599 4865 5600 4865 5600 4866 5599 4866 5601 4866 5600 4867 5601 4867 5602 4867 5602 4868 5601 4868 5603 4868 5602 4869 5603 4869 5604 4869 5605 4870 5606 4870 5607 4870 5607 4871 5606 4871 5608 4871 5607 4872 5608 4872 5609 4872 5609 4873 5608 4873 5386 4873 5609 4874 5386 4874 5604 4874 5604 4875 5386 4875 5385 4875 5604 4876 5385 4876 5602 4876 5602 4877 5385 4877 5387 4877 5602 4878 5387 4878 5600 4878 5422 4879 5423 4879 5421 4879 5421 4880 5423 4880 5425 4880 5421 4881 5425 4881 5610 4881 5610 4882 5425 4882 5591 4882 5610 4883 5591 4883 5611 4883 5611 4884 5591 4884 5593 4884 5611 4885 5593 4885 5612 4885 5612 4886 5593 4886 5595 4886 5612 4887 5595 4887 5613 4887 5613 4888 5595 4888 5597 4888 5613 4889 5597 4889 5614 4889 5615 4890 5605 4890 5616 4890 5616 4891 5605 4891 5607 4891 5616 4892 5607 4892 5617 4892 5617 4893 5607 4893 5609 4893 5617 4894 5609 4894 5618 4894 5618 4895 5609 4895 5604 4895 5618 4896 5604 4896 5619 4896 5619 4897 5604 4897 5603 4897 5619 4898 5603 4898 5620 4898 5620 4899 5603 4899 5601 4899 5620 4900 5601 4900 5621 4900 5621 4901 5601 4901 5599 4901 5621 4902 5599 4902 5622 4902 5622 4903 5599 4903 5598 4903 5150 4904 5147 4904 5574 4904 5574 4905 5147 4905 5615 4905 5574 4906 5615 4906 5575 4906 5575 4907 5615 4907 5616 4907 5575 4908 5616 4908 5576 4908 5576 4909 5616 4909 5617 4909 5576 4910 5617 4910 5577 4910 5577 4911 5617 4911 5618 4911 5623 4912 5624 4912 5625 4912 5626 4913 5627 4913 5628 4913 5628 4914 5627 4914 5629 4914 5628 4915 5629 4915 5630 4915 5630 4916 5629 4916 5631 4916 5630 4917 5631 4917 5632 4917 5632 4918 5631 4918 5633 4918 5632 4919 5633 4919 5634 4919 5627 4920 5635 4920 5629 4920 5629 4921 5635 4921 5636 4921 5629 4922 5636 4922 5631 4922 5631 4923 5636 4923 5637 4923 5631 4924 5637 4924 5633 4924 5434 4925 5419 4925 5432 4925 5432 4926 5419 4926 5421 4926 5432 4927 5421 4927 5494 4927 5494 4928 5421 4928 5610 4928 5494 4929 5610 4929 5496 4929 5496 4930 5610 4930 5611 4930 5496 4931 5611 4931 5498 4931 5498 4932 5611 4932 5612 4932 5498 4933 5612 4933 5500 4933 5500 4934 5612 4934 5613 4934 5500 4935 5613 4935 5502 4935 5502 4936 5613 4936 5614 4936 5502 4937 5614 4937 5515 4937 5515 4938 5614 4938 5638 4938 5515 4939 5638 4939 5516 4939 5516 4940 5638 4940 5639 4940 5516 4941 5639 4941 5518 4941 5518 4942 5639 4942 5640 4942 5518 4943 5640 4943 5641 4943 5641 4944 5640 4944 5624 4944 5624 4945 5623 4945 5641 4945 5641 4946 5623 4946 5642 4946 5641 4947 5642 4947 5518 4947 5518 4948 5642 4948 5512 4948 5518 4949 5512 4949 5520 4949 5520 4950 5512 4950 5514 4950 5520 4951 5514 4951 5523 4951 5643 4952 5644 4952 5645 4952 5645 4953 5644 4953 5646 4953 5645 4954 5646 4954 5647 4954 5647 4955 5646 4955 5648 4955 5647 4956 5649 4956 5645 4956 5645 4957 5649 4957 5526 4957 5645 4958 5526 4958 5643 4958 5643 4959 5526 4959 5525 4959 5643 4960 5525 4960 5650 4960 5650 4961 5525 4961 5572 4961 5650 4962 5572 4962 5651 4962 5651 4963 5572 4963 5347 4963 5651 4964 5347 4964 5362 4964 5652 4965 5529 4965 5653 4965 5653 4966 5529 4966 5528 4966 5653 4967 5528 4967 5654 4967 5654 4968 5528 4968 5527 4968 5654 4969 5527 4969 5655 4969 5655 4970 5527 4970 5656 4970 5657 4971 5656 4971 5658 4971 5658 4972 5656 4972 5527 4972 5658 4973 5527 4973 5659 4973 5659 4974 5527 4974 5388 4974 5659 4975 5388 4975 5660 4975 5660 4976 5388 4976 5390 4976 5660 4977 5390 4977 5451 4977 5242 4978 5661 4978 5626 4978 5626 4979 5661 4979 5662 4979 5626 4980 5662 4980 5627 4980 5627 4981 5662 4981 5663 4981 5627 4982 5663 4982 5635 4982 5635 4983 5663 4983 5513 4983 5635 4984 5513 4984 5636 4984 5636 4985 5513 4985 5512 4985 5636 4986 5512 4986 5637 4986 5637 4987 5512 4987 5642 4987 5637 4988 5642 4988 5633 4988 5633 4989 5642 4989 5623 4989 5633 4990 5623 4990 5634 4990 5634 4991 5623 4991 5625 4991 5362 4992 5565 4992 5651 4992 5651 4993 5565 4993 5523 4993 5651 4994 5523 4994 5650 4994 5650 4995 5523 4995 5514 4995 5650 4996 5514 4996 5643 4996 5643 4997 5514 4997 5513 4997 5643 4998 5513 4998 5644 4998 5644 4999 5513 4999 5663 4999 5644 5000 5663 5000 5646 5000 5646 5001 5663 5001 5662 5001 5646 5002 5662 5002 5648 5002 5648 5003 5662 5003 5661 5003 5242 5004 5626 5004 5243 5004 5243 5005 5626 5005 5628 5005 5243 5006 5628 5006 5244 5006 5244 5007 5628 5007 5630 5007 5244 5008 5630 5008 5245 5008 5245 5009 5630 5009 5632 5009 5245 5010 5632 5010 5246 5010 5246 5011 5632 5011 5634 5011 5246 5012 5634 5012 5147 5012 5147 5013 5634 5013 5625 5013 5147 5014 5625 5014 5615 5014 5615 5015 5625 5015 5624 5015 5615 5016 5624 5016 5605 5016 5605 5017 5624 5017 5640 5017 5605 5018 5640 5018 5606 5018 5606 5019 5640 5019 5639 5019 5606 5020 5639 5020 5608 5020 5608 5021 5639 5021 5638 5021 5608 5022 5638 5022 5386 5022 5386 5023 5638 5023 5614 5023 5386 5024 5614 5024 5387 5024 5387 5025 5614 5025 5597 5025 5387 5026 5597 5026 5600 5026 5600 5027 5597 5027 5596 5027 5600 5028 5596 5028 5598 5028 5156 5029 5664 5029 5192 5029 5192 5030 5664 5030 5665 5030 5192 5031 5665 5031 5194 5031 5194 5032 5665 5032 5666 5032 5194 5033 5666 5033 5195 5033 5195 5034 5666 5034 5667 5034 5195 5035 5667 5035 5197 5035 5197 5036 5667 5036 5668 5036 5197 5037 5668 5037 5198 5037 5198 5038 5668 5038 5669 5038 5198 5039 5669 5039 5200 5039 5200 5040 5669 5040 5670 5040 5200 5041 5670 5041 5201 5041 5201 5042 5670 5042 5671 5042 5201 5043 5671 5043 5202 5043 5202 5044 5671 5044 5672 5044 5202 5045 5672 5045 5203 5045 5203 5046 5672 5046 5673 5046 5203 5047 5673 5047 5204 5047 5204 5048 5673 5048 5674 5048 5204 5049 5674 5049 5160 5049 5160 5050 5674 5050 5675 5050 5160 5051 5675 5051 5161 5051 5161 5052 5675 5052 5676 5052 5161 5053 5676 5053 5162 5053 5162 5054 5676 5054 5677 5054 5162 5055 5677 5055 5164 5055 5164 5056 5677 5056 5678 5056 5164 5057 5678 5057 5165 5057 5165 5058 5678 5058 5679 5058 5165 5059 5679 5059 5167 5059 5167 5060 5679 5060 5680 5060 5167 5061 5680 5061 5206 5061 5206 5062 5680 5062 5681 5062 5206 5063 5681 5063 5208 5063 5208 5064 5681 5064 5682 5064 5208 5065 5682 5065 5209 5065 5209 5066 5682 5066 5683 5066 5209 5067 5683 5067 5211 5067 5211 5068 5683 5068 5684 5068 5211 5069 5684 5069 5212 5069 5212 5070 5684 5070 5685 5070 5212 5071 5685 5071 5214 5071 5214 5072 5685 5072 5686 5072 5214 5073 5686 5073 5215 5073 5215 5074 5686 5074 5687 5074 5215 5075 5687 5075 5216 5075 5216 5076 5687 5076 5688 5076 5216 5077 5688 5077 5217 5077 5217 5078 5688 5078 5689 5078 5217 5079 5689 5079 5218 5079 5218 5080 5689 5080 5690 5080 5218 5081 5690 5081 5169 5081 5169 5082 5690 5082 5691 5082 5169 5083 5691 5083 5172 5083 5172 5084 5691 5084 5692 5084 5172 5085 5692 5085 5173 5085 5173 5086 5692 5086 5693 5086 5173 5087 5693 5087 5175 5087 5175 5088 5693 5088 5694 5088 5175 5089 5694 5089 5176 5089 5176 5090 5694 5090 5695 5090 5176 5091 5695 5091 5178 5091 5178 5092 5695 5092 5696 5092 5178 5093 5696 5093 5220 5093 5220 5094 5696 5094 5697 5094 5220 5095 5697 5095 5222 5095 5222 5096 5697 5096 5698 5096 5222 5097 5698 5097 5223 5097 5223 5098 5698 5098 5699 5098 5223 5099 5699 5099 5225 5099 5225 5100 5699 5100 5700 5100 5225 5101 5700 5101 5226 5101 5226 5102 5700 5102 5701 5102 5226 5103 5701 5103 5228 5103 5228 5104 5701 5104 5702 5104 5228 5105 5702 5105 5229 5105 5229 5106 5702 5106 5703 5106 5229 5107 5703 5107 5230 5107 5230 5108 5703 5108 5704 5108 5230 5109 5704 5109 5231 5109 5231 5110 5704 5110 5705 5110 5231 5111 5705 5111 5232 5111 5232 5112 5705 5112 5706 5112 5232 5113 5706 5113 5182 5113 5182 5114 5706 5114 5707 5114 5182 5115 5707 5115 5183 5115 5183 5116 5707 5116 5708 5116 5183 5117 5708 5117 5184 5117 5184 5118 5708 5118 5652 5118 5184 5119 5652 5119 5186 5119 5186 5120 5652 5120 5653 5120 5186 5121 5653 5121 5187 5121 5187 5122 5653 5122 5654 5122 5187 5123 5654 5123 5189 5123 5189 5124 5654 5124 5655 5124 5189 5125 5655 5125 5234 5125 5234 5126 5655 5126 5656 5126 5234 5127 5656 5127 5236 5127 5236 5128 5656 5128 5657 5128 5236 5129 5657 5129 5237 5129 5664 5130 5709 5130 5665 5130 5665 5131 5709 5131 5710 5131 5665 5132 5710 5132 5666 5132 5666 5133 5710 5133 5711 5133 5666 5134 5711 5134 5667 5134 5667 5135 5711 5135 5712 5135 5667 5136 5712 5136 5668 5136 5668 5137 5712 5137 5713 5137 5668 5138 5713 5138 5669 5138 5669 5139 5713 5139 5714 5139 5669 5140 5714 5140 5670 5140 5670 5141 5714 5141 5715 5141 5670 5142 5715 5142 5671 5142 5671 5143 5715 5143 5716 5143 5671 5144 5716 5144 5672 5144 5672 5145 5716 5145 5717 5145 5672 5146 5717 5146 5673 5146 5673 5147 5717 5147 5718 5147 5673 5148 5718 5148 5674 5148 5674 5149 5718 5149 5719 5149 5674 5150 5719 5150 5675 5150 5675 5151 5719 5151 5720 5151 5675 5152 5720 5152 5676 5152 5676 5153 5720 5153 5721 5153 5676 5154 5721 5154 5677 5154 5677 5155 5721 5155 5722 5155 5677 5156 5722 5156 5678 5156 5678 5157 5722 5157 5723 5157 5678 5158 5723 5158 5679 5158 5679 5159 5723 5159 5724 5159 5679 5160 5724 5160 5680 5160 5680 5161 5724 5161 5725 5161 5680 5162 5725 5162 5681 5162 5681 5163 5725 5163 5726 5163 5681 5164 5726 5164 5682 5164 5682 5165 5726 5165 5727 5165 5682 5166 5727 5166 5683 5166 5683 5167 5727 5167 5728 5167 5683 5168 5728 5168 5684 5168 5684 5169 5728 5169 5729 5169 5684 5170 5729 5170 5685 5170 5685 5171 5729 5171 5730 5171 5685 5172 5730 5172 5686 5172 5686 5173 5730 5173 5731 5173 5686 5174 5731 5174 5687 5174 5687 5175 5731 5175 5732 5175 5687 5176 5732 5176 5688 5176 5688 5177 5732 5177 5733 5177 5688 5178 5733 5178 5689 5178 5689 5179 5733 5179 5734 5179 5689 5180 5734 5180 5690 5180 5690 5181 5734 5181 5735 5181 5690 5182 5735 5182 5691 5182 5691 5183 5735 5183 5736 5183 5691 5184 5736 5184 5692 5184 5692 5185 5736 5185 5737 5185 5692 5186 5737 5186 5693 5186 5738 5187 5739 5187 5740 5187 5741 5188 5742 5188 5743 5188 5744 5189 5745 5189 5746 5189 5746 5190 5745 5190 5741 5190 5746 5191 5741 5191 5747 5191 5747 5192 5741 5192 5743 5192 5740 5193 5748 5193 5738 5193 5738 5194 5748 5194 5749 5194 5738 5195 5749 5195 5742 5195 5742 5196 5749 5196 5750 5196 5742 5197 5750 5197 5743 5197 5751 5198 5752 5198 5753 5198 5753 5199 5752 5199 5754 5199 5753 5200 5754 5200 5491 5200 5755 5201 5382 5201 5756 5201 5756 5202 5382 5202 5381 5202 5756 5203 5381 5203 5757 5203 5758 5204 5759 5204 5760 5204 5760 5205 5759 5205 5761 5205 5760 5206 5761 5206 5762 5206 5751 5207 5753 5207 5763 5207 5763 5208 5753 5208 5491 5208 5763 5209 5491 5209 5443 5209 5443 5210 5491 5210 5490 5210 5443 5211 5490 5211 5444 5211 5444 5212 5490 5212 5456 5212 5444 5213 5456 5213 5452 5213 5452 5214 5456 5214 5455 5214 5452 5215 5455 5215 5453 5215 5453 5216 5455 5216 5368 5216 5453 5217 5368 5217 5367 5217 5759 5218 5757 5218 5761 5218 5761 5219 5757 5219 5381 5219 5761 5220 5381 5220 5762 5220 5762 5221 5381 5221 5383 5221 5762 5222 5383 5222 5764 5222 5764 5223 5383 5223 5765 5223 5764 5224 5765 5224 5766 5224 5766 5225 5765 5225 5472 5225 5766 5226 5472 5226 5480 5226 5480 5227 5472 5227 5474 5227 5480 5228 5474 5228 5481 5228 5481 5229 5474 5229 5476 5229 5481 5230 5476 5230 5482 5230 5482 5231 5476 5231 5478 5231 5482 5232 5478 5232 5373 5232 5373 5233 5478 5233 5375 5233 5752 5234 5758 5234 5754 5234 5754 5235 5758 5235 5760 5235 5754 5236 5760 5236 5491 5236 5491 5237 5760 5237 5762 5237 5491 5238 5762 5238 5489 5238 5489 5239 5762 5239 5764 5239 5489 5240 5764 5240 5487 5240 5487 5241 5764 5241 5766 5241 5487 5242 5766 5242 5485 5242 5485 5243 5766 5243 5480 5243 5485 5244 5480 5244 5483 5244 5483 5245 5480 5245 5458 5245 5483 5246 5458 5246 5357 5246 5357 5247 5458 5247 5345 5247 5767 5248 5739 5248 5449 5248 5449 5249 5739 5249 5738 5249 5449 5250 5738 5250 5447 5250 5447 5251 5738 5251 5742 5251 5447 5252 5742 5252 5445 5252 5445 5253 5742 5253 5741 5253 5445 5254 5741 5254 5443 5254 5443 5255 5741 5255 5745 5255 5443 5256 5745 5256 5763 5256 5763 5257 5745 5257 5744 5257 5763 5258 5744 5258 5751 5258 5768 5259 5769 5259 5770 5259 5770 5260 5769 5260 5771 5260 5770 5261 5771 5261 5772 5261 5772 5262 5771 5262 5773 5262 5774 5263 5773 5263 5775 5263 5775 5264 5773 5264 5771 5264 5775 5265 5771 5265 5776 5265 5776 5266 5771 5266 5769 5266 5776 5267 5769 5267 5777 5267 5777 5268 5769 5268 5768 5268 5777 5269 5768 5269 5778 5269 5380 5270 5379 5270 5779 5270 5779 5271 5379 5271 5780 5271 5779 5272 5780 5272 5781 5272 5780 5273 5782 5273 5781 5273 5781 5274 5782 5274 5783 5274 5781 5275 5783 5275 5784 5275 5785 5276 5786 5276 5787 5276 5783 5277 5788 5277 5784 5277 5784 5278 5788 5278 5789 5278 5784 5279 5789 5279 5787 5279 5787 5280 5789 5280 5790 5280 5787 5281 5790 5281 5785 5281 5785 5282 5791 5282 5786 5282 5786 5283 5791 5283 5792 5283 5786 5284 5792 5284 5579 5284 5579 5285 5792 5285 5793 5285 5579 5286 5793 5286 5580 5286 5794 5287 5795 5287 5796 5287 5796 5288 5795 5288 5797 5288 5796 5289 5797 5289 5798 5289 5799 5290 5800 5290 5801 5290 5801 5291 5800 5291 5802 5291 5801 5292 5802 5292 5803 5292 5803 5293 5802 5293 5804 5293 5803 5294 5804 5294 5805 5294 5805 5295 5804 5295 5806 5295 5805 5296 5806 5296 5807 5296 5807 5297 5806 5297 5808 5297 5807 5298 5808 5298 5809 5298 5809 5299 5808 5299 5810 5299 5809 5300 5810 5300 5811 5300 5811 5301 5810 5301 5812 5301 5811 5302 5812 5302 5813 5302 5813 5303 5812 5303 5814 5303 5813 5304 5814 5304 5815 5304 5815 5305 5814 5305 5816 5305 5815 5306 5816 5306 5817 5306 5817 5307 5816 5307 5818 5307 5817 5308 5818 5308 5819 5308 5819 5309 5818 5309 5820 5309 5819 5310 5820 5310 5821 5310 5411 5311 5398 5311 5405 5311 5405 5312 5398 5312 5400 5312 5405 5313 5400 5313 5822 5313 5822 5314 5400 5314 5823 5314 5822 5315 5823 5315 5824 5315 5824 5316 5823 5316 5825 5316 5824 5317 5825 5317 5826 5317 5402 5318 5403 5318 5400 5318 5400 5319 5403 5319 5397 5319 5400 5320 5397 5320 5823 5320 5823 5321 5397 5321 5457 5321 5823 5322 5457 5322 5825 5322 5817 5323 5826 5323 5815 5323 5815 5324 5826 5324 5825 5324 5815 5325 5825 5325 5813 5325 5813 5326 5825 5326 5457 5326 5813 5327 5457 5327 5811 5327 5811 5328 5457 5328 5391 5328 5811 5329 5391 5329 5809 5329 5809 5330 5391 5330 5393 5330 5809 5331 5393 5331 5807 5331 5807 5332 5393 5332 5504 5332 5807 5333 5504 5333 5805 5333 5805 5334 5504 5334 5536 5334 5805 5335 5536 5335 5803 5335 5803 5336 5536 5336 5542 5336 5803 5337 5542 5337 5801 5337 5801 5338 5542 5338 5564 5338 5801 5339 5564 5339 5799 5339 5799 5340 5564 5340 5571 5340 5362 5341 5361 5341 5565 5341 5565 5342 5361 5342 5340 5342 5565 5343 5340 5343 5566 5343 5566 5344 5340 5344 5339 5344 5566 5345 5339 5345 5567 5345 5567 5346 5339 5346 5342 5346 5567 5347 5342 5347 5568 5347 5568 5348 5342 5348 5364 5348 5568 5349 5364 5349 5569 5349 5569 5350 5364 5350 5363 5350 5569 5351 5363 5351 5570 5351 5570 5352 5363 5352 5360 5352 5570 5353 5360 5353 5571 5353 5571 5354 5360 5354 5359 5354 5571 5355 5359 5355 5799 5355 5799 5356 5359 5356 5341 5356 5799 5357 5341 5357 5800 5357 5800 5358 5341 5358 5543 5358 5800 5359 5543 5359 5802 5359 5802 5360 5543 5360 5545 5360 5802 5361 5545 5361 5804 5361 5804 5362 5545 5362 5547 5362 5804 5363 5547 5363 5806 5363 5806 5364 5547 5364 5549 5364 5806 5365 5549 5365 5808 5365 5808 5366 5549 5366 5551 5366 5808 5367 5551 5367 5810 5367 5810 5368 5551 5368 5553 5368 5810 5369 5553 5369 5812 5369 5812 5370 5553 5370 5555 5370 5812 5371 5555 5371 5814 5371 5814 5372 5555 5372 5557 5372 5814 5373 5557 5373 5816 5373 5816 5374 5557 5374 5559 5374 5816 5375 5559 5375 5818 5375 5821 5376 5378 5376 5819 5376 5819 5377 5378 5377 5380 5377 5819 5378 5380 5378 5817 5378 5817 5379 5380 5379 5779 5379 5817 5380 5779 5380 5826 5380 5826 5381 5779 5381 5781 5381 5826 5382 5781 5382 5824 5382 5824 5383 5781 5383 5784 5383 5824 5384 5784 5384 5822 5384 5822 5385 5784 5385 5787 5385 5822 5386 5787 5386 5405 5386 5405 5387 5787 5387 5786 5387 5405 5388 5786 5388 5407 5388 5407 5389 5786 5389 5579 5389 5407 5390 5579 5390 5414 5390 5414 5391 5579 5391 5578 5391 5414 5392 5578 5392 5592 5392 5592 5393 5578 5393 5583 5393 5592 5394 5583 5394 5594 5394 5594 5395 5583 5395 5586 5395 5594 5396 5586 5396 5596 5396 5596 5397 5586 5397 5588 5397 5596 5398 5588 5398 5598 5398 5598 5399 5588 5399 5587 5399 5598 5400 5587 5400 5622 5400 5776 5401 5798 5401 5775 5401 5775 5402 5798 5402 5797 5402 5775 5403 5797 5403 5774 5403 5774 5404 5797 5404 5827 5404 5774 5405 5827 5405 5773 5405 5773 5406 5827 5406 5828 5406 5773 5407 5828 5407 5772 5407 5772 5408 5828 5408 5829 5408 5772 5409 5829 5409 5770 5409 5770 5410 5829 5410 5830 5410 5770 5411 5830 5411 5768 5411 5768 5412 5830 5412 5831 5412 5768 5413 5831 5413 5778 5413 5778 5414 5831 5414 5832 5414 5374 5415 5376 5415 5833 5415 5833 5416 5376 5416 5479 5416 5833 5417 5479 5417 5834 5417 5834 5418 5479 5418 5477 5418 5834 5419 5477 5419 5835 5419 5835 5420 5477 5420 5475 5420 5835 5421 5475 5421 5836 5421 5836 5422 5475 5422 5473 5422 5836 5423 5473 5423 5837 5423 5837 5424 5473 5424 5472 5424 5837 5425 5472 5425 5794 5425 5794 5426 5472 5426 5765 5426 5794 5427 5765 5427 5795 5427 5795 5428 5765 5428 5383 5428 5795 5429 5383 5429 5797 5429 5797 5430 5383 5430 5382 5430 5797 5431 5382 5431 5827 5431 5827 5432 5382 5432 5755 5432 5827 5433 5755 5433 5828 5433 5821 5434 5838 5434 5378 5434 5378 5435 5838 5435 5839 5435 5378 5436 5839 5436 5379 5436 5379 5437 5839 5437 5840 5437 5379 5438 5840 5438 5780 5438 5780 5439 5840 5439 5841 5439 5780 5440 5841 5440 5782 5440 5782 5441 5841 5441 5842 5441 5782 5442 5842 5442 5783 5442 5783 5443 5842 5443 5843 5443 5783 5444 5843 5444 5788 5444 5788 5445 5843 5445 5844 5445 5788 5446 5844 5446 5789 5446 5789 5447 5844 5447 5845 5447 5789 5448 5845 5448 5790 5448 5790 5449 5845 5449 5846 5449 5790 5450 5846 5450 5785 5450 5785 5451 5846 5451 5847 5451 5785 5452 5847 5452 5791 5452 5791 5453 5847 5453 5848 5453 5791 5454 5848 5454 5792 5454 5792 5455 5848 5455 5849 5455 5792 5456 5849 5456 5793 5456 5793 5457 5849 5457 5850 5457 5793 5458 5850 5458 5580 5458 5580 5459 5850 5459 5851 5459 5580 5460 5851 5460 5581 5460 5581 5461 5851 5461 5852 5461 5581 5462 5852 5462 5582 5462 5582 5463 5852 5463 5853 5463 5582 5464 5853 5464 5584 5464 5584 5465 5853 5465 5854 5465 5584 5466 5854 5466 5585 5466 5585 5467 5854 5467 5855 5467 5585 5468 5855 5468 5590 5468 5590 5469 5855 5469 5856 5469 5590 5470 5856 5470 5589 5470 5589 5471 5856 5471 5857 5471 5589 5472 5857 5472 5587 5472 5587 5473 5857 5473 5858 5473 5587 5474 5858 5474 5622 5474 5622 5475 5858 5475 5859 5475 5622 5476 5859 5476 5621 5476 5621 5477 5859 5477 5860 5477 5621 5478 5860 5478 5620 5478 5620 5479 5860 5479 5861 5479 5620 5480 5861 5480 5619 5480 5619 5481 5861 5481 5862 5481 5619 5482 5862 5482 5618 5482 5350 5483 5349 5483 5451 5483 5451 5484 5349 5484 5377 5484 5451 5485 5377 5485 5660 5485 5660 5486 5377 5486 5524 5486 5660 5487 5524 5487 5659 5487 5659 5488 5524 5488 5526 5488 5659 5489 5526 5489 5658 5489 5658 5490 5526 5490 5649 5490 5658 5491 5649 5491 5657 5491 5657 5492 5649 5492 5647 5492 5657 5493 5647 5493 5237 5493 5237 5494 5647 5494 5648 5494 5237 5495 5648 5495 5384 5495 5384 5496 5648 5496 5661 5496 5384 5497 5661 5497 5240 5497 5240 5498 5661 5498 5242 5498 5343 5499 5374 5499 5460 5499 5460 5500 5374 5500 5833 5500 5460 5501 5833 5501 5462 5501 5462 5502 5833 5502 5834 5502 5462 5503 5834 5503 5464 5503 5464 5504 5834 5504 5835 5504 5464 5505 5835 5505 5466 5505 5466 5506 5835 5506 5836 5506 5466 5507 5836 5507 5468 5507 5468 5508 5836 5508 5837 5508 5468 5509 5837 5509 5470 5509 5470 5510 5837 5510 5794 5510 5470 5511 5794 5511 5471 5511 5471 5512 5794 5512 5796 5512 5471 5513 5796 5513 5558 5513 5558 5514 5796 5514 5798 5514 5558 5515 5798 5515 5559 5515 5559 5516 5798 5516 5776 5516 5559 5517 5776 5517 5818 5517 5818 5518 5776 5518 5777 5518 5818 5519 5777 5519 5820 5519 5820 5520 5777 5520 5778 5520 5820 5521 5778 5521 5821 5521 5821 5522 5778 5522 5832 5522 5821 5523 5832 5523 5838 5523 5351 5524 5451 5524 5450 5524 5450 5525 5451 5525 5390 5525 5450 5526 5390 5526 5449 5526 5449 5248 5390 5248 5389 5248 5449 5248 5389 5248 5767 5248 5767 5527 5389 5527 5529 5527 5767 5527 5529 5527 5739 5527 5739 5528 5529 5528 5652 5528 5739 5529 5652 5529 5740 5529 5740 5530 5652 5530 5708 5530 5740 5531 5708 5531 5748 5531 5748 5532 5708 5532 5707 5532 5748 5533 5707 5533 5749 5533 5749 5534 5707 5534 5706 5534 5749 5535 5706 5535 5750 5535 5750 5536 5706 5536 5705 5536 5750 5537 5705 5537 5743 5537 5743 5538 5705 5538 5704 5538 5743 5539 5704 5539 5747 5539 5747 5540 5704 5540 5703 5540 5747 5541 5703 5541 5746 5541 5746 5542 5703 5542 5702 5542 5746 5543 5702 5543 5744 5543 5744 5544 5702 5544 5701 5544 5744 5545 5701 5545 5751 5545 5751 5546 5701 5546 5700 5546 5751 5547 5700 5547 5752 5547 5752 5548 5700 5548 5699 5548 5752 5549 5699 5549 5758 5549 5758 5550 5699 5550 5698 5550 5758 5551 5698 5551 5759 5551 5759 5552 5698 5552 5697 5552 5759 5553 5697 5553 5757 5553 5757 5554 5697 5554 5696 5554 5757 5555 5696 5555 5756 5555 5756 5556 5696 5556 5695 5556 5756 5557 5695 5557 5755 5557 5755 5558 5695 5558 5694 5558 5755 5559 5694 5559 5828 5559 5828 5560 5694 5560 5693 5560 5828 5561 5693 5561 5829 5561 5829 5562 5693 5562 5737 5562 5829 5563 5737 5563 5830 5563 5830 5564 5737 5564 5736 5564 5830 5565 5736 5565 5831 5565 5831 5566 5736 5566 5735 5566 5831 5567 5735 5567 5832 5567 5832 5568 5735 5568 5734 5568 5832 5569 5734 5569 5838 5569 5838 5570 5734 5570 5733 5570 5838 5571 5733 5571 5839 5571 5839 5572 5733 5572 5732 5572 5839 5573 5732 5573 5840 5573 5840 5574 5732 5574 5731 5574 5840 5575 5731 5575 5841 5575 5841 5576 5731 5576 5730 5576 5841 5577 5730 5577 5842 5577 5842 5578 5730 5578 5729 5578 5842 5579 5729 5579 5843 5579 5843 5580 5729 5580 5728 5580 5843 5581 5728 5581 5844 5581 5844 5582 5728 5582 5727 5582 5844 5583 5727 5583 5845 5583 5845 5584 5727 5584 5726 5584 5845 5585 5726 5585 5846 5585 5846 5586 5726 5586 5725 5586 5846 5587 5725 5587 5847 5587 5847 5588 5725 5588 5724 5588 5847 5589 5724 5589 5848 5589 5848 5590 5724 5590 5723 5590 5848 5591 5723 5591 5849 5591 5849 5592 5723 5592 5722 5592 5849 5593 5722 5593 5850 5593 5850 5594 5722 5594 5721 5594 5850 5595 5721 5595 5851 5595 5851 5596 5721 5596 5720 5596 5851 5597 5720 5597 5852 5597 5852 5598 5720 5598 5719 5598 5852 5599 5719 5599 5853 5599 5853 5600 5719 5600 5718 5600 5853 5601 5718 5601 5854 5601 5854 5602 5718 5602 5717 5602 5854 5603 5717 5603 5855 5603 5855 5604 5717 5604 5716 5604 5855 5605 5716 5605 5856 5605 5856 5606 5716 5606 5715 5606 5856 5607 5715 5607 5857 5607 5857 5608 5715 5608 5714 5608 5857 5609 5714 5609 5858 5609 5858 5610 5714 5610 5713 5610 5858 5611 5713 5611 5859 5611 5859 5612 5713 5612 5712 5612 5859 5613 5712 5613 5860 5613 5860 5614 5712 5614 5711 5614 5860 5615 5711 5615 5861 5615 5861 5616 5711 5616 5710 5616 5861 5617 5710 5617 5862 5617 5862 5618 5710 5618 5709 5618 5862 5619 5709 5619 5618 5619 5618 5620 5709 5620 5664 5620 5618 5621 5664 5621 5577 5621 5577 5622 5664 5622 5156 5622 5577 5623 5156 5623 5154 5623 5417 5624 5416 5624 5266 5624 5424 5625 5423 5625 5269 5625 5434 5626 5433 5626 5276 5626 5257 5627 5396 5627 5395 5627 5257 5628 5395 5628 5285 5628 5438 5629 5437 5629 5250 5629 5250 5630 5437 5630 5436 5630 5250 5631 5436 5631 5257 5631 5257 5632 5436 5632 5435 5632 5257 5633 5435 5633 5396 5633 5442 5634 5441 5634 5274 5634 5274 5635 5441 5635 5440 5635 5274 5636 5440 5636 5250 5636 5250 5637 5440 5637 5439 5637 5250 5638 5439 5638 5438 5638 5276 5639 5433 5639 5274 5639 5274 5640 5433 5640 5431 5640 5274 5641 5431 5641 5430 5641 5430 5642 5429 5642 5274 5642 5274 5643 5429 5643 5428 5643 5274 5644 5428 5644 5442 5644 5269 5645 5423 5645 5272 5645 5423 5646 5422 5646 5272 5646 5272 5647 5422 5647 5420 5647 5272 5648 5420 5648 5276 5648 5276 5649 5420 5649 5419 5649 5276 5650 5419 5650 5434 5650 5266 5651 5416 5651 5268 5651 5268 5652 5416 5652 5415 5652 5268 5653 5415 5653 5413 5653 5413 5654 5412 5654 5268 5654 5268 5655 5412 5655 5427 5655 5268 5656 5427 5656 5269 5656 5269 5657 5427 5657 5426 5657 5269 5658 5426 5658 5424 5658 5252 5659 5410 5659 5409 5659 5409 5660 5404 5660 5252 5660 5252 5661 5404 5661 5406 5661 5252 5662 5406 5662 5264 5662 5264 5663 5406 5663 5408 5663 5264 5664 5408 5664 5266 5664 5266 5665 5408 5665 5418 5665 5266 5666 5418 5666 5417 5666 5258 5667 5399 5667 5398 5667 5258 5668 5398 5668 5252 5668 5252 5669 5398 5669 5411 5669 5252 5670 5411 5670 5410 5670 5395 5671 5403 5671 5285 5671 5285 5672 5403 5672 5402 5672 5285 5673 5402 5673 5258 5673 5258 5674 5402 5674 5401 5674 5258 5675 5401 5675 5399 5675 5863 5676 5864 5676 5865 5676 5866 1082 5867 1082 5868 1082 5869 5677 5870 5677 5871 5677 5872 1080 5873 1080 5874 1080 5875 1101 5876 1101 5877 1101 5875 1102 5878 1102 5876 1102 5876 1103 5878 1103 5879 1103 5876 5678 5879 5678 5880 5678 5879 1105 5881 1105 5880 1105 5880 1106 5881 1106 5882 1106 5880 1107 5882 1107 5883 1107 5883 5679 5882 5679 5884 5679 5883 1109 5884 1109 5885 1109 5886 1110 5887 1110 5888 1110 5888 5680 5889 5680 5886 5680 5886 5681 5889 5681 5890 5681 5886 5682 5890 5682 5891 5682 5890 5683 5892 5683 5891 5683 5891 5684 5892 5684 5893 5684 5891 5685 5893 5685 5894 5685 5894 5686 5893 5686 5895 5686 5894 1173 5895 1173 5896 1173 5897 1083 5898 1083 5899 1083 5897 1084 5900 1084 5898 1084 5898 1085 5900 1085 5901 1085 5898 5687 5901 5687 5902 5687 5901 1087 5903 1087 5902 1087 5902 1088 5903 1088 5904 1088 5902 1089 5904 1089 5905 1089 5905 5688 5904 5688 5906 5688 5905 1091 5906 1091 5907 1091 5908 1092 5909 1092 5910 1092 5910 5689 5911 5689 5908 5689 5908 5690 5911 5690 5912 5690 5908 5691 5912 5691 5913 5691 5912 5692 5914 5692 5913 5692 5913 5693 5914 5693 5915 5693 5913 5694 5915 5694 5916 5694 5916 5695 5915 5695 5917 5695 5916 5696 5917 5696 5918 5696 5885 1155 5884 1155 5919 1155 5919 5697 5884 5697 5920 5697 5919 5698 5920 5698 5921 5698 5920 5699 5922 5699 5921 5699 5921 5700 5922 5700 5923 5700 5921 5701 5923 5701 5924 5701 5923 1161 5925 1161 5924 1161 5924 5702 5925 5702 5926 5702 5924 5703 5926 5703 5927 5703 5926 1164 5928 1164 5927 1164 5927 5704 5928 5704 5929 5704 5927 5705 5929 5705 5871 5705 5871 1167 5929 1167 5930 1167 5871 5706 5930 5706 5869 5706 5869 5707 5930 5707 5931 5707 5869 5708 5931 5708 5887 5708 5887 1171 5931 1171 5932 1171 5887 1172 5932 1172 5888 1172 5896 5709 5895 5709 5933 5709 5933 1174 5895 1174 5934 1174 5933 5710 5934 5710 5935 5710 5934 5711 5936 5711 5935 5711 5935 5712 5936 5712 5937 5712 5935 5713 5937 5713 5938 5713 5937 5714 5939 5714 5938 5714 5938 5715 5939 5715 5940 5715 5938 5716 5940 5716 5941 5716 5940 5717 5942 5717 5941 5717 5941 1183 5942 1183 5943 1183 5941 5718 5943 5718 5868 5718 5868 1185 5943 1185 5944 1185 5868 1186 5944 1186 5866 1186 5866 5719 5944 5719 5945 5719 5866 1188 5945 1188 5899 1188 5899 5720 5945 5720 5946 5720 5899 1190 5946 1190 5897 1190 5907 1119 5906 1119 5947 1119 5947 5721 5906 5721 5948 5721 5947 5722 5948 5722 5949 5722 5948 5723 5950 5723 5949 5723 5949 5724 5950 5724 5951 5724 5949 5725 5951 5725 5952 5725 5951 1125 5953 1125 5952 1125 5952 5726 5953 5726 5954 5726 5952 5727 5954 5727 5955 5727 5954 1128 5956 1128 5955 1128 5955 5728 5956 5728 5957 5728 5955 5729 5957 5729 5865 5729 5865 1131 5957 1131 5958 1131 5865 5730 5958 5730 5863 5730 5863 5731 5958 5731 5959 5731 5863 5732 5959 5732 5909 5732 5909 1135 5959 1135 5960 1135 5909 1136 5960 1136 5910 1136 5918 1100 5917 1100 5961 1100 5961 1138 5917 1138 5962 1138 5961 5733 5962 5733 5963 5733 5962 5734 5964 5734 5963 5734 5963 5735 5964 5735 5965 5735 5963 5736 5965 5736 5966 5736 5965 5737 5967 5737 5966 5737 5966 5738 5967 5738 5968 5738 5966 5739 5968 5739 5969 5739 5968 5740 5970 5740 5969 5740 5969 1147 5970 1147 5971 1147 5969 5741 5971 5741 5874 5741 5874 1149 5971 1149 5972 1149 5874 1150 5972 1150 5872 1150 5872 5742 5972 5742 5973 5742 5872 1152 5973 1152 5877 1152 5877 5743 5973 5743 5974 5743 5877 1154 5974 1154 5875 1154 5867 88 5975 88 5868 88 5868 88 5975 88 5941 88 5976 88 5977 88 5978 88 5979 88 5980 88 5981 88 5981 88 5980 88 5982 88 5983 88 5984 88 5985 88 5941 88 5986 88 5938 88 5938 88 5986 88 5980 88 5938 88 5980 88 5935 88 5935 88 5980 88 5979 88 5987 88 5927 88 5988 88 5988 88 5927 88 5871 88 5988 88 5871 88 5870 88 5979 88 5989 88 5935 88 5935 88 5989 88 5990 88 5935 88 5990 88 5933 88 5933 88 5990 88 5896 88 5982 88 5980 88 5991 88 5991 88 5980 88 5992 88 5991 88 5992 88 5993 88 5993 88 5992 88 5994 88 5993 88 5994 88 5995 88 5996 88 5997 88 5998 88 5998 88 5997 88 5999 88 5999 88 5997 88 6000 88 5999 88 6000 88 6001 88 5978 88 5977 88 6002 88 6002 88 5977 88 6003 88 6002 88 6003 88 6004 88 6005 88 5976 88 5955 88 5955 88 5976 88 5978 88 5955 88 5978 88 5952 88 5952 88 5978 88 5985 88 5952 88 5985 88 5949 88 5949 88 5985 88 5984 88 5998 88 6006 88 5996 88 5996 88 6006 88 6007 88 5996 88 6007 88 6008 88 6005 88 5955 88 6009 88 6009 88 5955 88 5865 88 6009 88 5865 88 5864 88 5975 88 6010 88 5941 88 5941 88 6010 88 6011 88 5941 88 6011 88 5986 88 5986 88 6011 88 6012 88 5986 88 6012 88 6013 88 6013 88 6012 88 6014 88 6013 88 6014 88 5985 88 5985 88 6014 88 6015 88 5985 88 6015 88 5983 88 5984 88 6016 88 5949 88 5949 88 6016 88 6017 88 5949 88 6017 88 5947 88 5947 88 6017 88 5907 88 5987 88 5995 88 5927 88 5927 88 5995 88 5994 88 5927 88 5994 88 5924 88 5924 4588 5994 4588 5996 4588 5924 5744 5996 5744 5921 5744 5921 88 5996 88 6008 88 6008 88 6018 88 5921 88 5921 88 6018 88 6019 88 5921 88 6019 88 5919 88 5919 88 6019 88 5885 88 6020 88 5969 88 6021 88 6021 88 5969 88 5874 88 6021 88 5874 88 5873 88 6003 88 6022 88 6004 88 6004 88 6022 88 6023 88 6004 88 6023 88 6024 88 5918 88 5961 88 6025 88 6025 88 5961 88 5963 88 6025 88 5963 88 6026 88 6020 88 6001 88 5969 88 5969 88 6001 88 6000 88 5969 88 6000 88 5966 88 5966 88 6000 88 6004 88 5966 88 6004 88 5963 88 5963 88 6004 88 6024 88 5963 88 6024 88 6026 88 6027 88 5872 88 5877 88 6028 88 6029 88 6030 88 6031 88 6032 88 6033 88 6033 88 6032 88 6034 88 6030 88 6027 88 6028 88 6028 88 6027 88 5877 88 6028 88 5877 88 6035 88 6035 88 5877 88 5876 88 6035 88 5876 88 6036 88 6036 88 5876 88 5880 88 6036 88 5880 88 6034 88 6034 88 5880 88 5883 88 6034 88 5883 88 6033 88 6021 1275 5873 1275 6027 1275 6027 1275 5873 1275 5872 1275 6019 1273 6033 1273 5885 1273 5885 1274 6033 1274 5883 1274 6033 1276 6019 1276 6031 1276 6031 1277 6019 1277 6018 1277 6031 1278 6018 1278 6032 1278 6032 1279 6018 1279 6008 1279 6032 1280 6008 1280 6034 1280 6034 1281 6008 1281 6007 1281 6034 1282 6007 1282 6036 1282 6036 1283 6007 1283 6006 1283 6036 1284 6006 1284 6035 1284 6035 1285 6006 1285 5998 1285 6035 1286 5998 1286 6028 1286 6028 1286 5998 1286 5999 1286 6028 1287 5999 1287 6029 1287 6029 1287 5999 1287 6001 1287 6029 1288 6001 1288 6030 1288 6030 1288 6001 1288 6020 1288 6030 1289 6020 1289 6027 1289 6027 1290 6020 1290 6021 1290 6037 88 5869 88 5887 88 6038 88 6039 88 6040 88 6040 88 6037 88 6038 88 6038 88 6037 88 5887 88 6038 88 5887 88 6041 88 6041 88 5887 88 5886 88 6041 88 5886 88 6042 88 6042 88 5886 88 5891 88 6042 88 5891 88 6043 88 6044 88 6045 88 6046 88 6046 88 6045 88 6043 88 6046 88 6043 88 5894 88 5894 88 6043 88 5891 88 5990 5745 6046 5745 5896 5745 5896 5746 6046 5746 5894 5746 5988 1291 5870 1291 6037 1291 6037 1292 5870 1292 5869 1292 6046 1293 5990 1293 6044 1293 6044 1294 5990 1294 5989 1294 6044 1295 5989 1295 6045 1295 6045 1296 5989 1296 5979 1296 6045 1297 5979 1297 6043 1297 6043 1298 5979 1298 5981 1298 6043 1299 5981 1299 6042 1299 6042 1299 5981 1299 5982 1299 6042 1300 5982 1300 6041 1300 6041 1300 5982 1300 5991 1300 6041 1301 5991 1301 6038 1301 6038 1302 5991 1302 5993 1302 6038 1303 5993 1303 6039 1303 6039 1304 5993 1304 5995 1304 6039 1305 5995 1305 6040 1305 6040 1306 5995 1306 5987 1306 6040 1307 5987 1307 6037 1307 6037 1307 5987 1307 5988 1307 6047 88 5866 88 5899 88 6048 88 6049 88 6050 88 6051 88 6052 88 6053 88 6053 88 6052 88 6054 88 6050 88 6047 88 6048 88 6048 88 6047 88 5899 88 6048 88 5899 88 6055 88 6055 88 5899 88 5898 88 6055 88 5898 88 6056 88 6056 88 5898 88 5902 88 6056 88 5902 88 6054 88 6054 88 5902 88 5905 88 6054 88 5905 88 6053 88 6017 1237 6053 1237 5907 1237 5907 1238 6053 1238 5905 1238 5975 1236 5867 1236 6047 1236 6047 1236 5867 1236 5866 1236 6053 1239 6017 1239 6051 1239 6051 1240 6017 1240 6016 1240 6051 1241 6016 1241 6052 1241 6052 1242 6016 1242 5984 1242 6052 1243 5984 1243 6054 1243 6054 1244 5984 1244 5983 1244 6054 1245 5983 1245 6056 1245 6056 1246 5983 1246 6015 1246 6056 1247 6015 1247 6055 1247 6055 1248 6015 1248 6014 1248 6055 1249 6014 1249 6048 1249 6048 1249 6014 1249 6012 1249 6048 1250 6012 1250 6049 1250 6049 1250 6012 1250 6011 1250 6049 1251 6011 1251 6050 1251 6050 1251 6011 1251 6010 1251 6050 1252 6010 1252 6047 1252 6047 1253 6010 1253 5975 1253 6057 88 5863 88 5909 88 6058 88 6059 88 6060 88 6060 88 6057 88 6058 88 6058 88 6057 88 5909 88 6058 88 5909 88 6061 88 6061 88 5909 88 5908 88 6061 88 5908 88 6062 88 6062 88 5908 88 5913 88 6062 88 5913 88 6063 88 6064 88 6065 88 6066 88 6066 88 6065 88 6063 88 6066 88 6063 88 5916 88 5916 88 6063 88 5913 88 6025 1291 6066 1291 5918 1291 5918 1291 6066 1291 5916 1291 6009 1256 5864 1256 6057 1256 6057 1257 5864 1257 5863 1257 6066 1258 6025 1258 6064 1258 6064 1259 6025 1259 6026 1259 6064 1260 6026 1260 6065 1260 6065 1261 6026 1261 6024 1261 6065 1262 6024 1262 6063 1262 6063 1263 6024 1263 6023 1263 6063 1264 6023 1264 6062 1264 6062 1264 6023 1264 6022 1264 6062 1265 6022 1265 6061 1265 6061 1265 6022 1265 6003 1265 6061 1266 6003 1266 6058 1266 6058 1267 6003 1267 5977 1267 6058 1268 5977 1268 6059 1268 6059 1269 5977 1269 5976 1269 6059 1270 5976 1270 6060 1270 6060 1271 5976 1271 6005 1271 6060 1272 6005 1272 6057 1272 6057 1272 6005 1272 6009 1272 6067 0 6068 0 6069 0 6067 0 6069 0 6070 0 6071 0 6072 0 6073 0 6073 0 6072 0 6074 0 6069 0 6075 0 6076 0 6077 0 6078 0 6069 0 6069 0 6078 0 6079 0 6069 0 6079 0 6080 0 6080 0 6081 0 6069 0 6069 0 6081 0 6082 0 6069 0 6082 0 6083 0 6084 0 6085 0 6069 0 6069 0 6085 0 6073 0 6069 0 6073 0 6086 0 6086 0 6073 0 6074 0 6069 0 6087 0 6088 0 6068 0 6089 0 6069 0 6069 0 6089 0 6090 0 6069 0 6090 0 6075 0 6088 0 6091 0 6069 0 6069 0 6091 0 6092 0 6069 0 6092 0 6070 0 6076 0 6093 0 6069 0 6069 0 6093 0 6094 0 6069 0 6094 0 6077 0 6083 0 6095 0 6069 0 6069 0 6095 0 6096 0 6069 0 6096 0 6097 0 6097 0 6098 0 6069 0 6069 0 6098 0 6099 0 6069 0 6099 0 6084 0 6073 0 6100 0 6071 0 6071 0 6100 0 6101 0 6071 0 6101 0 6102 0 6102 0 6101 0 6103 0 6102 0 6103 0 6104 0 6077 5747 6094 5747 6105 5747 6106 5748 6107 5748 6108 5748 6109 5749 6110 5749 6111 5749 6112 5750 5967 5750 5965 5750 5967 5751 6112 5751 5968 5751 6113 5752 6114 5752 6115 5752 6116 5753 6117 5753 6118 5753 6119 5754 6120 5754 6121 5754 6122 5755 6082 5755 6081 5755 6123 5756 6124 5756 6125 5756 6126 5757 6127 5757 6128 5757 6128 5758 6127 5758 6129 5758 6128 5759 6129 5759 6130 5759 6123 5760 6125 5760 6131 5760 6132 5761 6133 5761 6134 5761 6134 5762 6133 5762 6135 5762 6134 5763 6135 5763 6136 5763 6132 5764 6137 5764 6133 5764 6133 5765 6137 5765 6138 5765 6133 5766 6138 5766 6139 5766 6140 5767 6141 5767 6142 5767 6142 5768 6141 5768 6143 5768 6143 5769 6144 5769 6142 5769 6142 5770 6144 5770 6145 5770 6142 5771 6145 5771 6135 5771 6135 5772 6145 5772 6146 5772 6135 5773 6146 5773 6136 5773 6147 5774 6148 5774 6149 5774 6149 5775 6148 5775 6150 5775 6151 5776 6152 5776 6153 5776 6153 5777 6152 5777 6154 5777 6153 5778 6154 5778 6155 5778 6156 5779 6157 5779 6120 5779 6158 5780 6159 5780 6160 5780 6160 5781 6159 5781 6161 5781 6160 5782 6161 5782 6162 5782 6163 5783 6164 5783 6119 5783 6164 5784 6165 5784 6119 5784 6119 5785 6165 5785 6166 5785 6119 5786 6166 5786 6167 5786 6167 5787 6168 5787 6119 5787 6119 5788 6168 5788 6169 5788 6119 5789 6169 5789 6120 5789 6120 5790 6169 5790 6170 5790 6120 5791 6170 5791 6156 5791 6171 5792 6172 5792 6173 5792 6173 5793 6172 5793 6174 5793 6173 5794 6174 5794 6175 5794 6175 5795 6174 5795 6176 5795 6175 5796 6176 5796 6177 5796 6177 5797 6176 5797 6178 5797 6079 5798 6078 5798 6179 5798 6180 5799 6181 5799 6122 5799 6172 5800 6180 5800 6174 5800 6174 5801 6180 5801 6122 5801 6174 5802 6122 5802 6176 5802 6176 5803 6122 5803 6081 5803 6176 5804 6081 5804 6178 5804 6178 5805 6081 5805 6080 5805 6178 5806 6080 5806 6079 5806 6182 5807 6183 5807 6184 5807 6096 5808 6183 5808 6097 5808 6097 5809 6183 5809 6182 5809 6097 5810 6182 5810 6098 5810 6181 5811 6095 5811 6122 5811 6122 5812 6095 5812 6083 5812 6122 5813 6083 5813 6082 5813 6124 5814 6163 5814 6125 5814 6125 5815 6163 5815 6119 5815 6125 5816 6119 5816 6185 5816 6100 5817 6073 5817 6186 5817 6187 5818 6188 5818 6189 5818 6189 5819 6188 5819 6190 5819 6189 5820 6190 5820 6191 5820 6191 5821 6190 5821 6192 5821 6191 5822 6192 5822 6193 5822 6193 5823 6192 5823 6194 5823 6193 5824 6194 5824 6195 5824 6195 5825 6194 5825 6196 5825 6195 5826 6196 5826 6197 5826 6197 5827 6196 5827 6198 5827 6197 5828 6198 5828 6199 5828 6200 5829 6201 5829 6202 5829 6202 5830 6201 5830 6203 5830 6202 5831 6203 5831 6204 5831 6204 5832 6203 5832 6205 5832 6204 5833 6205 5833 6206 5833 6206 5834 6205 5834 6207 5834 6206 5835 6207 5835 6103 5835 6103 5836 6207 5836 6104 5836 6208 5837 6209 5837 6186 5837 6186 5838 6209 5838 6210 5838 6186 5839 6210 5839 6100 5839 6100 5840 6210 5840 6101 5840 6085 5841 6084 5841 6211 5841 6211 5842 6084 5842 6212 5842 6211 5843 6212 5843 6213 5843 6213 5844 6212 5844 6214 5844 6213 5845 6214 5845 6215 5845 6215 5846 6214 5846 6216 5846 6215 5847 6216 5847 6217 5847 6217 5848 6216 5848 6218 5848 6217 5849 6218 5849 6219 5849 6084 5850 6099 5850 6212 5850 6212 5851 6099 5851 6098 5851 6212 5852 6098 5852 6214 5852 6214 5853 6098 5853 6182 5853 6214 5854 6182 5854 6216 5854 6216 5855 6182 5855 6184 5855 6216 5856 6184 5856 6218 5856 6220 5857 6160 5857 6221 5857 6221 5858 6160 5858 6222 5858 6221 5859 6222 5859 6223 5859 6223 5860 6222 5860 6224 5860 6223 5861 6224 5861 6225 5861 6225 5862 6224 5862 6226 5862 6225 5863 6226 5863 6227 5863 6227 5864 6226 5864 6228 5864 6227 5865 6228 5865 6229 5865 6229 5866 6228 5866 6230 5866 6229 5867 6230 5867 6231 5867 6232 5868 6121 5868 6220 5868 6220 5869 6121 5869 6120 5869 6220 5870 6120 5870 6160 5870 6160 5871 6120 5871 6157 5871 6160 5872 6157 5872 6158 5872 6232 5873 6220 5873 6233 5873 6233 5874 6220 5874 6221 5874 6233 5875 6221 5875 6234 5875 6234 5876 6221 5876 6223 5876 6234 5877 6223 5877 6235 5877 6235 5878 6223 5878 6225 5878 6235 5879 6225 5879 6236 5879 6236 5880 6225 5880 6227 5880 6236 5881 6227 5881 6237 5881 6237 5882 6227 5882 6229 5882 6237 5883 6229 5883 6238 5883 6238 5884 6229 5884 6231 5884 6238 5885 6231 5885 6239 5885 6240 5886 6241 5886 6242 5886 6243 5887 6244 5887 6245 5887 6245 5888 6244 5888 6246 5888 6245 5889 6246 5889 6247 5889 6247 5890 6246 5890 6248 5890 6249 5891 6247 5891 6250 5891 6250 5892 6247 5892 6248 5892 6250 5893 6248 5893 6251 5893 6252 5894 6253 5894 6254 5894 6255 5895 6256 5895 6116 5895 6116 5896 6256 5896 6257 5896 6116 5897 6257 5897 6117 5897 6239 5898 6258 5898 6238 5898 6238 5899 6258 5899 6259 5899 6238 5900 6259 5900 6237 5900 6237 5901 6259 5901 6260 5901 6237 5902 6260 5902 6236 5902 6236 5903 6260 5903 6261 5903 6236 5904 6261 5904 6235 5904 6235 5905 6261 5905 6262 5905 6235 5906 6262 5906 6234 5906 6234 5907 6262 5907 6263 5907 6234 5908 6263 5908 6233 5908 6233 5909 6263 5909 6264 5909 6233 5910 6264 5910 6232 5910 6258 5911 6265 5911 6259 5911 6259 5912 6265 5912 6266 5912 6259 5913 6266 5913 6260 5913 6260 5914 6266 5914 6267 5914 6260 5915 6267 5915 6261 5915 6261 5916 6267 5916 6268 5916 6261 5917 6268 5917 6262 5917 6262 5918 6268 5918 6269 5918 6262 5919 6269 5919 6263 5919 6263 5920 6269 5920 6270 5920 6263 5921 6270 5921 6264 5921 6069 5922 6086 5922 6271 5922 6271 5923 6086 5923 6272 5923 6271 5924 6272 5924 6273 5924 6273 5925 6272 5925 6274 5925 6273 5926 6274 5926 6275 5926 6275 5927 6274 5927 6276 5927 6275 5928 6276 5928 6277 5928 6277 5929 6276 5929 6278 5929 6277 5930 6278 5930 6279 5930 6279 5931 6278 5931 6280 5931 6279 5932 6280 5932 6281 5932 6281 5933 6280 5933 6282 5933 6281 5934 6282 5934 6283 5934 6283 5935 6282 5935 6284 5935 6283 5936 6284 5936 6285 5936 6285 5937 6284 5937 6286 5937 6285 5938 6286 5938 6287 5938 6074 5939 6072 5939 6187 5939 6187 5940 6072 5940 6071 5940 6187 5941 6071 5941 6188 5941 6086 5942 6074 5942 6272 5942 6272 5943 6074 5943 6187 5943 6272 5944 6187 5944 6274 5944 6274 5945 6187 5945 6189 5945 6274 5946 6189 5946 6276 5946 6276 5947 6189 5947 6191 5947 6276 5948 6191 5948 6278 5948 6278 5949 6191 5949 6193 5949 6278 5950 6193 5950 6280 5950 6280 5951 6193 5951 6195 5951 6280 5952 6195 5952 6282 5952 6282 5953 6195 5953 6197 5953 6282 5954 6197 5954 6284 5954 6284 5955 6197 5955 6199 5955 6284 5956 6199 5956 6286 5956 6230 5957 6243 5957 6231 5957 6231 5958 6243 5958 6245 5958 6231 5959 6245 5959 6239 5959 6239 5960 6245 5960 6247 5960 6239 5961 6247 5961 6258 5961 6258 5962 6247 5962 6249 5962 6258 5963 6249 5963 6265 5963 6265 5964 6249 5964 6288 5964 6265 5965 6288 5965 6266 5965 6266 5966 6288 5966 6289 5966 6266 5967 6289 5967 6267 5967 6267 5968 6289 5968 6290 5968 6267 5969 6290 5969 6268 5969 6268 5970 6290 5970 6291 5970 6268 5971 6291 5971 6269 5971 6269 5972 6291 5972 6292 5972 6269 5973 6292 5973 6270 5973 6251 5974 6293 5974 6250 5974 6250 5975 6293 5975 6294 5975 6250 5976 6294 5976 6249 5976 6249 5977 6294 5977 6295 5977 6249 5978 6295 5978 6288 5978 6288 5979 6295 5979 6296 5979 6288 5980 6296 5980 6289 5980 6289 5981 6296 5981 6297 5981 6289 5982 6297 5982 6290 5982 6290 5983 6297 5983 6298 5983 6290 5984 6298 5984 6291 5984 6291 5985 6298 5985 6299 5985 6291 5986 6299 5986 6292 5986 6300 5987 6253 5987 6301 5987 6301 5988 6253 5988 6252 5988 6301 5989 6252 5989 6105 5989 6105 5990 6094 5990 6301 5990 6301 5991 6094 5991 6093 5991 6301 5992 6093 5992 6300 5992 6300 5993 6093 5993 6076 5993 6300 5994 6076 5994 6075 5994 5878 5995 6302 5995 5879 5995 5879 5996 6302 5996 6303 5996 5879 5997 6303 5997 5881 5997 5881 5998 6303 5998 6304 5998 5881 5999 6304 5999 5882 5999 5882 6000 6304 6000 6305 6000 6306 6001 6307 6001 6308 6001 6308 6002 6309 6002 6306 6002 6306 6003 6309 6003 6310 6003 6306 6004 6310 6004 6311 6004 6310 6005 6312 6005 6311 6005 6311 6006 6312 6006 6313 6006 6311 6007 6313 6007 6314 6007 6315 6008 6316 6008 6317 6008 6317 6009 6316 6009 6314 6009 6317 6010 6314 6010 6318 6010 6318 6011 6314 6011 6313 6011 6155 6012 6140 6012 6153 6012 6153 6013 6140 6013 6142 6013 6153 6014 6142 6014 6319 6014 6319 6015 6142 6015 6320 6015 6319 6016 6320 6016 6321 6016 6321 6017 6320 6017 6322 6017 6321 6018 6322 6018 6323 6018 6323 6019 6322 6019 6324 6019 6323 6020 6324 6020 6325 6020 6326 6021 6327 6021 6328 6021 6328 6022 6327 6022 6329 6022 6328 6023 6329 6023 6330 6023 6330 6024 6329 6024 6331 6024 6330 6025 6331 6025 6332 6025 6333 6026 6334 6026 6335 6026 6335 6027 6334 6027 6336 6027 6335 6028 6336 6028 6337 6028 6337 6029 6336 6029 6114 6029 6337 6030 6114 6030 6332 6030 6332 6031 6114 6031 6113 6031 6332 6032 6113 6032 6330 6032 6330 6033 6113 6033 6115 6033 6330 6034 6115 6034 6328 6034 6150 6035 6151 6035 6149 6035 6149 6036 6151 6036 6153 6036 6149 6037 6153 6037 6338 6037 6338 6038 6153 6038 6319 6038 6338 6039 6319 6039 6339 6039 6339 6040 6319 6040 6321 6040 6339 6041 6321 6041 6340 6041 6340 6042 6321 6042 6323 6042 6340 6043 6323 6043 6341 6043 6341 6044 6323 6044 6325 6044 6341 6045 6325 6045 6342 6045 6343 6046 6333 6046 6344 6046 6344 6047 6333 6047 6335 6047 6344 6048 6335 6048 6345 6048 6345 6049 6335 6049 6337 6049 6345 6050 6337 6050 6346 6050 6346 6051 6337 6051 6332 6051 6346 6052 6332 6052 6347 6052 6347 6053 6332 6053 6331 6053 6347 6054 6331 6054 6348 6054 6348 6055 6331 6055 6329 6055 6348 6056 6329 6056 6349 6056 6349 6057 6329 6057 6327 6057 6349 6058 6327 6058 6350 6058 6350 6059 6327 6059 6326 6059 5878 6060 5875 6060 6302 6060 6302 6061 5875 6061 6343 6061 6302 6062 6343 6062 6303 6062 6303 6063 6343 6063 6344 6063 6303 6064 6344 6064 6304 6064 6304 6065 6344 6065 6345 6065 6304 6066 6345 6066 6305 6066 6305 6067 6345 6067 6346 6067 6351 6068 6352 6068 6353 6068 6354 6069 6355 6069 6356 6069 6356 6070 6355 6070 6357 6070 6356 6071 6357 6071 6358 6071 6358 6072 6357 6072 6359 6072 6358 6073 6359 6073 6360 6073 6360 6074 6359 6074 6361 6074 6360 6075 6361 6075 6362 6075 6355 6076 6363 6076 6357 6076 6357 6077 6363 6077 6364 6077 6357 6078 6364 6078 6359 6078 6359 6079 6364 6079 6365 6079 6359 6080 6365 6080 6361 6080 6162 6081 6147 6081 6160 6081 6160 6082 6147 6082 6149 6082 6160 6083 6149 6083 6222 6083 6222 6084 6149 6084 6338 6084 6222 6085 6338 6085 6224 6085 6224 6086 6338 6086 6339 6086 6224 6087 6339 6087 6226 6087 6226 6088 6339 6088 6340 6088 6226 6089 6340 6089 6228 6089 6228 6090 6340 6090 6341 6090 6228 6091 6341 6091 6230 6091 6230 6092 6341 6092 6342 6092 6230 6093 6342 6093 6243 6093 6243 6094 6342 6094 6366 6094 6243 6095 6366 6095 6244 6095 6244 6096 6366 6096 6367 6096 6244 6097 6367 6097 6246 6097 6246 6098 6367 6098 6368 6098 6246 6099 6368 6099 6369 6099 6369 6100 6368 6100 6352 6100 6352 6101 6351 6101 6369 6101 6369 6102 6351 6102 6370 6102 6369 6103 6370 6103 6246 6103 6246 6104 6370 6104 6240 6104 6246 6105 6240 6105 6248 6105 6248 6106 6240 6106 6242 6106 6248 6107 6242 6107 6251 6107 6371 6108 6372 6108 6373 6108 6373 6109 6372 6109 6374 6109 6373 6110 6374 6110 6375 6110 6375 6111 6374 6111 6376 6111 6375 6112 6377 6112 6373 6112 6373 6113 6377 6113 6254 6113 6373 6114 6254 6114 6371 6114 6371 6115 6254 6115 6253 6115 6371 6116 6253 6116 6378 6116 6378 6117 6253 6117 6300 6117 6378 6118 6300 6118 6379 6118 6379 6119 6300 6119 6075 6119 6379 6120 6075 6120 6090 6120 6380 6121 6257 6121 6381 6121 6381 6122 6257 6122 6256 6122 6381 6123 6256 6123 6382 6123 6382 6124 6256 6124 6255 6124 6382 6125 6255 6125 6383 6125 6383 6126 6255 6126 6384 6126 6385 6127 6384 6127 6386 6127 6386 6128 6384 6128 6255 6128 6386 6129 6255 6129 6387 6129 6387 6130 6255 6130 6116 6130 6387 6131 6116 6131 6388 6131 6388 6132 6116 6132 6118 6132 6388 6133 6118 6133 6179 6133 5970 6134 6389 6134 6354 6134 6354 6135 6389 6135 6390 6135 6354 6136 6390 6136 6355 6136 6355 6137 6390 6137 6391 6137 6355 6138 6391 6138 6363 6138 6363 6139 6391 6139 6241 6139 6363 6140 6241 6140 6364 6140 6364 6141 6241 6141 6240 6141 6364 6142 6240 6142 6365 6142 6365 6143 6240 6143 6370 6143 6365 6144 6370 6144 6361 6144 6361 6145 6370 6145 6351 6145 6361 6146 6351 6146 6362 6146 6362 6147 6351 6147 6353 6147 6090 6148 6293 6148 6379 6148 6379 6149 6293 6149 6251 6149 6379 6150 6251 6150 6378 6150 6378 6151 6251 6151 6242 6151 6378 6152 6242 6152 6371 6152 6371 6153 6242 6153 6241 6153 6371 6154 6241 6154 6372 6154 6372 6155 6241 6155 6391 6155 6372 6156 6391 6156 6374 6156 6374 6157 6391 6157 6390 6157 6374 6158 6390 6158 6376 6158 6376 6159 6390 6159 6389 6159 5970 6160 6354 6160 5971 6160 5971 6161 6354 6161 6356 6161 5971 6162 6356 6162 5972 6162 5972 6163 6356 6163 6358 6163 5972 6164 6358 6164 5973 6164 5973 6165 6358 6165 6360 6165 5973 6166 6360 6166 5974 6166 5974 6167 6360 6167 6362 6167 5974 6168 6362 6168 5875 6168 5875 6169 6362 6169 6353 6169 5875 6170 6353 6170 6343 6170 6343 6171 6353 6171 6352 6171 6343 6172 6352 6172 6333 6172 6333 6173 6352 6173 6368 6173 6333 6174 6368 6174 6334 6174 6334 6175 6368 6175 6367 6175 6334 6176 6367 6176 6336 6176 6336 6177 6367 6177 6366 6177 6336 6178 6366 6178 6114 6178 6114 6179 6366 6179 6342 6179 6114 6180 6342 6180 6115 6180 6115 6181 6342 6181 6325 6181 6115 6182 6325 6182 6328 6182 6328 6183 6325 6183 6324 6183 6328 6184 6324 6184 6326 6184 5884 6185 6392 6185 5920 6185 5920 6186 6392 6186 6393 6186 5920 6187 6393 6187 5922 6187 5922 6188 6393 6188 6394 6188 5922 6189 6394 6189 5923 6189 5923 6190 6394 6190 6395 6190 5923 6191 6395 6191 5925 6191 5925 6192 6395 6192 6396 6192 5925 6193 6396 6193 5926 6193 5926 6194 6396 6194 6397 6194 5926 6195 6397 6195 5928 6195 5928 6196 6397 6196 6398 6196 5928 6197 6398 6197 5929 6197 5929 6198 6398 6198 6399 6198 5929 6199 6399 6199 5930 6199 5930 6200 6399 6200 6400 6200 5930 6201 6400 6201 5931 6201 5931 6202 6400 6202 6401 6202 5931 6203 6401 6203 5932 6203 5932 6204 6401 6204 6402 6204 5932 6205 6402 6205 5888 6205 5888 6206 6402 6206 6403 6206 5888 6207 6403 6207 5889 6207 5889 6208 6403 6208 6404 6208 5889 6209 6404 6209 5890 6209 5890 6210 6404 6210 6405 6210 5890 6211 6405 6211 5892 6211 5892 6212 6405 6212 6406 6212 5892 6213 6406 6213 5893 6213 5893 6214 6406 6214 6407 6214 5893 6215 6407 6215 5895 6215 5895 6216 6407 6216 6408 6216 5895 6217 6408 6217 5934 6217 5934 6218 6408 6218 6409 6218 5934 6219 6409 6219 5936 6219 5936 6220 6409 6220 6410 6220 5936 6221 6410 6221 5937 6221 5937 6222 6410 6222 6411 6222 5937 6223 6411 6223 5939 6223 5939 6224 6411 6224 6412 6224 5939 6225 6412 6225 5940 6225 5940 6226 6412 6226 6413 6226 5940 6227 6413 6227 5942 6227 5942 6228 6413 6228 6414 6228 5942 6229 6414 6229 5943 6229 5943 6230 6414 6230 6415 6230 5943 6231 6415 6231 5944 6231 5944 6232 6415 6232 6416 6232 5944 6233 6416 6233 5945 6233 5945 6234 6416 6234 6417 6234 5945 6235 6417 6235 5946 6235 5946 6236 6417 6236 6418 6236 5946 6237 6418 6237 5897 6237 5897 6238 6418 6238 6419 6238 5897 6239 6419 6239 5900 6239 5900 6240 6419 6240 6420 6240 5900 6241 6420 6241 5901 6241 5901 6242 6420 6242 6421 6242 5901 6243 6421 6243 5903 6243 5903 6244 6421 6244 6422 6244 5903 6245 6422 6245 5904 6245 5904 6246 6422 6246 6423 6246 5904 6247 6423 6247 5906 6247 5906 6248 6423 6248 6424 6248 5906 6249 6424 6249 5948 6249 5948 6250 6424 6250 6425 6250 5948 6251 6425 6251 5950 6251 5950 6252 6425 6252 6426 6252 5950 6253 6426 6253 5951 6253 5951 6254 6426 6254 6427 6254 5951 6255 6427 6255 5953 6255 5953 6256 6427 6256 6428 6256 5953 6257 6428 6257 5954 6257 5954 6258 6428 6258 6429 6258 5954 6259 6429 6259 5956 6259 5956 6260 6429 6260 6430 6260 5956 6261 6430 6261 5957 6261 5957 6262 6430 6262 6431 6262 5957 6263 6431 6263 5958 6263 5958 6264 6431 6264 6432 6264 5958 6265 6432 6265 5959 6265 5959 6266 6432 6266 6433 6266 5959 6267 6433 6267 5960 6267 5960 6268 6433 6268 6434 6268 5960 6269 6434 6269 5910 6269 5910 6270 6434 6270 6435 6270 5910 6271 6435 6271 5911 6271 5911 6272 6435 6272 6436 6272 5911 6273 6436 6273 5912 6273 5912 6274 6436 6274 6380 6274 5912 6275 6380 6275 5914 6275 5914 6276 6380 6276 6381 6276 5914 6277 6381 6277 5915 6277 5915 6278 6381 6278 6382 6278 5915 6279 6382 6279 5917 6279 5917 6280 6382 6280 6383 6280 5917 6281 6383 6281 5962 6281 5962 6282 6383 6282 6384 6282 5962 6283 6384 6283 5964 6283 5964 6284 6384 6284 6385 6284 5964 6285 6385 6285 5965 6285 6392 6286 6437 6286 6393 6286 6393 6287 6437 6287 6438 6287 6393 6288 6438 6288 6394 6288 6394 6289 6438 6289 6439 6289 6394 6290 6439 6290 6395 6290 6395 6291 6439 6291 6440 6291 6395 6292 6440 6292 6396 6292 6396 6293 6440 6293 6441 6293 6396 6294 6441 6294 6397 6294 6397 6295 6441 6295 6442 6295 6397 6296 6442 6296 6398 6296 6398 6297 6442 6297 6443 6297 6398 6298 6443 6298 6399 6298 6399 6299 6443 6299 6444 6299 6399 6300 6444 6300 6400 6300 6400 6301 6444 6301 6445 6301 6400 6302 6445 6302 6401 6302 6401 6303 6445 6303 6446 6303 6401 6304 6446 6304 6402 6304 6402 6305 6446 6305 6447 6305 6402 6306 6447 6306 6403 6306 6403 6307 6447 6307 6448 6307 6403 6308 6448 6308 6404 6308 6404 6309 6448 6309 6449 6309 6404 6310 6449 6310 6405 6310 6405 6311 6449 6311 6450 6311 6405 6312 6450 6312 6406 6312 6406 6313 6450 6313 6451 6313 6406 6314 6451 6314 6407 6314 6407 6315 6451 6315 6452 6315 6407 6316 6452 6316 6408 6316 6408 6317 6452 6317 6453 6317 6408 6318 6453 6318 6409 6318 6409 6319 6453 6319 6454 6319 6409 6320 6454 6320 6410 6320 6410 6321 6454 6321 6455 6321 6410 6322 6455 6322 6411 6322 6411 6323 6455 6323 6456 6323 6411 6324 6456 6324 6412 6324 6412 6325 6456 6325 6457 6325 6412 6326 6457 6326 6413 6326 6413 6327 6457 6327 6458 6327 6413 6328 6458 6328 6414 6328 6414 6329 6458 6329 6459 6329 6414 6330 6459 6330 6415 6330 6415 6331 6459 6331 6460 6331 6415 6332 6460 6332 6416 6332 6416 6333 6460 6333 6461 6333 6416 6334 6461 6334 6417 6334 6417 6335 6461 6335 6462 6335 6417 6336 6462 6336 6418 6336 6418 6337 6462 6337 6463 6337 6418 6338 6463 6338 6419 6338 6419 6339 6463 6339 6464 6339 6419 6340 6464 6340 6420 6340 6420 6341 6464 6341 6465 6341 6420 6342 6465 6342 6421 6342 6466 6343 6467 6343 6468 6343 6469 6344 6470 6344 6471 6344 6472 6345 6473 6345 6474 6345 6474 6346 6473 6346 6469 6346 6474 6347 6469 6347 6475 6347 6475 6348 6469 6348 6471 6348 6468 6349 6476 6349 6466 6349 6466 6350 6476 6350 6477 6350 6466 6351 6477 6351 6470 6351 6470 6352 6477 6352 6478 6352 6470 6353 6478 6353 6471 6353 6479 6354 6480 6354 6481 6354 6481 6355 6480 6355 6482 6355 6481 6356 6482 6356 6219 6356 6483 6357 6110 6357 6484 6357 6484 6358 6110 6358 6109 6358 6484 6359 6109 6359 6485 6359 6486 6360 6487 6360 6488 6360 6488 6361 6487 6361 6489 6361 6488 6362 6489 6362 6490 6362 6479 6363 6481 6363 6491 6363 6491 6364 6481 6364 6219 6364 6491 6365 6219 6365 6171 6365 6171 6366 6219 6366 6218 6366 6171 6367 6218 6367 6172 6367 6172 6368 6218 6368 6184 6368 6172 6369 6184 6369 6180 6369 6180 6370 6184 6370 6183 6370 6180 6371 6183 6371 6181 6371 6181 6372 6183 6372 6096 6372 6181 6373 6096 6373 6095 6373 6487 6374 6485 6374 6489 6374 6489 6375 6485 6375 6109 6375 6489 6376 6109 6376 6490 6376 6490 6377 6109 6377 6111 6377 6490 6378 6111 6378 6492 6378 6492 6379 6111 6379 6493 6379 6492 6380 6493 6380 6494 6380 6494 6381 6493 6381 6200 6381 6494 6382 6200 6382 6208 6382 6208 6383 6200 6383 6202 6383 6208 6384 6202 6384 6209 6384 6209 6385 6202 6385 6204 6385 6209 6386 6204 6386 6210 6386 6210 6387 6204 6387 6206 6387 6210 6388 6206 6388 6101 6388 6101 6389 6206 6389 6103 6389 6480 6390 6486 6390 6482 6390 6482 6391 6486 6391 6488 6391 6482 6392 6488 6392 6219 6392 6219 6393 6488 6393 6490 6393 6219 6394 6490 6394 6217 6394 6217 6395 6490 6395 6492 6395 6217 6396 6492 6396 6215 6396 6215 6397 6492 6397 6494 6397 6215 6398 6494 6398 6213 6398 6213 6399 6494 6399 6208 6399 6213 6400 6208 6400 6211 6400 6211 6401 6208 6401 6186 6401 6211 6402 6186 6402 6085 6402 6085 6403 6186 6403 6073 6403 6495 6404 6467 6404 6177 6404 6177 6405 6467 6405 6466 6405 6177 6406 6466 6406 6175 6406 6175 6407 6466 6407 6470 6407 6175 6408 6470 6408 6173 6408 6173 6409 6470 6409 6469 6409 6173 6410 6469 6410 6171 6410 6171 6411 6469 6411 6473 6411 6171 6412 6473 6412 6491 6412 6491 6413 6473 6413 6472 6413 6491 6414 6472 6414 6479 6414 6496 6415 6497 6415 6498 6415 6498 6416 6497 6416 6499 6416 6498 6417 6499 6417 6500 6417 6500 6418 6499 6418 6501 6418 6502 6419 6501 6419 6503 6419 6503 6420 6501 6420 6499 6420 6503 6421 6499 6421 6504 6421 6504 6422 6499 6422 6497 6422 6504 6423 6497 6423 6505 6423 6505 6424 6497 6424 6496 6424 6505 6425 6496 6425 6506 6425 6108 6426 6107 6426 6507 6426 6507 6427 6107 6427 6508 6427 6507 6428 6508 6428 6509 6428 6508 6429 6510 6429 6509 6429 6509 6430 6510 6430 6511 6430 6509 6431 6511 6431 6512 6431 6513 6432 6514 6432 6515 6432 6511 6433 6516 6433 6512 6433 6512 6434 6516 6434 6517 6434 6512 6435 6517 6435 6515 6435 6515 6436 6517 6436 6518 6436 6515 6437 6518 6437 6513 6437 6513 6438 6519 6438 6514 6438 6514 6439 6519 6439 6520 6439 6514 6440 6520 6440 6307 6440 6307 6441 6520 6441 6521 6441 6307 6442 6521 6442 6308 6442 6522 6443 6523 6443 6524 6443 6524 6444 6523 6444 6525 6444 6524 6445 6525 6445 6526 6445 6527 6446 6528 6446 6529 6446 6529 6447 6528 6447 6530 6447 6529 6448 6530 6448 6531 6448 6531 6449 6530 6449 6532 6449 6531 6450 6532 6450 6533 6450 6533 6451 6532 6451 6534 6451 6533 6452 6534 6452 6535 6452 6535 6453 6534 6453 6536 6453 6535 6454 6536 6454 6537 6454 6537 6455 6536 6455 6538 6455 6537 6456 6538 6456 6539 6456 6539 6457 6538 6457 6540 6457 6539 6458 6540 6458 6541 6458 6541 6459 6540 6459 6542 6459 6541 6460 6542 6460 6543 6460 6543 6461 6542 6461 6544 6461 6543 6462 6544 6462 6545 6462 6545 6463 6544 6463 6546 6463 6545 6464 6546 6464 6547 6464 6547 6465 6546 6465 6548 6465 6547 6466 6548 6466 6549 6466 6139 6467 6126 6467 6133 6467 6133 6468 6126 6468 6128 6468 6133 6469 6128 6469 6550 6469 6550 6470 6128 6470 6551 6470 6550 6471 6551 6471 6552 6471 6552 6472 6551 6472 6553 6472 6552 6473 6553 6473 6554 6473 6130 6474 6131 6474 6128 6474 6128 6475 6131 6475 6125 6475 6128 6476 6125 6476 6551 6476 6551 6477 6125 6477 6185 6477 6551 6478 6185 6478 6553 6478 6545 6479 6554 6479 6543 6479 6543 6480 6554 6480 6553 6480 6543 6481 6553 6481 6541 6481 6541 6482 6553 6482 6185 6482 6541 6483 6185 6483 6539 6483 6539 6484 6185 6484 6119 6484 6539 6485 6119 6485 6537 6485 6537 6486 6119 6486 6121 6486 6537 6487 6121 6487 6535 6487 6535 6488 6121 6488 6232 6488 6535 6489 6232 6489 6533 6489 6533 6490 6232 6490 6264 6490 6533 6491 6264 6491 6531 6491 6531 6492 6264 6492 6270 6492 6531 6493 6270 6493 6529 6493 6529 6494 6270 6494 6292 6494 6529 6495 6292 6495 6527 6495 6527 6496 6292 6496 6299 6496 6090 6497 6089 6497 6293 6497 6293 6498 6089 6498 6068 6498 6293 6499 6068 6499 6294 6499 6294 6500 6068 6500 6067 6500 6294 6501 6067 6501 6295 6501 6295 6502 6067 6502 6070 6502 6295 6503 6070 6503 6296 6503 6296 6504 6070 6504 6092 6504 6296 6505 6092 6505 6297 6505 6297 6506 6092 6506 6091 6506 6297 6507 6091 6507 6298 6507 6298 6508 6091 6508 6088 6508 6298 6509 6088 6509 6299 6509 6299 6510 6088 6510 6087 6510 6299 6511 6087 6511 6527 6511 6527 6512 6087 6512 6069 6512 6527 6513 6069 6513 6528 6513 6528 6514 6069 6514 6271 6514 6528 6515 6271 6515 6530 6515 6530 6516 6271 6516 6273 6516 6530 6517 6273 6517 6532 6517 6532 6518 6273 6518 6275 6518 6532 6519 6275 6519 6534 6519 6534 6520 6275 6520 6277 6520 6534 6521 6277 6521 6536 6521 6536 6522 6277 6522 6279 6522 6536 6523 6279 6523 6538 6523 6538 6524 6279 6524 6281 6524 6538 6525 6281 6525 6540 6525 6540 6526 6281 6526 6283 6526 6540 6527 6283 6527 6542 6527 6542 6528 6283 6528 6285 6528 6542 6529 6285 6529 6544 6529 6544 6530 6285 6530 6287 6530 6544 6531 6287 6531 6546 6531 6549 6532 6106 6532 6547 6532 6547 6533 6106 6533 6108 6533 6547 6534 6108 6534 6545 6534 6545 6535 6108 6535 6507 6535 6545 6536 6507 6536 6554 6536 6554 6537 6507 6537 6509 6537 6554 6538 6509 6538 6552 6538 6552 6539 6509 6539 6512 6539 6552 6540 6512 6540 6550 6540 6550 6541 6512 6541 6515 6541 6550 6542 6515 6542 6133 6542 6133 6543 6515 6543 6514 6543 6133 6544 6514 6544 6135 6544 6135 6545 6514 6545 6307 6545 6135 6546 6307 6546 6142 6546 6142 6547 6307 6547 6306 6547 6142 6548 6306 6548 6320 6548 6320 6549 6306 6549 6311 6549 6320 6550 6311 6550 6322 6550 6322 6551 6311 6551 6314 6551 6322 6552 6314 6552 6324 6552 6324 6553 6314 6553 6316 6553 6324 6554 6316 6554 6326 6554 6326 6555 6316 6555 6315 6555 6326 6556 6315 6556 6350 6556 6504 6557 6526 6557 6503 6557 6503 6558 6526 6558 6525 6558 6503 6559 6525 6559 6502 6559 6502 6560 6525 6560 6555 6560 6502 6561 6555 6561 6501 6561 6501 6562 6555 6562 6556 6562 6501 6563 6556 6563 6500 6563 6500 6564 6556 6564 6557 6564 6500 6565 6557 6565 6498 6565 6498 6566 6557 6566 6558 6566 6498 6567 6558 6567 6496 6567 6496 6568 6558 6568 6559 6568 6496 6569 6559 6569 6506 6569 6506 6570 6559 6570 6560 6570 6102 6571 6104 6571 6561 6571 6561 6572 6104 6572 6207 6572 6561 6573 6207 6573 6562 6573 6562 6574 6207 6574 6205 6574 6562 6575 6205 6575 6563 6575 6563 6576 6205 6576 6203 6576 6563 6577 6203 6577 6564 6577 6564 6578 6203 6578 6201 6578 6564 6579 6201 6579 6565 6579 6565 6580 6201 6580 6200 6580 6565 6581 6200 6581 6522 6581 6522 6582 6200 6582 6493 6582 6522 6583 6493 6583 6523 6583 6523 6584 6493 6584 6111 6584 6523 6585 6111 6585 6525 6585 6525 6586 6111 6586 6110 6586 6525 6587 6110 6587 6555 6587 6555 6588 6110 6588 6483 6588 6555 6589 6483 6589 6556 6589 6549 6590 6566 6590 6106 6590 6106 6591 6566 6591 6567 6591 6106 6592 6567 6592 6107 6592 6107 6593 6567 6593 6568 6593 6107 6594 6568 6594 6508 6594 6508 6595 6568 6595 6569 6595 6508 6596 6569 6596 6510 6596 6510 6597 6569 6597 6570 6597 6510 6598 6570 6598 6511 6598 6511 6599 6570 6599 6571 6599 6511 6600 6571 6600 6516 6600 6516 6601 6571 6601 6572 6601 6516 6602 6572 6602 6517 6602 6517 6603 6572 6603 6573 6603 6517 6604 6573 6604 6518 6604 6518 6605 6573 6605 6574 6605 6518 6606 6574 6606 6513 6606 6513 6607 6574 6607 6575 6607 6513 6608 6575 6608 6519 6608 6519 6609 6575 6609 6576 6609 6519 6610 6576 6610 6520 6610 6520 6611 6576 6611 6577 6611 6520 6612 6577 6612 6521 6612 6521 6613 6577 6613 6578 6613 6521 6614 6578 6614 6308 6614 6308 6615 6578 6615 6579 6615 6308 6616 6579 6616 6309 6616 6309 6617 6579 6617 6580 6617 6309 6618 6580 6618 6310 6618 6310 6619 6580 6619 6581 6619 6310 6620 6581 6620 6312 6620 6312 6621 6581 6621 6582 6621 6312 6622 6582 6622 6313 6622 6313 6623 6582 6623 6583 6623 6313 6624 6583 6624 6318 6624 6318 6625 6583 6625 6584 6625 6318 6626 6584 6626 6317 6626 6317 6627 6584 6627 6585 6627 6317 6628 6585 6628 6315 6628 6315 6629 6585 6629 6586 6629 6315 6630 6586 6630 6350 6630 6350 6631 6586 6631 6587 6631 6350 6632 6587 6632 6349 6632 6349 6633 6587 6633 6588 6633 6349 6634 6588 6634 6348 6634 6348 6635 6588 6635 6589 6635 6348 6636 6589 6636 6347 6636 6347 6637 6589 6637 6590 6637 6347 6638 6590 6638 6346 6638 6078 6639 6077 6639 6179 6639 6179 6640 6077 6640 6105 6640 6179 6641 6105 6641 6388 6641 6388 6642 6105 6642 6252 6642 6388 6643 6252 6643 6387 6643 6387 6644 6252 6644 6254 6644 6387 6645 6254 6645 6386 6645 6386 6646 6254 6646 6377 6646 6386 6647 6377 6647 6385 6647 6385 6648 6377 6648 6375 6648 6385 6649 6375 6649 5965 6649 5965 6650 6375 6650 6376 6650 5965 6651 6376 6651 6112 6651 6112 6652 6376 6652 6389 6652 6112 6653 6389 6653 5968 6653 5968 6654 6389 6654 5970 6654 6071 6655 6102 6655 6188 6655 6188 6656 6102 6656 6561 6656 6188 6657 6561 6657 6190 6657 6190 6658 6561 6658 6562 6658 6190 6659 6562 6659 6192 6659 6192 6660 6562 6660 6563 6660 6192 6661 6563 6661 6194 6661 6194 6662 6563 6662 6564 6662 6194 6663 6564 6663 6196 6663 6196 6664 6564 6664 6565 6664 6196 6665 6565 6665 6198 6665 6198 6666 6565 6666 6522 6666 6198 6667 6522 6667 6199 6667 6199 6668 6522 6668 6524 6668 6199 6669 6524 6669 6286 6669 6286 6670 6524 6670 6526 6670 6286 6671 6526 6671 6287 6671 6287 6672 6526 6672 6504 6672 6287 6673 6504 6673 6546 6673 6546 6674 6504 6674 6505 6674 6546 6675 6505 6675 6548 6675 6548 6676 6505 6676 6506 6676 6548 6677 6506 6677 6549 6677 6549 6678 6506 6678 6560 6678 6549 6679 6560 6679 6566 6679 6079 6680 6179 6680 6178 6680 6178 6681 6179 6681 6118 6681 6178 6682 6118 6682 6177 6682 6177 6683 6118 6683 6117 6683 6177 6404 6117 6404 6495 6404 6495 6684 6117 6684 6257 6684 6495 6684 6257 6684 6467 6684 6467 6685 6257 6685 6380 6685 6467 6686 6380 6686 6468 6686 6468 6687 6380 6687 6436 6687 6468 6688 6436 6688 6476 6688 6476 6689 6436 6689 6435 6689 6476 6690 6435 6690 6477 6690 6477 6691 6435 6691 6434 6691 6477 6692 6434 6692 6478 6692 6478 6693 6434 6693 6433 6693 6478 6694 6433 6694 6471 6694 6471 6695 6433 6695 6432 6695 6471 6696 6432 6696 6475 6696 6475 6697 6432 6697 6431 6697 6475 6698 6431 6698 6474 6698 6474 6699 6431 6699 6430 6699 6474 6700 6430 6700 6472 6700 6472 6701 6430 6701 6429 6701 6472 6702 6429 6702 6479 6702 6479 6703 6429 6703 6428 6703 6479 6704 6428 6704 6480 6704 6480 6705 6428 6705 6427 6705 6480 6706 6427 6706 6486 6706 6486 6707 6427 6707 6426 6707 6486 6708 6426 6708 6487 6708 6487 6709 6426 6709 6425 6709 6487 6710 6425 6710 6485 6710 6485 6711 6425 6711 6424 6711 6485 6712 6424 6712 6484 6712 6484 6713 6424 6713 6423 6713 6484 6714 6423 6714 6483 6714 6483 6715 6423 6715 6422 6715 6483 6716 6422 6716 6556 6716 6556 6717 6422 6717 6421 6717 6556 6718 6421 6718 6557 6718 6557 6719 6421 6719 6465 6719 6557 6720 6465 6720 6558 6720 6558 6721 6465 6721 6464 6721 6558 6722 6464 6722 6559 6722 6559 6723 6464 6723 6463 6723 6559 6724 6463 6724 6560 6724 6560 6725 6463 6725 6462 6725 6560 6726 6462 6726 6566 6726 6566 6727 6462 6727 6461 6727 6566 6728 6461 6728 6567 6728 6567 6729 6461 6729 6460 6729 6567 6730 6460 6730 6568 6730 6568 6731 6460 6731 6459 6731 6568 6732 6459 6732 6569 6732 6569 6733 6459 6733 6458 6733 6569 6734 6458 6734 6570 6734 6570 6735 6458 6735 6457 6735 6570 6736 6457 6736 6571 6736 6571 6737 6457 6737 6456 6737 6571 6738 6456 6738 6572 6738 6572 6739 6456 6739 6455 6739 6572 6740 6455 6740 6573 6740 6573 6741 6455 6741 6454 6741 6573 6742 6454 6742 6574 6742 6574 6743 6454 6743 6453 6743 6574 6744 6453 6744 6575 6744 6575 6745 6453 6745 6452 6745 6575 6746 6452 6746 6576 6746 6576 6747 6452 6747 6451 6747 6576 6748 6451 6748 6577 6748 6577 6749 6451 6749 6450 6749 6577 6750 6450 6750 6578 6750 6578 6751 6450 6751 6449 6751 6578 6752 6449 6752 6579 6752 6579 6753 6449 6753 6448 6753 6579 6754 6448 6754 6580 6754 6580 6755 6448 6755 6447 6755 6580 6756 6447 6756 6581 6756 6581 6757 6447 6757 6446 6757 6581 6758 6446 6758 6582 6758 6582 6759 6446 6759 6445 6759 6582 6760 6445 6760 6583 6760 6583 6761 6445 6761 6444 6761 6583 6762 6444 6762 6584 6762 6584 6763 6444 6763 6443 6763 6584 6764 6443 6764 6585 6764 6585 6765 6443 6765 6442 6765 6585 6766 6442 6766 6586 6766 6586 6767 6442 6767 6441 6767 6586 6768 6441 6768 6587 6768 6587 6769 6441 6769 6440 6769 6587 6770 6440 6770 6588 6770 6588 6771 6440 6771 6439 6771 6588 6772 6439 6772 6589 6772 6589 6773 6439 6773 6438 6773 6589 6774 6438 6774 6590 6774 6590 6775 6438 6775 6437 6775 6590 6776 6437 6776 6346 6776 6346 6777 6437 6777 6392 6777 6346 6778 6392 6778 6305 6778 6305 6779 6392 6779 5884 6779 6305 6780 5884 6780 5882 6780 6145 6781 6144 6781 5994 6781 6152 6782 6151 6782 5997 6782 6162 6783 6161 6783 6004 6783 5985 6784 6124 6784 6123 6784 5985 6785 6123 6785 6013 6785 6166 6786 6165 6786 5978 6786 5978 6787 6165 6787 6164 6787 5978 6788 6164 6788 5985 6788 5985 6789 6164 6789 6163 6789 5985 6790 6163 6790 6124 6790 6170 6791 6169 6791 6002 6791 6002 6792 6169 6792 6168 6792 6002 6793 6168 6793 5978 6793 5978 6794 6168 6794 6167 6794 5978 6795 6167 6795 6166 6795 6004 6796 6161 6796 6002 6796 6002 6797 6161 6797 6159 6797 6002 6798 6159 6798 6158 6798 6158 6799 6157 6799 6002 6799 6002 6800 6157 6800 6156 6800 6002 6801 6156 6801 6170 6801 5997 6802 6151 6802 6000 6802 6151 6803 6150 6803 6000 6803 6000 6804 6150 6804 6148 6804 6000 6805 6148 6805 6004 6805 6004 6806 6148 6806 6147 6806 6004 6807 6147 6807 6162 6807 5994 6808 6144 6808 5996 6808 5996 6809 6144 6809 6143 6809 5996 6810 6143 6810 6141 6810 6141 6811 6140 6811 5996 6811 5996 6812 6140 6812 6155 6812 5996 6813 6155 6813 5997 6813 5997 6814 6155 6814 6154 6814 5997 6815 6154 6815 6152 6815 5980 6816 6138 6816 6137 6816 6137 6817 6132 6817 5980 6817 5980 6818 6132 6818 6134 6818 5980 6819 6134 6819 5992 6819 5992 6820 6134 6820 6136 6820 5992 6821 6136 6821 5994 6821 5994 6822 6136 6822 6146 6822 5994 6823 6146 6823 6145 6823 5986 6824 6127 6824 6126 6824 5986 6825 6126 6825 5980 6825 5980 6826 6126 6826 6139 6826 5980 6827 6139 6827 6138 6827 6123 6828 6131 6828 6013 6828 6013 6829 6131 6829 6130 6829 6013 6830 6130 6830 5986 6830 5986 6831 6130 6831 6129 6831 5986 6832 6129 6832 6127 6832

+
+
+
+ + + + -69.36405 95.68708 1.011006 -67.37509 95.67494 0.9990948 -68.12909 94.85231 1.009203 -66.94941 94.25352 0.9997467 -68.2493 93.40352 1.011849 -67.53302 92.50733 0.9976487 -69.56673 92.76013 1.010973 -69.13217 91.72969 0.9997467 -70.64134 91.96713 0.9989815 -70.78273 93.57973 1.011704 -71.67888 93.0278 0.9997467 -71.97361 94.84519 0.9976484 -70.68151 95.04264 1.011704 -70.91904 96.27692 0.9997467 -69.15045 96.78836 0.997435 -71.57837 96.00096 3.983448 -70.69666 95.43358 4.02765 -70.5884 96.75322 4 -69.91908 95.89669 4.033628 -68.97166 96.97979 4 -68.34201 91.69381 4 -68.7301 92.66291 4.031102 -69.95876 91.46723 4 -69.63978 92.43544 4.022938 -71.21851 92.10493 4 -70.8844 93.21344 4.03357 -72.01394 93.06395 4 -72.18516 94.73619 4 -68.75937 95.82026 4.037357 -67.49817 96.17077 4 -66.71302 94.73943 4 -67.8174 94.81184 4.034296 -67.06307 92.78463 4 -67.90235 93.43326 4.033075 -67.94599 94.10588 4.284836 -68.0679 93.61952 15.74694 -67.98508 94.56383 15.75091 -68.03321 94.7365 4.287179 -68.46348 95.36476 15.75078 -68.44229 95.36722 4.288241 -69.28939 95.74868 4.286399 -69.54108 95.75778 15.76327 -70.18275 95.57546 4.293378 -70.58523 95.24715 15.75046 -70.90172 94.80565 4.288959 -70.97296 94.39807 15.74978 -70.94947 93.8757 4.283035 -70.78117 93.45838 15.74632 -70.67675 93.30422 4.287581 -70.06788 92.82987 15.75075 -70.10607 92.8156 4.219274 -69.20812 92.70252 4.256752 -68.92133 92.78751 15.76372 -68.26853 93.24315 4.295463 -68.20778 93.948 16.00045 -68.79689 93.15196 16.00055 -69.93786 92.99526 16.00514 -70.7794 94.29349 16.00514 -69.80477 95.49501 16.00514 -68.50437 95.07781 16.00196 -66.98085 93.0017 1.247459 -68.10715 91.77489 1.244446 -69.72666 91.46734 1.247463 -70.97754 91.90454 1.247459 -72.05968 93.17051 1.244448 -72.16977 94.81526 1.247461 -71.58497 96.00436 1.247458 -70.51459 96.78548 1.24747 -68.85797 96.9569 1.244446 -67.44183 96.11318 1.24746 -66.69411 94.62502 1.244448 -70.03863 95.33398 1.124213 -68.79026 95.27539 1.124203 -68.21678 94.16491 1.124201 -68.89385 93.11195 1.124125 -70.14017 93.17166 1.124199 -70.71363 94.28211 1.1242 -69.44568 95.65157 2.265674 -69.4652 94.22351 3.021688 -68.79086 95.27567 2.323015 -68.17516 94.83643 2.265522 -68.26593 93.43083 2.235242 -70.68625 94.98303 2.228476 -70.73219 93.54298 2.241968 -69.53004 92.78203 2.199059 -71.15665 94.48484 4.064923 11.96346 -15.92885 16.5 11.96346 -15.92074 18.67826 12.67732 -12.83471 16.5 12.40023 -14.10259 18.90073 12.67165 -12.84545 18.68457 12.27255 -14.59442 18.8995 14.25419 -12.32411 18.9056 12.58736 -13.68027 18.9 13.02987 -13.01236 18.89656 15.71386 -11.90585 16.5 15.70186 -11.90631 18.68485 14.9366 -12.25073 18.9 14.94354 -12.25036 18.9034 16.46882 -12.61712 18.88777 18.03654 -14.07115 16.5 18.03458 -14.06735 18.66958 17.73808 -15.33428 18.9139 17.6502 -15.78281 18.89862 17.32427 -13.52777 18.90465 17.5537 -13.97966 18.9 17.75473 -14.63902 18.89785 17.32268 -17.16529 16.5 17.32407 -17.16259 18.69053 15.81556 -17.6667 18.89476 17.30466 -16.51809 18.9004 16.84857 -17.036 18.9 16.4855 -17.31426 18.9 14.28614 -18.09415 16.5 14.2892 -18.094 18.69051 13.71785 -17.43341 18.90212 12.92358 -16.8039 18.90122 15.0634 -17.74927 18.9 14.60679 -17.72174 18.9 14.16106 -17.61891 18.9 12.8744 -16.74374 18.91364 12.25317 -15.1363 18.90321 12.25304 -15.12935 18.9 12.92023 -16.79919 18.9 16.3051 -14.09566 18.89687 13.48822 -15.36016 18.89851 13.74744 -14.13428 18.89939 12.58736 -13.68027 18.9 16.3726 -15.71597 18.89865 17.7304 -15.32779 18.9 14.78358 -13.46254 18.89858 17.5537 -13.97966 18.9 17.41264 -16.31973 18.9 14.48707 -16.4612 18.89867 15.0634 -17.74927 18.9 15.54393 -16.40781 18.89984 14.16106 -17.61891 18.9 16.4855 -17.31426 18.9 17.16049 -16.7014 18.9 13.84347 -15.52679 18.6265 13.85483 -14.48163 18.62896 14.59613 -13.79917 18.62637 15.44581 -13.84294 18.62883 16.15653 -14.47321 18.6265 16.18519 -15.36841 18.62884 15.80345 -15.95554 18.62701 14.8536 -16.26943 18.62625 14.55552 -16.19059 16.7735 15.45053 -16.15647 16.77116 16.00947 -15.73454 16.77299 16.25606 -14.76501 16.77375 15.44448 -13.80941 16.7735 14.54947 -13.84353 16.77116 13.99053 -14.26547 16.77299 13.74394 -15.23497 16.77375 15.60636 -13.57329 16.50243 14.19003 -13.68158 16.50211 13.45212 -14.89186 16.50237 13.92907 -16.09418 16.50067 15.12772 -16.54812 16.50232 16.21129 -15.92266 16.50088 16.528 -14.72736 16.50231 -21.85709 -19.51332 16.5 -22.79273 -19.48529 21.5 -23.68442 -19.71229 16.5 -24.49277 -20.1843 21.5 -24.75081 -20.50107 16.5 -25.39684 -21.61542 16.5 -25.43302 -21.74398 21.5 -25.408 -23.43656 16.5 -25.35762 -23.58057 21.5 -24.49893 -24.75081 16.5 -24.42798 -24.81187 21.5 -23.38458 -25.39684 16.5 -23.25602 -25.43302 21.5 -21.56344 -25.408 16.5 -21.41943 -25.35762 21.5 -19.91332 -24.12564 16.5 -19.83539 -23.99448 21.5 -19.47532 -22.34046 16.5 -19.48529 -22.20727 21.5 -20.0877 -20.62532 16.5 -19.89758 -20.98697 21.5 -21.00552 -19.83539 21.5 -22.41189 -24.15316 16.5 -23.48549 -23.77364 16.5 -23.16406 -21.01232 16.5 -21.80975 -20.99525 16.5 -20.94313 -22.0201 16.5 -21.08942 -23.36659 16.5 -23.98357 -21.82681 16.5 -24.05687 -22.9799 16.5 -22.70328 -20.85702 21.5 -23.96763 -21.73398 21.5 -23.96413 -23.27268 21.5 -22.89277 -24.08111 21.5 -21.94545 -24.01189 21.5 -21.03238 -23.26603 21.5 -20.97566 -21.92508 21.5 -21.57076 -21.18476 21.5 -13.53215 -12.32698 7 -14.10965 -12.10799 4 -15.48346 -11.98904 7 -15.83481 -12.06696 4 -17.23088 -12.92087 7 -17.29078 -13.02293 4 -17.95566 -14.35151 4 -18.03751 -14.72951 7 -17.94714 -15.60827 4 -17.56316 -16.65222 7 -17.47893 -16.73534 4 -16.54853 -17.58025 4 -16.24014 -17.76017 7 -15.4022 -17.99912 4 -15.0453 -18.00891 7 -14.15043 -17.88684 4 -13.56508 -17.69084 7 -13.06588 -17.32715 4 -12.50582 -16.68364 7 -12.08796 -15.90534 4 -11.96249 -15.27048 7 -12.05286 -14.39174 4 -12.32603 -13.58355 7 -12.64934 -13.05732 4 -15.65176 -16.48883 4 -16.53716 -15.59439 4 -14.40561 -16.53716 4 -13.60082 -15.79445 4 -13.37582 -14.94123 4 -13.87297 -13.79753 4 -15.05877 -13.37582 4 -16.3425 -13.99465 4 -13.95304 -13.72719 7 -15.15135 -13.38182 7 -16.40824 -14.08901 7 -16.49553 -15.6925 7 -15.56574 -16.52359 7 -14.49237 -16.54393 7 -13.64049 -15.89058 7 -13.38182 -14.84865 7 13.53215 12.32698 7 14.10965 12.10799 4 15.48346 11.98904 7 15.83481 12.06696 4 17.23088 12.92087 7 17.29078 13.02293 4 17.95566 14.35151 4 18.03751 14.72951 7 17.94714 15.60827 4 17.56316 16.65222 7 17.47893 16.73534 4 16.54853 17.58025 4 16.24014 17.76017 7 15.4022 17.99912 4 15.0453 18.00891 7 14.15043 17.88684 4 13.56508 17.69084 7 13.06588 17.32715 4 12.50582 16.68364 7 12.08796 15.90534 4 11.96249 15.27048 7 12.05286 14.39174 4 12.32603 13.58355 7 12.64934 13.05732 4 15.65176 16.48883 4 16.53716 15.59439 4 14.40561 16.53716 4 13.60082 15.79445 4 13.37582 14.94123 4 13.87297 13.79753 4 15.05877 13.37582 4 16.3425 13.99465 4 13.95304 13.72719 7 15.15135 13.38182 7 16.40824 14.08901 7 16.49553 15.6925 7 15.56574 16.52359 7 14.49237 16.54393 7 13.64049 15.89058 7 13.38182 14.84865 7 15.92885 11.96346 16.5 15.92074 11.96346 18.67826 12.83471 12.67732 16.5 14.10259 12.40023 18.90073 12.84545 12.67165 18.68457 14.59442 12.27255 18.8995 12.32411 14.25419 18.9056 13.68027 12.58736 18.9 13.01236 13.02987 18.89656 11.90585 15.71386 16.5 11.90631 15.70186 18.68485 12.25073 14.9366 18.9 12.25036 14.94354 18.9034 12.61712 16.46882 18.88777 14.07115 18.03654 16.5 14.06735 18.03458 18.66958 15.33428 17.73808 18.9139 15.78281 17.6502 18.89862 13.52777 17.32427 18.90465 13.97966 17.5537 18.9 14.63902 17.75473 18.89785 17.16529 17.32268 16.5 17.16259 17.32407 18.69053 17.6667 15.81556 18.89476 16.51809 17.30466 18.9004 17.036 16.84857 18.9 17.31426 16.4855 18.9 18.09415 14.28614 16.5 18.094 14.2892 18.69051 17.43341 13.71785 18.90212 16.8039 12.92358 18.90122 17.74927 15.0634 18.9 17.72174 14.60679 18.9 17.61891 14.16106 18.9 16.74374 12.8744 18.91364 15.1363 12.25317 18.90321 15.12935 12.25304 18.9 16.79919 12.92023 18.9 14.09566 16.3051 18.89687 15.36016 13.48822 18.89851 14.13428 13.74744 18.89939 13.68027 12.58736 18.9 15.71597 16.3726 18.89865 15.32779 17.7304 18.9 13.46254 14.78358 18.89858 13.97966 17.5537 18.9 16.31973 17.41264 18.9 16.4612 14.48707 18.89867 17.74927 15.0634 18.9 16.40781 15.54393 18.89984 17.61891 14.16106 18.9 17.31426 16.4855 18.9 16.7014 17.16049 18.9 15.52679 13.84347 18.6265 14.48163 13.85483 18.62896 13.79917 14.59613 18.62637 13.84294 15.44581 18.62883 14.47321 16.15653 18.6265 15.36841 16.18519 18.62884 15.95554 15.80345 18.62701 16.26943 14.8536 18.62625 16.19059 14.55552 16.7735 16.15647 15.45053 16.77116 15.73454 16.00947 16.77299 14.76501 16.25606 16.77375 13.80941 15.44448 16.7735 13.84353 14.54947 16.77116 14.26547 13.99053 16.77299 15.23497 13.74394 16.77375 13.57329 15.60636 16.50243 13.68158 14.19003 16.50211 14.89186 13.45212 16.50237 16.09418 13.92907 16.50067 16.54812 15.12772 16.50232 15.92266 16.21129 16.50088 14.72736 16.528 16.50231 -15.75473 -12.06665 8.5 -16.62451 -12.41261 13.5 -16.92697 -12.68728 8.5 -17.85714 -13.91817 8.5 -17.90759 -14.06215 13.5 -17.88409 -16.0078 8.5 -17.89723 -15.88331 13.5 -17.25168 -16.99795 13.5 -16.76195 -17.46368 8.5 -15.93785 -17.90759 13.5 -15.03939 -18.05484 8.5 -13.84947 -17.83018 13.5 -13.50391 -17.6122 8.5 -12.53632 -16.76195 8.5 -12.64141 -16.87054 13.5 -11.97373 -15.4187 13.5 -11.98542 -15.29406 8.5 -12.16769 -13.98024 8.5 -12.20077 -13.89267 13.5 -12.837 -12.87971 8.5 -13.12426 -12.58852 13.5 -14.18694 -12.08228 8.5 -14.83913 -11.97539 13.5 -14.50274 -16.55142 8.5 -15.85078 -16.42017 8.5 -15.49726 -13.44859 8.5 -14.34343 -13.509 8.5 -16.28457 -14.02881 8.5 -13.48763 -15.67339 8.5 -13.51983 -14.31936 8.5 -16.65208 -15.10657 8.5 -15.41776 -13.39807 13.5 -16.32554 -14.08551 13.5 -16.64061 -15.22162 13.5 -15.74958 -16.47609 13.5 -14.21101 -16.45541 13.5 -13.41461 -15.37509 13.5 -13.56459 -14.22945 13.5 -14.25195 -13.5739 13.5 -15.92885 -11.96346 16.5 -15.92074 -11.96346 18.67826 -12.83471 -12.67732 16.5 -14.10259 -12.40023 18.90073 -12.84545 -12.67165 18.68457 -14.59442 -12.27255 18.8995 -12.32411 -14.25419 18.9056 -13.68027 -12.58736 18.9 -13.01236 -13.02987 18.89656 -11.90585 -15.71386 16.5 -11.90631 -15.70186 18.68485 -12.25073 -14.9366 18.9 -12.25036 -14.94354 18.9034 -12.61712 -16.46882 18.88777 -14.07115 -18.03654 16.5 -14.06735 -18.03458 18.66958 -15.33428 -17.73808 18.9139 -15.78281 -17.6502 18.89862 -13.52777 -17.32427 18.90465 -13.97966 -17.5537 18.9 -14.63902 -17.75473 18.89785 -17.16529 -17.32268 16.5 -17.16259 -17.32407 18.69053 -17.6667 -15.81556 18.89476 -16.51809 -17.30466 18.9004 -17.036 -16.84857 18.9 -17.31426 -16.4855 18.9 -18.09415 -14.28614 16.5 -18.094 -14.2892 18.69051 -17.43341 -13.71785 18.90212 -16.8039 -12.92358 18.90122 -17.74927 -15.0634 18.9 -17.72174 -14.60679 18.9 -17.61891 -14.16106 18.9 -16.74374 -12.8744 18.91364 -15.1363 -12.25317 18.90321 -15.12935 -12.25304 18.9 -16.79919 -12.92023 18.9 -14.09566 -16.3051 18.89687 -15.36016 -13.48822 18.89851 -14.13428 -13.74744 18.89939 -13.68027 -12.58736 18.9 -15.71597 -16.3726 18.89865 -15.32779 -17.7304 18.9 -13.46254 -14.78358 18.89858 -13.97966 -17.5537 18.9 -16.31973 -17.41264 18.9 -16.4612 -14.48707 18.89867 -17.74927 -15.0634 18.9 -16.40781 -15.54393 18.89984 -17.61891 -14.16106 18.9 -17.31426 -16.4855 18.9 -16.7014 -17.16049 18.9 -15.52679 -13.84347 18.6265 -14.48163 -13.85483 18.62896 -13.79917 -14.59613 18.62637 -13.84294 -15.44581 18.62883 -14.47321 -16.15653 18.6265 -15.36841 -16.18519 18.62884 -15.95554 -15.80345 18.62701 -16.26943 -14.8536 18.62625 -16.19059 -14.55552 16.7735 -16.15647 -15.45053 16.77116 -15.73454 -16.00947 16.77299 -14.76501 -16.25606 16.77375 -13.80941 -15.44448 16.7735 -13.84353 -14.54947 16.77116 -14.26547 -13.99053 16.77299 -15.23497 -13.74394 16.77375 -13.57329 -15.60636 16.50243 -13.68158 -14.19003 16.50211 -14.89186 -13.45212 16.50237 -16.09418 -13.92907 16.50067 -16.54812 -15.12772 16.50232 -15.92266 -16.21129 16.50088 -14.72736 -16.528 16.50231 19.51332 -21.85709 16.5 19.48529 -22.79273 21.5 19.71229 -23.68442 16.5 20.1843 -24.49277 21.5 20.50107 -24.75081 16.5 21.61542 -25.39684 16.5 21.74398 -25.43302 21.5 23.43656 -25.408 16.5 23.58057 -25.35762 21.5 24.75081 -24.49893 16.5 24.81187 -24.42798 21.5 25.39684 -23.38458 16.5 25.43302 -23.25602 21.5 25.408 -21.56344 16.5 25.35762 -21.41943 21.5 24.12564 -19.91332 16.5 23.99448 -19.83539 21.5 22.34046 -19.47532 16.5 22.20727 -19.48529 21.5 20.62532 -20.0877 16.5 20.98697 -19.89758 21.5 19.83539 -21.00552 21.5 24.15316 -22.41189 16.5 23.77364 -23.48549 16.5 21.01232 -23.16406 16.5 20.99525 -21.80975 16.5 22.0201 -20.94313 16.5 23.36659 -21.08942 16.5 21.82681 -23.98357 16.5 22.9799 -24.05687 16.5 20.85702 -22.70328 21.5 21.73398 -23.96763 21.5 23.27268 -23.96413 21.5 24.08111 -22.89277 21.5 24.01189 -21.94545 21.5 23.26603 -21.03238 21.5 21.92508 -20.97566 21.5 21.18476 -21.57076 21.5 22.08771 12.25 38.5 23.67542 14.99986 36.34135 23.67543 15 38.5 22.73072 13.37744 36.0861 23.03261 13.85999 36.10282 23.11173 15.98999 36.10072 23.24066 14.76944 36.09862 23.24047 15.22872 36.1 22.08768 17.75 36.34086 22.08771 17.75 38.5 22.56968 16.90002 36.11362 21.06951 17.74421 36.11279 20.23641 17.73837 36.09217 18.91229 17.75 38.5 20.2159 17.73813 36.09572 18.9163 17.75145 36.33042 18.29649 16.73396 36.09257 19.52903 17.60313 36.1021 18.93169 17.25896 36.1 17.32459 15.00014 36.34135 17.32457 15 38.5 18.26257 13.39973 36.09285 17.75934 15.23056 36.09862 17.75953 14.77128 36.1 17.88414 14.03685 36.10418 18.92021 12.24819 36.32178 18.91229 12.25 38.5 18.27464 13.3732 36.08715 20.50015 12.21136 36.10513 18.67088 12.92663 36.1011 19.74967 12.35413 36.09679 19.75643 12.35243 36.1 22.07601 12.24697 36.31538 21.24357 12.35243 36.1 21.28616 12.36397 36.08478 22.71768 13.37377 36.09802 21.12119 16.41856 36.10133 21.36021 13.70569 36.10149 19.87881 13.58144 36.10133 18.93314 14.85075 36.1029 19.63979 16.29431 36.10149 18.93169 17.25896 36.1 22.06686 15.14925 36.1029 23.24047 15.22872 36.1 17.75953 14.77128 36.1 20.98674 13.82605 36.3735 21.69112 14.59829 36.37104 21.61425 15.60297 36.37363 20.96291 16.15032 36.37117 20.01327 16.17395 36.3735 19.30889 15.40172 36.37104 19.38575 14.39703 36.37363 20.0371 13.84967 36.37117 20.01327 13.82605 38.2265 19.38187 14.46131 38.22884 19.26075 15.15106 38.22701 19.74147 16.02835 38.22625 20.98674 16.17395 38.2265 21.61813 15.53869 38.22884 21.73926 14.84894 38.22701 21.25853 13.97164 38.22625 20.83752 16.54937 38.49488 21.99147 15.41206 38.49789 21.70594 14.02362 38.49763 20.16248 13.45063 38.49488 19.00853 14.58794 38.49789 19.29406 15.97638 38.49763 -6.75 16.58771 38.5 -9.499861 18.17542 36.34135 -9.5 18.17543 38.5 -7.766041 17.20352 36.09257 -10.5286 17.60411 36.10535 -9.269445 17.74066 36.09862 -9.72872 17.74047 36.1 -12.25 16.58771 38.5 -11.1268 17.22536 36.08715 -11.12755 17.21676 36.09695 -12.13839 15.77746 36.08836 -12.14756 15.74357 36.1 -12.25188 16.57907 36.31999 -12.28852 14.99933 36.10465 -12.25 13.41229 38.5 -12.24236 13.40373 36.30592 -11.07547 12.74108 36.08732 -12.14756 14.25643 36.1 -11.90616 13.61081 36.10177 -11.46773 13.07893 36.1 -9.50014 11.82458 36.34135 -9.5 11.82457 38.5 -7.889014 12.76988 36.09597 -9.730562 12.25934 36.09862 -9.271281 12.25953 36.1 -8.536858 12.38414 36.10418 -6.75 13.41229 38.5 -6.748659 13.41745 36.29915 -6.808621 14.44462 36.11661 -6.750279 15.14223 36.10329 -7.532267 13.07893 36.1 -7.109211 13.61859 36.09709 -6.746976 16.57601 36.31538 -6.852435 15.74357 36.1 -7.108278 16.37978 36.09709 -6.765805 15.29441 36.1 -10.91856 15.62119 36.10133 -8.205691 15.86021 36.10149 -7.241042 16.56831 36.1 -7.012321 16.17216 36.1 -8.081441 14.37881 36.10133 -7.241042 13.43169 36.1 -7.532267 13.07893 36.1 -9.350755 13.43314 36.1029 -6.765805 14.70559 36.1 -6.852435 14.25643 36.1 -7.012321 13.82784 36.1 -10.79431 14.13979 36.10149 -12.14757 14.25643 36.1 -11.46773 13.07893 36.1 -9.649247 16.56686 36.1029 -9.728721 17.74047 36.1 -9.27128 12.25953 36.1 -8.326052 15.48674 36.3735 -9.098286 16.19112 36.37104 -10.10296 16.11425 36.37363 -10.65033 15.4629 36.37117 -10.67395 14.51326 36.3735 -9.901719 13.80889 36.37104 -8.897038 13.88575 36.37363 -8.349675 14.5371 36.37117 -8.326052 14.51326 38.2265 -8.961312 13.88187 38.22884 -9.651068 13.76075 38.22701 -10.52836 14.24147 38.22625 -10.67395 15.48674 38.2265 -10.03869 16.11813 38.22884 -9.348937 16.23926 38.22701 -8.47164 15.75853 38.22625 -11.04937 15.33753 38.49488 -9.91206 16.49147 38.49789 -8.523619 16.20594 38.49763 -7.950632 14.66247 38.49488 -9.087943 13.50853 38.49789 -10.47638 13.79406 38.49763 21.85709 19.51332 16.5 22.79273 19.48529 21.5 23.68442 19.71229 16.5 24.49277 20.1843 21.5 24.75081 20.50107 16.5 25.39684 21.61542 16.5 25.43302 21.74398 21.5 25.408 23.43656 16.5 25.35762 23.58057 21.5 24.49893 24.75081 16.5 24.42798 24.81187 21.5 23.38458 25.39684 16.5 23.25602 25.43302 21.5 21.56344 25.408 16.5 21.41943 25.35762 21.5 19.91332 24.12564 16.5 19.83539 23.99448 21.5 19.47532 22.34046 16.5 19.48529 22.20727 21.5 20.0877 20.62532 16.5 19.89758 20.98697 21.5 21.00552 19.83539 21.5 22.41189 24.15316 16.5 23.48549 23.77364 16.5 23.16406 21.01232 16.5 21.80975 20.99525 16.5 20.94313 22.0201 16.5 21.08942 23.36659 16.5 23.98357 21.82681 16.5 24.05687 22.9799 16.5 22.70328 20.85702 21.5 23.96763 21.73398 21.5 23.96413 23.27268 21.5 22.89277 24.08111 21.5 21.94545 24.01189 21.5 21.03238 23.26603 21.5 20.97566 21.92508 21.5 21.57076 21.18476 21.5 15.75473 12.06665 8.5 16.62451 12.41261 13.5 16.92697 12.68728 8.5 17.85714 13.91817 8.5 17.90759 14.06215 13.5 17.88409 16.0078 8.5 17.89723 15.88331 13.5 17.25168 16.99795 13.5 16.76195 17.46368 8.5 15.93785 17.90759 13.5 15.03939 18.05484 8.5 13.84947 17.83018 13.5 13.50391 17.6122 8.5 12.53632 16.76195 8.5 12.64141 16.87054 13.5 11.97373 15.4187 13.5 11.98542 15.29406 8.5 12.16769 13.98024 8.5 12.20077 13.89267 13.5 12.837 12.87971 8.5 13.12426 12.58852 13.5 14.18694 12.08228 8.5 14.83913 11.97539 13.5 14.50274 16.55142 8.5 15.85078 16.42017 8.5 15.49726 13.44859 8.5 14.34343 13.509 8.5 16.28457 14.02881 8.5 13.48763 15.67339 8.5 13.51983 14.31936 8.5 16.65208 15.10657 8.5 15.41776 13.39807 13.5 16.32554 14.08551 13.5 16.64061 15.22162 13.5 15.74958 16.47609 13.5 14.21101 16.45541 13.5 13.41461 15.37509 13.5 13.56459 14.22945 13.5 14.25195 13.5739 13.5 -24.25972 -24.37738 25.30034 -23.20486 -23.78589 25.28673 -22.42754 -25.03772 25.29911 -21.73858 -23.75399 25.28743 -20.62262 -24.25972 25.30034 -21.03316 -22.46664 25.2873 -19.99679 -22.73116 25.29863 -20.24511 -21.33368 25.2992 -23.26142 -21.24601 25.28743 -25.06513 -22.29471 25.30018 -23.9667 -22.53241 25.28743 -21.79557 -21.21404 25.28677 -21.72906 -20.04487 25.30018 -23.93874 -20.36664 25.30034 -22.75429 -19.74627 22.29844 -24.1786 -20.26723 22.29844 -23.84348 -21.37143 22.26753 -25.20449 -21.80094 22.29844 -20.26723 -20.82141 22.29844 -21.39666 -21.16259 22.26174 -21.5343 -19.90864 22.29844 -22.63533 -20.75238 22.26254 -24.22994 -22.43144 22.26835 -25.12811 -23.36068 22.29844 -24.49441 -24.41574 22.29844 -23.96809 -23.42902 22.25913 -23.19906 -25.20449 22.29844 -22.76795 -24.32523 22.28194 -21.63933 -25.12811 22.29844 -20.58426 -24.49441 22.29844 -21.35393 -23.83969 22.27057 -19.90864 -23.4657 22.29844 -20.74941 -22.59409 22.26317 -19.74627 -22.24572 22.29844 -21.04132 -22.92966 22.01205 -20.99793 -22.73307 12.55117 -21.39643 -23.54062 12.54768 -21.37187 -23.5558 22.07982 -22.13818 -23.98966 22.01274 -22.37265 -24.02733 12.53636 -22.49096 -24.05542 22.09948 -23.45288 -23.6843 12.55117 -23.60144 -23.54842 22.01205 -23.95299 -22.93541 12.54768 -23.96693 -22.94305 22.01143 -23.97099 -22.06852 22.01274 -23.88638 -21.84662 12.53636 -23.50692 -21.34994 22.00634 -23.0492 -21.08263 12.55117 -22.85725 -21.02192 22.01205 -22.15058 -21.02397 12.54768 -22.15022 -21.00808 22.01143 -21.39083 -21.44183 22.01274 -21.24097 -21.62606 12.53636 -21.35578 -21.79528 12.28911 -22.73722 -21.23809 12.29808 -21.57901 -23.43273 12.29423 -23.52286 -21.76116 12.29799 -23.76827 -22.83124 12.29423 -22.83346 -23.73863 12.29683 -19.75348 -22.17155 25.05051 -20.33311 -20.73708 25.05282 -21.60425 -19.88296 25.05051 -22.82845 -19.75348 25.05051 -24.26292 -20.33311 25.05282 -25.11704 -21.60425 25.05051 -25.24652 -22.82845 25.05051 -24.6669 -24.26292 25.05282 -23.39575 -25.11704 25.05051 -22.17156 -25.24652 25.05051 -20.73708 -24.6669 25.05282 -19.88296 -23.39575 25.05051 -23.58236 -23.1249 25.17424 -22.5 -23.7498 25.17424 -21.41765 -23.1249 25.17424 -21.41883 -21.87303 25.17432 -22.5 -21.2502 25.17424 -23.58236 -21.8751 25.17424 -21.05707 -22.5 24.08592 -22.5 -22.5 23.27675 -23.22515 -21.25279 24.08268 -23.94293 -22.5 24.08592 -21.78182 -23.75117 24.07153 -23.22514 -23.74722 24.08267 -21.78184 -21.24881 24.07153 -23.09161 -23.92157 22.08353 -20.99921 -22.16324 22.0458 12.32698 -13.53215 7 12.10799 -14.10965 4 11.98904 -15.48346 7 12.06696 -15.83481 4 12.92087 -17.23088 7 13.02293 -17.29078 4 14.35151 -17.95566 4 14.72951 -18.03751 7 15.60827 -17.94714 4 16.65222 -17.56316 7 16.73534 -17.47893 4 17.58025 -16.54853 4 17.76017 -16.24014 7 17.99912 -15.4022 4 18.00891 -15.0453 7 17.88684 -14.15043 4 17.69084 -13.56508 7 17.32715 -13.06588 4 16.68364 -12.50582 7 15.90534 -12.08796 4 15.27048 -11.96249 7 14.39174 -12.05286 4 13.58355 -12.32603 7 13.05732 -12.64934 4 16.48883 -15.65176 4 15.59439 -16.53716 4 16.53716 -14.40561 4 15.79445 -13.60082 4 14.94123 -13.37582 4 13.79753 -13.87297 4 13.37582 -15.05877 4 13.99465 -16.3425 4 13.72719 -13.95304 7 13.38182 -15.15135 7 14.08901 -16.40824 7 15.6925 -16.49553 7 16.52359 -15.56574 7 16.54393 -14.49237 7 15.89058 -13.64049 7 14.84865 -13.38182 7 24.37738 -24.25972 25.30034 23.78589 -23.20486 25.28673 25.03772 -22.42754 25.29911 23.75399 -21.73858 25.28743 24.25972 -20.62262 25.30034 22.46664 -21.03316 25.2873 22.73116 -19.99679 25.29863 21.33368 -20.24511 25.2992 21.24601 -23.26142 25.28743 22.29471 -25.06513 25.30018 22.53241 -23.9667 25.28743 21.21404 -21.79557 25.28677 20.04487 -21.72906 25.30018 20.36664 -23.93874 25.30034 19.74627 -22.75429 22.29844 20.26723 -24.1786 22.29844 21.37143 -23.84348 22.26753 21.80094 -25.20449 22.29844 20.82141 -20.26723 22.29844 21.16259 -21.39666 22.26174 19.90864 -21.5343 22.29844 20.75238 -22.63533 22.26254 22.43144 -24.22994 22.26835 23.36068 -25.12811 22.29844 24.41574 -24.49441 22.29844 23.42902 -23.96809 22.25913 25.20449 -23.19906 22.29844 24.32523 -22.76795 22.28194 25.12811 -21.63933 22.29844 24.49441 -20.58426 22.29844 23.83969 -21.35393 22.27057 23.4657 -19.90864 22.29844 22.59409 -20.74941 22.26317 22.24572 -19.74627 22.29844 22.92966 -21.04132 22.01205 22.73307 -20.99793 12.55117 23.54062 -21.39643 12.54768 23.5558 -21.37187 22.07982 23.98966 -22.13818 22.01274 24.02733 -22.37265 12.53636 24.05542 -22.49096 22.09948 23.6843 -23.45288 12.55117 23.54842 -23.60144 22.01205 22.93541 -23.95299 12.54768 22.94305 -23.96693 22.01143 22.06852 -23.97099 22.01274 21.84662 -23.88638 12.53636 21.34994 -23.50692 22.00634 21.08263 -23.0492 12.55117 21.02192 -22.85725 22.01205 21.02397 -22.15058 12.54768 21.00808 -22.15022 22.01143 21.44183 -21.39083 22.01274 21.62606 -21.24097 12.53636 21.79528 -21.35578 12.28911 21.23809 -22.73722 12.29808 23.43273 -21.57901 12.29423 21.76116 -23.52286 12.29799 22.83124 -23.76827 12.29423 23.73863 -22.83346 12.29683 22.17155 -19.75348 25.05051 20.73708 -20.33311 25.05282 19.88296 -21.60425 25.05051 19.75348 -22.82845 25.05051 20.33311 -24.26292 25.05282 21.60425 -25.11704 25.05051 22.82845 -25.24652 25.05051 24.26292 -24.6669 25.05282 25.11704 -23.39575 25.05051 25.24652 -22.17156 25.05051 24.6669 -20.73708 25.05282 23.39575 -19.88296 25.05051 23.1249 -23.58236 25.17424 23.7498 -22.5 25.17424 23.1249 -21.41765 25.17424 21.87303 -21.41883 25.17432 21.2502 -22.5 25.17424 21.8751 -23.58236 25.17424 22.5 -21.05707 24.08592 22.5 -22.5 23.27675 21.25279 -23.22515 24.08268 22.5 -23.94293 24.08592 23.75117 -21.78182 24.07153 23.74722 -23.22514 24.08267 21.24881 -21.78184 24.07153 23.92157 -23.09161 22.08353 22.16324 -20.99921 22.0458 24.25972 24.37738 25.30034 23.20486 23.78589 25.28673 22.42754 25.03772 25.29911 21.73858 23.75399 25.28743 20.62262 24.25972 25.30034 21.03316 22.46664 25.2873 19.99679 22.73116 25.29863 20.24511 21.33368 25.2992 23.26142 21.24601 25.28743 25.06513 22.29471 25.30018 23.9667 22.53241 25.28743 21.79557 21.21404 25.28677 21.72906 20.04487 25.30018 23.93874 20.36664 25.30034 22.75429 19.74627 22.29844 24.1786 20.26723 22.29844 23.84348 21.37143 22.26753 25.20449 21.80094 22.29844 20.26723 20.82141 22.29844 21.39666 21.16259 22.26174 21.5343 19.90864 22.29844 22.63533 20.75238 22.26254 24.22994 22.43144 22.26835 25.12811 23.36068 22.29844 24.49441 24.41574 22.29844 23.96809 23.42902 22.25913 23.19906 25.20449 22.29844 22.76795 24.32523 22.28194 21.63933 25.12811 22.29844 20.58426 24.49441 22.29844 21.35393 23.83969 22.27057 19.90864 23.4657 22.29844 20.74941 22.59409 22.26317 19.74627 22.24572 22.29844 21.04132 22.92966 22.01205 20.99793 22.73307 12.55117 21.39643 23.54062 12.54768 21.37187 23.5558 22.07982 22.13818 23.98966 22.01274 22.37265 24.02733 12.53636 22.49096 24.05542 22.09948 23.45288 23.6843 12.55117 23.60144 23.54842 22.01205 23.95299 22.93541 12.54768 23.96693 22.94305 22.01143 23.97099 22.06852 22.01274 23.88638 21.84662 12.53636 23.50692 21.34994 22.00634 23.0492 21.08263 12.55117 22.85725 21.02192 22.01205 22.15058 21.02397 12.54768 22.15022 21.00808 22.01143 21.39083 21.44183 22.01274 21.24097 21.62606 12.53636 21.35578 21.79528 12.28911 22.73722 21.23809 12.29808 21.57901 23.43273 12.29423 23.52286 21.76116 12.29799 23.76827 22.83124 12.29423 22.83346 23.73863 12.29683 19.75348 22.17155 25.05051 20.33311 20.73708 25.05282 21.60425 19.88296 25.05051 22.82845 19.75348 25.05051 24.26292 20.33311 25.05282 25.11704 21.60425 25.05051 25.24652 22.82845 25.05051 24.6669 24.26292 25.05282 23.39575 25.11704 25.05051 22.17156 25.24652 25.05051 20.73708 24.6669 25.05282 19.88296 23.39575 25.05051 23.58236 23.1249 25.17424 22.5 23.7498 25.17424 21.41765 23.1249 25.17424 21.41883 21.87303 25.17432 22.5 21.2502 25.17424 23.58236 21.8751 25.17424 21.05707 22.5 24.08592 22.5 22.5 23.27675 23.22515 21.25279 24.08268 23.94293 22.5 24.08592 21.78182 23.75117 24.07153 23.22514 23.74722 24.08267 21.78184 21.24881 24.07153 23.09161 23.92157 22.08353 20.99921 22.16324 22.0458 12.06665 -15.75473 8.5 12.41261 -16.62451 13.5 12.68728 -16.92697 8.5 13.91817 -17.85714 8.5 14.06215 -17.90759 13.5 16.0078 -17.88409 8.5 15.88331 -17.89723 13.5 16.99795 -17.25168 13.5 17.46368 -16.76195 8.5 17.90759 -15.93785 13.5 18.05484 -15.03939 8.5 17.83018 -13.84947 13.5 17.6122 -13.50391 8.5 16.76195 -12.53632 8.5 16.87054 -12.64141 13.5 15.4187 -11.97373 13.5 15.29406 -11.98542 8.5 13.98024 -12.16769 8.5 13.89267 -12.20077 13.5 12.87971 -12.837 8.5 12.58852 -13.12426 13.5 12.08228 -14.18694 8.5 11.97539 -14.83913 13.5 16.55142 -14.50274 8.5 16.42017 -15.85078 8.5 13.44859 -15.49726 8.5 13.509 -14.34343 8.5 14.02881 -16.28457 8.5 15.67339 -13.48763 8.5 14.31936 -13.51983 8.5 15.10657 -16.65208 8.5 13.39807 -15.41776 13.5 14.08551 -16.32554 13.5 15.22162 -16.64061 13.5 16.47609 -15.74958 13.5 16.45541 -14.21101 13.5 15.37509 -13.41461 13.5 14.22945 -13.56459 13.5 13.5739 -14.25195 13.5 -71.01712 76.82586 1.011005 -72.25209 77.66064 1.009203 -73.42597 77.6742 0.9976481 -72.13187 79.10942 1.01185 -73.15755 79.432 0.9997467 -71.82928 80.70696 0.9976484 -70.81444 79.75282 1.010973 -69.73983 80.54581 0.9989816 -69.59844 78.93321 1.011705 -68.7023 79.48515 0.9997467 -68.40756 77.66774 0.9976484 -69.69967 77.4703 1.011704 -69.72707 76.03961 0.999095 -71.83539 75.87445 0.9974349 -68.74582 76.57145 4 -69.69547 77.07717 4.030353 -70.07209 75.6195 4 -70.58092 76.56869 4.032122 -71.75273 75.65109 4 -71.09638 81.08373 4 -71.43299 79.96228 4.0328 -70.20391 79.9032 4.024268 -69.47213 80.65085 4 -69.44481 79.20749 4.031351 -68.36723 79.44898 4 -69.18639 78.01688 4.0328 -68.19602 77.77676 4 -71.9279 76.83976 4.027444 -72.88302 76.34219 4 -73.66815 77.77352 4 -72.62353 77.92891 4.0301 -73.43421 79.43813 4 -72.4351 79.122 4.040014 -72.61195 80.47682 4 -72.44488 78.53102 4.218322 -72.31328 78.89342 15.74694 -72.39609 77.94911 15.75091 -72.34796 77.77645 4.287185 -71.91769 77.14818 15.75078 -71.95023 77.13876 4.218828 -71.09178 76.76427 4.286406 -70.84008 76.75516 15.76327 -70.19843 76.93748 4.293376 -69.79595 77.26579 15.75046 -69.47946 77.7073 4.288964 -69.40821 78.11487 15.74978 -69.43171 78.63723 4.283032 -69.60001 79.05455 15.74632 -69.70444 79.20873 4.287588 -70.3133 79.68307 15.75075 -70.2751 79.69734 4.219273 -71.20769 79.79656 4.286752 -71.45986 79.72542 15.76373 -72.00511 79.36405 4.294349 -72.17188 78.56462 16.00196 -71.43216 79.46865 16.00045 -70.26617 79.39883 16.00196 -69.63649 78.4158 16.00196 -70.20011 77.18508 16.00514 -71.74505 77.26735 16.00514 -73.40033 79.51123 1.247461 -72.54798 80.52581 1.247463 -71.32173 81.02808 1.247464 -69.67226 80.79807 1.244448 -68.3215 79.34243 1.244448 -68.21141 77.69767 1.247462 -69.01139 76.23695 1.244442 -70.5102 75.55078 1.247465 -71.82939 75.6759 1.247467 -73.18307 76.64614 1.244446 -73.68357 78.21677 1.247463 -70.34253 77.17897 1.124214 -71.59093 77.23755 1.124201 -72.16439 78.34803 1.124202 -71.48732 79.40098 1.124128 -70.241 79.34129 1.124199 -69.66755 78.23082 1.124202 -70.9355 76.86138 2.265674 -70.91597 78.28942 3.021688 -71.59032 77.23728 2.323016 -72.20602 77.67652 2.265522 -72.11524 79.08211 2.235246 -69.69493 77.5299 2.228478 -69.64899 78.96997 2.241969 -70.85114 79.73091 2.19906 -11.08771 -12.25 38.5 -12.67542 -14.99986 36.34135 -12.67543 -15 38.5 -11.73072 -13.37744 36.0861 -12.03261 -13.86 36.10282 -12.11173 -15.98998 36.10071 -12.24066 -14.76944 36.09862 -12.24047 -15.22872 36.1 -11.08769 -17.75 36.34086 -11.08771 -17.75 38.5 -11.56968 -16.90002 36.11362 -10.06951 -17.74421 36.11279 -9.236404 -17.73837 36.09217 -7.912287 -17.75 38.5 -9.215901 -17.73813 36.09572 -7.90373 -17.74236 36.30592 -7.446737 -16.8267 36.11638 -7.031437 -16.22215 36.1014 -8.529032 -17.60313 36.1021 -7.931687 -17.25896 36.1 -6.324573 -15 38.5 -6.325999 -14.99484 36.29911 -6.891408 -14.13516 36.11638 -7.207306 -13.47324 36.1014 -6.738812 -15.00093 36.09709 -6.835356 -15.67983 36.1 -7.912287 -12.25 38.5 -7.910148 -12.2522 36.3095 -9.500149 -12.21136 36.10513 -7.740195 -12.87418 36.09959 -8.327842 -12.51232 36.1 -8.75643 -12.35243 36.1 -11.07601 -12.24697 36.31537 -10.24357 -12.35243 36.1 -10.28616 -12.36397 36.08478 -11.71768 -13.37378 36.09802 -10.12119 -16.41856 36.10133 -10.36021 -13.70569 36.10149 -6.835356 -15.67983 36.1 -8.878809 -13.58144 36.10133 -7.931686 -12.74104 36.1 -7.578926 -13.03227 36.1 -7.933139 -14.85075 36.1029 -8.75643 -12.35243 36.1 -8.639789 -16.29431 36.10149 -7.931686 -17.25896 36.1 -7.279321 -16.62206 36.1 -7.578926 -16.96773 36.1 -11.06686 -15.14925 36.1029 -12.24047 -15.22872 36.1 -6.835356 -14.32017 36.1 -6.759528 -14.77128 36.1 -6.759528 -15.22872 36.1 -6.984913 -13.88787 36.1 -9.986737 -13.82605 36.3735 -10.69111 -14.59828 36.37104 -10.61425 -15.60296 36.37363 -9.96291 -16.15032 36.37117 -9.013266 -16.17395 36.3735 -8.308887 -15.40172 36.37104 -8.385752 -14.39704 36.37363 -9.037103 -13.84967 36.37117 -9.013265 -13.82605 38.2265 -8.381875 -14.46131 38.22884 -8.260747 -15.15107 38.22701 -8.741466 -16.02835 38.22625 -9.986735 -16.17395 38.2265 -10.61813 -15.53869 38.22884 -10.73925 -14.84893 38.22701 -10.25853 -13.97164 38.22625 -9.837522 -16.54937 38.49488 -10.99147 -15.41206 38.49789 -10.70594 -14.02362 38.49763 -9.162474 -13.45063 38.49488 -8.008531 -14.58794 38.49789 -8.29406 -15.97638 38.49763 18.62965 13.3235 47.00008 19.79669 13.71403 46.98818 19.72755 12.58589 47.00057 21.26142 13.74601 46.98899 21.346 12.61075 47.00064 22.47529 13.43846 47.0003 21.96684 15.03337 46.98886 19.73859 16.25399 46.98899 18.1427 15.86719 47.00008 19.0333 14.96759 46.98899 18.00165 14.5574 47.00054 21.20318 16.28656 46.98891 20.70494 17.50338 47.00008 19.14944 17.18408 47.00214 23.0596 14.95083 47.00115 22.24315 16.88564 47.00214 18.29803 16.6739 44 19.36634 16.35152 43.96982 17.79869 15.59461 44 18.72041 15.181 43.97219 17.79869 14.40539 44 18.29802 13.32611 44 22.72312 16.68997 44 21.74123 16.20694 43.97022 21.24709 17.69075 44 20.65118 12.21156 44 22.30785 12.87163 44 21.8935 13.81255 43.98421 23.12119 14.11682 44 20.33992 16.72613 43.97114 19.46638 17.5942 44 19.11755 13.83181 43.98404 19.20439 12.55623 44 20.15506 13.2881 43.97332 23.24976 15.29906 44 22.30793 15.18356 43.98461 22.02681 14.75341 43.7813 22.04452 14.98315 36.25202 21.63952 14.0014 36.24933 20.98297 13.5499 43.71208 20.7004 13.46833 36.25197 20.29401 13.49406 43.71392 19.67172 13.73115 36.2493 19.52491 13.78141 43.79007 18.96283 15.13452 43.78032 19.0198 14.59042 36.24319 19.1271 15.64144 36.24926 19.26363 15.92447 43.78224 19.85302 16.38604 36.23896 19.78771 16.34117 43.71181 20.4243 16.52503 43.70894 20.92969 16.45619 36.25271 21.03027 16.47188 43.85274 21.64901 15.98751 36.24934 21.64721 16.01246 43.71264 21.76504 14.56706 35.99229 20.18385 16.27001 35.99907 21.37324 15.93599 35.99867 19.28584 15.4055 35.99867 19.39844 14.34794 35.99867 20.44565 13.69504 35.99652 23.26456 14.58122 46.75847 22.43859 12.98504 46.74647 21.1355 12.30423 46.75268 19.94485 12.28654 46.75268 18.85682 12.77043 46.75268 18.07251 13.66646 46.75268 17.70616 15.10392 46.75482 18.18918 16.52716 46.7544 19.06026 17.36625 46.74691 20.15967 17.74868 46.75268 21.35328 17.63516 46.7544 22.39483 17.0203 46.74691 23.05745 16.06326 46.75268 19.41767 14.37511 46.87578 20.5 13.75025 46.87577 21.58235 14.3751 46.8758 21.58115 15.62696 46.87586 20.5 16.24975 46.87577 19.41765 15.6249 46.8758 21.92571 15.05018 45.7153 20.5 15 44.97831 19.77374 16.24451 45.76333 19.07451 14.94649 45.72504 21.22626 13.75549 45.76333 19.78094 13.74851 45.80541 21.21906 16.25148 45.80541 20.81633 13.33787 43.93516 21.66388 13.98338 43.786 22.00428 15.31587 43.75102 19.07939 14.41195 43.78407 -7.967758 -12.94085 47.00177 -8.796689 -13.71403 46.98818 -10.07742 -12.49929 47.00193 -10.26142 -13.74601 46.98899 -11.47529 -13.43845 47.0003 -10.96684 -15.03336 46.98886 -8.738584 -16.25399 46.98899 -7.142699 -15.86719 47.00008 -8.033305 -14.96759 46.98899 -7.001654 -14.5574 47.00054 -10.20318 -16.28656 46.98891 -9.704936 -17.50338 47.00008 -8.149436 -17.18408 47.00214 -12.05959 -14.95083 47.00115 -11.24315 -16.88564 47.00214 -6.989668 -16.1614 44 -7.94499 -15.80314 43.96658 -6.734025 -15 44 -7.740886 -14.61141 43.98486 -6.989669 -13.8386 44 -12.12118 -15.88318 44 -11.0478 -15.78778 43.96751 -11.50808 -16.90216 44 -10.20897 -16.67669 43.98517 -10.24709 -17.69075 44 -9.350255 -12.23808 44 -10.3065 -13.34841 43.98364 -10.52379 -12.43047 44 -11.72312 -13.31003 44 -9.0551 -17.71377 44 -8.982216 -16.67764 43.97234 -7.932859 -17.31135 44 -8.270208 -13.78596 43.97103 -7.932864 -12.68865 44 -8.912397 -13.28811 43.98404 -11.24282 -14.48628 43.98555 -12.24976 -14.70095 44 -11.02681 -14.75341 43.7813 -11.04452 -14.98315 36.25202 -10.63952 -14.00139 36.24933 -10.66941 -13.99335 43.78087 -9.700394 -13.46833 36.25197 -9.144103 -13.49798 43.78145 -8.671715 -13.73116 36.2493 -8.426921 -13.90872 43.71323 -7.962827 -15.13451 43.78032 -8.019795 -14.59042 36.24318 -8.127103 -15.64144 36.24926 -8.263632 -15.92447 43.78224 -8.853022 -16.38604 36.23896 -8.911941 -16.4261 43.77899 -9.929688 -16.45619 36.25271 -9.851038 -16.51708 43.78747 -10.64901 -15.98751 36.24934 -10.63434 -16.03983 43.75133 -11.00149 -15.28325 43.71128 -10.59183 -14.22819 35.99229 -8.888844 -13.80438 35.99758 -10.52182 -15.81349 35.99652 -9.184498 -16.26741 35.99652 -8.216056 -15.23951 35.99652 -12.11002 -13.99775 46.75977 -11.18714 -12.80329 46.74691 -10.13551 -12.30423 46.75268 -8.944849 -12.28654 46.75268 -7.611294 -12.93835 46.75356 -6.840062 -14.22744 46.7544 -6.764465 -15.43455 46.74691 -7.189177 -16.52716 46.7544 -8.060255 -17.36625 46.74691 -9.159672 -17.74868 46.75268 -10.35328 -17.63516 46.7544 -11.6179 -16.82586 46.74525 -12.22622 -15.48862 46.75268 -8.417661 -14.37511 46.87578 -9.500001 -13.75025 46.87577 -10.58236 -14.3751 46.8758 -10.58115 -15.62695 46.87586 -9.5 -16.24975 46.87577 -8.417642 -15.6249 46.8758 -10.9257 -15.05019 45.7153 -9.5 -15 44.97831 -8.773737 -16.24451 45.76333 -8.074506 -14.94649 45.72504 -10.22626 -13.75549 45.76333 -8.780942 -13.74851 45.80541 -10.21906 -16.25148 45.80541 -9.962985 -13.52454 43.76791 -8.062132 -14.46608 43.78516 -7.81849 13.06106 47.00193 -8.214029 14.29669 46.98818 -7.033457 14.5256 47.00008 -8.246009 15.76142 46.98899 -7.110747 15.846 47.00064 -7.938455 16.97529 47.0003 -9.533366 16.46684 46.98886 -10.75399 14.23858 46.98899 -9.884629 12.46086 47.00196 -9.467591 13.5333 46.98899 -10.78656 15.70318 46.98891 -12.00338 15.20494 47.00008 -11.68408 13.64943 47.00214 -9.450829 17.5596 47.00115 -11.38564 16.74315 47.00214 -10.66141 12.48967 44 -10.97287 14.05769 43.96261 -9.978541 13.33925 43.96832 -9.198077 12.22383 44 -8.510587 13.42347 43.97982 -8.082227 12.64364 44 -10.92601 17.37004 44 -10.40914 16.59938 43.98265 -11.96724 16.30805 44 -11.30938 14.85297 43.9846 -12.26192 14.85025 44 -6.738082 14.85025 44 -7.815712 15.42361 43.96751 -7.03276 16.30805 44 -8.921163 16.63595 43.96554 -8.327445 17.53444 44 -11.81135 13.43286 44 -7.188648 13.43286 44 -9.799058 17.74976 44 -9.093588 16.46452 43.71369 -9.483148 16.54452 36.25202 -8.501397 16.13952 36.24933 -8.049904 15.48296 43.71208 -7.968328 15.20039 36.25197 -7.968261 14.66477 43.85346 -8.231158 14.17171 36.2493 -8.216865 14.16587 43.71337 -8.437287 13.87452 43.79778 -9.634511 13.46283 43.78031 -9.09042 13.51979 36.24318 -10.14144 13.6271 36.24926 -10.42447 13.76363 43.78224 -10.88604 14.35303 36.23896 -10.91947 14.42893 43.71275 -10.95619 15.42969 36.25271 -10.93004 15.62369 43.85947 -10.4875 16.14901 36.24934 -10.52276 16.15511 43.78059 -9.452953 16.2803 35.99971 -10.56842 15.75124 35.99652 -10.54815 14.16984 35.99229 -9.007339 13.79039 35.99652 -8.240489 14.77142 35.99867 -8.502446 15.80219 35.99867 -9.081222 17.76456 46.75847 -7.71887 17.12101 46.74874 -7.003871 16.20016 46.75268 -6.730642 15.04114 46.75268 -6.969324 13.87452 46.75268 -7.89257 12.71226 46.75356 -9.603919 12.20616 46.75482 -11.02716 12.68917 46.7544 -12.02917 13.80728 46.74525 -12.25757 15.25852 46.75268 -11.75411 16.65387 46.75482 -10.56326 17.55745 46.75268 -8.875111 13.91766 46.87578 -8.250247 15 46.87577 -8.875102 16.08236 46.8758 -10.12695 16.08115 46.87586 -10.74975 15 46.87577 -10.1249 13.91764 46.8758 -9.550187 16.42571 45.7153 -9.5 15 44.97831 -10.74451 14.27374 45.76333 -9.44649 13.57451 45.72504 -8.255491 15.72626 45.76333 -8.248516 14.28094 45.80541 -10.75148 15.71906 45.80541 -8.452778 16.16222 43.853 -11.03427 15.08771 43.78934 -9.819711 16.51049 43.77585 -8.966079 13.56213 43.78516 69.01838 94.17012 17.75108 70.2415 93.86322 17.00505 69.84543 93.23284 17 68.30162 93.12303 17.00281 69.24739 92.92219 17.00392 70.2127 94.56134 17.00284 67.81413 93.80207 17.00096 67.80393 94.52574 17.00168 68.35335 95.2508 17.00281 69.50319 95.37771 17.0027 79.58805 87.64846 17.75108 80.60948 86.89559 17.00281 80.85879 87.81308 16.99901 79.79981 86.39736 17.00281 78.52764 86.95684 17.0041 79.06819 86.51169 17 78.32069 87.85257 17.00356 78.92303 88.72914 17.00281 79.91794 88.87415 17.00267 80.4959 88.50772 17 71.36279 78.34281 17.75108 72.62415 78.07756 17.0019 72.04262 77.27155 17.00392 71.07581 77.10469 17.00147 70.33248 77.6096 17.00258 70.08553 78.51257 17.00073 70.69776 79.4235 17.00281 71.65934 79.57898 16.99882 72.42593 79.02948 17.00162 60.79312 84.86447 17.75108 62.00756 84.50886 17.00168 61.45814 83.7838 17.00281 60.52079 83.62513 17.0028 61.99738 85.23252 17.00096 59.6636 84.24932 17.00339 59.5961 85.27346 17.00249 61.55813 85.87733 17.00267 59.96605 85.80174 17 60.58091 86.11631 17.00336 84.45324 90.89112 13.59365 84.11097 90.84528 12.81053 84.17809 88.97962 12.40773 82.887 90.66463 12.01772 83.65096 88.17667 12.0799 85.10278 87.8803 13.67894 84.86533 87.84545 13.02826 83.37452 85.68187 12.00618 84.48405 85.84706 12.42953 85.12162 85.94078 13.38459 70.18765 93.70111 12 69.56277 93.03072 12 68.70606 92.93772 12 67.96385 93.46771 12 67.75428 94.4196 12 68.38692 95.27359 12 69.33068 95.40254 12 70.17656 94.75787 12 80.84005 87.87324 12 80.58689 86.86189 12 79.76013 86.3888 12 78.76857 86.6877 12 78.32305 87.55606 12 78.58922 88.43505 12 79.41597 88.90813 12 80.36283 88.65422 12 72.6278 78.43523 12 72.10843 77.29264 12 71.02121 77.12006 12 70.30826 77.64041 12 70.12647 78.66337 12 70.73133 79.44628 12 72.02297 79.46485 12 62.05722 84.61502 12 61.42457 83.76102 12 60.48081 83.63206 12 59.73859 84.16207 12 59.53295 84.86112 12 59.81502 85.67389 12 60.62103 86.12414 12 61.31296 86.00125 12 61.89188 85.48033 12 56.55754 86.76425 12.03097 56.69898 84.77455 12.06942 55.99715 81.62687 13.22367 55.46173 83.40803 13.73804 55.67279 83.43381 13.05619 56.16533 83.87665 12.38369 57.35463 81.82853 12.04514 55.53841 86.61191 12.81115 55.19427 86.55435 13.55482 64.65208 87.97713 15.5 64.67353 87.98828 12 55.18164 86.57142 15.49982 66.9588 91.01231 12 66.03199 90.24649 15.5 65.72903 89.90436 12 66.95884 91.01235 15.5 65.60085 100.1799 12.85508 65.76165 99.09907 12.04778 65.55043 100.5207 15.5 65.5513 100.5252 13.68623 71.90487 91.74497 15.5 71.92239 91.77355 12 70.69837 99.88951 12.03097 70.54602 100.9086 12.81116 70.51576 101.2821 15.49976 70.49068 101.2471 13.54813 74.94646 89.48822 12 73.94214 90.64015 12 73.24567 91.15327 15.5 74.98263 89.52888 15.5 84.46953 90.91902 15.49989 75.67908 84.54216 12 85.19648 85.92908 15.49985 75.67909 84.54217 15.5 73.44029 81.45224 12 75.08736 83.20134 15.5 75.15104 83.30899 12 73.43463 81.46737 15.5 74.78033 72.33307 12.85508 74.61952 73.41387 12.04778 74.83074 71.99221 15.5 74.82987 71.98777 13.68624 67.65781 86.51437 12 71.68029 88.32099 12 69.65318 88.74497 12 68.26359 87.84917 12 72.61136 86.95674 12 72.56934 85.38356 12 71.23366 83.93408 12 68.41327 80.73787 12 69.77477 83.79129 12 68.30418 84.54681 12 65.43471 83.02473 12 66.38967 81.91307 12 68.47631 80.76796 15.5 69.68281 72.62343 12.03097 69.83515 71.6043 12.81115 69.86542 71.23088 15.49976 69.8905 71.26589 13.54814 65.41529 83.0188 15.5 67.08266 81.39524 15.5 55.90814 81.6033 15.49989 63.92091 99.89673 15.50011 60.60864 97.83078 15.5 57.54423 94.45748 15.5 55.74987 90.35823 15.5 68.70863 99.74806 12.06942 67.81076 100.2817 12.38369 67.62985 100.9627 13.29584 81.36327 96.26503 15.5 83.21924 93.71387 15.5 74.57153 100.6296 15.5 76.9845 99.62968 15.5 79.47565 98.07027 15.5 83.31144 78.93382 15.5 81.2735 76.10692 15.5 79.15732 74.23159 15.5 76.46025 72.61621 15.50011 84.75972 82.57072 15.5 71.67258 72.76488 12.06942 72.57041 72.23122 12.38369 72.75131 71.5502 13.29583 59.01791 76.2479 15.5 57.25984 78.6031 15.5 66.01654 71.81965 15.5 63.39669 72.88326 15.5 60.90556 74.44264 15.5 55.23551 85.12693 23.69949 55.45637 83.35191 23.7 61.92354 98.80639 23.7 59.81168 97.08599 23.7 57.94246 94.96439 23.7 56.36465 92.10475 23.7 55.28816 88.17195 23.7 65.69464 100.58 23.69991 68.9413 101.2315 23.70003 72.60645 101.086 23.7 75.28646 100.3643 23.7 78.12978 98.99727 23.7 80.04614 97.56435 23.7 82.20206 95.2611 23.7 85.09494 88.4485 23.70012 83.96517 92.25972 23.7 77.60889 73.21926 23.7 82.52037 77.65539 23.7 84.01651 80.40816 23.7 74.68654 71.93295 23.69989 71.43986 71.2814 23.70003 68.6963 71.33109 23.7 62.25138 73.51567 23.7 60.33502 74.9486 23.7 58.1791 77.25186 23.7 56.55316 79.93009 23.7 85.07203 84.17787 23.7 79.77251 74.68215 23.7 65.8096 71.88341 23.7 74.42044 76.08359 23.7 77.13556 77.70388 23.7 78.57689 79.13819 23.7 80.07825 81.3971 23.7 80.7867 83.3031 23.7 65.01992 76.51828 23.7 67.09876 75.69993 23.7 69.57196 75.24804 23.7 71.80236 75.37519 23.7 60.502 80.98881 23.7 62.61763 78.25462 23.7 59.18008 86.85492 23.7 59.49833 83.60955 23.7 64.54476 95.71712 23.7 62.09029 93.72404 23.7 60.86963 92.09769 23.7 59.70798 89.64679 23.7 70.6082 97.26579 23.7 67.65721 96.98728 23.7 79.96456 91.35918 23.7 77.91413 94.12509 23.7 74.61201 96.40779 23.7 81.20384 85.75476 23.7 80.93154 88.73116 23.7 59.30931 84.6447 25.9 59.1939 87.03922 25.9 59.93829 90.29006 25.9 61.37712 92.88152 25.9 62.91245 94.50443 25.9 65.14202 96.04888 25.9 67.8378 97.03057 25.9 71.28979 97.21873 25.9 74.08535 96.57382 25.9 76.15332 95.50016 25.9 78.04711 93.99546 25.9 79.47554 92.15473 25.9 80.64387 89.73345 25.9 81.18344 87.0884 25.9 81.10083 84.85414 25.9 80.52271 82.40738 25.9 79.51154 80.41526 25.9 77.96219 78.43531 25.9 76.20989 77.04953 25.9 73.78175 75.84096 25.9 70.67568 75.24993 25.9 68.64558 75.36552 25.9 66.02316 76.05785 25.9 64.22787 77.01277 25.9 62.13621 78.7394 25.9 60.02242 81.87847 25.9 72.68867 86.0129 25.9 72.30899 84.92893 25.9 71.62568 84.18164 25.9 70.13253 83.73436 25.9 68.87884 84.10154 25.9 68.08037 84.91595 25.9 67.72258 85.77355 25.9 67.83047 87.12554 25.9 68.53646 88.13101 25.9 69.31867 88.61554 25.9 70.54173 88.73168 25.9 71.50235 88.41139 25.9 72.49293 87.29949 25.9 67.68415 85.99391 35.2 67.95836 87.41518 35.2 68.86564 88.40332 35.2 69.82426 88.72949 35.2 71.04802 88.62084 35.2 72.06034 87.95011 35.2 72.684 86.56928 35.2 70.89504 83.83195 35.2 69.33315 83.89211 35.2 72.0018 84.51149 35.2 72.59878 85.58522 35.2 68.32082 84.56285 35.2 72.5334 87.12893 15.5 72.65056 85.62441 15.50041 71.74433 84.29793 15.5 70.39764 83.71903 15.5 68.44344 84.40474 15.5 67.6454 86.31581 15.5 68.53161 88.1876 15.5 70.08478 88.75423 15.5 71.51455 88.43101 15.5 48.39444 79.17008 11.98899 48.17668 77.93422 12.00257 49.8227 78.74338 11.9908 49.93997 77.70522 12.00025 51.53289 78.62851 12.00235 50.86752 79.75421 11.98815 51.91189 81.0004 12.00235 50.53072 81.18115 11.98903 50.46353 82.51499 12.00102 49.12622 81.60279 11.98829 48.34869 82.50735 12.00235 48.05846 80.59769 11.9883 47.15866 81.18607 12.00025 46.96883 79.67013 12.0009 46.82769 81.12261 9 47.75813 80.59446 8.964501 46.86234 79.13705 9 47.87451 79.46055 8.974613 47.9515 77.85667 9 51.87857 81.52642 9 50.54213 81.53209 8.969173 50.97404 82.49437 9 49.72332 82.93109 9 49.64918 81.89583 8.972196 48.11841 82.63181 9 48.79409 81.77395 8.959937 49.2891 78.44453 8.967974 49.20225 77.41996 9 50.80713 77.71923 9 50.79946 78.8959 8.98223 51.94689 78.9548 9 52.22965 80.24902 9 51.18426 80.49526 8.967201 50.74691 79.33452 8.770378 50.81531 79.47702 -2.74694 50.17682 78.80076 8.772419 50.13717 78.81472 -2.750908 49.21435 78.67746 -2.750784 49.22587 78.65952 8.711767 48.39406 79.07331 8.713604 48.2276 79.26225 -2.763261 47.96215 79.87425 8.706627 47.9612 80.39363 -2.750462 48.01541 80.64409 8.712976 48.37253 81.23154 -2.74978 48.79162 81.54431 8.716994 49.22107 81.67844 -2.746323 49.40655 81.69531 8.712417 50.15929 81.52472 -2.750749 50.14427 81.54999 8.71116 50.81373 80.90457 8.713261 50.91841 80.66444 -2.763721 50.98423 80.01359 8.705645 50.77074 80.32125 -3.005136 50.00555 78.9766 -3.005136 48.4874 79.28622 -3.001471 49.9095 81.38112 -3.001961 48.92191 81.31674 -3.000546 48.25717 80.62225 -3.001961 51.982 79.02732 11.75254 52.22703 80.32955 11.75253 51.83883 81.59651 11.75253 50.90628 82.53797 11.75254 49.64307 82.93819 11.75253 48.01791 82.57396 11.75555 46.79083 81.01267 11.75555 46.90766 79.03031 11.75555 48.01926 77.81308 11.75253 49.62752 77.38034 11.75555 51.15984 77.9881 11.75254 48.24029 79.91574 11.87579 49.07651 78.98691 11.8758 50.29901 79.2467 11.8758 50.68478 80.43765 11.87587 49.84904 81.36414 11.8758 48.62655 81.10436 11.8758 48.37021 79.25573 10.73433 49.46277 80.17552 9.978313 49.07589 78.98722 10.67698 49.8058 78.78908 10.73448 50.83586 79.74977 10.76476 48.10157 80.63912 10.77152 49.18669 81.58696 10.75803 50.53702 81.13888 10.80094 48.35187 78.89491 8.933135 48.25335 81.1322 8.786177 47.14379 27.77011 0 30.09992 33.55859 0 47.14379 27.77011 -2 30.09992 33.55859 -2 55.18335 51.44215 0 55.18335 51.44215 -2 38.13948 57.23063 0 38.13948 57.23063 -2 53.78723 64.23677 0 53.78713 64.23693 -2.158656 56.53709 62.64907 -2.158651 56.53723 62.64906 0 54.78233 63.65945 -2.405725 55.66105 63.16161 -2.387336 57.5591 63.21575 -2.396921 59.28723 64.23681 -2.159142 59.28723 64.23677 0 58.16403 63.59912 -2.412847 58.19782 63.63251 -2.41388 59.28144 65.25495 -2.387208 59.27492 66.09992 -2.404691 59.28723 67.4122 0 59.27958 67.42076 -2.194079 58.148 68.05502 -2.404339 59.18479 66.56806 -2.4 58.92913 67.20427 -2.403158 58.50496 67.74556 -2.4 56.53734 68.99991 -2.158652 56.53723 68.99991 0 57.4134 68.48737 -2.387335 55.51536 68.43322 -2.396915 53.78723 67.4122 0 53.79584 67.42076 -2.184565 53.8451 66.44667 -2.413419 53.80014 66.10416 -2.404341 54.71093 67.8873 -2.394969 54.14645 67.2059 -2.402906 53.79322 65.25154 -2.387359 57.95579 65.20331 -2.398667 55.24292 64.96428 -2.398513 55.11867 66.44568 -2.398667 54.27827 67.3928 -2.4 54.56949 67.74556 -2.4 56.38799 67.39134 -2.397096 53.88966 66.56806 -2.4 54.04955 66.99665 -2.4 57.83153 66.68471 -2.398513 58.79618 67.3928 -2.4 59.0249 66.99665 -2.4 59.18479 66.56806 -2.4 58.50496 67.74556 -2.4 56.68647 64.25762 -2.397096 54.91516 68.04517 -2.4 55.36328 65.33777 -2.1265 56.1355 64.63338 -2.128956 57.1402 64.71025 -2.126378 57.68755 65.36158 -2.128828 57.71117 66.31123 -2.126501 56.93894 67.0156 -2.128958 55.93427 66.93874 -2.126374 55.3869 66.28738 -2.128827 55.36328 66.31123 -0.2734995 55.99854 66.94261 -0.2711588 56.6883 67.06375 -0.2729892 57.56558 66.58303 -0.2737491 57.71118 65.33777 -0.2734987 57.07592 64.70636 -0.271159 56.38615 64.58524 -0.2729915 55.50888 65.06594 -0.2737509 58.06783 65.86171 -6.71589e-4 57.58251 64.67543 -0.002317667 56.38615 64.30934 -8.75127e-4 55.29589 64.89273 -0.002307295 55.08019 66.35383 -0.002432227 56.12517 67.31596 -0.00210607 57.51362 67.03042 -0.002366304 44.23677 72.21278 0 44.23693 72.21289 -2.158655 42.64907 69.46292 -2.158652 42.64906 69.46278 0 43.65942 71.21765 -2.405725 43.16161 70.33896 -2.387336 43.22217 68.46526 -2.405725 44.2368 66.71279 -2.159144 44.23677 66.71278 0 43.7548 67.56276 -2.386382 45.25494 66.71858 -2.387211 46.0999 66.72507 -2.404688 47.4122 66.71278 0 47.42076 66.72043 -2.194078 48.05499 67.85198 -2.404333 46.56805 66.81521 -2.4 47.20427 67.07089 -2.403156 47.74555 67.49504 -2.4 48.9999 69.46264 -2.15865 48.99991 69.46278 0 48.48735 68.58659 -2.387336 48.43321 70.48464 -2.396923 47.4122 72.21278 0 47.42076 72.20416 -2.184567 46.44662 72.1549 -2.413422 46.10417 72.19986 -2.404342 47.88733 71.28903 -2.394956 47.20587 71.85358 -2.402913 45.25156 72.2068 -2.387359 45.20329 68.04423 -2.398667 44.96429 70.7571 -2.398512 46.44566 70.88134 -2.398667 47.3928 71.72174 -2.4 47.74556 71.43051 -2.4 47.39134 69.61203 -2.397096 46.56805 72.11034 -2.4 46.99664 71.95046 -2.4 46.68471 68.16848 -2.398513 47.3928 67.20382 -2.4 46.99664 66.9751 -2.4 46.56805 66.81521 -2.4 47.74556 67.49504 -2.4 44.25762 69.31353 -2.397096 48.04516 71.08484 -2.4 45.33776 70.63674 -2.126501 44.63337 69.8645 -2.128958 44.71024 68.85981 -2.126375 45.36156 68.31247 -2.128827 46.31122 68.28884 -2.126499 47.0156 69.06106 -2.128958 46.93873 70.06575 -2.126376 46.28738 70.61312 -2.128823 46.31121 70.63674 -0.2734992 46.9426 70.00148 -0.2711577 47.06374 69.31173 -0.2729915 46.58305 68.43446 -0.2737528 45.33775 68.28884 -0.2735006 44.70636 68.92409 -0.271157 44.58523 69.61383 -0.2729914 45.06599 70.49117 -0.2737502 45.48699 67.9134 -0.00511831 44.33301 69.05072 -0.002105712 44.61853 70.43914 -0.002365767 46.16202 71.01215 -0.005117237 47.31596 69.87483 -0.00210601 47.03041 68.48638 -0.002366721 40.13159 14.67648 -2.98874 40.70434 13.62328 -3.001437 38.73971 13.38359 -2.945321 38.66985 14.7909 -2.989515 40.96274 15.88762 -2.988995 42.05238 15.23542 -3.001437 40.3287 17.21058 -2.988995 41.90208 17.30671 -2.944126 38.86595 17.32296 -2.988995 39.60041 18.66255 -3.001437 41.0561 18.24501 -2.927002 37.59411 17.96318 -2.94434 36.89728 15.42983 -3.001437 38.03726 16.11238 -2.988995 36.98667 17.06219 -2.947659 37.63845 13.99007 -2.926782 38.07575 13.64755 0 38.66377 14.62802 0 37.63136 13.9824 0 38.32518 14.91382 0 37.26347 14.39986 0 38.06676 15.27375 0 36.98715 14.88282 0 36.8137 15.41152 0 37.92934 15.69498 0 36.75023 15.96432 0 37.89912 16.13703 0 36.79933 16.51857 0 36.95901 17.0516 0 38.05672 16.70608 0 37.2227 17.54157 0 37.57964 17.96843 0 38.31005 17.06959 0 38.01519 18.3147 0 38.64459 17.36011 0 38.51153 18.56621 0 39.19369 17.57727 0 39.04833 18.71266 0 39.60364 18.74805 0 39.63645 17.59417 0 40.15469 18.67093 0 40.06991 17.50227 0 40.67895 18.48447 0 41.15493 18.19629 0 40.45523 17.28356 0 41.56317 17.8182 0 40.77537 16.97725 0 41.88693 17.36567 0 42.11298 16.85723 0 40.98786 16.58844 0 42.23205 16.31369 0 41.0988 16.15946 0 42.23927 15.75731 0 41.04845 15.57115 0 42.13434 15.21087 0 41.92156 14.69673 0 40.86622 15.16727 0 41.60965 14.23595 0 40.59075 14.82022 0 41.21136 13.84739 0 40.74302 13.54696 0 40.09091 14.50587 0 40.22378 13.34696 0 39.67491 13.25557 0 39.51128 14.3933 0 39.11888 13.27654 0 38.57845 13.40901 0 39.07294 14.45805 0 40.55853 14.88923 0.07205384 40.45185 14.83539 5.935148 40.91159 15.56815 5.961895 40.9998 15.74148 0.06716579 40.91628 16.37873 5.951858 40.9138 16.56028 0.06881308 40.69079 16.93357 5.850426 40.41328 17.21761 0.06649893 40.04181 17.38109 5.936767 39.63711 17.51612 0.0659691 39.23817 17.43466 5.98368 38.81976 17.36214 0.06545126 38.49833 17.09041 5.930177 38.20524 16.80152 0.064947 38.05984 16.33296 5.948991 37.97701 16.00152 0.064462 38.03813 15.61279 5.85148 38.20329 15.20082 0.06399357 38.3973 15.05454 5.962274 38.80849 14.65227 5.850342 39.09675 14.5318 0.06473433 39.55935 14.52133 5.939351 40.51354 13.3687 -1.0394e-5 41.00114 13.65982 -2.84589 42.10545 14.92173 -1.03761e-5 42.02502 14.81183 -2.851102 42.26137 16.18324 -2.850361 42.19997 16.59146 -8.81425e-7 41.41604 18.06878 -1.03777e-5 40.02895 18.71643 -2.85036 39.88307 18.73733 -8.93085e-7 38.63871 18.65436 -2.851103 38.49813 18.601 -3.67795e-6 37.017 17.33633 -1.03979e-5 36.75612 15.39891 -2.845104 36.75405 15.68469 -8.89505e-7 37.3845 14.13568 -1.04107e-5 38.84197 13.31547 -9.01939e-7 39.80851 13.2498 -2.850359 39.56818 17.24796 -2.875808 40.61485 16.56492 -2.875808 40.54665 15.31698 -2.875799 39.42943 14.75221 -2.875863 38.3852 15.4351 -2.875774 38.45335 16.68302 -2.875799 38.76804 14.7804 -1.742881 39.5 16 -0.9783121 38.05884 16.07056 -1.782641 38.84339 17.28507 -1.783531 40.29618 17.20151 -1.765801 40.93992 15.9139 -1.787682 40.16336 14.72692 -1.78942 39.21611 14.421 -0.008422791 39.64255 14.41893 -0.02759134 40.58898 14.82188 -0.008422136 40.94103 15.29483 -0.008423805 38.66488 14.63018 -0.008423924 38.22444 15.02937 -0.0115022 38.01432 15.40932 -0.003898799 37.90291 15.84099 -0.006250917 37.9259 16.27992 -0.003898143 38.05897 16.70517 -0.008424282 38.41102 17.17812 -0.008423924 38.90999 17.4926 -0.006248652 39.33845 17.59061 -0.003897964 39.78411 17.57964 -0.006251633 40.2 17.43741 -0.003897368 40.5726 17.19304 -0.008421719 40.93115 16.725 -0.008421182 41.09708 16.15901 -0.006250023 41.0741 15.72008 -0.003897547 40.09001 14.5074 -0.006249606 40.72695 15.63706 4.000001 41.06512 14.00865 4.000001 40.21008 14.97127 4.000001 39.2876 14.73824 4.000001 40.49568 16.80359 4.000001 41.73288 17.19555 4.000001 41.97896 15.48057 4.000001 39.93412 13.53798 4.000001 38.55799 13.64889 4.000001 38.56436 15.1711 4.000001 37.26712 14.80446 4.000001 38.21813 16.04972 4.000001 37.02104 16.51943 4.000001 38.56436 16.8289 4.000001 37.58489 17.60697 4.000001 39.40427 17.27592 4.000001 38.71036 18.40656 4.000001 40.44201 18.35111 4.000001 40.21008 14.97127 38.5 41.18933 14.11287 38.5 40.75508 15.75117 38.5 42.00712 15.64025 38.5 40.41775 16.89156 38.5 39.40427 14.72408 38.5 38.71036 13.59344 38.5 39.93412 13.53798 38.5 39.2876 17.26176 38.5 39.06588 18.46202 38.5 37.81068 17.88714 38.5 38.56436 16.8289 38.5 38.21813 15.95028 38.5 36.99288 16.35975 38.5 37.34819 14.66404 38.5 38.56436 15.1711 38.5 41.65181 17.33597 38.5 40.28964 18.40656 38.5 39.91757 14.59421 42.98874 40.73496 13.55458 42.92678 41.68728 14.37536 42.94532 40.92629 15.65828 42.98952 38.48917 14.93677 42.98899 39.12714 13.36178 43.00144 38.07379 16.34379 42.98899 37.33094 14.4526 43.00144 39.08463 17.40702 42.98899 37.64199 17.90973 43.00144 36.87589 16.2361 43.00052 39.33601 18.62967 43.00046 40.51083 17.06324 42.98899 41.10634 18.12578 43.00144 42.14746 16.30032 43.00144 42.26845 15.4645 39.99999 41.7955 17.6376 39.99999 40.16726 18.70623 40 38.22889 18.51701 39.99999 37.0679 17.31323 40 36.69821 15.68218 39.99999 37.42385 14.17537 40 38.55337 14.79146 39.97613 38.56237 13.37516 40 39.95024 13.27292 40 40.01925 14.53166 39.98036 41.23159 13.81584 40 39.21746 14.54537 34.05341 39.82682 14.58246 34.04506 39.19403 14.50636 39.97753 38.58862 14.78879 34.1532 38.20423 15.33271 34.0399 38.0678 15.45254 39.97579 37.99048 15.89557 34.14958 37.9846 16.26127 39.97457 38.17674 16.65288 34.05413 38.36829 17.03539 39.97632 38.73997 17.27088 34.06991 38.86109 17.3841 39.97534 39.41028 17.53306 39.97853 39.5024 17.51263 34.14895 40.21437 17.35849 39.97481 40.28884 17.29045 34.14874 40.73286 16.89871 39.97788 40.84482 16.6917 34.14852 41.04779 16.12573 39.97776 40.93666 16.16928 34.00852 40.91621 15.46249 34.14966 40.79254 15.17076 39.97665 40.44607 14.87304 34.05173 39.94377 17.33414 33.99686 39.53935 13.23283 42.85036 38.04195 13.59911 42.8451 36.83634 15.13017 42.85814 36.90601 17.07769 42.8451 38.00462 18.33821 42.85502 39.45856 18.79029 42.8511 41.19347 18.24106 42.8451 42.08642 16.98448 42.85036 42.26186 15.60053 42.8511 38.61345 16.88095 42.87581 38.2938 15.6727 42.8758 39.18035 14.79177 42.8758 40.38819 15.12076 42.87586 40.70614 16.32728 42.87577 39.81965 17.20823 42.8758 40.86042 15.58472 41.74288 39.5 16 40.97831 40.52282 17.01773 41.78264 39.12677 17.39401 41.78353 38.10402 16.35884 41.7658 38.48851 14.97156 41.78768 39.86019 14.61038 41.78942 71.3628 -78.34281 17.75108 72.27062 -79.20208 17 71.68598 -79.56987 17.00281 72.63292 -78.46927 17.00264 70.94706 -79.52165 17 70.40848 -79.1714 17.00695 70.10372 -78.35475 17.00117 70.30359 -77.65042 17.00168 71.03961 -77.11576 17.00281 71.77851 -77.16397 17 72.34113 -77.53496 17.00392 79.58805 -87.64846 17.75108 80.64726 -88.34087 17.00168 80.10789 -88.78524 17 79.42805 -88.90724 17.00281 78.56227 -88.39606 17.00267 80.8474 -87.38716 17.00339 78.32881 -87.65162 17.00096 78.52885 -86.95606 17.00168 79.32232 -86.40729 17.00267 80.20796 -86.54129 17.00281 69.01838 -94.17012 17.75107 69.76158 -95.2004 16.99954 68.85839 -95.4289 17.00281 68.02886 -94.96446 17.00281 70.23883 -94.47247 17.00232 67.75914 -94.17328 17.00096 67.95918 -93.47772 17.00168 68.70246 -92.93897 17.00329 69.63829 -93.06295 17.00281 70.21701 -93.76709 17.00259 60.79312 -84.86447 17.75108 61.85232 -85.55688 17.00168 61.31296 -86.00125 17 60.63311 -86.12326 17.00281 59.8036 -85.65882 17.00281 62.05236 -84.86135 17.00096 59.53387 -84.86759 17.00096 59.86579 -83.98675 17.01732 60.90963 -83.60552 17.00823 61.77146 -84.05662 17.00392 85.18434 -85.95542 13.59365 84.84348 -85.90007 12.81053 84.36688 -87.70511 12.40773 83.6197 -85.71815 12.01772 83.62961 -88.3207 12.0799 84.93318 -89.02523 13.67892 84.69583 -88.98977 13.02826 82.64183 -90.62826 12.00618 83.75162 -90.79182 12.42953 84.38897 -90.88694 13.3846 72.60028 -78.62107 12 72.09072 -79.38516 12 71.41893 -79.59156 12 70.68139 -79.41403 12 70.14991 -78.70935 12 70.15578 -77.9807 12 70.63487 -77.30047 12 71.30666 -77.09407 12 72.312 -77.47228 12 80.72556 -88.25368 12 79.77874 -88.89676 12 78.93188 -88.73741 12 78.35794 -87.91934 12 78.38104 -87.28635 12 78.86013 -86.60611 12 80.14205 -86.48574 12 80.80093 -87.28193 12 70.10868 -94.83531 12 69.30281 -95.40927 12 68.36221 -95.25907 12 67.80551 -94.53666 12 67.88088 -93.56491 12 68.7644 -92.92621 12 69.67455 -93.08117 12 70.23126 -93.8036 12 61.93062 -85.46968 12 60.98381 -86.11277 12 60.13694 -85.95342 12 59.58025 -85.23103 12 59.58609 -84.50238 12 60.1487 -83.77851 12 61.34712 -83.70175 12 62.00598 -84.49794 12 57.29014 -81.81844 12.03097 56.84871 -83.76372 12.06942 55.27956 -86.57436 13.20894 55.27383 -84.62198 13.76099 56.07769 -84.46833 12.38369 56.62218 -86.77326 12.04514 56.27061 -81.6688 12.81115 55.61894 -83.52531 13.12969 55.66886 -82.49118 13.80053 55.95482 -81.62055 13.64835 65.4161 -83.01782 12 55.91742 -81.60413 15.49982 65.39339 -82.97826 15.5 68.47632 -80.76795 12 67.36724 -81.23223 15.5 66.97812 -81.47185 12 68.4763 -80.76796 15.5 69.83416 -71.60041 12.85509 69.67475 -72.68141 12.04778 69.86665 -71.21743 15.49978 69.88685 -71.25559 13.68622 73.42233 -81.50059 15.5 73.42234 -81.50061 12 74.62863 -73.35604 12.03097 74.77826 -72.3365 12.81114 74.85754 -71.97034 15.49976 74.82339 -71.99657 13.54815 75.69966 -84.54274 15.5 75.73212 -84.50968 12 74.65215 -82.60858 15.5 74.34918 -82.26644 12 85.20802 -85.93344 15.49989 74.96508 -89.49513 12 84.45723 -90.91984 15.49985 74.94646 -89.48821 15.5 71.9058 -91.78975 15.5 71.90488 -91.74497 12 73.29853 -91.1177 12 73.9915 -90.59989 15.5 70.54701 -100.9125 12.85508 70.70642 -99.83153 12.04778 70.51453 -101.2955 15.49978 70.49432 -101.2573 13.68622 67.6454 -86.31581 12 71.41182 -84.02262 12 69.34767 -83.8542 12 68.08036 -84.91596 12 72.72045 -85.80925 12.00008 72.21413 -87.78151 12 70.51565 -88.78151 12 66.95883 -91.01234 12 65.93171 -90.14951 12 68.5316 -88.1876 12 64.65122 -87.97528 12 66.95884 -91.01235 15.5 65.75254 -99.15691 12.03097 65.60292 -100.1764 12.81114 65.52363 -100.5426 15.49976 65.55778 -100.5164 13.54815 65.84714 -90.05735 15.5 64.67353 -87.98828 15.5 55.17252 -86.56951 15.49989 63.3967 -72.88325 15.5 61.16631 -74.24228 15.5 65.91654 -71.84894 15.5 58.28103 -77.08234 15.5 56.91107 -79.28119 15.5 72.68336 -72.91461 12.06942 71.97869 -72.14357 12.38369 72.00296 -71.43935 13.29583 84.15701 -80.70818 15.5 84.92195 -83.43034 15.5 78.55003 -73.77056 15.5 81.20286 -76.03031 15.5 82.90099 -78.29119 15.5 79.21488 -98.27064 15.5 75.79833 -100.1817 15.5 73.51087 -100.8844 15.5 81.8769 -95.70147 15.5 83.47013 -93.23168 15.5 67.69786 -99.59835 12.06942 68.40249 -100.3694 12.38369 68.37815 -101.0736 13.29583 56.59629 -92.59642 15.5 55.55956 -89.6168 15.5 62.7724 -99.29375 15.5 60.52097 -97.76052 15.5 57.87952 -94.87132 15.5 62.40774 -73.39453 23.7 59.59961 -75.59458 23.7 56.15336 -80.96908 23.7 70.03987 -71.24467 23.69991 73.33608 -71.56228 23.70003 76.80168 -72.76409 23.7 79.1573 -74.23157 23.7 85.0904 -88.47917 23.70012 55.27566 -84.19918 23.70003 57.43043 -78.32196 23.7 66.12516 -71.79099 23.7 81.34743 -76.19154 23.7 83.46854 -79.22268 23.7 85.03562 -83.64649 23.7 76.33076 -99.97873 23.7 79.38841 -98.14111 23.7 82.01352 -95.53347 23.7 68.83976 -101.2231 23.70004 66.2969 -100.7379 23.69982 64.43369 -100.1078 23.7 58.89893 -96.14875 23.7 57.4802 -94.22178 23.7 56.08453 -91.39242 23.7 83.83049 -92.55973 23.7 72.44417 -101.1124 23.7 61.83116 -98.7424 23.7 55.26721 -88.00888 23.7 72.65818 -97.0026 23.7 74.76519 -96.26012 23.7 77.08295 -94.85151 23.7 79.24023 -92.54004 23.7 62.3494 -94.011 23.7 65.14202 -96.04888 23.7 67.93248 -97.04856 23.7 70.15686 -97.25642 23.7 59.41306 -88.58312 23.7 60.51768 -91.5483 23.7 59.79568 -82.58367 23.7 59.19773 -85.42449 23.7 67.52967 -75.56541 23.7 65.61598 -76.25283 23.7 63.45075 -77.53047 23.7 61.30491 -79.72488 23.7 75.42082 -76.55014 23.7 73.34709 -75.71909 23.7 70.67572 -75.24993 23.7 81.10083 -84.85411 23.7 80.44287 -82.22286 23.7 78.87507 -79.47716 23.7 77.46871 -78.00852 23.7 80.64387 -89.73347 23.7 81.18772 -87.00169 23.7 59.21352 -85.2563 25.9 59.85721 -82.4082 25.9 61.41792 -79.57749 25.9 63.59733 -77.41645 25.9 66.47087 -75.87707 25.9 68.64553 -75.36553 25.9 71.35701 -75.30116 25.9 74.42046 -76.08359 25.9 76.20987 -77.04951 25.9 78.15968 -78.63664 25.9 79.51153 -80.41525 25.9 80.67319 -82.86614 25.9 81.20295 -85.9591 25.9 81.07186 -87.86827 25.9 80.4085 -90.37378 25.9 78.83334 -93.08892 25.9 76.53694 -95.26221 25.9 73.71781 -96.69381 25.9 71.73564 -97.14742 25.9 69.02414 -97.21178 25.9 67.03414 -96.79387 25.9 64.54476 -95.71712 25.9 62.22151 -93.87633 25.9 60.42799 -91.38568 25.9 59.37324 -88.40172 25.9 72.11896 -87.88617 25.9 70.96258 -88.65822 25.9 69.62197 -88.70639 25.9 68.53648 -88.13102 25.9 67.91014 -87.33534 25.9 68.18375 -84.74054 25.9 67.68681 -85.90106 25.9 69.1509 -83.98292 25.9 70.13253 -83.73436 25.9 71.55464 -84.13188 25.9 72.4228 -85.09775 25.9 72.69436 -86.6119 25.9 68.17826 -84.68498 35.2 69.637 -83.80311 35.2 70.5569 -83.78345 35.2 71.62567 -84.18164 35.2 72.55068 -85.38736 35.2 72.61386 -87.05741 35.2 69.31867 -88.61553 35.2 70.54173 -88.73168 35.2 71.41819 -88.45156 35.2 68.1745 -87.76008 35.2 67.65228 -86.46941 35.2 72.64319 -85.52459 15.50049 72.36169 -87.57453 15.50041 70.71181 -88.74842 15.5 68.68745 -88.31124 15.5 67.65781 -86.51437 15.5 68.08036 -84.91596 15.5 69.16267 -83.92734 15.5 71.23367 -83.93409 15.5 56.81039 -64.38309 11.98899 55.65324 -63.39631 12.00257 55.40415 -64.87754 11.9908 54.17406 -64.88075 12.0009 55.15317 -66.30947 11.98815 54.23311 -66.99481 12.00235 56.26448 -67.26582 11.98903 56.19153 -68.38534 12.00257 57.91097 -67.93231 12.00025 57.64852 -66.78124 11.9883 58.9004 -66.76821 12.0009 57.92144 -65.34046 11.9883 58.99522 -65.28746 12.00025 58.03355 -63.71744 12.00235 58.27642 -65.96414 8.960191 58.7323 -64.13847 9 57.86026 -64.69496 8.960119 57.69734 -63.31149 9 56.3966 -63.06021 9 54.80941 -67.98682 9 55.6704 -67.31474 8.97125 56.31592 -68.61585 9 56.51212 -67.55795 8.966372 57.94638 -68.20677 9 57.63631 -67.18202 8.961619 58.89206 -67.27906 9 59.33491 -65.70771 9 55.85837 -64.23044 8.973481 55.12808 -63.44219 9 54.18238 -64.36994 9 55.10237 -64.80848 8.966835 53.77615 -65.63091 9 55.03726 -66.69174 8.971082 54.00244 -66.93618 9 54.97224 -65.8487 8.864503 55.03245 -66.05453 -2.746942 55.19172 -65.12008 -2.750917 55.16799 -65.10312 8.781973 55.85754 -64.46658 -2.750779 55.83766 -64.45883 8.711779 56.75381 -64.30458 8.713602 56.99956 -64.35958 -2.763265 57.88016 -65.1182 -2.750456 58.07439 -65.62554 8.711047 58.03999 -66.03785 -2.749777 57.88483 -66.5372 8.716979 57.61626 -66.8982 -2.746326 57.47616 -67.02086 8.712427 56.76691 -67.32539 -2.75075 56.79394 -67.337 8.711148 55.87291 -67.20843 8.713267 55.6471 -67.07574 -2.763715 55.21125 -66.58791 8.705645 55.24822 -65.55904 -3.005136 56.48499 -67.11068 -3.000453 55.61911 -66.69164 -3.000546 57.68112 -66.47528 -3.005136 57.6072 -65.11161 -3.001961 56.39136 -64.51654 -3.005136 54.17456 -67.32712 11.75555 55.76518 -68.51597 11.75555 57.41231 -68.4511 11.75254 58.78001 -67.5008 11.75555 59.32758 -65.59197 11.75555 58.68283 -64.07485 11.75254 57.62399 -63.27815 11.75253 56.31616 -63.06478 11.75254 55.05898 -63.48362 11.75254 54.14044 -64.43875 11.75254 53.77099 -65.71131 11.75254 57.37343 -64.89567 11.87579 56.15096 -64.63587 11.8758 55.31473 -65.5647 11.8758 55.70276 -66.75491 11.87587 56.92349 -67.01309 11.8758 57.75973 -66.08426 11.8758 56.88036 -64.43814 10.73433 56.53723 -65.82449 9.978313 56.15162 -64.63577 10.67698 55.44469 -64.90458 10.73448 55.17618 -66.28727 10.76475 57.91093 -65.39931 10.77152 57.59031 -66.80398 10.75803 56.23453 -67.23533 10.80094 56.73396 -64.14628 8.937381 57.5489 -64.66413 8.742897 70.75352 93.52175 1.011005 70.78395 92.00127 0.9974345 69.48007 92.74692 1.009202 68.6983 91.7972 0.9990947 68.21315 93.45987 1.01185 67.49253 92.66188 0.9997467 66.9246 94.0802 0.999095 68.17721 94.92558 1.010974 67.30558 95.51422 0.999696 68.43027 96.54819 0.999095 69.42895 95.68947 1.011705 70.33092 96.75975 1.066193 70.79048 96.3958 0.9990949 70.71664 94.98789 1.011704 71.89768 94.97068 0.9990948 71.871 93.48712 0.9997467 71.93119 95.48047 4 71.21001 94.23984 4.031361 72.23285 94.19052 4 71.90051 92.90811 4 66.78586 94.9179 4 67.67744 93.96344 4.015468 68.40052 95.62545 4.028554 67.61428 96.32465 4 69.16436 96.97497 4 69.76446 95.94593 4.035564 70.77347 96.69921 4 70.80758 95.32134 4.031349 70.93649 93.31513 4.030896 71.01025 91.92704 4 69.90282 92.42584 4.015678 69.76605 91.47206 4 68.45292 91.64743 4 68.31369 92.89011 4.028406 67.3717 92.41291 4 66.77007 93.59324 4 68.60852 92.93433 4.218325 68.33392 93.20496 15.74694 69.15783 92.73621 15.75091 70.08529 92.83737 15.75078 70.08028 92.80386 4.21883 70.76572 93.39373 4.256206 70.89154 93.65317 15.76326 70.99317 94.31249 4.293378 70.86243 94.81517 15.75046 70.59295 95.28684 4.288957 70.25212 95.52143 15.74978 69.76746 95.71773 4.283013 69.31798 95.7386 15.74633 68.95858 95.68632 4.217058 68.44941 95.35207 15.75075 68.20904 95.12827 4.216413 67.93317 94.32746 15.76372 68.28565 93.63985 16.00514 68.43694 94.99792 16.00045 69.30415 95.47609 16.00055 70.40665 95.14313 16.00514 70.68098 93.80529 16.00196 69.65579 92.92134 16.00514 67.09276 92.73636 1.244449 66.69898 94.3371 1.247463 67.06862 95.60961 1.247463 67.98727 96.56458 1.247463 69.24451 96.98326 1.247467 71.13005 96.43556 1.247469 71.96734 95.40848 1.247462 72.23142 94.10995 1.247463 71.8618 92.83745 1.247468 70.94313 91.88246 1.247466 69.6859 91.46378 1.247464 68.3781 91.67733 1.247465 70.71361 94.28211 1.124211 70.14019 93.17166 1.124199 68.89174 93.11305 1.124203 68.21666 94.16729 1.124127 68.79025 95.27539 1.124202 70.03865 95.33399 1.124201 70.75525 93.61074 2.265673 69.4652 94.22351 3.021688 70.1407 93.17211 2.323017 69.48484 92.79541 2.265522 68.2449 93.4636 2.235245 70.66442 95.01705 2.228475 69.37448 95.65884 2.24197 68.18183 94.88309 2.19906 67.92513 94.46035 4.148309 68.01897 93.68119 4.221113 69.34052 92.69182 4.21356 52.21277 81.76323 0 52.21287 81.76309 -2.158655 49.46292 83.35094 -2.158651 49.46277 83.35095 0 51.21767 82.34056 -2.405726 50.33897 82.83838 -2.387337 48.44092 82.78425 -2.396921 46.71277 81.7632 -2.159142 46.71277 81.76323 0 47.83598 82.40089 -2.412846 47.80219 82.3675 -2.413881 46.71857 80.74506 -2.387209 46.72507 79.90007 -2.40469 46.71277 78.5878 0 46.72042 78.57925 -2.194079 47.85199 77.94499 -2.404339 46.81521 79.43195 -2.4 47.07087 78.79573 -2.403155 47.49504 78.25444 -2.4 49.46266 77.00009 -2.158649 49.46277 77.00009 0 48.5866 77.51264 -2.387336 50.48464 77.56679 -2.396915 52.21277 78.5878 0 52.20416 78.57926 -2.184565 52.15489 79.55334 -2.413419 52.19986 79.89585 -2.404341 51.28907 78.1127 -2.394967 51.85355 78.7941 -2.402907 52.20679 80.74846 -2.387359 48.04421 80.79669 -2.398667 50.75708 81.03573 -2.398513 50.88133 79.55433 -2.398667 51.72173 78.6072 -2.4 51.43051 78.25444 -2.4 49.61201 78.60866 -2.397096 52.11034 79.43195 -2.4 51.95045 79.00336 -2.4 48.16847 79.3153 -2.398513 47.20381 78.6072 -2.4 46.97509 79.00336 -2.4 46.81521 79.43195 -2.4 47.49504 78.25444 -2.4 49.31353 81.74238 -2.397096 51.08483 77.95484 -2.4 50.63673 80.66224 -2.1265 49.86449 81.36663 -2.128955 48.8598 81.28977 -2.126377 48.31245 80.63842 -2.128828 48.28883 79.68878 -2.126501 49.06107 78.9844 -2.128962 50.06573 79.06127 -2.126376 50.6131 79.71263 -2.128828 50.63672 79.68878 -0.2734984 50.00146 79.0574 -0.2711547 49.31169 78.93627 -0.272987 48.43442 79.41699 -0.2737479 48.28882 80.66224 -0.2735005 48.92409 81.29365 -0.2711603 49.61384 81.41477 -0.2729929 50.49112 80.93406 -0.2737507 47.9134 80.51303 -0.005117237 49.05072 81.66699 -0.002105772 50.43916 81.38146 -0.002367079 51.01214 79.83799 -0.005117893 49.87483 78.68405 -0.00210613 48.48638 78.96959 -0.002366304 46.82993 68.39445 11.98899 48.35518 69.98642 12.00235 47.25662 69.8227 11.9908 47.09997 71.66467 12.0009 46.24579 70.86752 11.98815 44.9996 71.9119 12.00235 44.81885 70.53073 11.98903 43.48501 70.46352 12.00102 44.39722 69.12622 11.9883 43.35418 68.98556 12.00025 44.0591 67.63013 12.0009 45.40232 68.05846 11.98829 45.71837 66.92036 12.0009 47.69288 67.67768 12.00257 44.87738 66.82769 9 45.61241 67.72947 8.963834 46.86296 66.86235 9 46.98755 68.14035 8.968295 48.14333 67.95149 9 44.19386 71.73912 9 44.58219 70.69277 8.965364 43.09445 70.08533 9 44.09518 69.59187 8.96865 43.36819 68.11844 9 44.41863 68.41652 8.968361 48.58004 69.20223 9 47.53442 69.22209 8.961218 48.38549 70.51266 9 47.31743 70.36772 8.962645 47.37468 71.79463 9 46.12714 71.19867 8.965065 45.75098 72.22966 9 46.70668 70.70249 8.713486 46.52299 70.81532 -2.746941 47.1853 70.13716 -2.750908 47.20279 70.13814 8.712887 47.32254 69.21437 -2.750779 47.34049 69.22589 8.71177 46.92671 68.39408 8.713596 46.73776 68.2276 -2.763262 45.60634 67.96121 -2.750461 45.08179 68.10231 8.711045 44.76844 68.37255 -2.749783 44.45571 68.79161 8.716982 44.32157 69.2211 -2.746325 44.30469 69.40655 8.712418 44.47529 70.1593 -2.750748 44.45002 70.14427 8.711148 45.09543 70.81374 8.71326 45.33556 70.91842 -2.763719 46.27173 70.66984 -3.000453 44.93777 70.43528 -3.005136 44.62557 68.91999 -3.005136 45.97021 68.15481 -3.005136 47.06241 69.81001 -3.001961 46.93284 68.85742 -3.000546 46.97269 71.982 11.75254 45.67045 72.22705 11.75254 44.10107 71.66958 11.75555 43.18523 70.29896 11.75254 43.14996 68.63389 11.75555 44.10676 67.29154 11.75254 45.31252 66.74198 11.75253 46.63558 66.81571 11.75254 48.02594 67.73255 11.75555 48.58715 69.2825 11.75254 48.22292 70.90763 11.75555 46.08427 68.24029 11.87579 47.01309 69.07651 11.8758 46.75331 70.29901 11.8758 45.56237 70.68479 11.87587 44.63587 69.84904 11.8758 44.89566 68.62655 11.8758 46.74427 68.37021 10.73433 45.82448 69.46278 9.978313 47.01279 69.0759 10.67698 47.21092 69.80581 10.73447 46.25023 70.83586 10.76476 45.36088 68.10157 10.77152 44.41305 69.18669 10.75803 44.86112 70.53704 10.80094 46.16846 67.96224 8.7429 45.94527 70.9971 8.742444 57.60556 66.82993 11.98899 56.66505 68.33721 12.00025 56.1773 67.25662 11.9908 54.89747 67.82194 12.00235 55.13248 66.2458 11.98815 54.05823 66.25428 12.00025 54.35687 64.43759 12.00257 55.46928 64.81886 11.98903 55.81177 63.41537 12.00025 56.87378 64.39723 11.98829 57.33955 63.40964 12.0009 58.53255 64.2919 12.00025 57.94154 65.40232 11.98829 59.11259 66.03928 12.00235 58.06877 67.85648 12.00102 59.24129 65.23371 9 58.26672 65.76713 8.967735 59.13766 66.86296 9 57.85825 67.10719 8.981367 58.04851 68.14333 9 54.12144 64.47358 9 55.75692 64.14408 8.979701 55.27941 63.32277 9 57.25468 63.11784 9 57.99235 64.74366 8.984503 58.657 64.04473 9 56.73211 67.53994 8.971039 56.79776 68.58005 9 55.19287 68.28078 9 55.71128 67.35388 8.964409 54.85806 66.25032 8.962116 54.05311 67.04521 9 53.77035 65.751 9 54.88405 65.31114 8.969837 55.29004 66.72322 8.78694 55.18469 66.523 -2.746937 55.86283 67.18529 -2.750909 55.86186 67.20279 8.712886 56.78565 67.32255 -2.750781 56.77413 67.34049 8.71177 57.58482 66.96623 8.772481 57.7724 66.73777 -2.763262 58.0388 65.60638 -2.750457 57.98459 65.35591 8.71298 57.62747 64.76847 -2.749778 57.20837 64.4557 8.716989 56.77892 64.32157 -2.746326 55.84071 64.47529 -2.750746 55.85386 64.43669 8.780735 55.19751 65.05982 8.743253 55.08159 65.33557 -2.763721 55.01578 65.98642 8.705647 55.25259 65.87679 -3.001961 55.99285 67.02693 -3.001472 55.73982 64.81594 -3.001961 57.08001 64.62557 -3.005135 57.7784 65.59129 -3.000546 57.50974 66.71118 -3.005135 54.018 66.97269 11.75254 53.77297 65.67047 11.75253 54.16117 64.4035 11.75254 55.38411 63.27293 11.75555 57.36611 63.14997 11.75555 58.70845 64.10675 11.75254 59.25802 65.31252 11.75253 59.09234 66.9697 11.75555 57.98074 68.18693 11.75253 56.71749 68.58716 11.75254 55.09236 68.22293 11.75555 57.75971 66.08426 11.87579 56.92349 67.01309 11.8758 55.701 66.75331 11.8758 55.31522 65.56237 11.87587 56.15096 64.63587 11.8758 57.37345 64.89566 11.8758 57.62979 66.74427 10.73433 56.53723 65.82449 9.978313 56.92411 67.0128 10.67698 56.1942 67.21092 10.73447 55.16414 66.25024 10.76476 57.89843 65.36089 10.77152 56.81331 64.41305 10.75803 55.46297 64.86112 10.80094 57.30272 64.31232 8.931707 57.75205 64.8804 8.778816 58.05108 66.13368 8.779545 56.58811 64.28883 8.78618 40.72695 -15.63706 38.5 41.06512 -14.00865 38.5 40.21008 -14.97127 38.5 39.2876 -14.73824 38.5 40.49568 -16.80359 38.5 41.73288 -17.19555 38.5 41.97896 -15.48057 38.5 39.93412 -13.53798 38.5 38.55799 -13.64889 38.5 38.56436 -15.1711 38.5 37.26712 -14.80446 38.5 38.21813 -16.04972 38.5 37.02104 -16.51943 38.5 38.56436 -16.8289 38.5 37.58489 -17.60697 38.5 39.40427 -17.27592 38.5 38.71036 -18.40656 38.5 40.44201 -18.35111 38.5 40.21008 -14.97127 4 41.18933 -14.11287 4 40.75508 -15.75117 4 42.00712 -15.64025 4 40.41775 -16.89156 4 39.40427 -14.72408 4 38.71036 -13.59344 4 39.93412 -13.53798 4 39.2876 -17.26176 4 39.06588 -18.46202 4 37.81068 -17.88714 4 38.56436 -16.8289 4 38.21813 -15.95028 4 36.99288 -16.35975 4 37.34819 -14.66404 4 38.56436 -15.1711 4 41.65181 -17.33597 4 40.28964 -18.40656 4 47.14379 -27.77011 -2 30.09992 -33.55859 -2 47.14379 -27.77011 0 30.09992 -33.55859 0 55.18335 -51.44215 -2 55.18335 -51.44215 0 38.13948 -57.23063 -2 38.13948 -57.23063 0 49.18961 -81.61692 11.98899 51.11668 -82.10938 12.0009 50.59585 -81.12246 11.9908 52.04684 -80.21002 12.00235 50.84682 -79.69053 11.98815 50.9591 -78.06848 12.00235 49.73552 -78.73419 11.98903 48.89705 -77.69468 12.00102 48.35148 -79.21878 11.9883 47.39413 -78.69367 12.0009 46.94553 -80.76042 12.00235 48.07856 -80.65956 11.9883 47.97905 -82.20744 12.00025 49.41836 -82.71965 12.00102 46.77434 -80.95845 9 47.59637 -80.72253 8.999633 47.96961 -82.54431 9 48.67742 -81.82689 8.984345 49.60341 -82.9398 9 51.19059 -78.01319 9 50.07265 -78.54674 8.967817 49.98777 -77.45791 9 48.6647 -77.52522 9 48.84535 -78.47899 8.985499 47.52447 -78.19966 9 47.9293 -79.32726 8.968361 46.82826 -79.32678 9 50.8497 -81.40244 8.980747 51.14814 -82.41163 9 52.2071 -80.73168 9 51.26441 -79.44245 8.999664 51.99756 -79.06382 9 50.98426 -80.1604 8.713478 50.96755 -79.94548 -2.746942 50.80828 -80.87992 -2.750917 50.83201 -80.89689 8.781973 50.20293 -81.53613 8.772007 50.14247 -81.53343 -2.750777 49.27207 -81.72863 8.840395 49.00044 -81.64044 -2.763262 48.11985 -80.8818 -2.750459 48.01647 -80.64733 8.712978 47.96001 -79.96215 -2.749779 48.11516 -79.4628 8.716983 48.38374 -79.10181 -2.746325 48.6519 -78.85683 8.782939 49.23309 -78.67462 -2.750751 50.1271 -78.79158 8.713264 50.3529 -78.92427 -2.763713 50.4352 -79.28873 -3.005136 50.66842 -80.62211 -3.001961 48.39151 -80.88925 -3.000453 49.30092 -78.92304 -3.000546 48.31888 -79.52473 -3.005136 49.60863 -81.48347 -3.005136 51.96476 -78.99023 11.75254 51.12735 -77.96327 11.75253 49.90856 -77.44309 11.75253 48.58769 -77.54891 11.75253 47.46729 -78.25643 11.75253 46.80401 -79.40363 11.75253 46.74983 -80.72763 11.75253 47.31716 -81.92515 11.75254 48.376 -82.72184 11.75254 50.02994 -82.9175 11.75555 51.70558 -81.85181 11.75555 52.22901 -80.28871 11.75253 48.62657 -81.10434 11.87579 49.84904 -81.36413 11.8758 50.68527 -80.43531 11.8758 50.29723 -79.2451 11.87587 49.07651 -78.98691 11.8758 48.24028 -79.91574 11.8758 49.11964 -81.56188 10.73433 49.46277 -80.17552 9.978313 49.84838 -81.36425 10.67698 50.55531 -81.09543 10.73448 50.82382 -79.71274 10.76476 48.08908 -80.6007 10.77152 48.40969 -79.19603 10.75803 49.76547 -78.76468 10.80094 47.8873 -80.21794 8.866542 48.0683 -81.12866 8.934292 51.12523 -79.76477 8.928236 48.45111 -81.33589 8.742899 50.775 -79.37127 8.742441 49.38154 -78.64169 8.78565 69.36405 -95.68708 1.011006 67.37509 -95.67494 0.9990948 68.12909 -94.85231 1.009203 66.94941 -94.25352 0.9997467 68.2493 -93.40352 1.011849 67.53302 -92.50733 0.9976487 69.56673 -92.76013 1.010973 69.13217 -91.72969 0.9997467 70.64134 -91.96713 0.9989815 70.78273 -93.57973 1.011704 71.67888 -93.0278 0.9997467 71.97361 -94.84519 0.9976484 70.68151 -95.04264 1.011704 70.91904 -96.27692 0.9997467 69.15045 -96.78836 0.997435 71.57837 -96.00096 3.983448 70.69666 -95.43358 4.02765 70.5884 -96.75322 4 69.91908 -95.89669 4.033628 68.97166 -96.97979 4 68.34201 -91.69381 4 68.7301 -92.66291 4.031102 69.95876 -91.46723 4 69.63978 -92.43544 4.022938 71.21851 -92.10493 4 70.8844 -93.21344 4.03357 72.01394 -93.06395 4 72.18516 -94.73619 4 68.75937 -95.82026 4.037357 67.49817 -96.17077 4 66.71302 -94.73943 4 67.8174 -94.81184 4.034296 67.06307 -92.78463 4 67.90235 -93.43326 4.033075 67.94599 -94.10588 4.284836 68.0679 -93.61952 15.74694 67.98508 -94.56383 15.75091 68.03321 -94.7365 4.287179 68.46348 -95.36476 15.75078 68.44229 -95.36722 4.288241 69.28939 -95.74868 4.286399 69.54108 -95.75778 15.76327 70.18275 -95.57546 4.293378 70.58523 -95.24715 15.75046 70.90172 -94.80565 4.288959 70.97296 -94.39807 15.74978 70.94947 -93.8757 4.283035 70.78117 -93.45838 15.74632 70.67675 -93.30422 4.287581 70.06788 -92.82987 15.75075 70.10607 -92.8156 4.219274 69.20812 -92.70252 4.256752 68.92133 -92.78751 15.76372 68.26853 -93.24315 4.295463 68.20778 -93.948 16.00045 68.79689 -93.15196 16.00055 69.93786 -92.99526 16.00514 70.7794 -94.29349 16.00514 69.80477 -95.49501 16.00514 68.50437 -95.07781 16.00196 66.98085 -93.0017 1.247459 68.10715 -91.77489 1.244446 69.72666 -91.46734 1.247463 70.97754 -91.90454 1.247459 72.05968 -93.17051 1.244448 72.16977 -94.81526 1.247461 71.58497 -96.00436 1.247458 70.51459 -96.78548 1.24747 68.85797 -96.9569 1.244446 67.44183 -96.11318 1.24746 66.69411 -94.62502 1.244448 70.03863 -95.33398 1.124213 68.79026 -95.27539 1.124203 68.21678 -94.16491 1.124201 68.89385 -93.11195 1.124125 70.14017 -93.17166 1.124199 70.71363 -94.28211 1.1242 69.44568 -95.65157 2.265674 69.4652 -94.22351 3.021688 68.79086 -95.27567 2.323015 68.17516 -94.83643 2.265522 68.26593 -93.43083 2.235242 70.68625 -94.98303 2.228476 70.73219 -93.54298 2.241968 69.53004 -92.78203 2.199059 71.15665 -94.48484 4.064923 44.38309 -69.18961 11.98899 43.34365 -70.02851 12.00102 44.87753 -70.59585 11.9908 44.34263 -71.53143 12.0009 45.75768 -71.97786 12.00025 46.30947 -70.84682 11.98815 47.23323 -71.58189 12.0009 47.26581 -69.73552 11.98903 48.28407 -70.11474 12.00102 48.19983 -68.63339 12.00025 46.78123 -68.35149 11.98829 47.30634 -67.39414 12.0009 45.23958 -66.94554 12.00235 45.34045 -68.07856 11.9883 43.5923 -68.24108 12.0009 44.71276 -66.928 9 44.58868 -68.15002 8.98781 43.45569 -67.96964 9 44.12686 -69.03919 8.965703 43.06128 -69.91593 9 48.48177 -70.34566 9 47.53846 -69.73888 8.966175 48.47478 -68.66471 9 47.39733 -68.7136 8.969837 47.80034 -67.52448 9 46.78262 -68.01926 8.971481 46.38062 -66.71845 9 45.58386 -67.73754 8.96643 44.20867 -70.26148 8.985075 43.84865 -71.4011 9 44.78319 -70.84808 8.969233 45.26835 -72.20712 9 45.82788 -71.20455 8.960321 47.22803 -71.88574 9 46.99271 -70.83926 8.985499 45.82339 -71.011 8.700813 46.05452 -70.96755 -2.746942 45.12007 -70.80828 -2.750916 44.82583 -70.62786 8.711897 44.46658 -70.14246 -2.750784 44.30458 -69.24621 8.713599 44.35957 -69.00044 -2.763266 44.69808 -68.40324 8.780657 45.11822 -68.11984 -2.750458 45.62553 -67.92561 8.711046 46.03787 -67.96002 -2.749781 46.50507 -68.08553 8.770911 46.89822 -68.38376 -2.746322 47.02087 -68.52384 8.712425 47.32539 -69.2331 -2.750746 47.337 -69.20607 8.711147 47.21649 -70.13999 8.781948 47.07574 -70.3529 -2.763716 46.17183 -70.70067 -3.001961 46.74296 -68.59534 -3.000091 47.11349 -69.72824 -3.005136 45.67863 -68.15483 -3.005136 44.61884 -69.01618 -3.001961 44.85206 -70.34957 -3.005136 46.71801 -72.11641 11.75555 48.25298 -70.85652 11.75555 48.58419 -69.2417 11.75254 48.16534 -67.98452 11.75254 47.21025 -67.06601 11.75254 45.93768 -66.69655 11.75253 44.63916 -66.9608 11.75254 43.39598 -68.06904 11.75555 43.08251 -70.02993 11.75555 43.90542 -71.45829 11.75254 45.05258 -72.12155 11.75253 44.89567 -68.62657 11.87579 44.63587 -69.84905 11.8758 45.56469 -70.68527 11.8758 46.7549 -70.29724 11.87587 47.01309 -69.0765 11.8758 46.08428 -68.24028 11.8758 44.43813 -69.11965 10.73432 45.82448 -69.46278 9.978313 44.63576 -69.84838 10.67698 44.90456 -70.55531 10.73448 46.28726 -70.82382 10.76476 45.39931 -68.08908 10.77152 46.80398 -68.4097 10.75803 47.23532 -69.76547 10.80094 46.71767 -70.71116 8.784855 44.38521 -69.99996 8.785919 53.78723 -67.4122 0 53.78713 -67.41206 -2.158654 56.53711 -68.99991 -2.158652 56.53723 -68.99991 0 54.78233 -67.98953 -2.405727 55.66105 -68.48737 -2.387336 57.5591 -68.43321 -2.396921 59.28723 -67.41217 -2.159143 59.28723 -67.4122 0 58.16402 -68.04986 -2.412848 58.19781 -68.01647 -2.413881 59.28144 -66.39402 -2.38721 59.27492 -65.54904 -2.40469 59.28723 -64.23677 0 59.27958 -64.22822 -2.194079 58.14802 -63.59397 -2.404334 59.18479 -65.08092 -2.4 58.92913 -64.4447 -2.403158 58.50496 -63.90341 -2.4 56.53736 -62.64907 -2.15865 56.53723 -62.64906 0 57.41341 -63.16162 -2.387336 55.51536 -63.21575 -2.396923 53.78723 -64.23677 0 53.79584 -64.22822 -2.184563 53.8451 -65.20231 -2.413421 53.80014 -65.54481 -2.40434 54.71095 -63.76166 -2.394954 54.14645 -64.44307 -2.402909 53.79322 -66.39743 -2.387359 57.95578 -66.44567 -2.398667 55.24292 -66.68471 -2.398513 55.11867 -65.20331 -2.398667 54.27827 -64.25617 -2.4 54.56949 -63.90341 -2.4 56.38799 -64.25762 -2.397096 53.88966 -65.08092 -2.4 54.04955 -64.65233 -2.4 57.83153 -64.96428 -2.398513 58.79618 -64.25617 -2.4 59.0249 -64.65233 -2.4 59.18479 -65.08092 -2.4 58.50496 -63.90341 -2.4 56.68647 -67.39134 -2.397096 54.91516 -63.6038 -2.4 55.36328 -66.31123 -2.1265 56.13552 -67.0156 -2.128958 57.14018 -66.93874 -2.126375 57.68755 -66.28739 -2.128827 57.71118 -65.33777 -2.126501 56.93895 -64.63338 -2.128957 55.93425 -64.71025 -2.126377 55.3869 -65.36158 -2.128828 55.36328 -65.33777 -0.2734997 55.99854 -64.70636 -0.2711595 56.6883 -64.58524 -0.2729906 57.56557 -65.06595 -0.2737501 57.71117 -66.31123 -0.2734985 57.07592 -66.94261 -0.2711583 56.38615 -67.06375 -0.2729901 55.50888 -66.58303 -0.2737499 58.06783 -65.78726 -6.71597e-4 57.58253 -66.97354 -0.002316832 56.38614 -67.33964 -8.75351e-4 55.29589 -66.75626 -0.002307415 55.08019 -65.29516 -0.002431809 56.12517 -64.33302 -0.002105712 57.51361 -64.61856 -0.002367138 47.4122 -72.21278 0 47.41772 -72.20685 -2.178254 48.9999 -69.46292 -2.158651 48.99991 -69.46278 0 48.46796 -70.37618 -2.391055 47.77305 -71.40345 -2.405406 48.49826 -68.60704 -2.38645 47.79649 -67.54524 -2.41051 47.4122 -66.71278 0 47.42067 -66.72131 -2.184845 47.74555 -67.49504 -2.4 47.37767 -67.19145 -2.407157 45.59258 -66.71858 -2.412246 44.23677 -66.71278 0 44.22821 -66.72043 -2.194079 43.59399 -67.85196 -2.404332 45.08091 -66.81521 -2.4 44.4447 -67.07089 -2.403155 43.90341 -67.49504 -2.4 42.64907 -69.46264 -2.158651 42.64906 -69.46278 0 43.16162 -68.5866 -2.387336 43.21575 -70.48464 -2.396923 44.23677 -72.21278 0 44.24193 -72.21411 -2.200862 45.58948 -72.20679 -2.412675 43.76164 -71.28903 -2.394955 44.44309 -71.85358 -2.402912 45.08091 -72.11034 -2.4 47.38121 -71.73132 -2.40574 47.74555 -71.43051 -2.4 46.44568 -68.04423 -2.398667 46.68467 -70.7571 -2.398512 45.20331 -70.88134 -2.398667 44.25617 -71.72174 -2.4 43.90341 -71.43051 -2.4 44.25762 -69.61203 -2.397096 45.08091 -72.11034 -2.4 44.65232 -71.95046 -2.4 44.96426 -68.16848 -2.398513 44.25617 -67.20382 -2.4 44.65232 -66.9751 -2.4 45.08091 -66.81521 -2.4 43.90341 -67.49504 -2.4 47.39134 -69.31354 -2.397096 43.6038 -71.08484 -2.4 46.31121 -70.63674 -2.126501 47.0156 -69.8645 -2.128957 46.93873 -68.85981 -2.126375 46.28741 -68.31247 -2.128827 45.33775 -68.28884 -2.126499 44.63337 -69.06105 -2.128958 44.71024 -70.06575 -2.126376 45.36158 -70.61312 -2.128823 45.33776 -70.63674 -0.273499 44.70636 -70.00148 -0.2711572 44.58523 -69.31172 -0.2729908 45.06592 -68.43446 -0.2737526 46.31122 -68.28884 -0.2735009 46.94261 -68.92409 -0.2711574 47.06374 -69.61383 -0.2729921 46.58298 -70.49117 -0.2737504 46.16198 -67.9134 -0.00511831 47.31596 -69.05073 -0.002105832 47.03043 -70.43914 -0.002365767 45.48695 -71.01215 -0.005117237 44.33301 -69.87484 -0.002105891 44.61855 -68.48638 -0.002366721 40.19377 -14.70798 -2.98874 41.1582 -13.91427 -3.001318 40.96595 -15.95438 -2.989515 38.72559 -14.75399 -2.988995 39.6532 -13.27573 -2.947659 38.03372 -16.04766 -2.988995 36.78751 -15.84182 -2.95327 37.6895 -14.04518 -3.001437 38.80813 -17.29367 -2.988995 36.98745 -17.05891 -2.951326 39.07197 -18.69479 -2.947659 37.69344 -18.09008 -2.916208 41.7949 -17.45467 -2.953269 40.27441 -17.24601 -2.988995 40.15789 -18.65587 -2.94434 42.15405 -15.76485 -3.001437 42.23927 -15.75731 0 41.0988 -16.15946 0 42.23205 -16.31369 0 42.11298 -16.85723 0 40.98786 -16.58844 0 41.88693 -17.36567 0 40.77537 -16.97725 0 41.56317 -17.8182 0 41.15493 -18.19629 0 40.45523 -17.28356 0 40.67895 -18.48447 0 40.06991 -17.50227 0 40.15469 -18.67093 0 39.60364 -18.74805 0 39.63645 -17.59417 0 39.04833 -18.71266 0 39.19369 -17.57727 0 38.51153 -18.56621 0 38.64459 -17.36011 0 38.01519 -18.3147 0 37.57964 -17.96843 0 38.31005 -17.06959 0 37.2227 -17.54157 0 38.05672 -16.70608 0 36.95901 -17.0516 0 36.79933 -16.51857 0 37.89912 -16.13703 0 36.75023 -15.96432 0 36.8137 -15.41152 0 37.92934 -15.69498 0 36.98715 -14.88282 0 38.06676 -15.27375 0 37.26347 -14.39986 0 37.63136 -13.9824 0 38.32518 -14.91382 0 38.07575 -13.64755 0 38.66377 -14.62802 0 38.57845 -13.40901 0 39.07294 -14.45805 0 39.11888 -13.27654 0 39.51128 -14.3933 0 39.67491 -13.25557 0 40.22378 -13.34696 0 40.09091 -14.50587 0 40.74302 -13.54696 0 41.21136 -13.84739 0 40.59075 -14.82022 0 41.60965 -14.23595 0 41.92156 -14.69673 0 40.86622 -15.16727 0 42.13434 -15.21087 0 41.04845 -15.57115 0 39.76974 -14.48953 0.07205271 39.51808 -14.51829 5.946587 40.10728 -14.67809 5.954937 38.85297 -14.62924 5.846804 38.82155 -14.63768 0.06716656 38.4011 -15.03857 5.94652 38.21211 -15.19125 0.06881415 38.04297 -15.59184 5.850424 37.97804 -15.98363 0.06649971 38.0435 -16.40946 5.85063 38.19634 -16.78605 0.06597101 38.46928 -17.10733 5.85084 38.80386 -17.35408 0.06545239 39.19584 -17.48174 5.851048 39.61937 -17.51809 0.06494534 40.01099 -17.42353 5.851264 40.39945 -17.22902 0.06445813 40.82959 -16.77451 5.850087 40.9113 -16.57305 0.06399142 41.00682 -16.54155 0.001528918 40.96188 -15.78579 5.946122 40.92242 -15.45691 0.06473863 40.63037 -15.04988 5.932566 40.52701 -14.88962 0.06313008 40.36735 -17.10969 6.000811 38.91477 -17.27843 6.003135 38.09566 -16.06855 6.003135 40.51354 -13.3687 -1.0394e-5 38.84197 -13.31547 -8.99609e-7 38.69895 -13.35102 -2.850359 37.3845 -14.13568 -1.04132e-5 37.61403 -13.9637 -2.855019 36.92011 -14.99854 -2.850361 36.75405 -15.6847 -8.91779e-7 37.017 -17.33633 -1.03996e-5 38.25065 -18.46553 -8.83696e-7 39.60504 -18.7853 -3.67833e-6 41.41604 -18.06878 -1.0376e-5 41.17028 -18.21665 -2.855018 42.19997 -16.59146 -8.83668e-7 42.23104 -16.44741 -2.850361 42.10545 -14.92172 -1.03769e-5 42.08913 -14.92849 -2.858142 41.00114 -13.65982 -2.84589 38.45334 -16.68303 -2.875808 38.38515 -15.43507 -2.875809 39.43181 -14.75206 -2.875798 40.54794 -15.31899 -2.875863 40.61479 -16.5649 -2.875773 39.56819 -17.24794 -2.875799 40.91635 -15.869 -1.742881 39.5 -16 -0.9783121 40.29538 -17.20388 -1.782642 38.85203 -17.28946 -1.783531 38.06027 -16.06852 -1.765801 38.71789 -14.78794 -1.787682 40.1343 -14.71219 -1.789421 40.94182 -15.29494 -0.006251215 40.58923 -14.82212 -0.008423566 39.51143 -14.39573 -0.008422493 41.07308 -15.71442 -0.003897547 41.09703 -16.15956 -0.006252408 40.77335 -16.97591 -0.008421003 40.33508 -17.37062 -0.006249964 39.92951 -17.54002 -0.00389713 39.48857 -17.60428 -0.00842297 38.90982 -17.49182 -0.008423268 38.41077 -17.17788 -0.008423089 38.05818 -16.70506 -0.006251573 37.92692 -16.28558 -0.003898859 37.90362 -15.84061 -0.008424341 38.069 -15.27469 -0.008424699 38.42765 -14.80673 -0.008423388 38.93112 -14.49993 -0.008423388 40.09019 -14.50819 -0.008422255 39.85029 -14.57595 42.98874 40.19775 -13.42854 43.00144 38.22531 -13.59193 42.94532 38.44207 -14.9842 42.98951 40.90963 -15.59354 42.98899 41.67986 -14.52006 43.00046 40.55681 -17.01754 42.98899 42.21106 -16.26626 42.96047 39.14719 -17.424 42.98899 39.60405 -18.66241 43.00144 41.26779 -18.07329 42.94532 37.64199 -17.90973 43.00144 36.87583 -16.23611 43.00046 38.09037 -16.40646 42.98899 37.21135 -14.69471 43.00052 37.60324 -13.95764 40 36.69821 -15.68218 39.99999 37.0679 -17.31323 40 38.22889 -18.51701 39.99999 40.44855 -18.65543 39.99999 41.75011 -17.60521 40 42.26952 -16.31415 40 41.8329 -14.41614 39.99999 40.63161 -14.96191 39.97968 40.22993 -13.30999 40 39.29278 -14.47467 39.97425 38.83831 -13.31637 40 40.23019 -14.69024 34.07931 40.84248 -15.38827 34.05475 40.94892 -15.51747 39.9734 40.98313 -16.43383 34.15848 41.01248 -16.25159 39.97579 40.79438 -16.80825 39.97792 40.41279 -17.23344 39.97674 40.3072 -17.27964 34.14937 39.79039 -17.49732 39.97775 39.55139 -17.47458 34.05404 39.09999 -17.48257 39.97647 38.74006 -17.27076 34.06982 38.39166 -17.06088 39.97663 38.16707 -16.71472 34.14874 38.00063 -16.3435 39.97492 37.98999 -15.91706 34.14852 38.05869 -15.46756 39.97763 38.40512 -14.95626 34.08495 38.54508 -14.80097 39.97146 39.25334 -14.5494 34.05173 40.7295 -16.68704 33.99919 38.11507 -16.24256 33.99686 40.86478 -13.59248 42.85036 41.97165 -14.66541 42.8451 41.96705 -17.25397 42.85036 40.16444 -18.69479 42.85502 38.64234 -18.65554 42.8511 37.36957 -17.78637 42.84589 36.70919 -16.25109 42.85814 37.14421 -14.5041 42.8511 39.52336 -13.2095 42.8511 39.81965 -17.20825 42.87581 40.7062 -16.3273 42.8758 40.38653 -15.11906 42.8758 39.17805 -14.7924 42.87586 38.29386 -15.67272 42.87577 38.61346 -16.88094 42.8758 38.53609 -14.95402 41.74288 39.5 -16 40.97831 38.10303 -16.36113 41.78264 39.11741 -17.39147 41.78353 40.52313 -17.01525 41.7658 40.8926 -15.62391 41.78768 39.89163 -14.61891 41.78942 40.04496 -14.57886 39.96392 52.21277 -78.5878 0 52.21287 -78.58795 -2.158655 49.46289 -77.00009 -2.158649 49.46277 -77.00009 0 51.21767 -78.01049 -2.405726 50.33895 -77.51264 -2.387336 48.44088 -77.56681 -2.396921 46.71277 -78.58784 -2.159144 46.71277 -78.5878 0 47.83598 -77.95015 -2.412845 47.80219 -77.98353 -2.41388 46.71857 -79.60599 -2.38721 46.72507 -80.45096 -2.40469 46.71277 -81.76323 0 46.72042 -81.77179 -2.19408 47.85198 -82.40604 -2.404334 46.81521 -80.91909 -2.4 47.07087 -81.5553 -2.403159 47.49504 -82.09659 -2.4 49.46263 -83.35094 -2.158651 49.46277 -83.35095 0 48.58657 -82.83838 -2.387337 50.48461 -82.78426 -2.396923 52.21277 -81.76323 0 52.20416 -81.77179 -2.184565 52.1549 -80.79769 -2.413423 52.19986 -80.45519 -2.40434 51.28903 -82.23834 -2.394936 51.85356 -81.55694 -2.402912 52.20679 -79.60258 -2.387359 48.04421 -79.55434 -2.398667 50.75708 -79.3153 -2.398513 50.88133 -80.7967 -2.398667 51.72173 -81.74383 -2.4 51.43051 -82.09659 -2.4 49.61201 -81.74238 -2.397096 52.11034 -80.91909 -2.4 51.95045 -81.34767 -2.4 48.16847 -81.03573 -2.398513 47.20381 -81.74383 -2.4 46.97509 -81.34767 -2.4 46.81521 -80.91909 -2.4 47.49504 -82.09659 -2.4 49.31354 -78.60866 -2.397096 51.08483 -82.3962 -2.4 50.63672 -79.68878 -2.126501 49.86447 -78.9844 -2.128962 48.85982 -79.06127 -2.126377 48.31245 -79.71263 -2.128828 48.28882 -80.66224 -2.126499 49.06105 -81.36663 -2.128955 50.06575 -81.28977 -2.126376 50.6131 -80.63843 -2.128829 50.63673 -80.66224 -0.2735003 50.00146 -81.29365 -0.2711602 49.31171 -81.41477 -0.2729921 48.43442 -80.93406 -0.2737499 48.28883 -79.68878 -0.2734987 48.92409 -79.0574 -0.2711547 49.61385 -78.93627 -0.2729878 50.49113 -79.41698 -0.2737488 47.9134 -79.838 -0.005117952 49.05072 -78.68405 -0.00210613 50.43917 -78.96959 -0.002366304 51.01215 -80.51303 -0.005117237 49.87483 -81.66699 -0.002105772 48.48639 -81.38146 -0.002367138 69.62765 78.9912 1.011005 70.46745 80.79422 0.999095 70.9011 79.76602 1.009203 72.5263 80.31067 0.9976485 72.16803 79.05307 1.011849 73.45657 78.43274 0.9990947 72.20397 77.58737 1.010974 72.91257 76.71203 0.9989818 71.67662 75.89119 0.9997468 70.95223 76.82347 1.011705 69.83615 75.94153 0.9976486 69.66454 77.52505 1.011705 68.4835 77.54226 0.9990949 68.71555 79.64427 0.997435 68.44999 77.03247 4 69.28192 77.65454 4.032123 68.14832 78.32244 4 68.48066 79.60483 4 69.31072 79.02518 4.028633 73.69471 77.9441 4 72.61418 77.95729 4.027804 72.96571 76.42944 4 71.32021 76.58858 4.035565 71.86652 75.68991 4 70.5496 75.54593 4 70.11469 76.74972 4.030138 69.3166 76.03044 4 69.37094 80.58591 4 70.35792 79.94059 4.038468 70.92386 81.08953 4 71.41683 79.94165 4.027651 72.51535 80.5484 4 72.52689 78.93574 4.030138 73.38195 79.5464 4 71.90711 79.49639 4.140627 72.04726 79.30799 15.74694 71.22332 79.77674 15.75092 71.21981 79.79391 4.287131 70.29589 79.67557 15.75078 70.3025 79.69586 4.288234 69.59608 79.09714 4.218864 69.48963 78.85977 15.76326 69.388 78.20046 4.293372 69.51873 77.69779 15.75046 69.78823 77.22611 4.288959 70.12905 76.99151 15.74978 70.61373 76.79521 4.283008 71.06316 76.77433 15.74633 71.24685 76.80503 4.287587 71.93177 77.16088 15.75075 71.92362 77.13262 4.288853 72.40762 77.92667 4.286739 72.44801 78.18548 15.76372 72.34667 78.83176 4.294353 72.05748 78.82965 16.00055 71.1371 79.58677 16.00514 70.89388 77.00236 16.00045 72.08148 77.67822 16.00514 69.73641 77.70577 16.00514 69.88893 79.06288 16.00196 73.28842 79.77658 1.244449 73.67794 77.82935 1.244446 72.91122 76.37009 1.247465 71.7907 75.66269 1.247466 70.46979 75.55707 1.247462 69.25112 76.07739 1.247462 68.41383 77.10447 1.24746 68.14976 78.40299 1.247463 68.51938 79.67549 1.247464 69.43805 80.63049 1.247465 70.69528 81.04917 1.247466 72.00307 80.83561 1.247461 69.66757 78.23082 1.124211 70.24101 79.34129 1.124203 71.48943 79.3999 1.124203 72.16452 78.34564 1.124126 71.59093 77.23756 1.124201 70.34252 77.17895 1.124202 69.62592 78.90219 2.265673 70.91597 78.28942 3.021688 70.24048 79.34084 2.323017 70.89633 79.71753 2.265523 72.13628 79.04934 2.235245 69.71675 77.4959 2.228476 71.00671 76.85411 2.241969 72.19935 77.62985 2.19906 72.27787 77.28132 4.06288 -55.86083 71.37966 8 -55.78458 71.24433 9 -54.67834 70.19944 8 -54.26598 69.96116 9 -53.13416 69.71073 8 -52.65977 69.75282 9 -51.23107 70.22364 8 -51.09076 70.3182 9 -49.96208 71.73181 8 -49.90093 71.88957 9 -49.8292 74.01752 8 -49.89378 74.2003 9 -51.5529 75.99921 8 -51.72987 76.07833 9 -53.55075 76.21819 8 -53.66696 76.19612 9 -55.04073 75.58316 8 -55.44559 75.26019 9 -56.26618 73.64916 8 -56.28937 73.13178 9 -54.60232 72.31455 8 -54.6392 73.50507 8 -53.73321 71.44937 8 -51.3608 72.49494 8 -51.89408 71.6889 8 -52.77851 71.29913 8 -54.10592 74.31111 8 -51.34796 73.46133 8 -51.85964 74.28127 8 -52.95789 74.74227 8 -57.37979 70.55626 9 -57.90766 71.96593 11.5 -57.93597 72.11079 9 -57.9432 73.99972 11.5 -57.89719 74.20508 9 -57.08466 75.91033 11.5 -56.99725 76.02927 9 -55.61243 77.31391 11.5 -55.79706 77.16304 9 -54.29376 77.84568 9 -53.62529 77.97629 11.5 -52.20344 77.97998 9 -51.9756 77.90969 11.5 -50.0988 77.12525 11.5 -50.31114 77.23373 9 -49.08216 76.13129 9 -48.69403 75.57157 11.5 -48.1195 74.27096 9 -48.09234 74.03408 11.5 -48.0568 72.00029 11.5 -48.10282 71.79492 9 -48.91534 70.08969 11.5 -49.00274 69.97076 9 -50.08166 68.92108 11.5 -50.20294 68.83697 9 -51.5642 68.1945 11.5 -51.70624 68.15433 9 -53.20236 67.98867 11.5 -53.34974 67.9968 9 -54.81853 68.32589 11.5 -54.95529 68.38143 9 -56.2377 69.16963 11.5 -56.34901 69.26657 9 -57.30598 70.42844 11.5 -49.99787 72.51317 11.5 -50.17324 74.04786 11.5 -51.07732 75.35651 11.5 -55.54713 71.38732 11.5 -54.39069 70.29524 11.5 -52.20361 70.02599 11.5 -53.16065 76.07461 11.5 -55.14262 75.15847 11.5 -50.67914 71.07589 11.5 -56.07456 73.16161 11.5 -50.13596 73.94122 10 -50.9548 75.25099 10 -52.9753 76.07871 10 -55.27139 75.07841 10 -55.99925 73.30508 10 -55.78394 71.77547 10 -54.53247 70.37297 10 -52.98985 69.98529 10 -51.49116 70.35932 10 -50.07961 72.02516 10 -51.33689 72.58036 10 -51.37402 73.54611 10 -51.92741 74.33851 10 -51.82779 71.74781 10 -53.08587 74.74066 10 -52.69087 71.31285 10 -54.66311 73.41966 10 -54.54769 72.19879 10 -54.17221 74.25219 10 -53.65206 71.41354 10 -53.10593 71.59523 12.95167 -53.12951 70.41548 13.00353 -52.36005 71.89987 12.92653 -51.1121 71.2918 13.00118 -51.72811 72.39526 12.95314 -50.4954 72.7633 13.00015 -51.74663 73.76119 12.9883 -50.92757 74.55309 13.00358 -53.03252 74.46605 12.9883 -52.89407 75.54683 13.00127 -54.90909 74.74745 13.00324 -54.28589 73.70486 12.9883 -55.52441 72.64086 13.00088 -54.25337 72.23882 12.9883 -54.77887 71.22106 13.00015 -50.3304 72.13258 9.999991 -51.24408 72.82872 9.965066 -50.46016 74.19515 9.999992 -51.89143 74.46083 9.983746 -51.66484 75.42861 9.999999 -53 75.77143 9.999999 -53.71782 74.59996 9.964968 -54.33516 75.42861 9.999999 -55.33998 74.48502 9.999999 -54.68906 73.49087 9.966698 -55.76595 73.17403 9.999999 -55.50765 71.81999 9.999999 -54.54415 72.20535 9.968204 -54.62899 70.75787 9.999999 -53.27133 71.06793 9.999559 -53.34736 70.25044 9.999999 -51.64773 70.54022 9.999992 -51.76005 71.67112 9.980438 -53.34239 71.48826 9.781834 -53.22756 71.49758 -3.750085 -54.12594 71.97138 -3.746064 -54.40917 72.41645 9.715975 -54.51715 72.89361 -3.751035 -54.51972 73.08559 9.712512 -54.26436 73.84504 -3.750929 -54.28038 73.85089 9.711318 -53.48183 74.44227 -3.750853 -53.50217 74.45268 9.710549 -52.49512 74.48058 9.824409 -52.52278 74.43903 -3.753787 -51.72057 73.87393 9.77985 -51.75526 73.8695 -3.750473 -51.47831 72.95575 -3.746149 -51.49771 73.32581 9.793117 -51.53042 72.55033 9.712489 -51.96402 71.82178 -3.735584 -52.50846 71.56137 9.710469 -54.01496 72.15309 -4.006336 -51.74335 72.85755 -4.000118 -52.42816 71.80819 -4.006336 -52.01499 73.83153 -4.002416 -53.36788 74.26968 -4.006335 -54.21553 73.3472 -4.000673 -54.14733 70.4333 12.75534 -55.59959 71.92815 12.76029 -55.6236 74.01193 12.74421 -54.23297 75.52716 12.76029 -52.14019 75.67793 12.74916 -50.76364 74.64564 12.74603 -50.18907 73.05473 12.75534 -50.91347 71.11567 12.75534 -52.43246 70.28233 12.75372 -53.6249 74.08236 12.8758 -54.2498 73.00001 12.8758 -52.3751 74.08236 12.8758 -54.2386 72.26679 11.77999 -53 73 10.97831 -52.97782 71.56242 11.74896 -54.25691 73.68523 11.75395 -53.03508 74.43112 11.75392 -51.76636 73.73917 11.75578 -51.74567 72.29145 11.78046 -53.32299 71.27897 9.93651 -54.05085 71.87489 9.789763 -51.95592 71.86952 9.788521 -44.38309 69.18961 11.98899 -43.34365 70.02851 12.00102 -44.87753 70.59585 11.9908 -44.34263 71.53143 12.0009 -45.75768 71.97786 12.00025 -46.30947 70.84682 11.98815 -47.23323 71.58189 12.0009 -47.26581 69.73552 11.98903 -48.28407 70.11474 12.00102 -48.19983 68.63339 12.00025 -46.78123 68.35149 11.98829 -47.30634 67.39414 12.0009 -45.23958 66.94554 12.00235 -45.34045 68.07856 11.9883 -43.5923 68.24108 12.0009 -44.71276 66.928 9 -44.58868 68.15002 8.98781 -43.45569 67.96964 9 -44.12686 69.03919 8.965703 -43.06128 69.91593 9 -48.48177 70.34566 9 -47.53846 69.73888 8.966175 -48.47478 68.66471 9 -47.39733 68.7136 8.969837 -47.80034 67.52448 9 -46.78262 68.01926 8.971481 -46.38062 66.71845 9 -45.58386 67.73754 8.96643 -44.20867 70.26148 8.985075 -43.84865 71.4011 9 -44.78319 70.84808 8.969233 -45.26835 72.20712 9 -45.82788 71.20455 8.960321 -47.22803 71.88574 9 -46.99271 70.83926 8.985499 -45.82339 71.011 8.700813 -46.05452 70.96755 -2.746942 -45.12007 70.80828 -2.750916 -44.82583 70.62786 8.711897 -44.46658 70.14246 -2.750784 -44.30458 69.24621 8.713599 -44.35957 69.00044 -2.763266 -44.69808 68.40324 8.780657 -45.11822 68.11984 -2.750458 -45.62553 67.92561 8.711046 -46.03787 67.96002 -2.749781 -46.50507 68.08553 8.770911 -46.89822 68.38376 -2.746322 -47.02087 68.52384 8.712425 -47.32539 69.2331 -2.750746 -47.337 69.20607 8.711147 -47.21649 70.13999 8.781948 -47.07574 70.3529 -2.763716 -46.17183 70.70067 -3.001961 -46.74296 68.59534 -3.000091 -47.11349 69.72824 -3.005136 -45.67863 68.15483 -3.005136 -44.61884 69.01618 -3.001961 -44.85206 70.34957 -3.005136 -46.71801 72.11641 11.75555 -48.25298 70.85652 11.75555 -48.58419 69.2417 11.75254 -48.16534 67.98452 11.75254 -47.21025 67.06601 11.75254 -45.93768 66.69655 11.75253 -44.63916 66.9608 11.75254 -43.39598 68.06904 11.75555 -43.08251 70.02993 11.75555 -43.90542 71.45829 11.75254 -45.05258 72.12155 11.75253 -44.89567 68.62657 11.87579 -44.63587 69.84905 11.8758 -45.56469 70.68527 11.8758 -46.7549 70.29724 11.87587 -47.01309 69.0765 11.8758 -46.08428 68.24028 11.8758 -44.43813 69.11965 10.73432 -45.82448 69.46278 9.978313 -44.63576 69.84838 10.67698 -44.90456 70.55531 10.73448 -46.28726 70.82382 10.76476 -45.39931 68.08908 10.77152 -46.80398 68.4097 10.75803 -47.23532 69.76547 10.80094 -46.71767 70.71116 8.784855 -44.38521 69.99996 8.785919 -13.6519 -14.42272 -2.98874 -12.5265 -13.8481 -2.947659 -12.28308 -14.93752 -2.94141 -13.82563 -15.8786 -2.989515 -14.82826 -13.54303 -2.988995 -14.13231 -12.4808 -3.001437 -16.1759 -14.12279 -2.988995 -15.84855 -12.40695 -2.933669 -16.34764 -15.57975 -2.988995 -17.69768 -15.37848 -2.960467 -17.06104 -13.3114 -3.001437 -16.58205 -17.14392 -3.001437 -14.26287 -17.59917 -3.003272 -15.17174 -16.45697 -2.988995 -12.47616 -16.03697 -2.947659 -12.70738 -16.51868 0 -13.66314 -15.8913 0 -13.06002 -16.94909 0 -14.0754 -16.31405 0 -13.49208 -17.29971 0 -13.98587 -17.55618 0 -14.61251 -16.55931 0 -14.52119 -17.708 0 -15.0761 -17.74895 0 -15.05381 -16.5991 0 -15.6279 -17.67736 0 -15.49143 -16.52974 0 -16.154 -17.49616 0 -16.63285 -17.21276 0 -16.01086 -16.24891 0 -17.04485 -16.83877 0 -17.37314 -16.38951 0 -16.39375 -15.79942 0 -17.60426 -15.88336 0 -16.58842 -15.24195 0 -17.72877 -15.34104 0 -17.74156 -14.78476 0 -16.56856 -14.65181 0 -17.64212 -14.23729 0 -17.4345 -13.72105 0 -16.33685 -14.10869 0 -17.12722 -13.25717 0 -16.73284 -12.86464 0 -16.03754 -13.782 0 -16.26753 -12.55953 0 -15.6674 -13.53844 0 -15.75032 -12.35434 0 -15.20239 -12.25746 0 -15.09435 -13.39604 0 -14.64618 -12.27286 0 -14.50857 -13.47026 0 -14.10445 -12.3999 0 -13.59939 -12.6334 0 -14.11243 -13.66875 0 -13.15167 -12.96379 0 -13.77688 -13.95809 0 -12.77962 -13.37753 0 -12.49847 -13.85771 0 -13.48309 -14.4703 0 -12.31973 -14.38464 0 -12.25073 -14.93677 0 -13.39417 -15.05403 0 -12.29428 -15.49149 0 -12.4486 -16.02609 0 -13.47668 -15.48937 0 -13.84711 -13.98751 0.0720514 -13.79766 -14.09627 5.935148 -14.51113 -13.60712 5.961894 -14.68072 -13.51195 0.06716728 -15.32085 -13.5695 5.951858 -15.50235 -13.5646 0.06881189 -15.8844 -13.77225 5.850426 -16.17949 -14.03799 0.06649833 -16.35793 -14.40251 5.936767 -16.50929 -14.80139 0.06597012 -16.43869 -15.25934 5.986041 -16.38866 -15.62431 0.06544977 -16.16187 -15.96856 5.851049 -15.85348 -16.26112 0.06494551 -15.5016 -16.38742 5.946149 -15.0634 -16.52168 0.06445759 -14.66616 -16.44221 5.930368 -14.25418 -16.32812 0.06399238 -13.79205 -15.91051 5.91505 -13.54941 -15.4626 0.06473731 -13.52014 -15.00081 5.939349 -13.50469 -14.77254 0.06312894 -12.32968 -14.09424 -1.04079e-5 -13.23845 -12.83566 -2.851103 -13.81673 -12.44053 -1.04145e-5 -14.6429 -12.24757 -2.855019 -15.48125 -12.27822 -8.95631e-7 -16.75634 -12.83569 -3.68975e-6 -16.73952 -12.85642 -2.847527 -17.59973 -13.95447 -2.858142 -17.67794 -14.22695 -3.68784e-6 -17.56499 -16.17127 -1.04189e-5 -17.17257 -16.75139 -2.851103 -16.16964 -17.53 -3.69094e-6 -16.15845 -17.50577 -2.847527 -14.9268 -17.78964 -2.851102 -14.79658 -17.7565 -8.89509e-7 -13.2232 -17.18952 -1.04118e-5 -13.23433 -17.1758 -2.858141 -12.34443 -15.76659 -8.96858e-7 -16.24415 -14.88115 -2.875808 -15.51915 -13.86311 -2.875808 -14.27501 -13.98197 -2.875798 -13.75611 -15.12123 -2.875862 -14.48088 -16.13684 -2.875773 -15.72499 -16.01803 -2.875798 -13.81116 -15.78093 -1.742882 -15 -15 -0.9783121 -15.12907 -16.43711 -1.782641 -16.3107 -15.60384 -1.783531 -16.16816 -14.15565 -1.765801 -14.85545 -13.56476 -1.787682 -13.70101 -14.38893 -1.78942 -13.43385 -15.34783 -0.008423328 -13.41395 -14.75859 -0.008423089 -13.88583 -13.85336 -0.003898322 -14.23644 -13.58828 -0.006250441 -13.66525 -15.8901 -0.008423328 -14.08203 -16.31396 -0.01150023 -14.4702 -16.50846 -0.003897786 -14.90595 -16.60156 -0.00842154 -15.49116 -16.52798 -0.006249845 -15.8845 -16.33184 -0.003897607 -16.22139 -16.04021 -0.008422851 -16.51468 -15.52874 -0.008422911 -16.6034 -14.94587 -0.008422493 -16.47558 -14.37032 -0.008423328 -16.14887 -13.87925 -0.00625205 -15.79796 -13.61457 -0.003897428 -15.38673 -13.44299 -0.00842303 -14.79816 -13.40843 -0.008424282 -13.60826 -14.20194 -0.008421957 -69.01838 -94.17012 17.75108 -70.2415 -93.86322 17.00505 -69.84543 -93.23284 17 -68.30162 -93.12303 17.00281 -69.24739 -92.92219 17.00392 -70.22264 -94.53819 17.00096 -67.81413 -93.80207 17.00096 -67.80393 -94.52574 17.00168 -68.35335 -95.2508 17.00281 -69.50319 -95.37771 17.0027 -79.58805 -87.64846 17.75108 -80.60948 -86.89559 17.00281 -80.85879 -87.81308 16.99901 -79.79981 -86.39736 17.00281 -78.52764 -86.95684 17.0041 -79.06819 -86.51169 17 -78.32069 -87.85257 17.00356 -78.92303 -88.72914 17.00281 -79.91794 -88.87415 17.00267 -80.4959 -88.50772 17 -71.36279 -78.34281 17.75108 -72.64051 -78.11421 16.99554 -72.04262 -77.27155 17.00392 -71.07581 -77.10469 17.00147 -70.33248 -77.6096 17.00258 -70.10597 -78.28981 17.00194 -70.34136 -79.09568 17.00281 -71.88264 -79.47959 17 -71.15863 -79.59735 17.00329 -72.42593 -79.02948 17.00162 -60.79312 -84.86447 17.75108 -62.00756 -84.50886 17.00168 -61.45814 -83.7838 17.00281 -60.52079 -83.62513 17.0028 -61.99738 -85.23252 17.00096 -59.53507 -84.65244 17.0023 -59.88528 -84.00521 17 -59.7388 -85.56007 17.00676 -61.55813 -85.87733 17.00267 -60.58091 -86.11631 17.00336 -84.45324 -90.89112 13.59365 -84.11097 -90.84528 12.81053 -84.17809 -88.97962 12.40773 -82.887 -90.66463 12.01772 -83.65096 -88.17667 12.0799 -85.10278 -87.8803 13.67894 -84.86533 -87.84545 13.02826 -83.37452 -85.68187 12.00618 -84.48405 -85.84706 12.42953 -85.12162 -85.94078 13.38459 -70.29265 -93.91405 12 -69.56277 -93.03072 12 -68.70606 -92.93772 12 -67.96385 -93.46771 12 -67.75428 -94.4196 12 -68.38692 -95.27359 12 -69.33068 -95.40254 12 -70.07292 -94.87252 12 -80.84005 -87.87324 12 -80.58689 -86.86189 12 -79.76013 -86.3888 12 -78.76857 -86.6877 12 -78.32305 -87.55606 12 -78.58922 -88.43505 12 -79.41597 -88.90813 12 -80.36283 -88.65422 12 -72.634 -78.44123 12 -72.10843 -77.29264 12 -71.02121 -77.12006 12 -70.30826 -77.64041 12 -70.10736 -78.3864 12 -70.36396 -79.1294 12 -71.22147 -79.60449 12 -72.18228 -79.30357 12 -62.05722 -84.61502 12 -61.42457 -83.76102 12 -60.48081 -83.63206 12 -59.73859 -84.16207 12 -59.53295 -84.86112 12 -59.86156 -85.717 12 -60.62103 -86.12414 12 -61.31296 -86.00125 12 -61.89188 -85.48033 12 -56.55754 -86.76425 12.03097 -56.69898 -84.77455 12.06942 -55.99715 -81.62687 13.22367 -55.46173 -83.40803 13.73804 -55.67279 -83.43381 13.05619 -56.16533 -83.87665 12.38369 -57.35463 -81.82853 12.04514 -55.53841 -86.61191 12.81115 -55.19427 -86.55435 13.55482 -64.65208 -87.97713 15.5 -64.67353 -87.98828 12 -55.18164 -86.57142 15.49982 -66.9588 -91.01231 12 -66.03199 -90.24649 15.5 -65.72903 -89.90436 12 -66.95884 -91.01235 15.5 -65.60085 -100.1799 12.85508 -65.76165 -99.09907 12.04778 -65.55043 -100.5207 15.5 -65.5513 -100.5252 13.68623 -71.90487 -91.74497 15.5 -71.92239 -91.77355 12 -70.69837 -99.88951 12.03097 -70.54602 -100.9086 12.81116 -70.51576 -101.2821 15.49976 -70.49068 -101.2471 13.54813 -74.94646 -89.48822 12 -73.94214 -90.64015 12 -73.24567 -91.15327 15.5 -74.98263 -89.52888 15.5 -84.46953 -90.91902 15.49989 -75.67908 -84.54216 12 -85.19648 -85.92908 15.49985 -75.67909 -84.54217 15.5 -73.44029 -81.45224 12 -75.08736 -83.20134 15.5 -75.15104 -83.30899 12 -73.43463 -81.46737 15.5 -74.78033 -72.33307 12.85508 -74.61952 -73.41387 12.04778 -74.83074 -71.99221 15.5 -74.82987 -71.98777 13.68624 -67.65781 -86.51437 12 -71.68029 -88.32099 12 -69.65318 -88.74497 12 -68.26359 -87.84917 12 -72.61136 -86.95674 12 -72.56934 -85.38356 12 -71.23366 -83.93408 12 -68.45879 -80.7394 12 -69.77477 -83.79129 12 -68.30418 -84.54681 12 -65.43471 -83.02473 12 -66.38967 -81.91307 12 -68.47432 -80.71592 15.5 -69.68281 -72.62343 12.03097 -69.83515 -71.6043 12.81115 -69.88471 -71.25959 15.5 -69.8905 -71.26589 13.54814 -65.43467 -83.02478 15.5 -66.29752 -81.99763 15.5 -55.90814 -81.6033 15.49989 -63.92091 -99.89673 15.50011 -60.60864 -97.83078 15.5 -57.54423 -94.45748 15.5 -55.74987 -90.35823 15.5 -68.70863 -99.74806 12.06942 -67.81076 -100.2817 12.38369 -67.62985 -100.9627 13.29584 -81.94891 -95.61523 15.5 -83.47013 -93.23168 15.5 -74.57153 -100.6296 15.5 -76.9845 -99.62968 15.5 -79.47565 -98.07027 15.5 -83.31144 -78.93382 15.5 -81.2735 -76.10692 15.5 -79.15732 -74.23159 15.5 -76.46025 -72.61621 15.50011 -84.75972 -82.57072 15.5 -71.67258 -72.76488 12.06942 -72.57041 -72.23122 12.38369 -72.75131 -71.5502 13.29583 -59.01791 -76.2479 15.5 -57.25984 -78.6031 15.5 -67.7165 -71.42783 15.50011 -64.27112 -72.44328 15.5 -60.90556 -74.44264 15.5 -55.23551 -85.12693 23.69949 -55.45637 -83.35191 23.7 -61.92354 -98.80639 23.7 -59.81168 -97.08599 23.7 -57.94246 -94.96439 23.7 -56.36465 -92.10475 23.7 -55.28816 -88.17195 23.7 -65.69464 -100.58 23.69991 -68.9413 -101.2315 23.70003 -72.60645 -101.086 23.7 -75.28646 -100.3643 23.7 -78.12978 -98.99727 23.7 -80.04614 -97.56435 23.7 -85.09494 -88.4485 23.70012 -82.08078 -95.44349 23.7 -83.96517 -92.25972 23.7 -77.60889 -73.21926 23.7 -82.52037 -77.65539 23.7 -84.01651 -80.40816 23.7 -74.68654 -71.93295 23.69989 -71.43986 -71.2814 23.70003 -67.77471 -71.42695 23.7 -61.07542 -74.30832 23.7 -58.1791 -77.25186 23.7 -56.55316 -79.93009 23.7 -85.07203 -84.17787 23.7 -79.77251 -74.68215 23.7 -64.07359 -72.53203 23.7 -74.42044 -76.08359 23.7 -77.13556 -77.70388 23.7 -78.57689 -79.13819 23.7 -80.07825 -81.3971 23.7 -80.7867 -83.3031 23.7 -65.01992 -76.51828 23.7 -67.09876 -75.69993 23.7 -69.57196 -75.24804 23.7 -71.80236 -75.37519 23.7 -60.502 -80.98881 23.7 -62.61763 -78.25462 23.7 -59.18008 -86.85492 23.7 -59.49833 -83.60955 23.7 -64.54476 -95.71712 23.7 -62.09029 -93.72404 23.7 -60.86963 -92.09769 23.7 -59.70798 -89.64679 23.7 -70.6082 -97.26579 23.7 -67.65721 -96.98728 23.7 -79.96456 -91.35918 23.7 -77.91413 -94.12509 23.7 -74.61201 -96.40779 23.7 -81.20384 -85.75476 23.7 -80.93154 -88.73116 23.7 -59.30931 -84.6447 25.9 -59.1939 -87.03922 25.9 -59.93829 -90.29006 25.9 -61.37712 -92.88152 25.9 -62.91245 -94.50443 25.9 -65.14202 -96.04888 25.9 -67.8378 -97.03057 25.9 -71.28979 -97.21873 25.9 -74.08535 -96.57382 25.9 -76.15332 -95.50016 25.9 -78.04711 -93.99546 25.9 -79.47554 -92.15473 25.9 -80.64387 -89.73345 25.9 -81.18344 -87.0884 25.9 -81.10083 -84.85414 25.9 -80.52271 -82.40738 25.9 -79.51154 -80.41526 25.9 -77.96219 -78.43531 25.9 -76.20989 -77.04953 25.9 -73.78175 -75.84096 25.9 -70.67568 -75.24993 25.9 -68.64558 -75.36552 25.9 -66.02316 -76.05785 25.9 -64.22787 -77.01277 25.9 -62.13621 -78.7394 25.9 -60.02242 -81.87847 25.9 -72.68867 -86.0129 25.9 -72.30899 -84.92893 25.9 -71.62568 -84.18164 25.9 -70.13253 -83.73436 25.9 -68.87884 -84.10154 25.9 -68.08037 -84.91595 25.9 -67.72258 -85.77355 25.9 -67.83047 -87.12554 25.9 -68.53646 -88.13101 25.9 -69.31867 -88.61554 25.9 -70.54173 -88.73168 25.9 -71.50235 -88.41139 25.9 -72.49293 -87.29949 25.9 -67.68415 -85.99391 35.2 -67.95836 -87.41518 35.2 -68.86564 -88.40332 35.2 -69.82426 -88.72949 35.2 -71.04802 -88.62084 35.2 -72.06034 -87.95011 35.2 -72.684 -86.56928 35.2 -70.89504 -83.83195 35.2 -69.33315 -83.89211 35.2 -72.0018 -84.51149 35.2 -72.59878 -85.58522 35.2 -68.32082 -84.56285 35.2 -72.5334 -87.12893 15.5 -72.65056 -85.62441 15.50041 -71.74433 -84.29793 15.5 -70.39764 -83.71903 15.5 -68.44344 -84.40474 15.5 -67.6454 -86.31581 15.5 -68.53161 -88.1876 15.5 -70.08478 -88.75423 15.5 -71.51455 -88.43101 15.5 -47.4122 72.21278 0 -47.41772 72.20685 -2.178254 -48.9999 69.46292 -2.158651 -48.99991 69.46278 0 -48.46796 70.37618 -2.391055 -47.77305 71.40345 -2.405406 -48.49826 68.60704 -2.38645 -47.79649 67.54524 -2.41051 -47.4122 66.71278 0 -47.42067 66.72131 -2.184845 -47.74555 67.49504 -2.4 -47.37767 67.19145 -2.407157 -45.59258 66.71858 -2.412246 -44.23677 66.71278 0 -44.22821 66.72043 -2.194079 -43.59399 67.85196 -2.404332 -45.08091 66.81521 -2.4 -44.4447 67.07089 -2.403155 -43.90341 67.49504 -2.4 -42.64907 69.46264 -2.158651 -42.64906 69.46278 0 -43.16162 68.5866 -2.387336 -43.21575 70.48464 -2.396923 -44.23677 72.21278 0 -44.24193 72.21411 -2.200862 -45.58948 72.20679 -2.412675 -43.76164 71.28903 -2.394955 -44.44309 71.85358 -2.402912 -45.08091 72.11034 -2.4 -47.38121 71.73132 -2.40574 -47.74555 71.43051 -2.4 -46.44568 68.04423 -2.398667 -46.68467 70.7571 -2.398512 -45.20331 70.88134 -2.398667 -44.25617 71.72174 -2.4 -43.90341 71.43051 -2.4 -44.25762 69.61203 -2.397096 -45.08091 72.11034 -2.4 -44.65232 71.95046 -2.4 -44.96426 68.16848 -2.398513 -44.25617 67.20382 -2.4 -44.65232 66.9751 -2.4 -45.08091 66.81521 -2.4 -43.90341 67.49504 -2.4 -47.39134 69.31354 -2.397096 -43.6038 71.08484 -2.4 -46.31121 70.63674 -2.126501 -47.0156 69.8645 -2.128957 -46.93873 68.85981 -2.126375 -46.28741 68.31247 -2.128827 -45.33775 68.28884 -2.126499 -44.63337 69.06105 -2.128958 -44.71024 70.06575 -2.126376 -45.36158 70.61312 -2.128823 -45.33776 70.63674 -0.273499 -44.70636 70.00148 -0.2711572 -44.58523 69.31172 -0.2729908 -45.06592 68.43446 -0.2737526 -46.31122 68.28884 -0.2735009 -46.94261 68.92409 -0.2711574 -47.06374 69.61383 -0.2729921 -46.58298 70.49117 -0.2737504 -46.16198 67.9134 -0.00511831 -47.31596 69.05073 -0.002105832 -47.03043 70.43914 -0.002365767 -45.48695 71.01215 -0.005117237 -44.33301 69.87484 -0.002105891 -44.61855 68.48638 -0.002366721 -56.81039 64.38309 11.98899 -55.65324 63.39631 12.00257 -55.40415 64.87754 11.9908 -54.17406 64.88075 12.0009 -55.15317 66.30947 11.98815 -54.23311 66.99481 12.00235 -56.26448 67.26582 11.98903 -56.19153 68.38534 12.00257 -57.91097 67.93231 12.00025 -57.64852 66.78124 11.9883 -58.9004 66.76821 12.0009 -57.92144 65.34046 11.9883 -58.99522 65.28746 12.00025 -58.03355 63.71744 12.00235 -58.27642 65.96414 8.960191 -58.7323 64.13847 9 -57.86026 64.69496 8.960119 -57.69734 63.31149 9 -56.3966 63.06021 9 -54.80941 67.98682 9 -55.6704 67.31474 8.97125 -56.31592 68.61585 9 -56.51212 67.55795 8.966372 -57.94638 68.20677 9 -57.63631 67.18202 8.961619 -58.89206 67.27906 9 -59.33491 65.70771 9 -55.85837 64.23044 8.973481 -55.12808 63.44219 9 -54.18238 64.36994 9 -55.10237 64.80848 8.966835 -53.77615 65.63091 9 -55.03726 66.69174 8.971082 -54.00244 66.93618 9 -54.97224 65.8487 8.864503 -55.03245 66.05453 -2.746942 -55.19172 65.12008 -2.750917 -55.16799 65.10312 8.781973 -55.85754 64.46658 -2.750779 -55.83766 64.45883 8.711779 -56.75381 64.30458 8.713602 -56.99956 64.35958 -2.763265 -57.88016 65.1182 -2.750456 -58.07439 65.62554 8.711047 -58.03999 66.03785 -2.749777 -57.88483 66.5372 8.716979 -57.61626 66.8982 -2.746326 -57.47616 67.02086 8.712427 -56.76691 67.32539 -2.75075 -56.79394 67.337 8.711148 -55.87291 67.20843 8.713267 -55.6471 67.07574 -2.763715 -55.21125 66.58791 8.705645 -55.24822 65.55904 -3.005136 -56.48499 67.11068 -3.000453 -55.61911 66.69164 -3.000546 -57.68112 66.47528 -3.005136 -57.6072 65.11161 -3.001961 -56.39136 64.51654 -3.005136 -54.17456 67.32712 11.75555 -55.76518 68.51597 11.75555 -57.41231 68.4511 11.75254 -58.78001 67.5008 11.75555 -59.32758 65.59197 11.75555 -58.68283 64.07485 11.75254 -57.62399 63.27815 11.75253 -56.31616 63.06478 11.75254 -55.05898 63.48362 11.75254 -54.14044 64.43875 11.75254 -53.77099 65.71131 11.75254 -57.37343 64.89567 11.87579 -56.15096 64.63587 11.8758 -55.31473 65.5647 11.8758 -55.70276 66.75491 11.87587 -56.92349 67.01309 11.8758 -57.75973 66.08426 11.8758 -56.88036 64.43814 10.73433 -56.53723 65.82449 9.978313 -56.15162 64.63577 10.67698 -55.44469 64.90458 10.73448 -55.17618 66.28727 10.76475 -57.91093 65.39931 10.77152 -57.59031 66.80398 10.75803 -56.23453 67.23533 10.80094 -56.73396 64.14628 8.937381 -57.5489 64.66413 8.742897 14.42272 -13.6519 -2.98874 13.8481 -12.5265 -2.947659 14.93752 -12.28308 -2.94141 15.8786 -13.82563 -2.989515 13.54303 -14.82826 -2.988995 12.4808 -14.13231 -3.001437 14.12279 -16.1759 -2.988995 12.40695 -15.84855 -2.933669 15.57975 -16.34764 -2.988995 15.37848 -17.69768 -2.960467 13.3114 -17.06104 -3.001437 17.14392 -16.58205 -3.001437 17.59917 -14.26287 -3.003272 16.45697 -15.17174 -2.988995 16.03697 -12.47616 -2.947659 16.51868 -12.70738 0 15.8913 -13.66314 0 16.94909 -13.06002 0 16.31405 -14.0754 0 17.29971 -13.49208 0 17.55618 -13.98587 0 16.55931 -14.61251 0 17.708 -14.52119 0 17.74895 -15.0761 0 16.5991 -15.05381 0 17.67736 -15.6279 0 16.52974 -15.49143 0 17.49616 -16.154 0 17.21276 -16.63285 0 16.24891 -16.01086 0 16.83877 -17.04485 0 16.38951 -17.37314 0 15.79942 -16.39375 0 15.88336 -17.60426 0 15.24195 -16.58842 0 15.34104 -17.72877 0 14.78476 -17.74156 0 14.65181 -16.56856 0 14.23729 -17.64212 0 13.72105 -17.4345 0 14.10869 -16.33685 0 13.25717 -17.12722 0 12.86464 -16.73284 0 13.782 -16.03754 0 12.55953 -16.26753 0 13.53844 -15.6674 0 12.35434 -15.75032 0 12.25746 -15.20239 0 13.39604 -15.09435 0 12.27286 -14.64618 0 13.47026 -14.50857 0 12.3999 -14.10445 0 12.6334 -13.59939 0 13.66875 -14.11243 0 12.96379 -13.15167 0 13.95809 -13.77688 0 13.37753 -12.77962 0 13.85771 -12.49847 0 14.4703 -13.48309 0 14.38464 -12.31973 0 14.93677 -12.25073 0 15.05403 -13.39417 0 15.49149 -12.29428 0 16.02609 -12.4486 0 15.48937 -13.47668 0 13.98751 -13.84711 0.0720514 14.09627 -13.79766 5.935148 13.60712 -14.51113 5.961894 13.51195 -14.68072 0.06716728 13.5695 -15.32085 5.951858 13.5646 -15.50235 0.06881189 13.77225 -15.8844 5.850426 14.03799 -16.17949 0.06649833 14.40251 -16.35793 5.936767 14.80139 -16.50929 0.06597012 15.25934 -16.43869 5.986041 15.62431 -16.38866 0.06544977 15.96856 -16.16187 5.851049 16.26112 -15.85348 0.06494551 16.38742 -15.5016 5.946149 16.52168 -15.0634 0.06445759 16.44221 -14.66616 5.930368 16.32812 -14.25418 0.06399238 15.91051 -13.79205 5.91505 15.4626 -13.54941 0.06473731 15.00081 -13.52014 5.939349 14.77254 -13.50469 0.06312894 14.09424 -12.32968 -1.04079e-5 12.83566 -13.23845 -2.851103 12.44053 -13.81673 -1.04145e-5 12.24757 -14.6429 -2.855019 12.27822 -15.48125 -8.95631e-7 12.83569 -16.75634 -3.68975e-6 12.85642 -16.73952 -2.847527 13.95447 -17.59973 -2.858142 14.22695 -17.67794 -3.68784e-6 16.17127 -17.56499 -1.04189e-5 16.75139 -17.17257 -2.851103 17.53 -16.16964 -3.69094e-6 17.50577 -16.15845 -2.847527 17.78964 -14.9268 -2.851102 17.7565 -14.79658 -8.89509e-7 17.18952 -13.2232 -1.04118e-5 17.1758 -13.23433 -2.858141 15.76659 -12.34443 -8.96858e-7 14.88115 -16.24415 -2.875808 13.86311 -15.51915 -2.875808 13.98197 -14.27501 -2.875798 15.12123 -13.75611 -2.875862 16.13684 -14.48088 -2.875773 16.01803 -15.72499 -2.875798 15.78093 -13.81116 -1.742882 15 -15 -0.9783121 16.43711 -15.12907 -1.782641 15.60384 -16.3107 -1.783531 14.15565 -16.16816 -1.765801 13.56476 -14.85545 -1.787682 14.38893 -13.70101 -1.78942 15.34783 -13.43385 -0.008423328 14.75859 -13.41395 -0.008423089 13.85336 -13.88583 -0.003898322 13.58828 -14.23644 -0.006250441 15.8901 -13.66525 -0.008423328 16.31396 -14.08203 -0.01150023 16.50846 -14.4702 -0.003897786 16.60156 -14.90595 -0.00842154 16.52798 -15.49116 -0.006249845 16.33184 -15.8845 -0.003897607 16.04021 -16.22139 -0.008422851 15.52874 -16.51468 -0.008422911 14.94587 -16.6034 -0.008422493 14.37032 -16.47558 -0.008423328 13.87925 -16.14887 -0.00625205 13.61457 -15.79796 -0.003897428 13.44299 -15.38673 -0.00842303 13.40843 -14.79816 -0.008424282 14.20194 -13.60826 -0.008421957 13.6519 14.42272 -2.98874 12.5265 13.8481 -2.947659 12.28308 14.93752 -2.94141 13.82563 15.8786 -2.989515 14.82826 13.54303 -2.988995 14.13231 12.4808 -3.001437 16.1759 14.12279 -2.988995 15.84855 12.40695 -2.933669 16.34764 15.57975 -2.988995 17.69768 15.37848 -2.960467 17.06104 13.3114 -3.001437 16.58205 17.14392 -3.001437 14.26287 17.59917 -3.003272 15.17174 16.45697 -2.988995 12.47616 16.03697 -2.947659 12.70738 16.51868 0 13.66314 15.8913 0 13.06002 16.94909 0 14.0754 16.31405 0 13.49208 17.29971 0 13.98587 17.55618 0 14.61251 16.55931 0 14.52119 17.708 0 15.0761 17.74895 0 15.05381 16.5991 0 15.6279 17.67736 0 15.49143 16.52974 0 16.154 17.49616 0 16.63285 17.21276 0 16.01086 16.24891 0 17.04485 16.83877 0 17.37314 16.38951 0 16.39375 15.79942 0 17.60426 15.88336 0 16.58842 15.24195 0 17.72877 15.34104 0 17.74156 14.78476 0 16.56856 14.65181 0 17.64212 14.23729 0 17.4345 13.72105 0 16.33685 14.10869 0 17.12722 13.25717 0 16.73284 12.86464 0 16.03754 13.782 0 16.26753 12.55953 0 15.6674 13.53844 0 15.75032 12.35434 0 15.20239 12.25746 0 15.09435 13.39604 0 14.64618 12.27286 0 14.50857 13.47026 0 14.10445 12.3999 0 13.59939 12.6334 0 14.11243 13.66875 0 13.15167 12.96379 0 13.77688 13.95809 0 12.77962 13.37753 0 12.49847 13.85771 0 13.48309 14.4703 0 12.31973 14.38464 0 12.25073 14.93677 0 13.39417 15.05403 0 12.29428 15.49149 0 12.4486 16.02609 0 13.47668 15.48937 0 13.84711 13.98751 0.0720514 13.79766 14.09627 5.935148 14.51113 13.60712 5.961894 14.68072 13.51195 0.06716728 15.32085 13.5695 5.951858 15.50235 13.5646 0.06881189 15.8844 13.77225 5.850426 16.17949 14.03799 0.06649833 16.35793 14.40251 5.936767 16.50929 14.80139 0.06597012 16.43869 15.25934 5.986041 16.38866 15.62431 0.06544977 16.16187 15.96856 5.851049 15.85348 16.26112 0.06494551 15.5016 16.38742 5.946149 15.0634 16.52168 0.06445759 14.66616 16.44221 5.930368 14.25418 16.32812 0.06399238 13.79205 15.91051 5.91505 13.54941 15.4626 0.06473731 13.52014 15.00081 5.939349 13.50469 14.77254 0.06312894 12.32968 14.09424 -1.04079e-5 13.23845 12.83566 -2.851103 13.81673 12.44053 -1.04145e-5 14.6429 12.24757 -2.855019 15.48125 12.27822 -8.95631e-7 16.75634 12.83569 -3.68975e-6 16.73952 12.85642 -2.847527 17.59973 13.95447 -2.858142 17.67794 14.22695 -3.68784e-6 17.56499 16.17127 -1.04189e-5 17.17257 16.75139 -2.851103 16.16964 17.53 -3.69094e-6 16.15845 17.50577 -2.847527 14.9268 17.78964 -2.851102 14.79658 17.7565 -8.89509e-7 13.2232 17.18952 -1.04118e-5 13.23433 17.1758 -2.858141 12.34443 15.76659 -8.96858e-7 16.24415 14.88115 -2.875808 15.51915 13.86311 -2.875808 14.27501 13.98197 -2.875798 13.75611 15.12123 -2.875862 14.48088 16.13684 -2.875773 15.72499 16.01803 -2.875798 13.81116 15.78093 -1.742882 15 15 -0.9783121 15.12907 16.43711 -1.782641 16.3107 15.60384 -1.783531 16.16816 14.15565 -1.765801 14.85545 13.56476 -1.787682 13.70101 14.38893 -1.78942 13.43385 15.34783 -0.008423328 13.41395 14.75859 -0.008423089 13.88583 13.85336 -0.003898322 14.23644 13.58828 -0.006250441 13.66525 15.8901 -0.008423328 14.08203 16.31396 -0.01150023 14.4702 16.50846 -0.003897786 14.90595 16.60156 -0.00842154 15.49116 16.52798 -0.006249845 15.8845 16.33184 -0.003897607 16.22139 16.04021 -0.008422851 16.51468 15.52874 -0.008422911 16.6034 14.94587 -0.008422493 16.47558 14.37032 -0.008423328 16.14887 13.87925 -0.00625205 15.79796 13.61457 -0.003897428 15.38673 13.44299 -0.00842303 14.79816 13.40843 -0.008424282 13.60826 14.20194 -0.008421957 -53.78723 67.4122 0 -53.78713 67.41206 -2.158654 -56.53711 68.99991 -2.158652 -56.53723 68.99991 0 -54.78233 67.98953 -2.405727 -55.66105 68.48737 -2.387336 -57.5591 68.43321 -2.396921 -59.28723 67.41217 -2.159143 -59.28723 67.4122 0 -58.16402 68.04986 -2.412848 -58.19781 68.01647 -2.413881 -59.28144 66.39402 -2.38721 -59.27492 65.54904 -2.40469 -59.28723 64.23677 0 -59.27958 64.22822 -2.194079 -58.14802 63.59397 -2.404334 -59.18479 65.08092 -2.4 -58.92913 64.4447 -2.403158 -58.50496 63.90341 -2.4 -56.53736 62.64907 -2.15865 -56.53723 62.64906 0 -57.41341 63.16162 -2.387336 -55.51536 63.21575 -2.396923 -53.78723 64.23677 0 -53.79584 64.22822 -2.184563 -53.8451 65.20231 -2.413421 -53.80014 65.54481 -2.40434 -54.71095 63.76166 -2.394954 -54.14645 64.44307 -2.402909 -53.79322 66.39743 -2.387359 -57.95578 66.44567 -2.398667 -55.24292 66.68471 -2.398513 -55.11867 65.20331 -2.398667 -54.27827 64.25617 -2.4 -54.56949 63.90341 -2.4 -56.38799 64.25762 -2.397096 -53.88966 65.08092 -2.4 -54.04955 64.65233 -2.4 -57.83153 64.96428 -2.398513 -58.79618 64.25617 -2.4 -59.0249 64.65233 -2.4 -59.18479 65.08092 -2.4 -58.50496 63.90341 -2.4 -56.68647 67.39134 -2.397096 -54.91516 63.6038 -2.4 -55.36328 66.31123 -2.1265 -56.13552 67.0156 -2.128958 -57.14018 66.93874 -2.126375 -57.68755 66.28739 -2.128827 -57.71118 65.33777 -2.126501 -56.93895 64.63338 -2.128957 -55.93425 64.71025 -2.126377 -55.3869 65.36158 -2.128828 -55.36328 65.33777 -0.2734997 -55.99854 64.70636 -0.2711595 -56.6883 64.58524 -0.2729906 -57.56557 65.06595 -0.2737501 -57.71117 66.31123 -0.2734985 -57.07592 66.94261 -0.2711583 -56.38615 67.06375 -0.2729901 -55.50888 66.58303 -0.2737499 -58.06783 65.78726 -6.71597e-4 -57.58253 66.97354 -0.002316832 -56.38614 67.33964 -8.75351e-4 -55.29589 66.75626 -0.002307415 -55.08019 65.29516 -0.002431809 -56.12517 64.33302 -0.002105712 -57.51361 64.61856 -0.002367138 -13.5 10 40 -11.6 13.3 40 42.65 0.8687501 40 42.5 22.5 40 42.00497 16.99144 40 41.83923 17.85 40 41.29583 16.13928 40 30.39897 14.49666 40 23.83616 16.07834 40 34.21323 14.64397 40 22.99503 17.50856 40 22.6 22.5 40 22.6 13.3 40 23.16077 16.65 40 23.70417 18.36072 40 41.16384 18.42166 40 14.5 -10 40 -3.5 -10 40 12.5 -8 40 19.65 -13.52776 40 20.5 -13.3 40 24.5 -10 40 21.35 -13.52776 40 22.1615 -14.4637 40 26.5 -8.000001 40 24.5 10 40 26.5 8.000001 40 12.5 8 40 14.5 10 40 46.66149 16.53631 40 46.2952 14.82925 40 70.5 12 40 44.6337 14.29295 40 43.33851 15.4637 40 43.70481 17.17075 40 45.3663 17.70705 40 70.5 -12 40 46.2952 -17.17075 40 42.5 -22.5 40 44.6337 -17.70705 40 43.33851 -16.5363 40 43.70481 -14.82925 40 45.3663 -14.29295 40 46.66149 -15.4637 40 41.21322 -16.10603 40 41.60103 -18.24666 40 41.97282 -16.87144 40 21.35 16.47224 40 21.97224 15.85 40 18.83851 14.4637 40 19.02776 15.85 40 19.65 16.47224 40 20.5 16.7 40 22.20705 14.6337 40 21.35 13.52776 40 20.5 13.3 40 19.65 13.52776 40 18.79296 -14.6337 40 21.97224 -15.85 40 22.6 -22.5 40 21.35 -16.47224 40 20.5 -16.7 40 19.65 -16.47224 40 19.02776 -15.85 40 -7.8 -15 40 -8.027757 -15.85 40 6.95 -22.5 40 -8.650001 -16.47224 40 -11.6 -22.5 40 -9.5 -16.7 40 -10.35 -16.47224 40 -10.97224 -15.85 40 -11.20154 -14.70115 40 -11.6 -13.8 40 -1.5 -8 40 -10.35 -13.52776 40 -9.5 -13.3 40 -8.650001 -13.52776 40 -8.027757 -14.15 40 -10.97224 15.85 40 -11.6 22.5 40 -11.20154 14.70115 40 -10.35 16.47224 40 -9.5 16.7 40 6.95 22.5 40 -7.8 15 40 -3.5 10 40 -8.027757 15.85 40 -8.650001 16.47224 40 -8.027757 14.15 40 -8.650001 13.52776 40 -9.5 13.3 40 -10.35 13.52776 40 -10.97224 14.15 40 -13.5 -10 40 -1.5 8 40 -15.5 8 40 -15.5 -8 40 -37.83851 -15.4637 40 -23.5 -10 40 -35.5 8 40 -38.02776 15.15 40 -35.5 -8.000003 40 -33.5 10 40 -23.5 10 40 -21.5 7.999999 40 -21.5 -8 40 -33.5 -10 40 -12.83616 18.42166 40 -12.16077 17.85 40 -11.99503 16.99144 40 -12.77853 16.08826 40 -30.60103 18.24666 40 -36.65 22.5 40 -30.97282 16.87144 40 -30.21322 16.10603 40 -18.5 22.5 40 -12.16077 -17.85 40 -12.02718 -16.87144 40 -12.83616 -16.07834 40 -12.77853 -18.41175 40 -27.575 -22.5 40 -30.48605 -18.31858 40 -31.00498 -16.99144 40 -30.29583 -16.13928 40 23.83616 -18.42166 40 23.16077 -17.85 40 22.99503 -16.99144 40 23.77853 -16.08826 40 34.60103 12.50334 40 34.97282 13.87856 40 30.78677 12.35603 40 30.02718 13.12144 40 -38.9637 14.3385 40 -40.35 14.52776 40 -40.7952 17.17075 40 -41.5 22.5 40 -41.16149 15.4637 40 -39.1337 17.70705 40 -37.83851 16.53631 40 4.65 -1.472243 40 3.838505 -0.5362994 40 6.35 1.472243 40 6.972243 0.85 40 7.2 0 40 6.972243 -0.85 40 6.036299 -1.661496 40 4.027757 0.85 40 4.963701 1.661496 40 -38.96371 -17.6615 40 -41.5 -22.5 40 -40.35 -17.47224 40 -41.16149 -16.53631 40 -40.7952 -14.82925 40 -39.1337 -14.29295 40 -38.02775 -16.85 40 -41.3875 0.8406248 40 -41.5 -22.5 38.5 6.95 -22.5 38.5 12.5 -8 38.5 29.99503 13.24144 38.5 24.5 10 38.5 70.5 12 38.5 -7.792953 -14.6337 38.5 -8.963702 -13.3385 38.5 -3.5 -10 38.5 14.5 -10 38.5 24.5 -10 38.5 23.83616 -16.07834 38.5 12.5 8 38.5 14.5 10 38.5 26.5 8.000002 38.5 19.9637 13.33851 38.5 -30.21322 -16.10603 38.5 -30.97282 -16.87144 38.5 -37.79296 -15.6337 38.5 -36.65 -22.5 38.5 -30.60103 -18.24666 38.5 -18.5 -22.5 38.5 -12.83616 -18.42166 38.5 -11.6 -22.5 38.5 -12.16077 -17.85 38.5 -11.99503 -16.99144 38.5 -11.16149 -14.4637 38.5 -12.77853 -16.08826 38.5 -30.97282 17.62857 38.5 -33.5 10 38.5 -30.60103 16.25334 38.5 -12.16077 17.85 38.5 -11.6 22.5 38.5 -12.02718 16.87144 38.5 -11.20705 14.6337 38.5 -12.83616 16.07834 38.5 -12.77853 18.41175 38.5 -18.5 22.5 38.5 -36.65 22.5 38.5 -30.21322 18.39397 38.5 -23.5 -10 38.5 -33.5 -10 38.5 -35.5 -8.000002 38.5 -35.5 8.000003 38.5 -21.5 8 38.5 -23.5 10 38.5 -13.5 -10 38.5 -1.5 -8 38.5 -10.35 -13.52776 38.5 -15.5 -8 38.5 -15.5 8 38.5 -21.5 -7.999999 38.5 -13.5 10 38.5 -10.0363 13.3385 38.5 -3.5 10 38.5 -1.5 8 38.5 -8.650001 13.52776 38.5 -7.838504 14.4637 38.5 -8.027757 15.85 38.5 6.95 22.5 38.5 -8.963703 16.6615 38.5 -10.67075 16.2952 38.5 -10.7952 -16.17075 38.5 -9.133703 -16.70705 38.5 -8.027757 -15.85 38.5 19.02776 -15.85 38.5 19.9637 -16.6615 38.5 22.20705 -14.6337 38.5 21.0363 -13.33851 38.5 19.65 -13.52776 38.5 18.83851 -14.4637 38.5 22.6 -22.5 38.5 21.67075 -16.2952 38.5 22.6 13.8 38.5 21.67075 13.7048 38.5 22.20705 15.3663 38.5 22.6 22.5 38.5 19.32925 16.2952 38.5 21.0363 16.6615 38.5 18.79296 14.6337 38.5 26.5 -8.000001 38.5 34.97282 13.12144 38.5 42.65 13.8 38.5 43.29296 15.6337 38.5 46.47224 15.15 38.5 46.70705 16.36631 38.5 45.5363 17.6615 38.5 42.5 22.5 38.5 44.15 14.52776 38.5 45.3663 14.29295 38.5 43.82926 17.2952 38.5 30.51395 14.56858 38.5 41.97282 16.87144 38.5 34.60103 14.49666 38.5 23.77853 16.08826 38.5 41.21322 16.10603 38.5 42.65 -13.8 38.5 41.60103 -16.25334 38.5 41.21322 -18.39397 38.5 41.97282 -17.62857 38.5 42.5 -22.5 38.5 43.82926 -14.7048 38.5 43.29296 -16.3663 38.5 44.15 -17.47224 38.5 46.70705 -15.6337 38.5 70.5 -12 38.5 45.5363 -14.3385 38.5 45.3663 -17.70705 38.5 46.47224 -16.85 38.5 22.99503 16.99144 38.5 23.83616 18.42166 38.5 23.16077 17.85 38.5 41.60103 18.24666 38.5 22.99503 -17.50856 38.5 23.16077 -16.65 38.5 23.77853 -18.41175 38.5 30.70417 12.38928 38.5 34.21323 12.35603 38.5 -38.9637 -14.3385 38.5 -40.67075 -14.70481 38.5 -41.35 5.65625 38.5 -40.7952 -17.17075 38.5 -41.2 -16 38.5 -39.1337 -17.70705 38.5 -38.02775 -16.85 38.5 4.963701 -1.661496 38.5 6.670747 -1.295197 38.5 7.2 0 38.5 6.795196 1.170748 38.5 5.133701 1.707047 38.5 4.027757 0.85 38.5 3.792953 -0.3662995 38.5 -39.1337 14.29295 38.5 -38.02775 15.15 38.5 -40.35 14.52776 38.5 -37.79296 16.36631 38.5 -38.96371 17.6615 38.5 -40.67075 17.2952 38.5 -41.20705 15.6337 38.5 -41.5 22.5 38.5 7.2 0 40 -40.19377 14.70798 -2.98874 -41.1582 13.91427 -3.001318 -40.96595 15.95438 -2.989515 -38.72559 14.75399 -2.988995 -39.6532 13.27573 -2.947659 -38.03372 16.04766 -2.988995 -36.78751 15.84182 -2.95327 -37.6895 14.04518 -3.001437 -38.80813 17.29367 -2.988995 -36.98745 17.05891 -2.951326 -39.07197 18.69479 -2.947659 -37.69344 18.09008 -2.916208 -41.7949 17.45467 -2.953269 -40.27441 17.24601 -2.988995 -40.15789 18.65587 -2.94434 -42.15405 15.76485 -3.001437 -42.23927 15.75731 0 -41.0988 16.15946 0 -42.23205 16.31369 0 -42.11298 16.85723 0 -40.98786 16.58844 0 -41.88693 17.36567 0 -40.77537 16.97725 0 -41.56317 17.8182 0 -41.15493 18.19629 0 -40.45523 17.28356 0 -40.67895 18.48447 0 -40.06991 17.50227 0 -40.15469 18.67093 0 -39.60364 18.74805 0 -39.63645 17.59417 0 -39.04833 18.71266 0 -39.19369 17.57727 0 -38.51153 18.56621 0 -38.64459 17.36011 0 -38.01519 18.3147 0 -37.57964 17.96843 0 -38.31005 17.06959 0 -37.2227 17.54157 0 -38.05672 16.70608 0 -36.95901 17.0516 0 -36.79933 16.51857 0 -37.89912 16.13703 0 -36.75023 15.96432 0 -36.8137 15.41152 0 -37.92934 15.69498 0 -36.98715 14.88282 0 -38.06676 15.27375 0 -37.26347 14.39986 0 -37.63136 13.9824 0 -38.32518 14.91382 0 -38.07575 13.64755 0 -38.66377 14.62802 0 -38.57845 13.40901 0 -39.07294 14.45805 0 -39.11888 13.27654 0 -39.51128 14.3933 0 -39.67491 13.25557 0 -40.22378 13.34696 0 -40.09091 14.50587 0 -40.74302 13.54696 0 -41.21136 13.84739 0 -40.59075 14.82022 0 -41.60965 14.23595 0 -41.92156 14.69673 0 -40.86622 15.16727 0 -42.13434 15.21087 0 -41.04845 15.57115 0 -39.76974 14.48953 0.07205271 -39.51808 14.51829 5.946587 -40.10728 14.67809 5.954937 -38.85297 14.62924 5.846804 -38.82155 14.63768 0.06716656 -38.4011 15.03857 5.94652 -38.21211 15.19125 0.06881415 -38.07191 15.60737 5.929934 -37.97804 15.98363 0.06649971 -38.1126 16.46176 5.984569 -38.19634 16.78605 0.06597101 -38.46928 17.10733 5.85084 -38.80386 17.35408 0.06545239 -39.24977 17.45326 5.960566 -39.61937 17.51809 0.06494534 -40.01099 17.42353 5.851264 -40.39945 17.22902 0.06445813 -40.82959 16.77451 5.850087 -40.9113 16.57305 0.06399142 -41.00682 16.54155 0.001528918 -40.96188 15.78579 5.946122 -40.92242 15.45691 0.06473863 -40.63037 15.04988 5.932566 -40.52701 14.88962 0.06313008 -40.48545 16.96602 6.001203 -40.51354 13.3687 -1.0394e-5 -38.84197 13.31547 -8.99609e-7 -38.69895 13.35102 -2.850359 -37.3845 14.13568 -1.04132e-5 -37.61403 13.9637 -2.855019 -36.92011 14.99854 -2.850361 -36.75405 15.6847 -8.91779e-7 -37.017 17.33633 -1.03996e-5 -38.25065 18.46553 -8.83696e-7 -39.60504 18.7853 -3.67833e-6 -41.41604 18.06878 -1.0376e-5 -41.17028 18.21665 -2.855018 -42.19997 16.59146 -8.83668e-7 -42.23104 16.44741 -2.850361 -42.10545 14.92172 -1.03769e-5 -42.08913 14.92849 -2.858142 -41.00114 13.65982 -2.84589 -38.45334 16.68303 -2.875808 -38.38515 15.43507 -2.875809 -39.43181 14.75206 -2.875798 -40.54794 15.31899 -2.875863 -40.61479 16.5649 -2.875773 -39.56819 17.24794 -2.875799 -40.91635 15.869 -1.742881 -39.5 16 -0.9783121 -40.29538 17.20388 -1.782642 -38.85203 17.28946 -1.783531 -38.06027 16.06852 -1.765801 -38.71789 14.78794 -1.787682 -40.1343 14.71219 -1.789421 -40.94182 15.29494 -0.006251215 -40.58923 14.82212 -0.008423566 -39.51143 14.39573 -0.008422493 -41.07308 15.71442 -0.003897547 -41.09703 16.15956 -0.006252408 -40.77335 16.97591 -0.008421003 -40.33508 17.37062 -0.006249964 -39.92951 17.54002 -0.00389713 -39.48857 17.60428 -0.00842297 -38.90982 17.49182 -0.008423268 -38.41077 17.17788 -0.008423089 -38.05818 16.70506 -0.006251573 -37.92692 16.28558 -0.003898859 -37.90362 15.84061 -0.008424341 -38.069 15.27469 -0.008424699 -38.42765 14.80673 -0.008423388 -38.93112 14.49993 -0.008423388 -40.09019 14.50819 -0.008422255 61 8.000003 4 59 10 4 -49.7772 67.09818 4 54.75 69.96891 4 53 69.5 4 50.46825 66.41615 4 55.43534 64.60549 4 54.93059 66.16925 4 55.12095 87.8493 4 55.58849 77.53776 4 42.93772 68.75981 4 43.38956 69.94924 4 -58.64815 77.48486 4 -59.62803 86.567 4 -60.36096 -86.06967 4 -55.12096 -87.8493 4 -64.59908 -82.51113 4 40.61573 -81.46345 4 38.3897 -76.39694 4 44.2 -17.38564 4 76.38015 -7.35 4 67 -20 4 76.73519 -8.675 4 80.35516 -9.644968 4 79.03015 -10 4 77.56378 -16.99526 4 74.39337 -17.15526 4 75.2 -16.11436 4 77.70516 -9.644968 4 76.34476 -15.89337 4 76.38015 7.35 4 76.73519 8.675 4 77.70516 9.644968 4 79.03015 10 4 80.35516 9.644968 4 85.39232 13.9125 4 81.32512 8.675 4 88 10.18532 4 81.68015 7.35 4 88 -10.18532 4 81.61756 -8.153496 4 68 -21 4 46.68614 -23.2405 4 47.30947 -21.25275 4 46.60663 -16.34476 4 48.794 -20.07793 4 66.65719 -66.79666 4 58.13722 -65.82449 4 57.75624 -66.92636 4 54.97346 -66.32924 4 55.31821 -64.72261 4 56.53723 -64.22448 4 58.87342 -59.19772 4 57.63911 -64.60549 4 56.19248 -67.43112 4 53 -69.5 4 63.4784 -62.26673 4 67.97708 -72.17092 4 64.59908 -82.51113 4 67.25843 -77.65803 4 63.05701 -77.39494 4 50.56465 -78.95651 4 51.06941 -80.52027 4 55.12095 -87.8493 4 60.36098 -86.06966 4 49.96754 -81.73928 4 49.59225 -87.60778 4 44.52739 -85.378 4 38.15228 -70.86806 4 43.21058 -69.81641 4 39.93578 -65.62937 4 22.97838 -20.02931 4 7.75 -17.1 4 24.74922 -21.21082 4 -23.12203 -20.05892 4 -22 -8.000001 4 -24.7113 -21.20505 4 -37.89337 -16.34476 4 -38.99525 -17.56376 4 -39.93579 -65.62937 4 -38.15228 -70.86806 4 -44.52739 -85.378 4 -40.61573 -81.46345 4 -38.3897 -76.39694 4 -48.24377 -81.27741 4 -49.59225 -87.60778 4 -49.46277 -81.77552 4 -67.25843 -77.65803 4 -62.32034 -78.48646 4 -58.56896 -77.39639 4 -61.25101 -78.76795 4 -59.99695 -74.74866 4 -58.92762 -75.03015 4 -56.5 -73 4 -62.67902 -76.12023 4 -67.97708 -72.17092 4 -63.02472 -77.55741 4 -58.22325 -75.95922 4 -66.65718 -66.79666 4 -58.87342 -59.19772 4 -63.4784 -62.26673 4 -57.75624 -64.72261 4 -58.10099 -66.32924 4 -56.88197 -67.43112 4 -54.93059 -66.16925 4 -55.73723 -67.21012 4 -53 -69.5 4 -46.9075 -23.96476 4 -56.53723 -64.22448 4 -55.43534 -64.60549 4 -46.78057 -22.56015 4 -41.06376 -16.50476 4 -47.30947 -21.25275 4 -48.92235 -20.05786 4 -62 -20 4 -65 -17 4 -65 17 4 -55 8.000003 4 -62 20 4 -48.794 20.07793 4 -43 10 4 -47.30947 21.25275 4 -46.69086 23.20653 4 -54.97346 66.32924 4 -55.31821 64.72261 4 -58.87342 59.19772 4 -66.65718 66.79666 4 -63.4784 62.26673 4 -57.74779 70.73113 4 -67.97708 72.17092 4 -62.59983 76.03176 4 -67.25843 77.65803 4 -58.19096 76.12168 4 -58.92762 75.03015 4 -59.87856 74.73973 4 -63.05701 77.39494 4 -64.59908 82.51113 4 -62.32034 78.48646 4 -61.3694 78.77689 4 -47.85614 79.83077 4 -38.3897 76.39694 4 -44.52739 85.378 4 -48.3609 81.39453 4 -48.95801 78.61177 4 -53 76.50001 4 -50.56465 78.95651 4 -51.06941 80.52027 4 -55.12097 87.8493 4 -49.96754 81.73928 4 -49.59225 87.60778 4 -39.93578 65.62936 4 -38.15228 70.86806 4 -29.95 15.575 4 -22.96151 20.02201 4 -24.74922 21.21082 4 10.7 18.35 4 23.27618 20.13897 4 37.83438 14.1875 4 24.7113 21.20505 4 39.93579 65.62937 4 44.52739 85.378 4 40.61573 81.46345 4 38.3897 76.39694 4 47.93651 75.26888 4 48.36089 78.95651 4 47.86277 80.17552 4 38.15228 70.86806 4 48.24377 81.27741 4 49.59225 87.60778 4 49.46277 81.77552 4 51.06941 79.83078 4 50.56465 81.39454 4 49.96754 78.61177 4 58.56896 77.39639 4 61.25101 78.76795 4 60.36096 86.06967 4 64.59908 82.51113 4 62.32034 78.48646 4 67.25843 77.65803 4 63.02472 77.55741 4 67.97708 72.17092 4 62.67902 76.12023 4 63.4784 62.26673 4 66.65718 66.79666 4 58.87342 59.19772 4 47.30947 21.25275 4 46.66256 23.08957 4 43.18438 18.35 4 49.74815 20 4 48.37733 20.33151 4 67 20 4 74.39337 17.84474 4 68 21 4 75.2 18.88564 4 76.34476 19.10663 4 80.43363 21 4 77.56378 18.00474 4 77.38565 16.7 4 76.50476 15.93624 4 74.89813 16.28099 4 77.38565 -18.3 4 80.43363 -21 4 76.50476 -19.06376 4 74.89813 -18.71902 4 16.56376 -14.49525 4 16.38564 -15.8 4 15.34475 -13.39337 4 20 -10 4 22 -8.000001 4 13.43624 -15.50475 4 15.50475 -16.56376 4 14.2 -16.38564 4 10 -10 4 13.78099 -13.89812 4 45 -7.999999 4 22 8 4 20 10 4 10 10 4 8 -8 4 8 8 4 59.87856 -74.73973 4 62.59983 -76.03176 4 58.64815 -77.48486 4 58.19096 -76.12168 4 56.03108 -71.25 4 58.92762 -75.03015 4 61.3694 -78.77689 4 62.32034 -78.48646 4 43.0747 -68.18412 4 44.36314 -67.17759 4 47.81557 -69.58573 4 47.24315 -70.88221 4 49.5 -73.00001 4 46.02459 -71.24819 4 47.29187 -68.46315 4 45.92527 71.23545 4 44.82677 67.24797 4 43.61747 67.51622 4 47.36247 68.53416 4 47.13457 70.96718 4 47.8143 69.72359 4 -54.75 76.03109 4 -53 69.5 4 -54.75 69.96891 4 -56.03109 71.25 4 -56.5 73 4 -56.03109 74.75 4 -51.25 76.03109 4 -49.96891 74.75 4 -49.5 73.00001 4 -49.96891 71.25 4 -51.25 69.96891 4 -56.19248 67.43112 4 -57.75624 66.92636 4 -56.53723 64.22448 4 -57.63911 64.60549 4 -58.13722 65.82449 4 -47.81557 69.58573 4 -47.24315 70.88221 4 -43.21058 69.81641 4 -43.0747 68.18412 4 -46.02459 71.24819 4 -40.61573 81.46345 4 -44.36314 67.17759 4 -47.29187 68.46315 4 -54.75 -69.96891 4 -53 -76.5 4 -54.75 -76.03109 4 -56.03109 -74.75 4 -56.03109 -71.25 4 -51.25 -76.03109 4 -51.06941 -79.83078 4 -49.96891 -74.75 4 -47.13457 -70.96718 4 -49.5 -73 4 -49.96891 -71.25 4 -50.56465 -81.39454 4 -49.96754 -78.61177 4 -48.36089 -78.95651 4 -47.86278 -80.17552 4 -42.93772 -68.75981 4 -45.92527 -71.23545 4 -47.8143 -69.72359 4 -51.25 -69.96891 4 -43.38956 -69.94924 4 -47.36247 -68.53416 4 -43.61747 -67.51622 4 -44.82677 -67.24797 4 49.5 73 4 49.96891 71.25 4 51.25 69.96891 4 56.03109 71.25 4 58.17698 70.73113 4 56.5 73 4 56.03109 74.75 4 54.75 76.03109 4 53 76.5 4 51.25 76.03109 4 49.96891 74.75 4 55.73723 67.21012 4 56.88197 67.43112 4 58.10099 66.32924 4 57.75624 64.72261 4 56.53723 64.22448 4 59.99695 74.74866 4 58.92762 75.03015 4 58.22325 75.95922 4 53 -76.50001 4 54.75 -76.03109 4 56.5 -73 4 56.03109 -74.75 4 51.25 -76.03109 4 49.96891 -74.75 4 49.96891 -71.25 4 51.25 -69.96891 4 54.75 -69.96891 4 47.85614 -79.83077 4 48.95801 -78.61177 4 48.3609 -81.39453 4 -15.50475 -13.43624 4 -10 -10 4 -20 -10 4 -16.38564 -14.2 4 -13.61436 -14.2 4 -13.39337 -15.34475 4 -16.56376 -15.50475 4 -14.2 -13.61436 4 -8 -8 4 -14.49525 -16.56376 4 -15.8 -16.38564 4 -20 10 4 -10 10 4 -8 8 4 -1.385641 -0.8 4 -1.606632 0.3447525 4 1.321205 -1.03267 4 -0.3447525 -1.606632 4 -0.8 1.385641 4 0.3447525 1.606632 4 1.462173 0.5319727 4 1.6 0 4 -22 8 4 16.56376 15.50475 4 15.8 16.38564 4 14.49525 16.56376 4 13.89812 13.78099 4 13.39337 15.34475 4 16.38564 14.2 4 15.50475 13.43624 4 -16.56376 14.49525 4 -16.38564 15.8 4 -15.50475 16.56376 4 4.8 15.575 4 -13.43624 15.50475 4 -14.2 16.38564 4 -15.34475 13.39337 4 -13.78099 13.89812 4 45.50475 -17.56376 4 47 -10 4 45 -14.4 4 43.43624 -16.50477 4 43.78099 -14.89812 4 46.10189 -14.78099 4 -40.3 -17.38564 4 -40.71902 -14.89812 4 -43 -10 4 -41 -7.999999 4 -39.15525 -14.39337 4 -38.11436 -15.2 4 59 -10 4 61 -8.000003 4 47 10 4 45 8 4 -55.60663 -14.65524 4 -53 -10 4 -55 -8.000003 4 -55.10188 -16.21901 4 -52.61436 -15.8 4 -53.49525 -16.56376 4 -54.50475 -13.43624 4 -53.2 -13.61436 4 -52.43624 -14.49525 4 -41 8 4 -53 10 4 -55.60663 15.34476 4 -52.78099 13.89812 4 -52.43624 15.50475 4 -54.50475 16.56376 4 -53.2 16.38564 4 -54.34475 13.39337 4 -55.38564 14.2 4 44.49525 17.56376 4 46.10188 17.21901 4 44.65525 14.39337 4 46.21901 14.89812 4 43.43624 15.49523 4 43.61436 16.8 4 46.6 16 4 -40.60189 14.781 4 -41.10663 16.34476 4 -40.3 17.38564 4 -39.15525 17.60663 4 -38.11436 16.8 4 -37.89337 15.65524 4 -38.99525 14.43624 4 -47.82302 75.26888 0 66.65718 66.79666 0 56.03109 71.25 0 47.74635 -69.29797 0 47.44331 -68.6536 0 52.82764 -41.39624 0 49.96891 74.75 0 49.5 73.00001 0 61 -8 0 67 -20 0 66.65718 -66.79666 0 67.97708 -72.17093 0 63.4784 -62.26673 0 50.84841 -80.97553 0 51.06277 -80.17552 0 -24.50122 -20.97301 0 -25.13024 -22.03526 0 -22 -8.000001 0 -57.92287 -66.62448 0 -57.33722 -67.21012 0 -57.31861 -68.46224 0 -50.84841 80.97552 0 -51.06277 80.17552 0 -55.12095 87.8493 0 77.70516 9.644968 0 76.73519 8.675 0 61 8.000003 0 79.03015 10 0 85.39232 13.9125 0 80.35516 9.644968 0 77.38565 16.7 0 74.4 17.5 0 74.61437 16.7 0 75.2 16.11436 0 76 15.9 0 76.80001 16.11436 0 77.60001 17.5 0 77.38565 18.3 0 80.43363 21 0 74.61437 18.3 0 67 20 0 75.2 18.88564 0 68 21 0 76 19.1 0 76.80001 18.88564 0 46.68791 23.22779 0 47.30947 21.25275 0 47.93651 18.35 0 48.37733 20.3315 0 49.74815 20 0 55.15158 66.62448 0 54.93722 65.82449 0 53 69.5 0 55.15158 65.02449 0 58.13722 65.82449 0 58.87342 59.19772 0 57.92287 65.02449 0 55.73723 64.43885 0 56.53723 64.22448 0 57.33722 64.43885 0 67.97708 72.17092 0 67.25843 77.65803 0 62.86634 77.86369 0 64.59908 82.51113 0 62.32034 78.48646 0 60.36096 86.06967 0 61.53612 78.7528 0 55.12095 87.8493 0 60.72378 78.59135 0 49.46277 78.57552 0 50.26277 78.78987 0 54.75001 76.03109 0 50.84841 79.37551 0 51.06277 80.17552 0 48.66277 81.56116 0 44.52739 85.378 0 49.46277 81.77552 0 49.59225 87.60778 0 50.26277 81.56116 0 50.84841 80.97552 0 48.07713 80.97552 0 47.86277 80.17552 0 48.07714 79.37551 0 48.66276 78.78987 0 38.15228 70.86805 0 38.3897 76.39694 0 40.61573 81.46345 0 43.32707 67.83471 0 39.93578 65.62937 0 37.83438 14.1875 0 23.11193 20.08709 0 24.74922 21.21082 0 -23.0613 20.02738 0 10.7 18.35 0 4.8 15.575 0 -29.95 15.575 0 -39.93578 65.62936 0 -24.7113 21.20505 0 -40.61573 81.46345 0 -38.3897 76.39694 0 -38.15228 70.86806 0 -50.84841 79.37551 0 -51.24999 76.03109 0 -50.26277 78.78987 0 -49.46277 78.57552 0 -48.66277 78.78987 0 -44.52739 85.378 0 -48.66277 81.56116 0 -49.59225 87.60778 0 -49.46277 81.77552 0 -50.26277 81.56116 0 -48.07713 79.37551 0 -47.86277 80.17552 0 -48.07713 80.97552 0 -58.25751 87.04843 0 -59.10929 77.79547 0 -60.72378 78.59135 0 -60.36096 86.06967 0 -61.53612 78.7528 0 -64.59908 82.51113 0 -62.32034 78.48646 0 -67.25843 77.65803 0 -62.86634 77.86369 0 -63.02779 77.05136 0 -67.97708 72.17092 0 -59.71185 74.7638 0 -58.92762 75.03015 0 -57.74779 70.73113 0 -60.52418 74.92527 0 -58.38164 75.65292 0 -58.22018 76.46525 0 -58.48652 77.24948 0 -62.76145 76.26713 0 -62.13867 75.72114 0 -66.65718 66.79666 0 -58.13722 65.82449 0 -57.92287 65.02449 0 -58.87342 59.19772 0 -57.33722 64.43885 0 -56.53723 64.22448 0 -49.7772 66.41615 0 -46.66256 23.08957 0 -42.03438 18.35 0 -47.30947 21.25275 0 -48.92235 20.05786 0 -62 20 0 -65 17 0 -65 -17 0 -62 -20 0 -48.794 -20.07793 0 -45.90579 -17.1 0 -47.30947 -21.25275 0 -46.68791 -23.22779 0 -56.53723 -67.42449 0 -55.73723 -67.21012 0 -49.7772 -68.46224 0 -58.87342 -59.19772 0 -55.15158 -66.62448 0 -54.93722 -65.82449 0 -55.15158 -65.02449 0 -63.4784 -62.26673 0 -58.13722 -65.82449 0 -55.73723 -64.43885 0 -56.53723 -64.22448 0 -57.33722 -64.43885 0 -57.92287 -65.02449 0 -66.65718 -66.79666 0 -56.5 -73.00001 0 -67.97708 -72.17092 0 -62.13867 -75.72114 0 -62.76145 -76.26713 0 -67.25843 -77.65803 0 -58.92762 -75.03015 0 -59.71185 -74.7638 0 -60.52418 -74.92527 0 -58.22018 -76.46525 0 -58.38164 -75.65292 0 -63.02779 -77.05136 0 -62.86634 -77.86369 0 -64.59908 -82.51113 0 -62.32034 -78.48646 0 -61.53612 -78.7528 0 -60.72378 -78.59135 0 -59.10929 -77.79547 0 -58.48652 -77.24948 0 -55.12095 -87.8493 0 -50.26277 -81.56116 0 -49.59225 -87.60778 0 -49.46277 -81.77552 0 -44.52739 -85.37801 0 -48.66277 -81.56116 0 -23.01201 -20.04386 0 24.7113 -21.20505 0 23.08057 -20.03738 0 7.75 -17.1 0 48.07714 -79.37551 0 47.86277 -80.17552 0 44.52739 -85.378 0 40.61573 -81.46345 0 48.07713 -80.97552 0 48.66277 -81.56116 0 49.59225 -87.60778 0 49.46277 -81.77552 0 55.12095 -87.8493 0 50.26277 -81.56116 0 55.58849 -78.21979 0 60.36096 -86.06967 0 61.53612 -78.7528 0 64.59908 -82.51113 0 62.32034 -78.48646 0 67.25843 -77.65803 0 62.86634 -77.86369 0 63.02779 -77.05136 0 62.76145 -76.26713 0 57.92287 -65.02449 0 57.33722 -64.43885 0 58.87342 -59.19772 0 57.92287 -66.62448 0 58.13722 -65.82449 0 55.73723 -64.43885 0 55.15158 -65.02449 0 54.93722 -65.82449 0 53 -69.5 0 55.15158 -66.62448 0 56.53723 -64.22448 0 55.73723 -67.21012 0 56.53723 -67.42449 0 57.33722 -67.21012 0 46.66256 -23.08956 0 44.2 -17.38564 0 45 -17.6 0 45.8 -17.38564 0 47.30947 -21.25275 0 48.92235 -20.05786 0 59 -10 0 68 -21 0 80.43363 -21 0 77.38565 -18.3 0 88 -10.18532 0 77.60001 -17.5 0 77.38565 -16.7 0 75.2 -16.11436 0 74.61437 -16.7 0 74.4 -17.5 0 74.61437 -18.3 0 75.2 -18.88564 0 76 -19.1 0 76.80001 -18.88564 0 76.73519 -8.675 0 77.70516 -9.644968 0 76 -15.9 0 81.68015 -7.35 0 88 10.18532 0 81.68015 7.35 0 81.32512 8.675 0 76.38015 7.35 0 76.38015 -7.35 0 76.80001 -16.11436 0 79.03015 -10 0 80.35516 -9.644968 0 81.32512 -8.675 0 -52.61436 14.2 0 -53.2 13.61436 0 -52.4 15 0 -52.61436 15.8 0 -55.6 15 0 -55.38564 15.8 0 -53.2 16.38564 0 -54 16.6 0 -54.8 16.38564 0 -54.8 13.61436 0 -54 13.4 0 -53 10 0 -40.61573 -81.46345 0 -38.3897 -76.39694 0 -42.03438 -70.73113 0 -38.15228 -70.86806 0 -39.93578 -65.62937 0 -38.7 -17.38564 0 -38.11436 -16.8 0 -37.9 -16 0 -41.1 -16 0 -40.88564 -16.8 0 -40.3 -17.38564 0 -39.5 -17.6 0 -38.11436 -15.2 0 -38.7 -14.61436 0 -41 -7.999999 0 -39.5 -14.4 0 -43 -10 0 -40.3 -14.61436 0 -40.88564 -15.2 0 -53 -10 0 -55.6 -15 0 -55.38564 -15.8 0 -52.61436 -15.8 0 -52.4 -15 0 -55.38564 -14.2 0 -54.8 -13.61436 0 -55 -8.000002 0 -54 -13.4 0 -52.61436 -14.2 0 -53.2 -13.61436 0 -54.8 -16.38564 0 -54 -16.6 0 -53.2 -16.38564 0 -43 10 0 -55.38564 14.2 0 -55 8 0 -41 8 0 43.61436 -15.2 0 43.4 -16 0 45 -7.999999 0 46.38564 -16.8 0 45 7.999999 0 43.61436 -16.8 0 46.6 -16 0 46.38564 -15.2 0 47 -10 0 45.8 -14.61436 0 45 -14.4 0 44.2 -14.61436 0 47 10 0 59 10 0 -16.38564 15.8 0 -20 10 0 -16.6 15 0 -13.4 15 0 -13.61436 15.8 0 -14.2 16.38564 0 -15 16.6 0 -15.8 16.38564 0 -16.38564 14.2 0 -15.8 13.61436 0 -15 13.4 0 -14.2 13.61436 0 -13.61436 14.2 0 16.38564 14.2 0 16.6 15 0 16.38564 15.8 0 15.8 16.38564 0 15 16.6 0 14.2 16.38564 0 13.61436 15.8 0 10 10 0 13.4 15 0 15 13.4 0 14.2 13.61436 0 13.61436 14.2 0 15.8 13.61436 0 -49.5 -73.00001 0 -47.7398 -70.01 0 -47.74635 -69.29797 0 -47.42496 -70.64868 0 -46.86418 -71.08751 0 -46.16854 -71.23957 0 -45.47581 -71.07474 0 -43.86132 -70.27886 0 -43.30871 -69.82979 0 -43.00568 -69.18543 0 -43.01222 -68.47339 0 -43.32707 -67.83471 0 -46.8907 -68.20453 0 -47.44331 -68.6536 0 -43.88785 -67.39588 0 -44.58349 -67.24383 0 -45.27621 -67.40866 0 -48.07713 -79.37551 0 -47.82302 -77.53776 0 -47.86277 -80.17552 0 -48.07713 -80.97552 0 -48.66277 -78.78987 0 -49.46277 -78.57552 0 -53 -76.50001 0 -50.26277 -78.78987 0 -50.84841 -79.37551 0 -51.06277 -80.17552 0 -50.84841 -80.97552 0 -51.25 -69.96891 0 -53 -69.5 0 -54.75 -69.96891 0 -56.03109 -71.25 0 -56.03109 -74.75 0 -54.75 -76.03109 0 -51.25 -76.03109 0 -49.96891 -74.75 0 -49.96891 -71.25 0 -54.75 69.96891 0 -53 69.5 0 -51.25 69.96891 0 -53 76.5 0 -54.75 76.03109 0 -56.03109 74.75 0 -56.5 73 0 -56.03109 71.25 0 -49.96891 71.25 0 -49.5 73 0 -49.96891 74.75 0 -55.73723 64.43885 0 -55.15158 65.02449 0 -54.93722 65.82449 0 -55.15158 66.62448 0 -55.73723 67.21012 0 -56.53723 67.42449 0 -57.33722 67.21012 0 -57.92287 66.62448 0 -63.4784 62.26673 0 -44.58349 67.24383 0 -43.88785 67.39588 0 -43.32707 67.83471 0 -43.01222 68.4734 0 -45.27621 67.40866 0 -47.44331 68.6536 0 -46.8907 68.20453 0 -43.00568 69.18543 0 -43.30871 69.82979 0 -46.86418 71.08751 0 -47.42496 70.64868 0 -47.7398 70.01 0 -47.74635 69.29797 0 -43.86132 70.27886 0 -45.47581 71.07474 0 -46.16854 71.23957 0 53 76.5 0 51.25 76.03109 0 59.10929 77.79547 0 58.48652 77.24948 0 56.5 73 0 56.03109 74.75 0 49.96891 71.25 0 51.25 69.96891 0 54.75 69.96891 0 57.92287 66.62448 0 55.73723 67.21012 0 56.53723 67.42449 0 57.33722 67.21012 0 47.42496 70.64868 0 46.86418 71.08751 0 46.16854 71.23957 0 45.47581 71.07474 0 43.86132 70.27886 0 43.30871 69.82979 0 43.00568 69.18543 0 43.01222 68.47339 0 47.7398 70.01 0 47.74635 69.29797 0 47.44331 68.6536 0 46.8907 68.20453 0 43.88785 67.39588 0 44.58349 67.24383 0 45.27621 67.40866 0 59.71185 74.7638 0 60.52418 74.92527 0 62.13867 75.72114 0 62.76145 76.26713 0 63.02779 77.05136 0 58.22018 76.46525 0 58.38164 75.65292 0 58.92762 75.03015 0 49.5 -73 0 49.96891 -71.25 0 56.5 -73 0 56.03109 -71.25 0 54.75 -69.96891 0 51.25 -69.96891 0 54.75 -76.03109 0 56.03109 -74.75 0 49.96891 -74.75 0 38.15228 -70.86805 0 51.25 -76.03109 0 50.26277 -78.78987 0 53 -76.5 0 50.84841 -79.37551 0 49.46277 -78.57552 0 48.66277 -78.78987 0 43.30871 -69.82979 0 43.00568 -69.18543 0 43.01222 -68.47339 0 39.93578 -65.62937 0 43.32707 -67.83471 0 43.88785 -67.39588 0 44.58349 -67.24383 0 45.27621 -67.40866 0 46.8907 -68.20453 0 47.7398 -70.01 0 47.42496 -70.64868 0 46.86418 -71.08751 0 43.86132 -70.27886 0 45.47581 -71.07474 0 46.16854 -71.23957 0 59.10929 -77.79547 0 60.72378 -78.59135 0 62.13867 -75.72114 0 60.52418 -74.92527 0 59.71185 -74.7638 0 58.92762 -75.03015 0 58.38164 -75.65292 0 58.22018 -76.46525 0 58.48652 -77.24948 0 -13.61436 -15.8 0 -13.4 -15 0 -16.38564 -15.8 0 -15.8 -16.38564 0 -15 -16.6 0 -14.2 -16.38564 0 -15 -13.4 0 -20 -10 0 -14.2 -13.61436 0 -10 -10 0 -13.61436 -14.2 0 -15.8 -13.61436 0 -16.38564 -14.2 0 -16.6 -15 0 -22 8 0 -0.8 -1.385641 0 0 -1.6 0 8 -8 0 0.8 -1.385641 0 1.385641 -0.8 0 1.6 0 0 1.385641 0.8 0 0.8 1.385641 0 0 1.6 0 -1.385641 -0.8 0 -8 -8 0 -8 8 0 -10 10 0 -0.8 1.385641 0 -1.385641 0.8 0 -1.6 0 0 13.61436 -14.2 0 13.4 -15 0 13.61436 -15.8 0 16.38564 -15.8 0 16.6 -15 0 14.2 -16.38564 0 15 -16.6 0 15.8 -16.38564 0 16.38564 -14.2 0 20 -10 0 15.8 -13.61436 0 10 -10 0 15 -13.4 0 14.2 -13.61436 0 8 8 0 20 10 0 22 -8.000001 0 22 8 0 38.3897 -76.39694 0 -60.36096 -86.06967 0 46.38564 16.8 0 45.8 17.38564 0 43.18438 18.35 0 45 17.6 0 44.2 17.38564 0 44.2 14.61436 0 45 14.4 0 45.8 14.61436 0 46.38564 15.2 0 46.6 16 0 43.61436 16.8 0 43.4 16 0 43.61436 15.2 0 -40.3 17.38564 0 -40.88564 16.8 0 -41.1 16 0 -40.88564 15.2 0 -40.3 14.61436 0 -39.5 14.4 0 -38.7 14.61436 0 -38.11436 15.2 0 -37.9 16 0 -38.11436 16.8 0 -38.7 17.38564 0 -39.5 17.6 0 63.4784 62.26673 0 -47.85614 80.52027 0 -48.95801 81.73928 0 -50.56465 81.39454 0 -51.06277 80.17552 0 -50.68178 79.07363 0 -49.11801 78.56889 0 -48.07713 79.37551 0 -54.93059 66.16924 0 -56.03248 67.38825 0 -57.63911 67.04349 0 -58.13722 65.82449 0 -57.75624 64.72261 0 -56.53723 64.22448 0 -55.43534 64.60549 0 -44.82677 67.24797 0 -43.61746 67.51622 0 -42.93772 68.75981 0 -43.38956 69.94924 0 -45.92527 71.23545 0 -47.13457 70.96718 0 -47.8143 69.72359 0 -47.36247 68.53417 0 -59.99695 74.74866 0 -58.63732 75.21622 0 -58.22018 76.46525 0 -58.56896 77.39638 0 -61.25101 78.76795 0 -62.32034 78.48646 0 -63.02472 77.55741 0 -62.67902 76.12023 0 -47.85614 -79.83077 0 -48.95801 -78.61177 0 -50.56465 -78.95651 0 -51.06941 -80.52027 0 -49.96754 -81.73928 0 -48.3609 -81.39453 0 -54.97346 -66.32924 0 -55.31821 -64.72261 0 -56.53723 -64.22448 0 -57.63911 -64.60549 0 -58.14386 -66.16925 0 -57.04197 -67.38825 0 -55.73723 -67.21012 0 -43.21058 -69.81641 0 -43.0747 -68.18412 0 -44.36315 -67.17759 0 -47.29187 -68.46315 0 -47.81557 -69.58573 0 -47.24315 -70.88221 0 -46.02459 -71.24819 0 -58.64815 -77.48486 0 -58.22018 -76.46525 0 -58.52812 -75.34078 0 -59.87856 -74.73973 0 -62.59983 -76.03176 0 -63.05701 -77.39494 0 -62.32034 -78.48646 0 -61.3694 -78.77689 0 51.06941 80.52027 0 49.96754 81.73928 0 48.3609 81.39453 0 47.85614 79.83077 0 48.95801 78.61177 0 50.56465 78.95651 0 58.14386 66.16925 0 57.04197 67.38825 0 55.73723 67.21012 0 54.97346 66.32924 0 55.31821 64.72261 0 56.53723 64.22448 0 57.63911 64.60549 0 43.21058 69.81641 0 43.0747 68.18412 0 44.36315 67.17759 0 47.29187 68.46315 0 47.81557 69.58573 0 47.24315 70.88221 0 46.02459 71.24819 0 58.64815 77.48486 0 58.22018 76.46525 0 58.52812 75.34078 0 59.87856 74.73973 0 62.59983 76.03176 0 63.05701 77.39494 0 62.32034 78.48646 0 61.3694 78.77689 0 51.06277 -80.17552 0 50.68178 -79.07363 0 49.11801 -78.56889 0 48.07713 -79.37551 0 47.85614 -80.52027 0 48.95801 -81.73928 0 50.56465 -81.39454 0 58.13722 -65.82449 0 57.75624 -64.72261 0 56.53723 -64.22448 0 55.43534 -64.60549 0 54.93059 -66.16924 0 56.03248 -67.38825 0 57.63911 -67.04349 0 44.82677 -67.24797 0 43.61746 -67.51622 0 42.93772 -68.75981 0 43.38956 -69.94924 0 45.92527 -71.23545 0 47.13457 -70.96718 0 47.8143 -69.72359 0 47.36247 -68.53417 0 59.99695 -74.74866 0 58.63732 -75.21622 0 58.22018 -76.46525 0 58.56896 -77.39638 0 61.25101 -78.76795 0 62.32034 -78.48646 0 63.02472 -77.55741 0 62.67902 -76.12023 0 1.56376 -0.5047524 0 1.385641 0.8 0 0.5047524 1.56376 0 -0.8 1.385641 0 -1.56376 0.5047524 0 -1.385641 -0.8 0 -0.5047524 -1.56376 0 0.8 -1.385641 0 16.56376 14.49525 0 16.38564 15.8 0 15.50475 16.56376 0 14.2 16.38564 0 13.43624 15.50475 0 13.61436 14.2 0 14.49525 13.43624 0 15.8 13.61436 0 16.56376 -15.50475 0 16.38564 -14.2 0 15.50475 -13.43624 0 14.2 -13.61436 0 13.43624 -14.49525 0 13.61436 -15.8 0 14.49525 -16.56376 0 15.8 -16.38564 0 -13.43624 -15.50475 0 -13.61436 -14.2 0 -14.49525 -13.43624 0 -15.8 -13.61436 0 -16.56376 -14.49525 0 -16.38564 -15.8 0 -15.50475 -16.56376 0 -14.2 -16.38564 0 -13.43624 14.49525 0 -13.61436 15.8 0 -14.49525 16.56376 0 -15.8 16.38564 0 -16.56376 15.50475 0 -16.38564 14.2 0 -15.50475 13.43624 0 -14.2 13.61436 0 46.6 -16 0 46.21901 -14.89812 0 44.65525 -14.39337 0 43.43624 -15.49523 0 43.61436 -16.8 0 44.49525 -17.56376 0 46.10188 -17.21901 0 46.60663 16.34476 0 45.50475 17.56376 0 44.2 17.38564 0 43.43624 16.50476 0 43.78099 14.89812 0 45 14.4 0 46.10189 14.78099 0 -37.93624 -16.50476 0 -38.28099 -14.89812 0 -39.84475 -14.39337 0 -40.88564 -15.2 0 -41.10663 -16.34476 0 -40.00475 -17.56376 0 -38.7 -17.38564 0 -37.93624 15.49524 0 -38.11436 16.8 0 -38.99525 17.56376 0 -40.3 17.38564 0 -41.06376 16.50476 0 -40.71902 14.89813 0 -39.15525 14.39337 0 77.60665 -17.15526 0 76.50476 -15.93624 0 75.2 -16.11436 0 74.43624 -16.99526 0 74.78101 -18.60189 0 76 -19.1 0 77.10189 -18.71902 0 77.60665 17.84475 0 76.50476 19.06376 0 75.2 18.88564 0 74.43624 18.00474 0 74.78101 16.39811 0 76 15.9 0 77.10189 16.28099 0 -52.43624 -15.50475 0 -52.78099 -13.89812 0 -54.34475 -13.39337 0 -55.56375 -14.49524 0 -55.38564 -15.8 0 -54.50475 -16.56376 0 -53.2 -16.38564 0 -52.43624 14.49525 0 -52.61436 15.8 0 -53.49525 16.56376 0 -55.10188 16.21901 0 -55.60663 14.65524 0 -54.50475 13.43624 0 -53.2 13.61436 0 81.68015 7.35 0 81.32512 8.675 0 80.35516 9.644968 0 79.03015 10 0 77.70516 9.644968 0 76.73519 8.675 0 76.38015 7.35 0 76.38015 -7.35 0 76.73519 -8.675 0 77.70516 -9.644968 0 79.03015 -10 0 80.35516 -9.644968 0 81.48298 -8.444975 0 -40.72695 15.63706 38.5 -41.06512 14.00865 38.5 -40.21008 14.97127 38.5 -39.2876 14.73824 38.5 -40.49568 16.80359 38.5 -41.73288 17.19555 38.5 -41.97896 15.48057 38.5 -39.93412 13.53798 38.5 -38.55799 13.64889 38.5 -38.56436 15.1711 38.5 -37.26712 14.80446 38.5 -38.21813 16.04972 38.5 -37.02104 16.51943 38.5 -38.56436 16.8289 38.5 -37.58489 17.60697 38.5 -39.40427 17.27592 38.5 -38.71036 18.40656 38.5 -40.44201 18.35111 38.5 -40.21008 14.97127 4 -41.18933 14.11287 4 -40.75508 15.75117 4 -42.00712 15.64025 4 -40.41775 16.89156 4 -39.40427 14.72408 4 -38.71036 13.59344 4 -39.93412 13.53798 4 -39.2876 17.26176 4 -39.06588 18.46202 4 -37.81068 17.88714 4 -38.56436 16.8289 4 -38.21813 15.95028 4 -36.99288 16.35975 4 -37.34819 14.66404 4 -38.56436 15.1711 4 -41.65181 17.33597 4 -40.28964 18.40656 4 -14.21191 -14.66704 44 -10.67075 -16.2952 44 5.5 -5.656855 44 -9.133702 -13.29295 44 19.9637 -13.33851 44 23.51526 -12.2902 44 23.5 19.3204 44 24.77882 18.06638 44 -22 19.25237 44 -23.5 21.90192 44 -25 21.5 44 -26.5 21.90192 44 -27.59808 23 44 -28 24.5 44 -22 24.5 44 -11.16777 19.83745 44 -22.40192 26 44 -23.47793 27.08521 44 -22.40192 23 44 -8.186755 19.30072 44 -9.872652 19.87366 44 -8.027757 15.85 44 -11.1615 14.4637 44 -10.7952 16.17075 44 -14.21191 14.66704 44 -9.133703 16.70705 44 -7.792953 14.6337 44 -8.963702 13.33851 44 -0.1568546 0 44 -13.23833 13.08148 44 -10.35 13.52776 44 -9.978428 9.821574 44 5.5 5.656855 44 17.5 6.343146 44 17.5 17.65685 44 22 35.90192 44 23.09808 37 44 23.5 38.5 44 17.5 38.5 44 17.90192 37 44 19 35.90192 44 20.5 35.5 44 21.67075 16.2952 44 19.9637 16.6615 44 25.38218 16.37999 44 25.18912 14.59935 44 23.52091 12.24719 44 22.20705 14.6337 44 21.35 13.52776 44 20.1337 13.29295 44 18.83851 14.4637 44 19.02776 15.85 44 18.79295 -14.6337 44 17.5 -6.343146 44 17.5 -17.65685 44 20.1337 -16.70705 44 19.02776 -15.85 44 21.35 -13.52776 44 22.1615 -14.4637 44 23.5 -19.3204 44 21.7952 -16.17075 44 25.18912 -14.59935 44 25.38218 -16.37999 44 24.77882 -18.06638 44 17.90192 -37 44 19 -35.90192 44 20.5 -35.5 44 22 -35.90192 44 23.09808 -37 44 23.5 -38.5 44 17.5 -38.5 44 11.15685 0 44 -10.79519 -13.82925 44 -9.978428 -9.821574 44 -13.23833 -13.08148 44 -11.2 -15 44 -8.963703 -16.6615 44 -7.838505 -14.4637 44 -8.027757 -15.85 44 -9.872652 -19.87366 44 -8.162419 -19.25866 44 -11.16777 -19.83745 44 -22.40192 -26 44 -23.47793 -27.08521 44 -22 -19.25237 44 -23.5 -21.90192 44 -22.40192 -23 44 -28 0 44 -28 -24.5 44 -27.59808 -23 44 -22 -24.5 44 -25 -21.5 44 -26.5 -21.90192 44 -8.242385 19.29858 40 -9.872652 19.87366 40 -11.16777 19.83745 40 -14.21191 14.66704 40 -13.23833 13.08147 40 -23.5 27.09808 49 -27.59808 26 40 -22.40192 26 49 -22 24.5 49 -22.40192 23 49 -23.5 21.90192 49 -25 21.5 49 -26.5 21.90192 49 -27.59808 23 49 -28 24.5 49 -27.59808 26 49 -26.5 27.09808 49 -26.5 27.09808 40 -25 27.5 49 -25 27.5 40 -23.4998 27.09802 40 -22 -19.25237 40 -22 19.25237 40 -27.77266 -25.65899 40 -23.49977 -27.09802 40 -22.40192 -26 49 -22 -24.5 49 -22.40192 -23 49 -23.5 -21.90192 49 -25 -21.5 49 -26.5 -21.90192 49 -27.59808 -23 49 -28 -24.5 49 -27.59808 -26 49 -26.5 -27.09808 40 -26.5 -27.09808 49 -25 -27.5 40 -25 -27.5 49 -23.5 -27.09808 49 -13.23833 -13.08148 40 -14.21191 -14.66704 40 11.15685 0 44 17.5 6.343146 40 11.15685 0 40 11.15685 0 40 11.15685 0 44 17.5 -6.343146 40 17.5 17.65685 40 5.5 5.656855 40 23.51526 12.2902 40 25.18912 14.59935 40 25.38218 16.37999 40 24.77882 18.06638 40 -9.978428 -9.821574 40 -0.1568542 0 40 -0.1568542 0 44 -11.16777 -19.83745 40 -9.872652 -19.87366 40 -8.178528 -19.29717 40 5.5 -5.656855 40 23.5 19.3204 40 21.97224 -15.85 40 23.5 -19.3204 40 23.09808 -40 40 22 -41.09807 40 -0.1568546 0 40 -10.97224 15.85 40 -10.97224 -14.15 40 -10.97224 -15.85 40 -24.08575 -23.67359 40 -25.25856 -23.29503 40 -28 -19.62618 40 -26.17282 -24.12143 40 -26.03923 -25.1 40 -25.37857 -25.67282 40 -24.4 -25.53923 40 -23.82718 -24.87857 40 21.70498 -38.24144 40 20.87857 -37.32718 40 23.5 -38.5 40 17.5 -17.65685 40 19.6736 -37.58574 40 17.90192 -40 40 17.5 -38.5 40 19 -41.09807 40 19.29503 -38.75856 40 20.12144 -39.67282 40 20.5 -41.5 40 21.32641 -39.41426 40 23.52091 -12.24719 40 22.20705 -14.6337 40 25.18912 -14.59935 40 25.38218 -16.37999 40 24.77882 -18.06638 40 21.97224 15.85 40 22.1615 14.4637 40 17.90192 40 40 19 41.09808 40 20.5 41.5 40 23.09808 40 40 22 41.09807 40 17.5 38.5 40 19.02776 15.85 40 18.79295 14.6337 40 -26.03923 23.9 40 -25.37856 23.32718 40 -26.17282 24.87857 40 -25.25856 25.70497 40 -24.08575 25.32641 40 -24.4 23.46077 40 -23.82718 24.12144 40 23.5 38.5 40 18.83851 -14.4637 40 19.02776 -15.85 40 20.12143 37.32718 40 21.32641 37.58574 40 21.7 38.5 40 21.41426 39.32641 40 20.5 39.7 40 19.67359 39.41426 40 19.29503 38.24144 40 -28 24.5 40 -0.1568542 0 44 17.5 -38.5 49 17.90192 -40 49 19 -41.09807 49 20.5 -41.5 49 22 -41.09807 49 23.09808 -40 49 23.5 -38.5 49 23.09808 -37 49 22 -35.90192 49 20.5 -35.5 49 19 -35.90192 49 17.90192 -37 49 23.5 38.5 49 23.09808 40 49 22 41.09807 49 20.5 41.5 49 19 41.09807 49 17.90192 40 49 17.5 38.5 49 17.90192 37 49 19 35.90192 49 20.5 35.5 49 22 35.90192 49 23.09808 37 49 19.67359 -39.41425 49 20.5 -39.7 49 21.41426 -39.32641 49 21.7 -38.5 49 21.32641 -37.58574 49 20.12143 -37.32718 49 19.29503 -38.24144 49 19.9 37.46077 49 20.87857 37.32718 49 21.70498 38.24144 49 21.32641 39.41426 49 20.5 39.7 49 19.58575 39.32641 49 19.32718 38.12144 49 -26.03923 23.9 49 -25.25856 23.29503 49 -24.08575 23.67359 49 -23.82718 24.87857 49 -24.4 25.53923 49 -25.37856 25.67282 49 -26.20498 24.75857 49 -26.03923 -25.1 49 -25.25856 -25.70497 49 -24.08575 -25.32641 49 -23.82718 -24.12144 49 -24.4 -23.46077 49 -25.37856 -23.32718 49 -26.20498 -24.24143 49 22.2391 -18.51893 59.2 21.2391 -18.51893 59.2 22.2391 -19.51893 59.2 21.2391 -19.51893 59.2 21.2391 -19.51893 51.2 21.2391 -18.51893 51.2 22.2391 -18.51893 51.2 22.2391 -19.51893 51.2 22.2391 -22.01893 59.2 21.2391 -22.01893 59.2 22.2391 -23.01893 59.2 21.2391 -23.01893 59.2 21.2391 -23.01893 51.2 21.2391 -22.01893 51.2 22.2391 -22.01893 51.2 22.2391 -23.01893 51.2 18.7391 -22.01893 59.2 17.7391 -22.01893 59.2 18.7391 -23.01893 59.2 17.7391 -23.01893 59.2 17.7391 -23.01893 51.2 17.7391 -22.01893 51.2 18.7391 -22.01893 51.2 18.7391 -23.01893 51.2 18.7391 -18.51893 59.2 17.7391 -18.51893 59.2 18.7391 -19.51893 59.2 17.7391 -19.51893 59.2 17.7391 -19.51893 51.2 17.7391 -18.51893 51.2 18.7391 -18.51893 51.2 18.7391 -19.51893 51.2 22.2391 -12.41893 59.2 21.2391 -12.41893 59.2 22.2391 -13.41893 59.2 21.2391 -13.41893 59.2 21.2391 -13.41893 51.2 21.2391 -12.41893 51.2 22.2391 -12.41893 51.2 22.2391 -13.41893 51.2 22.2391 -15.91893 59.2 21.2391 -15.91893 59.2 22.2391 -16.91893 59.2 21.2391 -16.91893 59.2 21.2391 -16.91893 51.2 21.2391 -15.91893 51.2 22.2391 -15.91893 51.2 22.2391 -16.91893 51.2 18.7391 -15.91893 59.2 17.7391 -15.91893 59.2 18.7391 -16.91893 59.2 17.7391 -16.91893 59.2 17.7391 -16.91893 51.2 17.7391 -15.91893 51.2 18.7391 -15.91893 51.2 18.7391 -16.91893 51.2 18.7391 -12.41893 59.2 17.7391 -12.41893 59.2 18.7391 -13.41893 59.2 17.7391 -13.41893 59.2 17.7391 -13.41893 51.2 17.7391 -12.41893 51.2 18.7391 -12.41893 51.2 18.7391 -13.41893 51.2 22.2391 -6.318928 59.2 21.2391 -6.318928 59.2 22.2391 -7.318927 59.2 21.2391 -7.318927 59.2 21.2391 -7.318927 51.2 21.2391 -6.318928 51.2 22.2391 -6.318928 51.2 22.2391 -7.318927 51.2 22.2391 -9.818928 59.2 21.2391 -9.818928 59.2 22.2391 -10.81893 59.2 21.2391 -10.81893 59.2 21.2391 -10.81893 51.2 21.2391 -9.818928 51.2 22.2391 -9.818928 51.2 22.2391 -10.81893 51.2 18.7391 -9.818928 59.2 17.7391 -9.818928 59.2 18.7391 -10.81893 59.2 17.7391 -10.81893 59.2 17.7391 -10.81893 51.2 17.7391 -9.818928 51.2 18.7391 -9.818928 51.2 18.7391 -10.81893 51.2 18.7391 -6.318928 59.2 17.7391 -6.318928 59.2 18.7391 -7.318927 59.2 17.7391 -7.318927 59.2 17.7391 -7.318927 51.2 17.7391 -6.318928 51.2 18.7391 -6.318928 51.2 18.7391 -7.318927 51.2 22.2391 -0.2189276 59.2 21.2391 -0.2189276 59.2 22.2391 -1.218928 59.2 21.2391 -1.218928 59.2 21.2391 -1.218928 51.2 21.2391 -0.2189276 51.2 22.2391 -0.2189276 51.2 22.2391 -1.218928 51.2 22.2391 -3.718928 59.2 21.2391 -3.718928 59.2 22.2391 -4.718928 59.2 21.2391 -4.718928 59.2 21.2391 -4.718928 51.2 21.2391 -3.718928 51.2 22.2391 -3.718928 51.2 22.2391 -4.718928 51.2 18.7391 -3.718928 59.2 17.7391 -3.718928 59.2 18.7391 -4.718928 59.2 17.7391 -4.718928 59.2 17.7391 -4.718928 51.2 17.7391 -3.718928 51.2 18.7391 -3.718928 51.2 18.7391 -4.718928 51.2 18.7391 -0.2189276 59.2 17.7391 -0.2189276 59.2 18.7391 -1.218928 59.2 17.7391 -1.218928 59.2 17.7391 -1.218928 51.2 17.7391 -0.2189276 51.2 18.7391 -0.2189276 51.2 18.7391 -1.218928 51.2 22.2391 5.881072 59.2 21.2391 5.881072 59.2 22.2391 4.881072 59.2 21.2391 4.881072 59.2 21.2391 4.881072 51.2 21.2391 5.881072 51.2 22.2391 5.881072 51.2 22.2391 4.881072 51.2 22.2391 2.381072 59.2 21.2391 2.381072 59.2 22.2391 1.381072 59.2 21.2391 1.381072 59.2 21.2391 1.381072 51.2 21.2391 2.381072 51.2 22.2391 2.381072 51.2 22.2391 1.381072 51.2 18.7391 2.381072 59.2 17.7391 2.381072 59.2 18.7391 1.381072 59.2 17.7391 1.381072 59.2 17.7391 1.381072 51.2 17.7391 2.381072 51.2 18.7391 2.381072 51.2 18.7391 1.381072 51.2 18.7391 5.881072 59.2 17.7391 5.881072 59.2 18.7391 4.881072 59.2 17.7391 4.881072 59.2 17.7391 4.881072 51.2 17.7391 5.881072 51.2 18.7391 5.881072 51.2 18.7391 4.881072 51.2 22.2391 11.98107 59.2 21.2391 11.98107 59.2 22.2391 10.98107 59.2 21.2391 10.98107 59.2 21.2391 10.98107 51.2 21.2391 11.98107 51.2 22.2391 11.98107 51.2 22.2391 10.98107 51.2 22.2391 8.481073 59.2 21.2391 8.481073 59.2 22.2391 7.481072 59.2 21.2391 7.481072 59.2 21.2391 7.481072 51.2 21.2391 8.481073 51.2 22.2391 8.481073 51.2 22.2391 7.481072 51.2 18.7391 8.481073 59.2 17.7391 8.481073 59.2 18.7391 7.481072 59.2 17.7391 7.481072 59.2 17.7391 7.481072 51.2 17.7391 8.481073 51.2 18.7391 8.481073 51.2 18.7391 7.481072 51.2 18.7391 11.98107 59.2 17.7391 11.98107 59.2 18.7391 10.98107 59.2 17.7391 10.98107 59.2 17.7391 10.98107 51.2 17.7391 11.98107 51.2 18.7391 11.98107 51.2 18.7391 10.98107 51.2 22.2391 18.08107 59.2 21.2391 18.08107 59.2 22.2391 17.08107 59.2 21.2391 17.08107 59.2 21.2391 17.08107 51.2 21.2391 18.08107 51.2 22.2391 18.08107 51.2 22.2391 17.08107 51.2 22.2391 14.58107 59.2 21.2391 14.58107 59.2 22.2391 13.58107 59.2 21.2391 13.58107 59.2 21.2391 13.58107 51.2 21.2391 14.58107 51.2 22.2391 14.58107 51.2 22.2391 13.58107 51.2 18.7391 14.58107 59.2 17.7391 14.58107 59.2 18.7391 13.58107 59.2 17.7391 13.58107 59.2 17.7391 13.58107 51.2 17.7391 14.58107 51.2 18.7391 14.58107 51.2 18.7391 13.58107 51.2 18.7391 18.08107 59.2 17.7391 18.08107 59.2 18.7391 17.08107 59.2 17.7391 17.08107 59.2 17.7391 17.08107 51.2 17.7391 18.08107 51.2 18.7391 18.08107 51.2 18.7391 17.08107 51.2 22.2391 24.18107 59.2 21.2391 24.18107 59.2 22.2391 23.18107 59.2 21.2391 23.18107 59.2 21.2391 23.18107 51.2 21.2391 24.18107 51.2 22.2391 24.18107 51.2 22.2391 23.18107 51.2 22.2391 20.68107 59.2 21.2391 20.68107 59.2 22.2391 19.68107 59.2 21.2391 19.68107 59.2 21.2391 19.68107 51.2 21.2391 20.68107 51.2 22.2391 20.68107 51.2 22.2391 19.68107 51.2 18.7391 20.68107 59.2 17.7391 20.68107 59.2 18.7391 19.68107 59.2 17.7391 19.68107 59.2 17.7391 19.68107 51.2 17.7391 20.68107 51.2 18.7391 20.68107 51.2 18.7391 19.68107 51.2 18.7391 24.18107 59.2 17.7391 24.18107 59.2 18.7391 23.18107 59.2 17.7391 23.18107 59.2 17.7391 23.18107 51.2 17.7391 24.18107 51.2 18.7391 24.18107 51.2 18.7391 23.18107 51.2 22.2391 30.28107 59.2 21.2391 30.28107 59.2 22.2391 29.28107 59.2 21.2391 29.28107 59.2 21.2391 29.28107 51.2 21.2391 30.28107 51.2 22.2391 30.28107 51.2 22.2391 29.28107 51.2 22.2391 26.78107 59.2 21.2391 26.78107 59.2 22.2391 25.78107 59.2 21.2391 25.78107 59.2 21.2391 25.78107 51.2 21.2391 26.78107 51.2 22.2391 26.78107 51.2 22.2391 25.78107 51.2 18.7391 26.78107 59.2 17.7391 26.78107 59.2 18.7391 25.78107 59.2 17.7391 25.78107 59.2 17.7391 25.78107 51.2 17.7391 26.78107 51.2 18.7391 26.78107 51.2 18.7391 25.78107 51.2 18.7391 30.28107 59.2 17.7391 30.28107 59.2 18.7391 29.28107 59.2 17.7391 29.28107 59.2 17.7391 29.28107 51.2 17.7391 30.28107 51.2 18.7391 30.28107 51.2 18.7391 29.28107 51.2 17.38128 24.88398 50.2 17.38128 24.88398 51.2 17.38128 28.30415 50.2 17.38128 30.98398 51.2 17.38128 30.98398 50.2 22.72862 30.98398 51.2 22.72862 30.98398 50.2 22.17681 30.98398 50.2 18.37814 30.98398 50.2 22.72862 24.88398 51.2 22.72862 24.88398 50.2 22.86431 28.30415 50.2 18.37814 24.88398 50.2 22.17681 24.88398 50.2 22.2391 36.38107 59.2 21.2391 36.38107 59.2 22.2391 35.38107 59.2 21.2391 35.38107 59.2 21.2391 35.38107 51.2 21.2391 36.38107 51.2 22.2391 36.38107 51.2 22.2391 35.38107 51.2 22.2391 32.88107 59.2 21.2391 32.88107 59.2 22.2391 31.88107 59.2 21.2391 31.88107 59.2 21.2391 31.88107 51.2 21.2391 32.88107 51.2 22.2391 32.88107 51.2 22.2391 31.88107 51.2 18.7391 32.88107 59.2 17.7391 32.88107 59.2 18.7391 31.88107 59.2 17.7391 31.88107 59.2 17.7391 31.88107 51.2 17.7391 32.88107 51.2 18.7391 32.88107 51.2 18.7391 31.88107 51.2 18.7391 36.38107 59.2 17.7391 36.38107 59.2 18.7391 35.38107 59.2 17.7391 35.38107 59.2 17.7391 35.38107 51.2 17.7391 36.38107 51.2 18.7391 36.38107 51.2 18.7391 35.38107 51.2 17.38128 37.08329 51.2 17.38128 37.08329 50.2 22.72862 37.08329 51.2 22.72862 37.08329 50.2 -27.96487 38.72142 55.53714 -27.96487 38.72142 50.69111 -27.96487 29.02936 55.53714 -27.96487 29.02936 50.69111 -35.96487 38.72142 55.53714 -35.96487 29.02936 55.53714 -35.96487 38.72142 50.69111 -35.96487 29.02936 50.69111 -27.96487 -29.12128 55.26895 -27.96487 -29.12128 50.9593 -27.96487 -38.91359 55.26895 -27.96487 -38.91359 50.9593 -35.96487 -29.12128 55.26895 -35.96487 -38.91359 55.26895 -35.96487 -29.12128 50.9593 -35.96487 -38.91359 50.9593 -36.12835 -3.592746 56.2 -26.18563 -3.592746 56.2 -36.12835 10.61113 56.2 -26.18563 10.61113 56.2 -26.18563 -3.592746 50.2 -26.18563 10.61114 50.2 -35 -3.592746 50.2 -36.12835 -3.592746 50.2 -36.06296 9.125929 55.27317 -36.08748 9.125929 50.94972 -36.12835 10.61113 50.2 -36.06296 -2.237176 50.94014 -36.08748 -2.237176 55.27106 -35 10.61114 50.2 -36.04479 14.53809 53.2 -26.60339 14.53809 53.2 -36.04479 22.392 53.2 -26.60339 22.392 53.2 -26.60339 14.53809 50.2 -26.60339 22.392 50.2 -35 14.53809 50.2 -36.04479 14.53809 50.2 -36.01283 21.35069 52.67595 -36.02481 21.35069 50.49981 -36.04479 22.392 50.2 -36.00484 15.61636 50.49743 -36.02481 15.6544 52.59645 -35 22.392 50.2 -22.56624 -6.349971 56.2 -36.18526 -6.349971 56.2 -22.56624 -20.80451 56.2 -36.18526 -20.80451 56.2 -36.18526 -6.349971 46.2 -22.56624 -6.349971 46.2 -36.18526 -20.80451 46.2 -22.56624 -20.80451 46.2 -22.56624 -20.80451 50.2 -22.56624 -6.349971 50.2 -22.56624 -6.349971 49 -35 -6.349971 49 -35 -6.349971 50.2 -36.05932 -17.21255 48.19329 -36.07507 -16.37224 48.19329 -36.18526 -16.37223 46.83895 -36.1118 -10.75261 48.19329 -36.05303 -9.912289 48.19329 -36.18526 -20.13609 50.18904 -36.1118 -17.21255 50.18905 -36.07507 -9.912289 50.18905 -36.18526 -7.101941 50.18904 -36.18526 -7.101941 55.52839 -36.18526 -20.13609 55.52839 -36.18526 -10.75261 46.83895 -35 -20.80451 50.2 -22.56624 -20.80451 49 -35 -20.80451 49 -22.59652 -28.10394 56.2 -35.96487 -28.10394 56.2 -22.59652 -39.57338 56.2 -35.96487 -39.57338 56.2 -35.96487 -28.10394 50.2 -35.96487 -39.57338 50.2 -35 -28.10394 50.2 -22.59652 -28.10394 50.2 -22.59652 -39.57338 50.2 -35 -39.57338 50.2 -35.96487 28.10394 56.2 -22.59652 28.10394 56.2 -35.96487 39.57338 56.2 -22.59652 39.57338 56.2 -22.59652 39.57339 50.2 -22.59652 28.10394 50.2 -35 28.10394 50.2 -35.96487 28.10394 50.2 -35.96487 39.57338 50.2 -35 39.57338 50.2 -18.30426 37.55802 60.2 -19.2917 37.55802 60.2 -18.30426 1 60.2 -19.2917 1 60.2 -19.2917 37.55802 50.2 -19.2917 1 50.2 -18.30426 1 50.2 -18.30426 37.55802 50.2 -16.30426 37.55802 60.2 -17.2917 37.55802 60.2 -16.30426 1 60.2 -17.2917 1 60.2 -17.2917 37.55802 50.2 -17.2917 1 50.2 -16.30426 1 50.2 -16.30426 37.55802 50.2 -14.30426 37.55802 60.2 -15.2917 37.55802 60.2 -14.30426 1 60.2 -15.2917 1 60.2 -15.2917 37.55802 50.2 -15.2917 1 50.2 -14.30426 1 50.2 -14.30426 37.55802 50.2 -12.30426 37.55802 60.2 -13.2917 37.55802 60.2 -12.30426 1 60.2 -13.2917 1 60.2 -13.2917 37.55802 50.2 -13.2917 1 50.2 -12.30426 37.55802 50.2 -12.30426 1 50.2 -10.30426 37.55802 60.2 -11.2917 37.55802 60.2 -10.30426 1 60.2 -11.2917 1 60.2 -11.2917 37.55802 50.2 -11.2917 1 50.2 -10.30426 1 50.2 -10.30426 37.55802 50.2 -8.304263 37.55802 60.2 -9.291698 37.55802 60.2 -8.304263 1 60.2 -9.291698 1 60.2 -9.291698 37.55802 50.2 -9.291698 1 50.2 -8.304263 1 50.2 -8.304263 37.55802 50.2 -6.304262 37.55802 60.2 -7.291698 37.55802 60.2 -6.304262 1 60.2 -7.291698 1 60.2 -7.291698 37.55802 50.2 -7.291698 1 50.2 -6.304262 1 50.2 -6.304262 37.55802 50.2 -4.304262 37.55802 60.2 -5.291698 37.55802 60.2 -4.304262 1 60.2 -5.291698 1 60.2 -5.291698 37.55802 50.2 -5.291698 1 50.2 -4.304262 1 50.2 -4.304262 37.55802 50.2 -2.304262 37.55802 60.2 -3.291698 37.55802 60.2 -2.304262 1 60.2 -3.291698 1 60.2 -3.291698 37.55802 50.2 -3.291698 1 50.2 -2.304262 1 50.2 -2.304262 37.55802 50.2 -0.3042621 37.55802 60.2 -1.291698 37.55802 60.2 -0.3042621 1 60.2 -1.291558 0.9998084 60.46469 -1.291698 37.55802 50.2 -1.291698 1 50.2 -0.3042621 1 50.2 -0.3042621 37.55802 50.2 1.695738 37.55802 60.2 0.7083021 37.55802 60.2 1.695738 1 60.2 0.7083021 1 60.2 0.7083021 37.55802 50.2 0.7083021 1 50.2 1.695738 37.55802 50.2 1.695738 1 50.2 3.695738 37.55802 60.2 2.708302 37.55802 60.2 3.695738 1 60.2 2.708302 1 60.2 2.708302 37.55802 50.2 2.708302 1 50.2 3.695738 37.55802 50.2 3.695738 1 50.2 5.695738 37.55802 60.2 4.708302 37.55802 60.2 5.695738 1 60.2 4.708302 1 60.2 4.708302 37.55802 50.2 4.708302 1 50.2 5.695738 1 50.2 5.695738 37.55802 50.2 7.695737 37.55802 60.2 6.708302 37.55802 60.2 7.695737 1 60.2 6.708302 1 60.2 6.708303 37.55802 50.2 6.708303 1 50.2 7.695737 1 50.2 7.695737 37.55802 50.2 9.695738 37.55802 60.2 8.708302 37.55802 60.2 9.695738 1 60.2 8.708302 1 60.2 8.708302 37.55802 50.2 8.708302 1 50.2 9.695738 1 50.2 9.695738 37.55802 50.2 11.69574 37.55802 60.2 10.7083 37.55802 60.2 11.69574 1 60.2 10.7083 1 60.2 10.7083 37.55802 50.2 10.7083 1 50.2 11.69574 1 50.2 11.69574 37.55802 50.2 13.69574 37.55802 60.2 12.7083 37.55802 60.2 13.69574 1 60.2 12.7083 1 60.2 12.7083 37.55802 50.2 12.7083 1 50.2 13.69574 1 50.2 13.69574 37.55802 50.2 15.69574 37.55802 60.2 14.7083 37.55802 60.2 15.69574 1 60.2 14.7083 1 60.2 14.7083 37.55802 50.2 14.7083 1 50.2 15.69574 1 50.2 15.69574 37.55802 50.2 -0.2862716 -35.56235 60.38734 -0.2571027 -34.62858 59.94574 -4.141693 -34.42351 59.95445 -2.819533 -33.88981 59.21291 -1.500447 -33.41711 58.1494 -3.944155 -33.20548 58.10622 -1.46073 -1.826752 58.1494 -3.964029 -2.029203 58.13568 -8.694357 -3.581702 58.10412 -6.149211 -2.524551 58.13307 -10.77441 -4.859039 58.13565 -12.51187 -6.309464 58.13001 -14.29711 -8.403299 58.11421 -17.09068 -15.24662 58.12345 -16.45211 -12.57811 58.1262 -15.55475 -10.47097 58.13346 -17.2653 -17.63876 58.12923 -17.10306 -19.95446 58.12147 -16.4635 -22.61103 58.13185 -12.55421 -28.8828 58.13943 -14.31989 -26.81757 58.11568 -15.53652 -24.79941 58.12312 -10.74792 -30.39381 58.11536 -8.7127 -31.65748 58.10866 -6.220277 -32.68892 58.14627 -19.42626 -18.81275 60.38924 -18.65213 -23.59383 60.45215 -16.9261 -26.84305 60.39089 -15.93552 -29.62252 60.49987 -13.32066 -31.16466 60.39089 -9.074014 -34.10824 60.4378 -2.399795 -35.99126 60.47752 -20.20024 -16.21615 60.49582 -18.66887 -11.61762 60.4379 -15.02332 -5.781857 60.39089 -13.95971 -4.163868 60.45983 -8.297498 -0.8155196 60.4401 -1.184166 0.4549331 60.3916 -7.781045 -32.67985 59.21292 -12.12583 -29.99591 59.21292 -15.42859 -26.10071 59.21291 -17.36602 -21.37556 59.21291 -17.74846 -16.28298 59.21291 -16.53849 -11.32145 59.21291 -14.65266 -8.051853 59.22502 -12.03693 -5.172016 59.21291 -7.673025 -2.519268 59.21291 -2.702968 -1.344875 59.21291 -8.111298 -33.33042 59.94574 -12.64097 -30.51257 59.94574 -16.07817 -26.43292 59.94574 -18.08646 -21.49078 59.94574 -18.4916 -17.62193 59.95445 -18.03294 -13.53019 59.94574 -15.9584 -8.615495 59.94574 -12.46666 -4.582406 59.94574 -7.899528 -1.825721 59.94574 -4.141693 -0.8203433 59.95445 -0.02857965 -0.6332638 59.94574 -3.670434 -7.669818 58.27003 -5.558876 -8.306568 58.3404 -11.59055 -18.72704 58.31237 -10.88502 -21.88185 57.35818 -11.01994 -20.72146 58.64805 -4.54388 -27.47879 57.35541 -3.565995 -27.43302 58.64805 -4.322668 -26.60042 59.63448 -3.969944 -25.68849 60.27563 -7.921623 -12.06436 60.28059 -7.94513 -14.11534 60.50085 -4.293227 -24.42001 60.50034 -7.680981 -23.44676 60.28059 -8.570746 -20.17864 60.50535 -9.711117 -19.49936 60.27563 -9.76317 -15.98939 60.27563 -10.11281 -13.85691 59.63448 -7.728836 -24.66821 59.63448 -10.05462 -21.51763 59.63448 -10.89788 -17.69346 59.63448 -11.60092 -16.49011 58.2754 -6.595718 -26.28582 58.67617 -9.033403 -24.38352 58.41217 -10.16706 -22.63707 58.64805 -10.36893 -12.63314 58.26804 -11.13432 -14.42585 58.34075 -8.98791 -10.80972 58.41164 -7.835142 -10.67137 59.63448 -3.992015 -10.61752 60.5016 -7.367218 -9.306709 58.2651 1.806295 -24.4123 60.50402 -0.473762 -26.00362 60.27563 -0.4250714 -26.98016 59.63448 -1.51453 -27.75904 58.41229 -7.340407 -26.05986 57.51247 -5.295756 -9.052908 59.62132 -3.42484 -9.339816 60.28059 -2.53609 -8.263693 59.63448 -1.446631 -7.484817 58.41229 2.044835 -11.06759 60.50135 5.573424 -19.70833 60.50051 5.451969 -15.16384 60.50064 -1.480583 -7.363289 50.2 -4.370776 -7.778835 50.2 -7.026822 -8.991812 50.2 -9.233546 -10.90395 50.2 -10.81217 -13.36034 50.2 -11.6348 -16.16197 50.2 -11.6348 -19.08189 50.2 -10.81217 -21.88352 50.2 -9.233546 -24.33991 50.2 -7.026822 -26.25205 50.2 -4.370776 -27.46502 50.2 -1.480583 -27.88057 50.2 -11.9155 -29.40052 50.2 -8.793483 -31.55549 50.2 -5.246463 -32.9007 50.2 -1.480583 -33.35796 50.2 1.409609 -27.46502 50.2 2.285296 -32.9007 50.2 4.065656 -26.25205 50.2 5.832316 -31.55549 50.2 8.954339 -29.40052 50.2 6.272379 -24.33991 50.2 11.46992 -26.56101 50.2 7.851004 -21.88352 50.2 13.23286 -23.202 50.2 8.673639 -19.08189 50.2 14.14072 -19.5187 50.2 8.673639 -16.16197 50.2 14.14072 -15.72516 50.2 7.851004 -13.36034 50.2 13.23286 -12.04185 50.2 6.272379 -10.90395 50.2 -11.9155 -5.843337 50.2 -14.43109 -8.682842 50.2 -16.19403 -12.04185 50.2 -17.10188 -15.72516 50.2 -17.10188 -19.5187 50.2 -16.19403 -23.202 50.2 -14.43109 -26.56101 50.2 11.46992 -8.682842 50.2 8.954339 -5.843337 50.2 4.065656 -8.991812 50.2 5.832316 -3.688361 50.2 1.409609 -7.778835 50.2 2.285296 -2.343154 50.2 -1.480583 -1.885894 50.2 -5.246463 -2.343154 50.2 -8.793483 -3.688361 50.2 3.188015 -32.71931 58.13307 1.002884 -33.21465 58.13568 5.733187 -31.66216 58.10411 9.55069 -28.9344 58.13 7.813248 -30.38481 58.13565 11.33594 -26.84056 58.11421 13.49094 -22.66574 58.1262 12.59358 -24.77288 58.13346 14.12951 -19.99724 58.12345 14.1419 -15.28939 58.12148 14.30413 -17.6051 58.12922 13.50233 -12.63283 58.13184 11.35872 -8.426283 58.11568 12.57535 -10.44444 58.12312 9.59305 -6.361056 58.13943 5.751544 -3.586379 58.10867 7.786761 -4.850042 58.11536 3.259114 -2.554937 58.14627 0.9829925 -2.038378 58.10622 -20.2 -36 60.5 16.8 1 60.5 16.78952 -19.44256 60.47057 16.8 1 50.2 16.76548 -15.99 60.47044 16.8 -36 60.5 4.489326 -35.98911 60.52201 -20.2 -36 50.2 -20.2 1 50.2 -20.2 1 60.5 20.49453 -39.60894 50.19211 21.32182 -39.28561 50.18397 21.60895 -38.50547 50.19211 21.2856 -37.67817 50.18397 20.18109 -37.40761 50.18601 20.15298 -39.57508 49 21.25754 -39.33807 49 21.60456 -38.26298 49 20.84702 -37.42492 49 -25.00547 -25.60894 50.19211 -24.17818 -25.28561 50.18397 -23.89106 -24.50547 50.19211 -24.2144 -23.67817 50.18397 -25.3189 -23.40761 50.18601 -25.34702 -25.57509 49 -24.24246 -25.33807 49 -23.89544 -24.26299 49 -24.45 -23.54737 49 -25.23702 -23.39544 49 20.22998 37.39451 50.18601 21.32182 37.71439 50.18397 21.59603 38.81885 50.19262 20.76944 39.60452 50.18397 20.15298 37.42492 49 21.25754 37.66193 49 21.60456 38.73702 49 20.84702 39.57508 49 -24.68111 23.40674 50.1876 -23.89451 24.22998 50.18601 -24.03832 25.04977 50.18978 -24.73056 25.60452 50.18397 -24.76298 23.39544 49 -24.04737 23.95 49 -23.89544 24.73701 49 -24.65298 25.57509 49 19.74246 39.33807 49 19.39544 38.26299 49 -35 -41 49 19.42492 -38.15299 49 19.54737 -39.05 49 23 -41 49 23 41 49 -35 41 49 -25.55 25.45263 49 -26.07509 24.84702 49 -26.10456 -24.73702 49 -25.95263 -23.95 49 -25.83807 23.74246 49 19.95 -37.54737 49 -35 41 50.2 23 41 50.2 23 30.98364 50.2 23 18.78364 50.2 23 12.68364 50.2 23 6.583636 50.2 23 0.4836359 50.2 23 -5.616364 50.2 23 -11.71636 50.2 23 -17.81637 50.2 23 -41 50.2 17.73439 -41 50.2 -22.0375 -41 50.2 -35 -41 50.2 13.57006 -29.019 60.49952 8.811097 -1.643213 60.49877 14.82133 -9.519545 60.43524 -28.0448 21.35069 52.56465 -28.0448 15.6544 52.75544 -28.02482 15.54789 50.50661 -28.0448 21.35069 50.49743 -28.00484 15.56564 52.51696 -35.96487 21.73809 50.51171 -35.96487 21.73809 52.51696 -27.96487 21.73809 52.51696 -27.96487 21.73809 50.51171 -35.96487 15.38811 52.51696 -28.12835 9.125929 55.27053 -28.12835 -2.237176 55.27148 -28.12835 -2.237176 50.95355 -28.12835 9.125929 50.94493 -35.96487 9.617329 50.9593 -35.96487 9.617329 55.26895 -27.96487 9.617329 55.26895 -27.96487 9.617329 50.9593 -27.96487 -2.919812 55.26895 -27.96487 -2.919812 50.9593 -35.96487 -2.919812 55.26895 -35.96487 -2.919812 50.9593 -28.18526 -16.37223 46.83895 -28.18526 -10.75261 46.83895 -28.18526 -20.13609 55.52839 -28.18526 -20.13609 50.18904 -28.18526 -7.101941 55.52839 -28.18526 -7.101941 50.18904 -28.18526 -7.583381 50.18904 -35.96487 -7.583381 50.18904 -35.96487 -10.75261 47.68805 -28.18526 -10.75261 47.68805 -35.96487 -16.37223 47.68805 -28.18526 -16.37223 47.68805 -35.96487 -19.39857 50.18904 -28.18526 -19.39857 50.18904 -28.09711 -19.39857 54.85679 -28.13016 -7.583381 54.85679 -35.96487 -7.583381 47.68805 -27.96487 -7.583381 47.68805 -27.96487 -19.39857 47.68805 -35.96487 -19.39857 47.68805 16.8 -36 50.2 22.72862 -23.91602 50.2 17.09064 18.78364 50.2 -26.09239 24.18109 50.18601 -25.55921 23.54236 50.19211 -25.82238 25.28659 50.18601 -25.78561 -25.32183 50.18397 -26.10549 -24.22997 50.18601 19.67763 39.28659 50.18601 19.40101 38.1812 50.198 17.09064 -17.81637 50.2 17.09064 -11.71636 50.2 17.09064 0.4836359 50.2 17.09064 -5.616364 50.2 17.09064 6.583636 50.2 17.09064 12.68364 50.2 17.09064 30.98364 50.2 22.72862 18.78398 50.2 22.72862 12.68398 50.2 22.17681 18.78398 50.2 17.38128 12.68398 50.2 17.38128 18.78398 50.2 18.37814 18.78398 50.2 18.37814 12.68398 50.2 22.72862 6.583979 50.2 22.17681 12.68398 50.2 22.72862 0.4839789 50.2 22.17681 6.583979 50.2 17.38128 0.4839789 50.2 17.38128 6.583979 50.2 18.37814 6.583979 50.2 18.37814 0.4839789 50.2 22.72862 -5.616021 50.2 22.17681 0.4839789 50.2 22.72862 -11.71602 50.2 22.17681 -5.616021 50.2 17.38128 -11.71602 50.2 17.38128 -5.616021 50.2 18.37814 -5.616021 50.2 18.37814 -11.71602 50.2 22.72862 -17.81602 50.2 22.17681 -11.71602 50.2 22.17681 -17.81602 50.2 17.38128 -23.91602 50.2 17.38128 -17.81602 50.2 18.37814 -17.81602 50.2 19.7144 -39.32183 50.18397 19.39451 -38.22998 50.18601 17.38128 18.78398 51.2 22.72862 18.78398 51.2 17.38128 12.68398 51.2 22.72862 12.68398 51.2 17.38128 6.583979 51.2 22.72862 6.583979 51.2 17.38128 0.4839789 51.2 22.72862 0.4839789 51.2 17.38128 -5.616021 51.2 22.72862 -5.616021 51.2 17.38128 -11.71602 51.2 22.72862 -11.71602 51.2 17.38128 -17.81602 51.2 22.72862 -17.81602 51.2 17.38128 -23.91602 51.2 22.72862 -23.91602 51.2 0.7092621 -27.57404 58.27003 2.597709 -26.93729 58.3404 4.406047 -25.93715 58.26511 7.407765 -22.61072 58.26804 6.026745 -24.43413 58.41164 8.173154 -20.81801 58.34075 8.629388 -16.51682 58.31237 8.639753 -18.75375 58.2754 7.923854 -13.36201 57.35818 6.072237 -10.86033 58.41216 4.379248 -9.184004 57.51246 1.58272 -7.765071 57.35541 8.058778 -14.5224 58.64805 0.6048289 -7.810836 58.64805 1.361503 -8.643442 59.63448 1.814588 -9.778754 60.28059 6.664065 -20.07921 60.28059 5.274764 -12.55915 60.27563 6.749949 -15.7445 60.27563 7.745798 -19.50993 59.63448 4.767669 -10.57565 59.63448 7.093458 -13.72623 59.63448 3.634544 -8.958031 58.67617 7.205893 -12.60679 58.64805 6.180216 -23.09942 59.63448 3.664221 -24.39722 60.28059 3.290005 -25.74179 59.63448 7.847992 -16.64146 59.62132 1.066418 -1.540796 59.22502 5.595061 -1.083236 60.39089 10.35949 -4.079189 60.39089 14.4799 -26.10827 60.39035 10.04323 -31.43478 60.39089 5.210822 -34.31978 60.39089 4.819889 -2.564016 59.21291 9.164678 -5.247961 59.21291 12.46743 -9.143156 59.21291 14.40485 -13.8683 59.21291 14.7873 -18.96087 59.21291 13.57733 -23.92241 59.21291 10.89339 -28.26719 59.21291 6.998207 -31.56993 59.21291 2.273047 -33.50736 59.21291 5.150141 -1.913442 59.94574 9.679797 -4.731276 59.94574 13.117 -8.810938 59.94574 15.12529 -13.75307 59.94574 15.53043 -17.62193 59.95445 15.07178 -21.71367 59.94574 13.67634 -25.34477 59.95445 11.41007 -28.78231 59.94574 7.330408 -32.21951 59.94574 3.776111 -33.80036 59.95445 -52.21277 78.5878 0 -52.21287 78.58795 -2.158655 -49.46289 77.00009 -2.158649 -49.46277 77.00009 0 -51.21767 78.01049 -2.405726 -50.33895 77.51264 -2.387336 -48.44088 77.56681 -2.396921 -46.71277 78.58784 -2.159144 -46.71277 78.5878 0 -47.83598 77.95015 -2.412845 -47.80219 77.98353 -2.41388 -46.71857 79.60599 -2.38721 -46.72507 80.45096 -2.40469 -46.71277 81.76323 0 -46.72042 81.77179 -2.19408 -47.85198 82.40604 -2.404334 -46.81521 80.91909 -2.4 -47.07087 81.5553 -2.403159 -47.49504 82.09659 -2.4 -49.46263 83.35094 -2.158651 -49.46277 83.35095 0 -48.58657 82.83838 -2.387337 -50.48461 82.78426 -2.396923 -52.21277 81.76323 0 -52.20416 81.77179 -2.184565 -52.1549 80.79769 -2.413423 -52.19986 80.45519 -2.40434 -51.28903 82.23834 -2.394936 -51.85356 81.55694 -2.402912 -52.20679 79.60258 -2.387359 -48.04421 79.55434 -2.398667 -50.75708 79.3153 -2.398513 -50.88133 80.7967 -2.398667 -51.72173 81.74383 -2.4 -51.43051 82.09659 -2.4 -49.61201 81.74238 -2.397096 -52.11034 80.91909 -2.4 -51.95045 81.34767 -2.4 -48.16847 81.03573 -2.398513 -47.20381 81.74383 -2.4 -46.97509 81.34767 -2.4 -46.81521 80.91909 -2.4 -47.49504 82.09659 -2.4 -49.31354 78.60866 -2.397096 -51.08483 82.3962 -2.4 -50.63672 79.68878 -2.126501 -49.86447 78.9844 -2.128962 -48.85982 79.06127 -2.126377 -48.31245 79.71263 -2.128828 -48.28882 80.66224 -2.126499 -49.06105 81.36663 -2.128955 -50.06575 81.28977 -2.126376 -50.6131 80.63843 -2.128829 -50.63673 80.66224 -0.2735003 -50.00146 81.29365 -0.2711602 -49.31171 81.41477 -0.2729921 -48.43442 80.93406 -0.2737499 -48.28883 79.68878 -0.2734987 -48.92409 79.0574 -0.2711547 -49.61385 78.93627 -0.2729878 -50.49113 79.41698 -0.2737488 -47.9134 79.838 -0.005117952 -49.05072 78.68405 -0.00210613 -50.43917 78.96959 -0.002366304 -51.01215 80.51303 -0.005117237 -49.87483 81.66699 -0.002105772 -48.48639 81.38146 -0.002367138 -39.85029 14.57595 42.98874 -40.19775 13.42854 43.00144 -38.22531 13.59193 42.94532 -38.44207 14.9842 42.98951 -40.90963 15.59354 42.98899 -41.67986 14.52006 43.00046 -40.55681 17.01754 42.98899 -42.21106 16.26626 42.96047 -39.14719 17.424 42.98899 -39.60405 18.66241 43.00144 -41.26779 18.07329 42.94532 -37.64199 17.90973 43.00144 -36.87583 16.23611 43.00046 -38.09037 16.40646 42.98899 -37.21135 14.69471 43.00052 -37.60324 13.95764 40 -36.69821 15.68218 39.99999 -37.0679 17.31323 40 -38.22889 18.51701 39.99999 -40.44855 18.65543 39.99999 -41.75011 17.60521 40 -42.26952 16.31415 40 -41.8329 14.41614 39.99999 -40.63161 14.96191 39.97968 -40.22993 13.30999 40 -39.29278 14.47467 39.97425 -38.83831 13.31637 40 -40.23019 14.69024 34.07931 -40.84248 15.38827 34.05475 -40.94892 15.51747 39.9734 -40.98313 16.43383 34.15848 -41.01248 16.25159 39.97579 -40.79438 16.80825 39.97792 -40.41279 17.23344 39.97674 -40.3072 17.27964 34.14937 -39.79039 17.49732 39.97775 -39.55139 17.47458 34.05404 -39.09999 17.48257 39.97647 -38.74006 17.27076 34.06982 -38.39166 17.06088 39.97663 -38.16707 16.71472 34.14874 -38.00063 16.3435 39.97492 -37.98999 15.91706 34.14852 -38.05869 15.46756 39.97763 -38.40512 14.95626 34.08495 -38.54508 14.80097 39.97146 -39.25334 14.5494 34.05173 -40.7295 16.68704 33.99919 -38.11507 16.24256 33.99686 -40.86478 13.59248 42.85036 -41.97165 14.66541 42.8451 -41.96705 17.25397 42.85036 -40.16444 18.69479 42.85502 -38.64234 18.65554 42.8511 -37.36957 17.78637 42.84589 -36.70919 16.25109 42.85814 -37.14421 14.5041 42.8511 -39.52336 13.2095 42.8511 -39.81965 17.20825 42.87581 -40.7062 16.3273 42.8758 -40.38653 15.11906 42.8758 -39.17805 14.7924 42.87586 -38.29386 15.67272 42.87577 -38.61346 16.88094 42.8758 -38.53609 14.95402 41.74288 -39.5 16 40.97831 -38.10303 16.36113 41.78264 -39.11741 17.39147 41.78353 -40.52313 17.01525 41.7658 -40.8926 15.62391 41.78768 -39.89163 14.61891 41.78942 -40.04496 14.57886 39.96392 -5.604074 24.05008 19.05189 -6.083612 24.05008 19.29376 -6.050879 24.05008 18.85516 -4.13217 24.05008 19.05824 -4.525939 24.05008 19.34681 -4.495631 24.05008 18.81059 -5.623885 18.25007 21.15919 -6.097498 18.25008 21.02251 -5.979062 18.25007 21.501 -4.129606 18.25007 21.23147 -4.479054 18.25008 21.501 -4.543882 18.24997 20.96134 -6.083613 21.65009 18.86138 -5.604074 21.65009 19.10325 -6.050877 21.65009 19.29998 -4.696217 21.65009 19.05189 -4.249413 21.65009 18.85516 -4.216679 21.65009 19.29376 -6.132933 19.74835 21.34354 -5.842769 19.75032 21.47564 -5.636109 19.74952 21.22929 -5.749398 19.73141 20.99883 -4.655872 19.74807 21.15262 -4.584124 19.7491 21.39073 -4.342761 19.75028 21.47564 -4.127948 19.74526 21.17778 -6.900149 22.95009 19.47757 -6.900149 22.95009 18.67757 -7.500144 22.95009 19.47757 -7.500144 22.95009 18.67757 -3.400149 21.65009 18.17757 -6.900149 21.70009 18.17757 -3.400149 21.65009 19.52757 -6.900149 21.61675 19.5609 -2.800147 22.95009 19.47757 -2.800147 22.95009 18.67757 -3.400149 22.95009 19.47757 -3.400149 22.95009 18.67757 -3.400149 21.35009 19.82757 -3.400149 21.35009 20.87757 -6.900149 21.35009 20.87757 -6.200145 21.95008 18.17757 -4.100146 22.95009 18.17757 -3.400149 22.95009 18.17757 -3.400149 24.75009 18.17757 -3.400149 21.95008 18.17757 -4.100146 21.95008 18.17757 -6.900149 24.75009 18.17757 -6.900149 22.95009 18.17757 -6.200145 22.95009 18.17757 -6.900149 24.75009 19.47757 -7.500144 24.75009 19.47757 -2.800147 24.75009 19.47757 -3.400149 24.75009 19.47757 -3.400149 24.75009 20.87757 -6.900149 24.75009 20.87757 -7.500144 24.75009 18.67757 -6.900149 24.75009 18.67757 -3.400149 24.75009 18.67757 -2.800147 24.75009 18.67757 -5.939458 19.72903 20.94492 -6.121889 19.7425 21.08115 -4.34697 19.72934 20.94814 -4.570707 19.74285 21.00291 -2.666811 23.61258 20.72757 -2.685859 21.99294 20.72757 -2.750146 23.65008 17.79632 -2.685859 21.95009 17.80257 -2.600143 22.05009 21.27757 -2.750146 23.56437 21.42757 -2.200144 23.55009 21.4109 -2.200144 22.05009 21.34424 -2.650144 19.75008 19.37757 -2.150143 19.75008 19.37757 -2.650144 18.75008 19.97757 -2.150143 18.75008 19.97757 -8.150149 18.75008 19.97757 -8.150148 19.75008 19.37757 -7.650147 18.75008 19.97757 -7.650147 19.75008 19.37757 -6.200145 22.95009 17.77757 -6.900149 22.95009 17.77757 -4.100146 21.95008 17.77757 -3.400149 21.95008 17.77757 -6.900149 21.95008 17.77757 -6.200145 21.95008 17.77757 -4.100146 22.95009 17.77757 -3.400149 22.95009 17.77757 -2.150143 24.75009 17.77757 -8.150148 24.75009 17.77757 -2.150143 24.75009 21.47757 -8.150148 24.75009 21.47757 -7.650147 18.75008 21.47757 -7.650147 19.75008 21.47757 -2.800147 22.01008 21.47757 -2.150143 19.75008 17.77757 -2.150143 21.95008 17.77757 -2.150143 21.95008 21.47757 -2.150143 18.75008 21.47757 -8.150149 18.75008 21.47757 -2.650144 18.75008 21.47757 -2.650144 19.75008 21.47757 -8.150148 19.75008 17.77757 -2.150143 23.65008 17.77757 -2.150143 23.65008 21.47757 -8.150148 21.95008 21.47757 -8.150148 21.95008 17.77757 -7.500144 22.02509 21.47757 -7.625146 21.98759 20.72757 -8.100148 22.05009 21.4109 -8.100148 23.55009 21.34424 -8.150148 23.65008 21.47757 -8.150148 23.65008 17.77757 -7.600146 21.95009 17.799 -7.580145 23.65008 17.79632 -7.580145 23.57509 21.45939 -7.700148 22.05009 21.27757 -7.625146 23.60723 20.72757 18.10007 -8.524392 22.85678 18.10007 -8.791811 22.44347 18.10007 -8.366602 22.34453 18.10007 -5.271116 22.61151 18.10007 -5.733536 22.7769 18.10007 -5.645556 22.29373 18.10007 -6.954587 22.82769 18.10007 -7.294406 22.63959 18.10007 -6.805731 22.48185 18.10007 -7.145565 22.29374 18.10007 -9.8596 22.73288 18.10007 -9.866607 22.34453 18.10007 -10.23354 22.7769 18.10007 -10.24054 22.38855 18.10007 -16.02439 22.85678 18.10007 -15.8666 22.34453 18.10007 -16.29181 22.44347 18.10007 -11.25401 22.53503 18.10007 -11.73354 22.7769 18.10007 -11.70081 22.33831 18.10007 -12.77112 22.61151 18.10007 -13.23354 22.7769 18.10007 -13.14556 22.29373 18.10007 -14.30833 22.67795 18.10007 -14.79363 22.73099 18.10007 -14.49928 22.28176 21.90007 -18.25007 22.37738 23.40007 -18.25007 22.44405 21.90007 -17.85007 22.51071 23.42507 -17.73007 22.33571 23.40007 -3.35007 22.37738 21.90007 -3.35007 22.44405 23.40007 -3.75007 22.51071 21.87507 -3.870072 22.32738 19.5967 -8.279882 22.59423 19.59942 -8.471752 22.32548 19.59719 -8.786458 22.43327 19.5967 -5.279887 22.59426 19.59942 -5.471751 22.32548 19.59719 -5.786461 22.43327 19.5967 -6.779878 22.59423 19.59989 -6.971754 22.32551 19.59719 -7.286455 22.43326 19.5967 -9.779889 22.59426 19.59942 -9.971754 22.32548 19.59719 -10.28645 22.43326 19.5967 -15.77988 22.59423 19.59942 -15.97175 22.32548 19.59719 -16.28646 22.43327 19.5967 -11.27988 22.59423 19.59942 -11.47175 22.32548 19.59719 -11.78645 22.43326 19.5967 -12.77989 22.59426 19.59942 -12.97175 22.32548 19.59719 -13.28646 22.43327 19.5967 -14.27988 22.59423 19.59942 -14.47176 22.32548 19.59719 -14.78645 22.43326 23.45722 -17.76436 23.06071 21.84293 -3.825071 23.06071 21.83757 -17.78341 23.06071 21.87507 -17.65007 22.31071 23.46257 -3.825071 23.06071 23.42507 -3.950073 22.31071 21.80007 -17.70007 25.99196 23.50007 -17.76436 25.98929 21.80007 -3.870072 25.98929 23.50007 -3.850071 25.99196 18.60007 -3.80007 23.81071 18.60007 -3.300069 23.81071 18.60007 -3.80007 22.31071 18.60007 -3.300069 22.31071 18.60007 -17.80007 23.81071 19.60007 -17.80007 24.41071 18.60007 -17.80007 22.31071 19.60007 -17.80007 22.31071 19.59257 -8.734635 22.77154 19.57976 -8.486344 22.84203 19.59257 -5.734642 22.77153 19.57976 -5.486346 22.84203 19.59257 -7.234643 22.77153 19.57975 -6.986354 22.84203 19.59257 -10.23464 22.77153 19.57975 -9.986348 22.84203 19.59257 -16.23464 22.77154 19.57975 -15.98635 22.84203 19.60007 -3.80007 24.41071 19.60007 -3.800071 22.31071 19.59257 -11.73464 22.77154 19.57976 -11.48634 22.84203 19.59257 -13.23464 22.77153 19.57975 -12.98635 22.84203 19.60007 -3.300069 24.41071 19.59257 -14.73464 22.77153 19.57975 -14.48636 22.84203 18.60007 -18.30007 22.31071 18.60007 -18.30007 23.81071 19.60007 -18.30007 24.41071 23.50007 -3.300069 22.31071 24.60007 -3.300069 22.31071 24.60007 -18.30007 22.31071 23.50007 -18.30007 22.31071 21.80007 -18.30007 22.31071 21.80007 -3.300069 22.31071 19.60007 -11.1749 22.31478 22.80007 -3.950073 25.11071 22.80007 -3.950073 24.31071 24.60007 -3.950073 25.11071 24.60007 -3.950073 24.31071 22.80007 -17.65007 24.31071 22.80007 -17.65007 25.11071 24.60007 -17.65007 24.31071 24.60007 -17.65007 25.11071 23.50007 -18.30007 26.01071 23.50007 -3.300069 26.01071 21.80007 -18.30007 26.01071 24.60007 -3.300069 26.01071 21.80007 -3.300069 26.01071 24.60007 -18.30007 26.01071 19.60007 -3.300069 26.01071 19.60007 -18.30007 26.01071 19.60007 -16.30034 26.01071 19.60007 -15.2999 22.31884 19.60007 -13.7999 22.31884 19.60007 -12.2999 22.31884 19.60007 -9.299903 22.31884 19.60007 -7.7999 22.31884 19.60007 -8.924901 26.01071 19.60007 -13.0499 26.01071 23.90008 -15.89934 24.48831 23.90008 -15.92427 24.97996 23.90008 -16.31705 24.61523 23.90007 -11.33388 24.52725 23.90007 -11.57575 25.00678 23.90007 -11.77248 24.55999 23.90007 -14.45458 24.44373 23.90007 -14.81931 24.83651 23.90007 -14.32766 24.86144 23.90007 -6.954584 24.44373 23.90007 -7.319314 24.83651 23.90007 -6.827661 24.86144 23.90007 -9.954586 24.44374 23.90007 -10.31931 24.83651 23.90007 -9.827659 24.86144 23.90007 -12.754 24.73639 23.90007 -13.26626 24.89418 23.90007 -13.16732 24.46898 22.80007 -5.250072 25.61071 21.52735 -5.250072 25.61071 22.80007 -5.250072 26.01071 21.80007 -5.250072 26.01071 21.80007 -16.35008 25.61071 22.80007 -16.35008 25.61071 21.80007 -16.35008 26.01071 22.80007 -16.35008 26.01071 22.80007 -4.550069 25.87738 22.80007 -4.550068 24.31071 24.60007 -4.550068 24.31071 22.80007 -4.550068 25.11071 24.60007 -4.550068 25.11071 21.80007 -4.550068 25.61071 21.80007 -4.550068 26.01071 22.80007 -17.05007 24.31071 22.80007 -17.05007 25.11071 21.20007 -4.550068 22.91071 21.20007 -4.550068 23.96071 21.20007 -17.05007 22.91071 21.49007 -17.05007 24.25071 24.60007 -17.05007 22.91071 24.60007 -4.550068 22.91071 24.60007 -17.05007 24.31071 24.60007 -4.550068 25.61071 24.60007 -17.05007 25.61071 24.60007 -17.05007 25.11071 21.80007 -17.05007 26.01071 22.80007 -17.05007 26.01071 22.80007 -17.05007 25.61071 21.53341 -17.05007 25.61071 23.90007 -8.399339 24.48831 23.90007 -8.424275 24.97996 23.90007 -8.817052 24.61523 21.50007 -16.29181 24.59347 21.50007 -16.02439 25.00678 21.50007 -15.8666 24.49453 21.50007 -11.79364 24.88099 21.50007 -11.30833 24.82796 21.50007 -11.49928 24.43176 21.50007 -4.550069 24.26071 21.50007 -14.73354 24.9269 21.50007 -14.254 24.68503 21.50007 -14.7008 24.48831 21.50007 -7.233539 24.9269 21.50007 -6.754002 24.68503 21.50007 -7.200804 24.48831 21.50007 -10.23354 24.9269 21.50007 -9.771113 24.76151 21.50007 -10.14556 24.44374 21.50007 -13.29441 24.78958 21.50007 -12.95458 24.97769 21.50007 -12.8666 24.49453 21.50007 -13.24054 24.53855 21.50007 -4.550068 25.61071 21.50007 -13.80007 25.61071 21.50007 -15.30007 25.61071 21.50007 -12.30007 25.61071 21.50007 -9.675072 25.61071 21.50007 -8.791811 24.59347 21.50007 -8.524391 25.00678 21.50007 -8.366603 24.49453 21.50007 -5.366605 24.49453 21.50007 -5.82903 24.65992 21.50007 -5.454579 24.97769 21.50007 -9.300074 24.36071 21.50007 -10.80007 24.36071 23.90007 -5.454578 24.44374 23.90007 -5.424273 24.97996 23.90007 -5.81805 24.69139 0.4750009 -15.475 21.48984 0.4750009 -14.525 21.48984 -1.224998 -15.475 21.48984 -1.224998 -14.525 21.48984 0.4750009 -15.475 20.58984 -1.224998 -15.475 20.58984 0.4750009 -14.525 20.58984 -1.224998 -14.525 20.58984 0.500005 -16.925 21.48984 0.500005 -15.975 21.48984 -1.200001 -16.925 21.48984 -1.200001 -15.975 21.48984 0.500005 -16.925 20.58984 -1.200001 -16.925 20.58984 0.500005 -15.975 20.58984 -1.200001 -15.975 20.58984 13.6 2.200002 21.48984 12.65 2.200002 21.48984 13.6 0.4999952 21.48984 12.65 0.4999952 21.48984 13.6 2.200002 20.58984 13.6 0.4999952 20.58984 12.65 2.200002 20.58984 12.65 0.4999952 20.58984 -2.124998 15.85 21.48984 -3.074999 15.85 21.48984 -2.124998 14.15 21.48984 -3.074999 14.15 21.48984 -2.124998 15.85 20.58984 -2.124998 14.15 20.58984 -3.074999 15.85 20.58984 -3.074999 14.15 20.58984 -19.00009 3.155042 22.30044 -19.00009 3.208374 22.50044 -19.77509 7.275041 22.34844 -19.00009 7.155043 22.30044 -19.73009 7.075044 22.36294 -19.00009 7.208375 22.50044 -19.00009 6.275045 22.36711 -19.00009 6.075042 22.43378 -19.77509 6.275045 22.35294 -19.73759 6.075042 22.36294 -19.00009 2.275045 22.36711 -19.00009 2.075041 22.43378 -19.77509 2.275045 22.35294 -19.73759 2.075042 22.36294 -19.00009 5.275043 22.36711 -19.00009 5.07504 22.43378 -19.77509 5.275043 22.35187 -19.73759 5.07504 22.36294 -19.77509 3.275039 22.35044 -19.80009 3.075043 22.34044 -19.77509 4.275042 22.35044 -19.00009 4.155044 22.30044 -19.73759 4.075046 22.36294 -19.00009 4.208376 22.50044 -19.70008 6.275045 22.50044 -19.70009 3.108376 22.46544 -19.70008 4.275042 22.50044 -19.70008 5.275043 22.50044 -19.70008 2.275045 22.50044 -19.70008 7.27504 22.50044 -20.25008 8.175041 23.76044 -19.70008 8.175041 23.76044 -20.25008 8.675042 23.76044 -19.70008 8.675042 23.76044 -20.25008 8.175041 24.76044 -20.25008 8.675042 24.76044 -20.90008 8.175041 24.76044 -20.90008 8.675042 24.76044 -19.70008 1.175041 23.76044 -20.25009 1.175041 23.76044 -19.70008 0.6750401 23.76044 -20.25009 0.6750401 23.76044 -20.25009 1.175041 24.76044 -20.90008 1.175041 24.76044 -20.25009 0.6750401 24.76044 -20.90008 0.6750401 24.76044 -22.45009 0.717898 22.91044 -23.45009 0.9150443 22.91044 -23.45009 8.675042 23.56044 -23.45009 8.475044 22.91044 -23.45009 8.375044 23.56044 -22.45009 8.675042 22.91044 -22.45009 8.375044 22.91044 -22.45009 8.675042 22.36044 -22.45009 8.275042 22.34377 -22.45009 1.060758 22.34377 -22.45009 0.6750401 22.36044 -19.70008 1.175041 25.26044 -21.18876 1.175041 25.26044 -21.18876 8.175041 25.26044 -19.70008 8.175041 25.26044 -19.70008 0.6750401 22.36044 -19.70008 8.675042 22.36044 -21.18876 8.675042 25.26044 -21.18876 0.6750401 25.26044 -23.45009 0.7500415 23.56044 -23.95008 1.075043 22.32294 -23.95009 8.675042 23.56044 -23.95009 8.675042 25.26044 -23.95009 8.300043 22.34794 -23.95009 8.275043 23.62711 -23.95008 0.6750402 25.26044 -23.95008 0.6750402 23.56044 -23.95008 1.025044 23.66044 -21.55009 7.945043 23.76044 -21.55009 8.225042 24.36044 -23.95009 7.99171 24.36044 -21.55009 1.387539 24.36044 -21.55009 1.12504 23.76044 -23.95008 1.241707 24.36044 -21.55009 7.875043 24.36044 -23.95009 7.875043 23.76044 -21.55009 1.475039 23.76044 -23.95008 1.475039 23.76044 -23.95008 1.475039 22.76044 -23.95009 7.875043 22.76044 -23.95008 1.475039 24.86044 -23.95009 7.875043 24.86044 -22.70008 2.175043 24.44044 -22.70008 2.175043 24.09044 -22.70008 7.175042 24.44044 -22.70008 7.175042 24.09044 -22.70008 5.175042 24.44044 -22.70008 5.175042 24.09044 -22.70008 4.175044 24.44044 -22.70008 4.175044 24.09044 -22.70008 6.175044 24.44044 -22.70008 6.175044 24.09044 -20.95008 7.175042 23.96044 -20.95008 6.175044 23.96044 -20.95008 2.075042 24.44044 -20.95009 2.175043 23.96044 -20.95008 2.275045 24.44044 -20.95008 4.275042 24.44044 -20.95008 4.075046 24.44044 -20.95009 4.175044 23.96044 -20.95009 5.175042 23.96044 -20.95008 5.275043 24.44044 -20.95008 7.875043 24.86044 -20.95008 7.875043 22.76044 -20.95009 1.475039 24.86044 -20.95008 6.675045 24.86044 -20.95008 2.675044 24.86044 -20.95008 5.675043 24.86044 -20.95008 4.675041 24.86044 -20.95008 3.675039 24.86044 -20.95008 5.07504 24.44044 -20.95008 7.075044 24.44044 -20.95008 7.27504 24.44044 -20.95009 1.475039 22.76044 -20.95008 6.075042 24.44044 -20.95008 6.275045 24.44044 -22.70008 3.175041 24.09044 -20.95009 3.175041 23.96044 -22.70008 3.175041 24.44044 -20.95008 3.275039 24.44044 -20.95008 3.075043 24.44044 7.475001 14.875 21.48984 4.075003 14.875 21.48984 7.475001 13.075 21.48984 4.075003 13.075 21.48984 7.475001 14.875 20.88984 7.475001 13.075 20.88984 4.075003 14.875 20.88984 4.075003 13.075 20.88984 -2.749997 0.1250004 21.48984 -2.749997 1.075002 21.48984 -4.449996 0.1250005 21.48984 -4.449996 1.075002 21.48984 -2.749997 0.1250004 20.58984 -4.449996 0.1250005 20.58984 -2.749997 1.075002 20.58984 -4.449996 1.075002 20.58984 -10.1 8.225004 21.48984 -8.300003 8.225004 21.48984 -10.1 11.625 21.48984 -8.300003 11.625 21.48984 -10.1 8.225004 20.18984 -10.1 11.625 20.18984 -8.300003 8.225004 20.18984 -8.300003 11.625 20.18984 0.1250025 -11.27501 21.48984 0.1250025 -10.32501 21.48984 -1.574996 -11.27501 21.48984 -1.574996 -10.32501 21.48984 0.1250025 -11.27501 20.58984 -1.574996 -11.27501 20.58984 0.1250025 -10.32501 20.58984 -1.574996 -10.32501 20.58984 6.625001 -0.7999968 21.48984 6.625001 0.1500043 21.48984 4.925002 -0.7999968 21.48984 4.925002 0.1500044 21.48984 6.625001 -0.7999968 20.58984 4.925002 -0.7999968 20.58984 6.625001 0.1500043 20.58984 4.925002 0.1500044 20.58984 -2.749998 -6.700007 21.48984 -2.749998 -5.750006 21.48984 -4.449996 -6.700007 21.48984 -4.449996 -5.750006 21.48984 -2.749998 -6.700007 20.58984 -4.449996 -6.700007 20.58984 -2.749998 -5.750006 20.58984 -4.449996 -5.750006 20.58984 -2.749998 -3.999999 21.48984 -2.749998 -3.049997 21.48984 -4.449996 -3.999999 21.48984 -4.449996 -3.049997 21.48984 -2.749998 -3.999999 20.58984 -4.449996 -3.999999 20.58984 -2.749998 -3.049997 20.58984 -4.449996 -3.049997 20.58984 -2.749997 -1.250004 21.48984 -2.749997 -0.300003 21.48984 -4.449996 -1.250004 21.48984 -4.449996 -0.3000029 21.48984 -2.749997 -1.250004 20.58984 -4.449996 -1.250004 20.58984 -2.749997 -0.300003 20.58984 -4.449996 -0.3000029 20.58984 6.625001 -3.475001 21.48984 6.625001 -2.525 21.48984 4.925002 -3.475001 21.48984 4.925002 -2.525 21.48984 6.625001 -3.475001 20.58984 4.925002 -3.475001 20.58984 6.625001 -2.525 20.58984 4.925002 -2.525 20.58984 3.000003 -6.124994 21.48984 2.050002 -6.124994 21.48984 3.000003 -7.825 21.48984 2.050002 -7.825 21.48984 3.000003 -6.124994 20.58984 3.000003 -7.825 20.58984 2.050002 -6.124994 20.58984 2.050002 -7.825 20.58984 0.2249969 -6.124994 21.48984 -0.7249969 -6.124994 21.48984 0.2249968 -7.825 21.48984 -0.7249969 -7.825 21.48984 0.2249969 -6.124994 20.58984 0.2249968 -7.825 20.58984 -0.7249969 -6.124994 20.58984 -0.7249969 -7.825 20.58984 -9.650003 -8.849999 21.48984 -9.650003 -7.899997 21.48984 -11.35 -8.849999 21.48984 -11.35 -7.899997 21.48984 -9.650003 -8.849999 20.58984 -11.35 -8.849999 20.58984 -9.650003 -7.899997 20.58984 -11.35 -7.899997 20.58984 -11.34999 -5.950002 23.34844 -11.34999 -2.850001 23.34844 -14.44999 -5.950001 23.34844 -14.44999 -2.850001 23.34844 -11.34999 -5.950002 22.30844 -14.44999 -5.950001 22.30844 -11.34999 -2.850001 22.30844 -14.44999 -2.850001 22.30844 -3.099996 -15.55001 21.48984 -3.099996 -14.60001 21.48984 -4.799995 -15.55001 21.48984 -4.799995 -14.60001 21.48984 -3.099996 -15.55001 20.58984 -4.799995 -15.55001 20.58984 -3.099996 -14.60001 20.58984 -4.799995 -14.60001 20.58984 19.875 -3.825 21.48984 16.475 -3.825 21.48984 19.875 -5.624993 21.48984 16.475 -5.624993 21.48984 19.875 -3.825 20.88984 19.875 -5.624993 20.88984 16.475 -3.825 20.88984 16.475 -5.624993 20.88984 7.449996 -16.85 21.48984 7.449996 -15.9 21.48984 5.749997 -16.85 21.48984 5.749997 -15.9 21.48984 7.449996 -16.85 20.58984 5.749997 -16.85 20.58984 7.449996 -15.9 20.58984 5.749997 -15.9 20.58984 7.449996 -15.42499 21.48984 7.449996 -14.47499 21.48984 5.749997 -15.42499 21.48984 5.749997 -14.47499 21.48984 7.449996 -15.42499 20.58984 5.749997 -15.42499 20.58984 7.449996 -14.47499 20.58984 5.749997 -14.47499 20.58984 -9.650003 -7.424993 21.48984 -9.650003 -6.474999 21.48984 -11.35 -7.424993 21.48984 -11.35 -6.474999 21.48984 -9.650003 -7.424993 20.58984 -11.35 -7.424993 20.58984 -9.650003 -6.474999 20.58984 -11.35 -6.474999 20.58984 -1.175004 -6.124994 21.48984 -2.125006 -6.124994 21.48984 -1.175004 -7.825 21.48984 -2.125006 -7.825 21.48984 -1.175004 -6.124994 20.58984 -1.175004 -7.825 20.58984 -2.125006 -6.124994 20.58984 -2.125006 -7.825 20.58984 1.624998 -6.124994 21.48984 0.6750045 -6.124994 21.48984 1.624998 -7.825 21.48984 0.6750044 -7.825 21.48984 1.624998 -6.124994 20.58984 1.624998 -7.825 20.58984 0.6750045 -6.124994 20.58984 0.6750044 -7.825 20.58984 4.399997 -6.124994 21.48984 3.449995 -6.124994 21.48984 4.399997 -7.825 21.48984 3.449995 -7.825 21.48984 4.399997 -6.124994 20.58984 4.399997 -7.825 20.58984 3.449995 -6.124994 20.58984 3.449995 -7.825 20.58984 6.625001 -2.125001 21.48984 6.625001 -1.174999 21.48984 4.925002 -2.125 21.48984 4.925002 -1.174999 21.48984 6.625001 -2.125001 20.58984 4.925002 -2.125 20.58984 6.625001 -1.174999 20.58984 4.925002 -1.174999 20.58984 6.625001 -4.799997 21.48984 6.625001 -3.849996 21.48984 4.925002 -4.799997 21.48984 4.925002 -3.849996 21.48984 6.625001 -4.799997 20.58984 4.925002 -4.799997 20.58984 6.625001 -3.849996 20.58984 4.925002 -3.849996 20.58984 -2.749998 -2.625001 21.48984 -2.749997 -1.675 21.48984 -4.449996 -2.625001 21.48984 -4.449996 -1.675 21.48984 -2.749998 -2.625001 20.58984 -4.449996 -2.625001 20.58984 -2.749997 -1.675 20.58984 -4.449996 -1.675 20.58984 -2.749998 -5.349999 21.48984 -2.749998 -4.399998 21.48984 -4.449996 -5.349999 21.48984 -4.449996 -4.399998 21.48984 -2.749998 -5.349999 20.58984 -4.449996 -5.349999 20.58984 -2.749998 -4.399998 20.58984 -4.449996 -4.399998 20.58984 -2.775002 -8.074997 21.48984 -2.775002 -7.124996 21.48984 -4.475001 -8.074997 21.48984 -4.475001 -7.124996 21.48984 -2.775002 -8.074997 20.58984 -4.475001 -8.074997 20.58984 -2.775002 -7.124996 20.58984 -4.475001 -7.124996 20.58984 -2.749997 3.550003 21.48984 -2.749997 4.500004 21.48984 -4.449996 3.550003 21.48984 -4.449996 4.500004 21.48984 -2.749997 3.550003 20.58984 -4.449996 3.550003 20.58984 -2.749997 4.500004 20.58984 -4.449996 4.500004 20.58984 0.1500067 -9.824997 21.48984 0.1500067 -8.874996 21.48984 -1.55 -9.824997 21.48984 -1.55 -8.874996 21.48984 0.1500067 -9.824997 20.58984 -1.55 -9.824997 20.58984 0.1500067 -8.874996 20.58984 -1.55 -8.874996 20.58984 -6.825003 11.30001 21.48984 -7.775004 11.30001 21.48984 -6.825003 9.600001 21.48984 -7.775004 9.600001 21.48984 -6.825003 11.30001 20.58984 -6.825003 9.600001 20.58984 -7.775004 11.30001 20.58984 -7.775004 9.600001 20.58984 -9.750005 -11.64999 20.58984 -11.55 -11.64999 20.58984 -9.750005 -14.74999 20.58984 -11.55 -14.74999 20.58984 -9.750005 -11.64999 20.03984 -9.750005 -14.74999 20.03984 -11.55 -11.64999 20.03984 -11.55 -14.74999 20.03984 -14.725 -14.45 21.48984 -15.675 -14.45 21.48984 -14.725 -16.15 21.48984 -15.675 -16.15 21.48984 -14.725 -14.45 20.58984 -14.725 -16.15 20.58984 -15.675 -14.45 20.58984 -15.675 -16.15 20.58984 15.85 14.875 21.48984 12.45 14.875 21.48984 15.85 13.075 21.48984 12.45 13.075 21.48984 15.85 14.875 20.88984 15.85 13.075 20.88984 12.45 14.875 20.88984 12.45 13.075 20.88984 13.6 5.449997 21.48984 12.65 5.449997 21.48984 13.6 3.749998 21.48984 12.65 3.749998 21.48984 13.6 5.449997 20.58984 13.6 3.749998 20.58984 12.65 5.449997 20.58984 12.65 3.749998 20.58984 -3.099996 -16.95001 21.48984 -3.099996 -16.00001 21.48984 -4.799995 -16.95001 21.48984 -4.799995 -16.00001 21.48984 -3.099996 -16.95001 20.58984 -4.799995 -16.95001 20.58984 -3.099996 -16.00001 20.58984 -4.799995 -16.00001 20.58984 3.850002 -16.875 21.48984 3.850002 -15.925 21.48984 2.149996 -16.875 21.48984 2.149996 -15.925 21.48984 3.850002 -16.875 20.58984 2.149996 -16.875 20.58984 3.850002 -15.925 20.58984 2.149996 -15.925 20.58984 3.850002 -15.45 21.48984 3.850002 -14.5 21.48984 2.149996 -15.45 21.48984 2.149996 -14.5 21.48984 3.850002 -15.45 20.58984 2.149996 -15.45 20.58984 3.850002 -14.5 20.58984 2.149996 -14.5 20.58984 19.475 -11.6 21.48984 19.475 -8.200004 21.48984 17.675 -11.6 21.48984 17.675 -8.200004 21.48984 19.475 -11.6 20.88984 17.675 -11.6 20.88984 19.475 -8.200004 20.88984 17.675 -8.200004 20.88984 9.725003 14.7 21.48984 8.775001 14.7 21.48984 9.725002 13 21.48984 8.775001 13 21.48984 9.725003 14.7 20.58984 9.725002 13 20.58984 8.775001 14.7 20.58984 8.775001 13 20.58984 -23.90785 -4.190097 22.29844 -23.35396 -4.064868 22.29844 -21.54125 -2.5475 22.29844 -15.12488 20.39653 22.29881 -21.35718 21.46699 22.29844 -14 -17.05 22.29844 -13.05 -17.05 22.29844 22.65369 18.42533 22.29844 22.65369 13.34533 22.29844 25 14.83 22.29844 17.72215 2.254897 22.29844 18.39524 2.334132 22.29844 17.66467 4.213684 22.29844 -23.64282 -21.46698 22.29844 -22.50001 -21 22.29844 -21.29631 -9.179662 22.29844 -20.62466 -9.308691 22.29844 -20.75369 -7.440336 22.29844 -21.29631 -4.099662 22.29844 -20.62466 -4.228691 22.29844 17.89312 7.505559 22.29844 16.036 8.714999 22.29844 16.04734 20.96431 22.29844 17.85676 22.84386 22.29844 0.8073374 20.96431 22.29844 -21 22.5 22.29844 -12.27488 20.40215 22.30188 -12.27488 19.67495 22.32047 -13.82488 19.67495 22.32488 -14.22488 19.67495 22.32247 -13.75001 14.625 22.29844 -14.87489 20.39441 22.29876 -14.87489 19.67495 22.3425 -14.47488 19.67495 22.31166 -12.175 -7.674997 22.29844 -10.275 -14.525 22.29844 -12.3 -19.65 22.29844 -13.05 -18.75 22.29844 -6.250005 -16.15 22.29844 -5.275 -14.525 22.29844 -5.300004 -16.15 22.29844 -5.300004 -17.85 22.29844 -12.53334 14.625 22.29844 -12.8 12.925 22.29844 -12.76244 12.44096 22.29844 -13.75001 12.925 22.29844 -12.4 12.925 22.29844 -11.45 12.925 22.29844 -10.1 -7.425001 22.29844 -8.399997 -7.625 22.29844 -10.1 -6.475007 22.29844 -6.900001 6.725 22.29844 -8.600001 6.725 22.29844 -9.570503 -25 22.29844 -10.5 -19.65 22.29844 -10 -19.65001 22.29844 -10 -16.25 22.29844 -10.5 -16.25 22.29844 -12.3 -16.25 22.29844 -10.275 -11.525 22.29844 -7.575002 -16.15 22.29844 -5.275 -11.525 22.29844 1.874995 -18.8 22.29844 3.139443 -21.17189 22.29844 3.575001 -18.8 22.29844 5.9 -17.85 22.29844 3.711431 -20.49788 22.29844 4.009136 -21.33024 22.29844 3.757128 -25 22.29844 3.575001 -17.85 22.29844 7.599998 -17.85 22.29844 7.599998 -18.8 22.29844 5.9 -18.8 22.29844 11.85581 -25 22.29844 6.194801 -21.48236 22.29844 5.677647 -21.03479 22.29844 6.018028 -20.5602 22.29844 6.640563 -20.82812 22.29844 -8.200001 -19.65001 22.29844 -8.200001 -16.25 22.29844 -12.17501 -8.624999 22.29844 -13.875 -8.624999 22.29844 -6.625 -16.15 22.29844 -6.437503 -17.85 22.29844 -7.575001 -17.85 22.29844 -15.12488 19.67495 22.32047 -15.55983 12.38691 22.29844 -13.57488 19.67495 22.3425 -13.17488 19.67495 22.32488 -12.92488 19.67495 22.31496 -12.92488 20.43878 22.38614 -13.18316 22.58436 22.29844 -13.17488 20.39814 22.30178 -14.11244 20.69142 22.29844 -13.82488 20.46227 22.397 -13.57488 20.43437 22.376 -12.52488 20.45773 22.3858 -12.52488 19.67495 22.32488 -23.64282 23.53301 22.29844 -25 25 22.29844 -24 22.5 22.29844 -25 14.57876 22.29844 -23.53302 21.35719 22.29844 -22.5 21 22.29844 -21.46699 23.64282 22.29844 -22.5 24 22.29844 -18.46374 25 22.29844 3.21831 22.83267 22.29844 5.876135 22.90276 22.29844 2.557867 23.56324 22.29844 5.578427 23.73512 22.29844 3.347336 23.50431 22.29844 0.1356914 21.09333 22.29844 2.637096 22.89015 22.29844 0.6783083 20.29266 22.29844 -11.45 14.625 22.29844 0.00666356 20.42169 22.29844 5.215692 21.09333 22.29844 2.675691 21.09333 22.29844 2.546663 20.42169 22.29844 3.218308 20.29266 22.29844 3.347337 20.96431 22.29844 5.086663 20.42169 22.29844 5.758307 20.29266 22.29844 5.006437 23.06112 22.29844 7.75569 21.09333 22.29844 7.546437 23.06112 22.29844 8.427338 23.50431 22.29844 9.297004 23.8415 22.29844 10.77804 21.12813 22.29844 7.885041 23.67281 22.29844 8.298311 22.83267 22.29844 5.887337 20.96431 22.29844 7.684154 18.4629 22.29844 7.626664 20.42169 22.29844 9.297004 19.95898 22.29844 8.29831 20.29266 22.29844 8.427337 20.96431 22.29844 10.13187 20.90404 22.29844 3.218309 17.75266 22.29844 2.546664 17.88169 22.29844 2.604155 18.4629 22.29844 3.277239 18.54213 22.29844 5.086665 17.88169 22.29844 5.144155 18.4629 22.29844 5.698043 18.58813 22.29844 5.876134 17.82276 22.29844 7.626664 17.88169 22.29844 8.667754 13.63548 22.29844 8.29831 17.75266 22.29844 8.357239 18.54213 22.29844 13.4169 21.03584 22.29844 12.72976 21.0339 22.29866 15.50504 21.13281 22.29844 15.81888 20.21244 22.29844 10.47557 20.19088 22.29844 12.78173 20.35792 22.29851 15.16688 20.65757 22.2983 13.50033 20.36495 22.29836 11.01902 20.59506 22.29829 13.49613 22.90276 22.29844 12.70666 22.96169 22.29844 15.24666 22.96169 22.29844 16.03606 22.90273 22.29844 15.85804 23.66813 22.29844 13.31804 23.66813 22.29844 15.30415 23.5429 22.29844 12.76415 23.5429 22.29844 10.35596 22.79787 22.29844 10.13187 23.44404 22.29844 10.77804 23.66813 22.29844 11.00213 23.02196 22.29844 18.62213 23.02196 22.29844 18.39804 23.66813 22.29844 21.03398 22.02679 22.29844 17.84415 23.5429 22.29844 15.51754 17.67041 22.29844 18.30675 14.23274 22.29844 16.09926 18.03152 22.29844 15.25787 18.48324 22.29844 10.83831 17.75267 22.29844 10.16666 17.88169 22.29844 13.43724 18.54213 22.29844 13.37831 17.75266 22.29844 12.70666 17.88169 22.29844 10.22415 18.4629 22.29844 10.89724 18.54213 22.29844 12.76416 18.4629 22.29844 18.58734 18.42431 22.29844 18.45831 17.75267 22.29844 17.91569 18.55333 22.29844 17.78667 17.88169 22.29844 15.9569 18.49584 22.29844 18.57613 20.36276 22.29844 18.4969 21.03585 22.29844 17.8771 20.35016 22.29844 17.79787 21.02324 22.29844 21.20096 23.25 22.29844 22.0268 23.96603 22.29844 25 21.1441 22.29844 23.64283 21.46699 22.29844 22.1768 20.99378 22.29844 25 25 22.29844 23.53302 23.64282 22.29844 24 22.5 22.29844 23.35605 4.920128 22.29844 25 5.355002 22.29844 20.46701 4.929336 22.29845 22.70987 4.696044 22.29844 23.59687 4.388035 22.29844 25 1.945001 22.29844 20.94785 4.175096 22.29844 21.00534 4.756307 22.29844 20.5775 3.215002 22.29844 20.3967 4.046137 22.29847 23.05357 3.982883 22.29844 17.89312 4.96556 22.29844 20.15314 4.581968 22.29844 18.33632 4.084669 22.29844 18.50481 4.626964 22.29844 20.94785 6.715097 22.29844 20.3967 6.586138 22.29847 23.53414 6.694759 22.29844 23.35605 7.460128 22.29844 25 8.714998 22.29844 20.46701 7.469336 22.29845 21.00534 7.296307 22.29844 22.8351 6.682151 22.29844 22.70987 7.236043 22.29844 18.33632 6.624669 22.29844 17.66467 6.753683 22.29844 18.50481 7.166964 22.29844 20.15314 7.121968 22.29844 -25 -7.603751 22.29844 -23.96533 -7.311308 22.29844 -25 -5.712499 22.29844 -23.35396 -6.604868 22.29844 -23.17586 -4.830236 22.29844 -23.90784 -6.730095 22.29844 -21.42533 -7.311307 22.29844 -23.17586 -7.370236 22.29844 -21.42533 -4.771307 22.29844 -18.75631 -4.099664 22.29844 -18.1751 -4.157155 22.29844 -18.04987 -4.711042 22.29844 -18.15476 -6.650865 22.29844 -20.75369 -4.900336 22.29844 -18.81524 -4.889132 22.29844 -21.29631 -6.639662 22.29844 -18.98712 -6.948573 22.29844 -20.62466 -6.76869 22.29844 -13.875 -7.674997 22.29844 -18.31312 -7.520562 22.29844 -20.75369 -9.980336 22.29844 -21.42533 -9.851307 22.29844 -23.17586 -9.910236 22.29844 -18.75631 -9.179663 22.29844 -18.08466 -9.308691 22.29844 -17.39846 -10.7775 22.29844 -18.21369 -9.980335 22.29844 -18.88533 -9.851309 22.29844 -21.29631 -11.71966 22.29844 -21.42533 -12.39131 22.29844 -21.46013 -14.44896 22.29844 -18.75631 -11.71966 22.29844 -18.08466 -11.84869 22.29844 -18.39357 -14.15788 22.29844 -18.21369 -12.52033 22.29844 -20.75369 -12.52034 22.29844 -18.88533 -12.39131 22.29844 -20.62466 -11.84869 22.29844 -25 -18.77501 22.29844 -24 -22.5 22.29844 -25 -25 22.29844 -23.53301 -23.64282 22.29844 -20.99378 -22.8232 22.29844 -19.09298 -25 22.29844 -22.0268 -23.96603 22.29844 -21.467 -21.35717 22.29844 -20.75369 -17.60034 22.29844 -20.75369 -15.06034 22.29844 -21.3349 -15.00284 22.29844 -23.12987 -14.87104 22.29844 -18.69604 -15.09513 22.29844 -21.29631 -16.79966 22.29844 -18.93686 -14.56304 22.29844 -18.04987 -14.87104 22.29844 -20.69476 -14.27086 22.29844 -21.42534 -17.47131 22.29844 -18.75631 -16.79966 22.29844 -18.1751 -16.85716 22.29844 -18.81524 -17.58913 22.29844 -14 -18.75 22.29844 -18.04987 -17.41104 22.29844 -20.62467 -16.92869 22.29844 20.46701 -0.1506639 22.29845 20.94785 1.635097 22.29844 20.3967 1.506138 22.29847 23.53414 1.614759 22.29844 23.35605 2.380129 22.29844 21.00534 2.216307 22.29844 20.46701 2.389336 22.29847 22.8351 1.602151 22.29844 22.70987 2.156044 22.29844 18.33632 1.544669 22.29844 16.036 0.6750018 22.29844 17.66467 1.673683 22.29844 20.15314 2.041968 22.29844 23.54534 -0.3236902 22.29844 22.87369 -0.1946678 22.29844 25 -7.590158 22.29844 23.41631 -0.9953377 22.29844 20.94785 -0.9048987 22.29844 22.74467 -0.8663129 22.29844 21.00534 -0.3236924 22.29844 18.23688 -1.075563 22.29844 17.56288 -0.5035749 22.29844 20.15314 -0.4980316 22.29844 18.39524 -0.2058679 22.29844 20.3967 -1.033853 22.29847 -1.62825 -25 22.29844 0.6796718 -21.27132 22.29844 0.808691 -20.59967 22.29844 1.389899 -20.65715 22.29844 1.469137 -21.33024 22.29844 15.45 -23.05 22.29844 15.45 -21.25 22.29844 18.85 -21.25 22.29844 20.5775 -25 22.29844 18.85 -23.05 22.29844 22.82321 -20.99379 22.29844 21.75 -21.20096 22.29844 23.96603 -22.0268 22.29844 25 -25 22.29844 23.79904 -23.25 22.29844 22.9732 -23.96603 22.29844 21.46699 -23.64282 22.29844 20.99379 -22.1768 22.29844 23.36481 10.54696 22.29844 23.19631 10.00466 22.29844 22.52467 10.13369 22.29844 25 12.44096 22.29844 22.75312 10.88556 22.29844 22.59476 12.55586 22.29844 23.32534 13.21631 22.29844 23.26784 12.63509 22.29844 22.78304 15.92481 22.29844 23.09688 15.00443 22.29844 23.32534 15.75631 22.29844 22.59476 17.63586 22.29844 23.23491 18.36784 22.29844 23.36013 17.81396 22.29844 22.44265 15.4502 22.29844 15.35312 -0.1144407 22.29844 8.825066 2.480002 22.29844 16.02712 -0.6864292 22.29844 15.19476 -0.9841356 22.29844 15.35312 2.425559 22.29844 15.19476 1.55587 22.29844 16.02712 1.853567 22.29844 15.35312 4.965559 22.29844 8.982378 7.035 22.29844 16.02712 4.393567 22.29844 15.19476 4.09587 22.29844 15.35312 7.505558 22.29844 15.79632 6.624669 22.29844 15.12467 6.753682 22.29844 15.96481 7.166965 22.29844 -6.900001 5.775 22.29844 1.874995 -17.85 22.29844 0.7372387 18.54213 22.29844 0.6783093 17.75266 22.29844 0.006664812 17.88169 22.29844 0.06415557 18.4629 22.29844 0.807336 23.50431 22.29844 0.6783105 22.83267 22.29844 -0.0735625 23.06112 22.29844 0.2650405 23.67281 22.29844 -0.9794372 -20.82811 22.29844 -1.425197 -21.48235 22.29844 -1.942352 -21.03479 22.29844 -2.73 -18.77501 22.29844 -1.601975 -20.5602 22.29844 -8.399997 -6.475007 22.29844 -4.389133 -20.66976 22.29844 -3.690104 -20.65714 22.29844 -3.610862 -21.33024 22.29844 -4.309892 -21.34285 22.29844 -8.600001 5.775 22.29844 4.58544 11.17524 22.29844 -8.399997 -8.775001 22.29844 -10.1 -8.775001 22.29844 -10.1 -7.825 22.29844 -16.76192 11.18483 22.29844 -14.88808 11.71516 22.29844 -16.09016 10.51308 22.29844 -14.8762 1.201408 22.29844 -14.22488 20.43878 22.38614 -14.47488 20.45773 22.3858 0.9346204 25 22.29844 -23.83631 -16.79966 22.29844 -23.08444 -17.02812 22.29844 -23.5302 -17.68235 22.29844 -25 -16.2 22.29844 -24.00481 -17.34196 22.29844 -23.66196 -15.11186 22.29844 -24.06712 -14.56857 22.29844 -25 -12.08375 22.29844 -23.35396 -14.22487 22.29844 -23.35396 -11.68487 22.29844 -23.11313 -12.21696 22.29844 -23.53021 -12.60235 22.29844 -24.06712 -12.02857 22.29844 -23.35396 -9.144868 22.29844 -23.90785 -9.270096 22.29844 -23.96533 -9.851307 22.29844 -23.96533 -4.771308 22.29844 -18.75631 -12.52033 21.5 -18.82785 -14.9699 21.5 -18.15476 -15.04913 21.5 -20.57313 -17.10304 21.5 -15.75688 -25 21.5 15.7681 22.78066 21.5 16.12966 23.3623 21.5 17.78667 20.96431 21.5 22.1768 24.00622 21.5 25 25 21.5 17.07594 -25 21.5 22.8232 -24.00622 21.5 25 -25 21.5 23.79904 -23.25 21.5 24.00622 -22.1768 21.5 25 -7.333753 21.5 22.97321 -21.03398 21.5 21.03398 -22.0268 21.5 21.35718 -23.53301 21.5 5.679442 -20.82812 21.5 6.301978 -20.5602 21.5 4.553501 -25 21.5 6.125204 -21.48236 21.5 6.642358 -21.03479 21.5 3.283501 -15.93 21.5 3.761978 -20.5602 21.5 3.139442 -20.82812 21.5 3.585203 -21.48236 21.5 4.102358 -21.03479 21.5 -3.368436 -11.96125 21.5 1.221978 -20.5602 21.5 0.5994424 -20.82812 21.5 1.153503 -25 21.5 1.045204 -21.48236 21.5 1.562358 -21.03479 21.5 -21.11643 -16.69788 21.5 -20.69476 -15.04913 21.5 -21.36784 -14.9699 21.5 -21.46013 -17.41104 21.5 -25 -25 21.5 -21.46699 -23.64282 21.5 -20.81396 -17.63513 21.5 -20.99378 -22.1768 21.5 -22.02679 -21.03398 21.5 -20.75369 -14.25966 21.5 -21.16696 -12.55981 21.5 -21.42533 -14.38869 21.5 -23.22215 -14.3501 21.5 -23.77604 -16.76487 21.5 -25 -15.93 21.5 -23.46804 -17.65186 21.5 -23.06288 -17.10857 21.5 -24.00013 -17.41104 21.5 -23.53301 -21.35717 21.5 -24 -22.5 21.5 -23.64282 -23.53302 21.5 -22.5 -24 21.5 -20.75369 -11.71966 21.5 -21.50556 -11.94812 21.5 -20.81396 -10.01513 21.5 -20.62466 -12.39131 21.5 -21.475 -9.579998 21.5 -21.36784 -9.889903 21.5 -20.58987 -9.36896 21.5 -20.69476 -7.429133 21.5 -21.23604 -9.144867 21.5 -19.755 -8.310003 21.5 -21.42533 -4.228691 21.5 -21.42533 -6.76869 21.5 -21.36784 -7.349903 21.5 -20.75369 -4.099662 21.5 -22.5 21 21.5 -21.36784 -4.809903 21.5 -20.75369 -6.639662 21.5 -20.69476 -4.889133 21.5 18.637 18.153 21.5 22.59476 18.41413 21.5 22.65369 17.62466 21.5 25 21.29225 21.5 25 17.197 21.5 23.32534 17.75369 21.5 23.26785 18.3349 21.5 18.39804 20.25787 21.5 18.45831 18.55333 21.5 16.04734 20.42169 21.5 17.78667 18.42431 21.5 22.44265 15.51979 21.5 18.39804 17.71787 21.5 17.84415 17.8431 21.5 16.0473 17.88166 21.5 15.81888 18.63356 21.5 23.64282 23.53301 21.5 23.96603 22.02679 21.5 22.8232 20.99378 21.5 21.35718 21.46699 21.5 18.57613 21.02324 21.5 21.03398 22.97321 21.5 18.45831 23.63334 21.5 18.58734 22.96169 21.5 17.84416 20.3831 21.5 15.91831 21.09333 21.5 15.19884 20.92036 21.5001 10.29569 22.83266 21.5 10.83831 21.09333 21.5 10.16666 20.96431 21.5 12.7971 21.03584 21.5 13.37831 21.09333 21.5 13.55153 20.55418 21.49997 11.01153 20.55417 21.49997 10.39512 20.21244 21.5 10.95613 18.48324 21.5 9.297004 17.197 21.5 13.31804 17.71787 21.5 10.16666 18.42431 21.5 10.22415 17.8431 21.5 12.7971 18.49584 21.5 12.67187 17.94196 21.5 10.77804 17.71787 21.5 15.16465 18.18779 21.5 13.49613 18.48324 21.5 13.20396 20.24114 21.5 15.50504 17.71319 21.5 15.42209 20.27592 21.5 12.66947 20.48454 21.49996 17.91569 22.83267 21.5 17.78667 23.50431 21.5 15.55004 23.68487 21.5 12.83569 22.83267 21.5 13.50734 22.96169 21.5 15.14488 23.14157 21.5 10.8769 22.89016 21.5 12.70666 23.50431 21.5 11.01887 23.32996 21.5 13.37831 23.63334 21.5 10.16666 23.50431 21.5 7.815959 23.66813 21.5 10.70896 23.67281 21.5 8.298311 18.55334 21.5 7.626664 18.42431 21.5 5.817238 17.76387 21.5 7.684155 17.8431 21.5 8.357238 17.76387 21.5 8.427336 20.42169 21.5 7.755691 20.29266 21.5 7.626664 20.96431 21.5 5.75831 18.55334 21.5 5.69804 20.25787 21.5 5.086664 18.42431 21.5 5.144156 17.8431 21.5 5.144154 20.3831 21.5 3.382132 18.36404 21.5 5.086663 20.96431 21.5 3.15804 20.25787 21.5 2.44488 18.06157 21.5 3.158043 17.71787 21.5 2.85004 18.60486 21.5 2.604154 20.3831 21.5 8.298311 21.09333 21.5 8.123959 22.78113 21.5 5.876134 21.02324 21.5 0.6180433 17.71787 21.5 0.7961353 18.48324 21.5 2.546663 20.96431 21.5 0.7169048 20.35016 21.5 0.006663382 20.96431 21.5 -15.62781 20.5871 21.5 0.06415629 17.8431 21.5 0.1356921 20.29266 21.5 0.006664276 18.42431 21.5 3.336134 21.02324 21.5 8.529122 23.32443 21.5 7.591869 23.02196 21.5 5.215691 22.83267 21.5 5.967563 23.06112 21.5 5.628961 23.67281 21.5 5.086665 23.50431 21.5 0.7961348 21.02324 21.5 2.67569 22.83267 21.5 3.427563 23.06112 21.5 3.08896 23.67281 21.5 2.546665 23.50431 21.5 0.5489605 23.67281 21.5 0.1356906 22.83267 21.5 0.8875635 23.06112 21.5 0.006665349 23.50431 21.5 -25 25 21.5 -23.53301 23.64282 21.5 -20.27125 25 21.5 -22.0268 23.96603 21.5 -20.99378 22.82321 21.5 -25 21.29225 21.5 -21.46699 21.35718 21.5 -23.64282 21.46699 21.5 -24 22.5 21.5 -23.95413 -14.99024 21.5 -23.16466 -14.93131 21.5 -23.77604 -14.22487 21.5 -25 -13.39 21.5 -23.46804 -12.57186 21.5 -23.77604 -11.68487 21.5 -24.00013 -12.33104 21.5 -25 -10.85 21.5 -23.06288 -12.02857 21.5 -23.06288 -9.488574 21.5 -23.77604 -9.144867 21.5 -25 -8.310003 21.5 -24.00013 -9.791042 21.5 -23.46804 -10.03186 21.5 -23.06288 -6.948573 21.5 -23.8749 -4.157155 21.5 -25 8.42269 21.5 -23.29369 -4.099664 21.5 -24.00013 -4.711042 21.5 -23.23476 -4.889132 21.5 -24.00013 -7.251042 21.5 -23.46804 -7.491864 21.5 -23.77604 -6.604868 21.5 -18.08466 -17.47131 21.5 -18.14215 -16.8901 21.5 -18.69604 -16.76487 21.5 -18.87413 -17.53024 21.5 -18.21369 -14.25966 21.5 -18.88533 -14.38869 21.5 -18.1751 -12.46284 21.5 -18.81524 -11.73086 21.5 -18.04987 -11.90896 21.5 -18.08466 -9.851307 21.5 -18.14215 -9.270097 21.5 -18.69604 -9.144867 21.5 -18.87413 -9.910238 21.5 -18.08466 -4.771308 21.5 -18.31312 -4.019436 21.5 -18.1751 -7.382843 21.5 -18.04987 -6.828957 21.5 -18.92481 -4.358039 21.5 -18.75631 -7.440334 21.5 -18.75631 -4.900334 21.5 -18.81524 -6.650866 21.5 -1.248944 -21.43513 21.5 -1.070862 -20.66976 21.5 -4.091425 -20.49788 21.5 -3.517642 -21.03479 21.5 -1.76989 -20.65714 21.5 -4.435125 -21.21105 21.5 -3.903017 -21.45186 21.5 -1.895125 -21.21105 21.5 15.96481 -0.7369689 21.5 15.92533 1.673683 21.5 15.86785 -0.2851032 21.5 15.19476 -0.205868 21.5 7.102657 -6.528126 21.5 6.681485 3.532502 21.5 15.35312 -1.075563 21.5 15.19476 2.334132 21.5 15.25368 1.54467 21.5 15.86785 2.254897 21.5 17.66467 2.216307 21.5 15.92533 4.213683 21.5 15.92533 6.753682 21.5 15.86785 4.794897 21.5 15.19476 4.874132 21.5 15.25368 4.08467 21.5 15.19476 7.414132 21.5 15.25368 6.62467 21.5 15.86785 7.334896 21.5 18.46534 -0.8663119 21.5 21.75 -21.20096 21.5 18.40785 -0.2851016 21.5 17.73476 -0.2058672 21.5 17.79369 -0.995336 21.5 18.39525 1.555869 21.5 17.72216 1.635095 21.5 18.33631 2.345332 21.5 20.27229 4.156144 21.49999 18.37491 4.142151 21.5 17.96805 4.936864 21.5 18.50013 4.696043 21.5 17.6252 4.626962 21.5 17.79368 4.084669 21.5 17.79368 6.624669 21.5 18.23688 7.505559 21.5 22.4852 10.54697 21.5 18.46533 6.753683 21.5 17.6252 7.166962 21.5 20.94855 -0.9686513 21.49985 21.765 0.6750017 21.5 20.77653 -0.1158123 21.49997 20.1652 -0.4530326 21.5 20.27229 -0.9238537 21.49995 20.94857 1.57137 21.49985 20.27229 1.616144 21.49995 20.94785 2.254895 21.5 20.94857 4.11137 21.49995 20.27782 2.341452 21.50006 20.77653 4.964188 21.49999 20.1652 4.626967 21.5 20.83322 6.60306 21.49988 20.27229 6.696144 21.49995 21.04013 7.236044 21.5 20.27782 7.421452 21.50006 -0.1604822 11.21148 21.5 2.182502 25 21.5 23.54534 -0.8663139 21.5 25 1.945001 21.5 23.41631 -0.1946665 21.5 22.74467 -0.3236913 21.5 22.87369 -0.9953369 21.5 23.47525 1.555868 21.5 22.70987 1.733947 21.5 23.41631 2.345333 21.5 22.8351 2.287841 21.5 23.54533 4.21368 21.5 25 5.755001 21.5 23.41631 4.885334 21.5 22.8351 4.827841 21.5 22.75587 4.154759 21.5 22.58215 10.0951 21.5 23.13604 9.969868 21.5 23.54533 6.75368 21.5 22.75587 6.694759 21.5 23.37686 10.50196 21.5 25 12.945 21.5 23.41631 7.425333 21.5 22.8351 7.36784 21.5 22.95979 10.88735 21.5 23.31413 13.27524 21.5 22.52467 13.21631 21.5 22.58215 12.63509 21.5 23.13604 12.50987 21.5 23.01643 14.98288 21.5 23.36013 15.69604 21.5 22.82804 15.93686 21.5 -15.12488 19.97495 22.43063 -15.12488 20.53054 22.50484 -14.87489 19.97495 22.43063 -14.87489 20.5224 22.50556 -14.47488 19.97495 22.43063 -14.22488 19.97495 22.43063 -13.82488 19.97495 22.43063 -13.57488 19.97495 22.43063 -13.17488 19.97495 22.43063 -13.17488 20.48944 22.43736 -12.92488 19.97495 22.43063 -12.52488 19.97495 22.43063 -12.27488 19.97495 22.43063 -13.34988 22.12495 22.35438 -13.34988 21.67495 22.32492 -15.19988 21.67495 22.35438 -15.19988 22.12495 22.32492 -14.48989 22.12495 22.39063 -14.50988 22.12495 22.34396 -14.45491 24.21537 22.61063 -14.43198 24.22512 22.41063 -13.77804 23.91671 22.61063 -13.76417 23.924 22.41063 -12.21488 23.46462 23.74852 -12.18752 21.17496 23.5951 -12.58488 21.17496 23.64063 -15.18626 23.85636 23.66082 -15.18488 23.45249 23.73034 -15.18707 21.17496 23.60239 -14.16488 23.46462 23.74852 -14.16488 21.17496 23.64063 -14.53489 21.17496 23.64063 -14.53489 23.87558 23.80031 -14.53489 23.45249 23.73034 -14.53489 23.80866 23.60838 -14.16488 23.87601 23.79959 -14.16488 23.8027 23.61023 -13.51488 21.17496 23.64063 -13.88488 21.17496 23.64063 -13.88488 23.87559 23.80031 -13.88488 23.45383 23.72897 -13.88488 23.80865 23.60838 -13.51488 23.8601 23.66032 -13.51488 23.46397 23.7445 -12.86488 23.46462 23.74852 -12.86488 21.17496 23.64063 -13.23488 23.45249 23.73034 -13.23488 21.17496 23.64063 -13.23488 23.86261 23.66737 -12.86488 23.8601 23.66032 -15.38474 23.81372 23.64474 -15.42215 21.17496 23.64685 -15.38441 23.81197 24.11935 -15.40452 21.17497 24.13527 -14.90988 20.97495 24.46063 -14.90988 20.97495 24.76063 -16.06988 20.97495 24.46063 -16.01228 20.69995 24.78794 -16.02618 20.67495 24.47122 -15.89599 19.97495 24.75357 -15.49099 20.0403 24.11237 -15.31442 20.03482 24.35497 -15.28322 20.65317 24.33312 -17.11293 19.97495 24.43146 -17.11227 24.67496 24.43377 -17.08059 19.97495 24.75165 -17.05085 24.67496 24.7565 -17.43873 24.67496 24.39452 -17.43689 19.97495 24.37739 -11.91521 21.1753 22.61147 -11.92555 21.1736 22.32118 -14.4356 21.77401 22.61063 -14.42172 21.76671 22.41063 -13.76778 22.07511 22.61063 -13.75192 22.06677 22.41063 -13.68989 21.67495 22.36063 -13.68989 21.19495 22.53563 -13.70988 21.19495 22.31063 -13.70988 21.19495 22.61063 -15.47481 21.17316 22.32191 -15.48404 21.17635 22.6114 -15.48988 20.79495 22.3273 -11.90988 20.79495 22.4948 -10.29709 19.97495 24.4359 -10.28683 24.67495 24.43146 -10.26426 24.67495 23.36248 -10.22441 23.25749 23.55063 -11.43958 23.23644 22.61063 -11.43204 23.24806 22.31063 -11.39173 22.99258 22.61063 -11.40382 23.00071 22.31063 -9.847649 22.93889 22.31063 -9.835942 22.92718 22.61063 -9.849651 22.1105 22.61063 -9.835433 22.12472 22.31063 -11.43958 22.02643 22.61063 -11.43204 22.03805 22.31063 -11.39172 21.78258 22.61063 -11.40382 21.79072 22.31063 -16.11197 23.29842 22.57636 -15.99594 23.25919 22.31063 -15.96019 23.02346 22.61063 -15.96773 23.01185 22.31063 -16.00803 22.05732 22.61063 -15.99593 22.04919 22.31063 -15.96019 21.81346 22.61063 -15.96773 21.80185 22.31063 -17.55211 22.11101 22.31063 -17.56382 22.12272 22.61063 -17.55011 22.93941 22.61063 -17.56433 22.92518 22.31063 -17.15583 21.75956 23.40556 -17.35862 21.76495 23.15294 -16.40488 21.76494 22.62796 -16.52756 21.76495 22.3468 -16.47447 20.79495 22.32022 -16.52756 23.28495 22.3468 -16.48277 24.67496 22.32542 -16.99318 20.76615 22.77967 -17.06031 19.99844 22.84153 -17.44797 23.29669 23.33336 -10.87546 20.79412 22.72606 -10.40153 20.76336 22.78471 -16.51668 20.79597 22.71821 -10.90362 20.79495 22.33379 -10.8848 21.76495 22.33281 -10.889 23.28495 22.34294 -10.90853 24.67495 22.32176 -10.02288 21.76494 23.17249 -10.34626 20.00503 22.83999 -9.970426 24.67492 23.26953 -10.03295 23.28495 23.16964 -16.62924 20.00503 22.83999 -10.77651 20.01296 22.834 -10.21884 21.77787 23.50181 -10.99546 21.76494 22.62842 -10.26254 19.97496 23.35948 -11.01632 24.67495 22.61884 -10.99833 23.28495 22.62707 -9.940125 23.23461 23.57851 -14.22488 20.61496 22.52663 -14.47488 20.57082 22.55536 -13.57488 20.61496 22.52663 -13.82488 20.57082 22.55536 -12.92488 20.61496 22.52663 -13.17488 20.57082 22.55536 -12.52488 20.57082 22.55536 -11.77488 19.67495 22.81063 -15.62488 19.67495 22.81063 -11.77488 19.97495 22.81063 -15.62488 19.97495 22.63452 -10.73544 20.52519 22.61063 -10.74965 20.53941 22.31063 -11.73497 20.53505 22.61063 -11.73131 20.53139 22.31063 -11.77488 19.76274 22.33989 -10.69989 19.72828 22.38529 -11.83113 19.97495 22.57972 -15.66043 20.52519 22.61063 -15.67465 20.5394 22.31063 -16.65011 20.53941 22.61063 -16.66433 20.52519 22.31063 -10.74023 19.97495 22.71599 -16.66209 19.97495 22.74413 -10.79199 19.67495 23.59221 -10.68327 19.97495 22.94134 -10.88273 19.97495 23.61743 -11.79706 19.79495 23.71063 -12.47364 19.97495 24.06376 -12.48988 19.67495 24.11063 -13.32341 20.64113 24.76063 -13.33978 20.62484 24.56063 -14.05542 20.62941 24.56063 -14.06947 20.63387 24.2221 -13.3521 20.61939 24.18063 -14.07648 20.63292 24.76063 -14.10229 21.0446 24.21269 -14.10988 20.96056 24.69376 -13.31864 20.65196 24.25078 -13.28988 20.979 24.72197 -13.27473 21.15071 24.43088 -13.27683 21.12278 24.18063 -14.12289 21.13999 24.45837 -14.10988 20.57495 24.45563 -14.10988 20.57495 24.46063 -16.39286 21.17496 22.62759 -17.12845 21.17496 23.36115 -17.13436 19.97495 23.37543 -17.06657 19.97495 24.37732 -17.06952 21.17496 24.39702 -16.06988 20.69495 24.45563 -16.06988 19.97495 24.45563 -16.06988 20.69495 24.03563 -16.06988 19.97495 24.03563 -14.9232 19.97495 24.06448 -14.90988 20.69495 24.03563 -11.32988 20.69495 24.03563 -11.32988 20.69495 24.45563 -12.48988 20.69495 24.03563 -12.48988 20.69495 24.45563 -14.90988 20.69495 24.45563 -11.32989 19.97495 24.24563 -11.00691 21.17496 22.62759 -10.26684 21.17496 23.36765 -10.26957 19.97495 23.36878 -10.34776 21.17496 24.40403 -10.32495 19.97495 24.38556 -12.48988 19.97495 24.45813 -13.28988 20.57495 24.45563 -14.90988 19.97495 24.45763 -15.62488 19.72905 22.38228 -16.69988 19.74661 22.36472 -16.60212 19.67495 23.57376 -16.56302 19.97495 23.61287 -15.6027 19.77495 23.71063 -14.90988 19.67495 24.11063 -15.48988 19.97495 22.4923 -11.90988 20.61496 22.47063 -15.48988 20.72745 22.53863 -12.27488 20.61496 22.53063 -16.38492 24.67496 22.61569 -17.14008 24.67495 23.37486 -17.17588 23.26182 23.53335 -17.13457 19.97495 23.35807 -17.43611 19.97499 23.31199 -17.4582 21.81926 23.58484 -17.41783 24.6749 23.24191 -17.44988 23.12856 23.63943 -17.14988 21.97937 23.65206 -9.941713 21.81952 23.59331 -9.983928 19.97499 23.23184 -9.964609 19.97495 24.39972 -9.96287 24.67495 24.37739 -10.32285 24.67495 24.75417 -10.34079 19.97495 24.75194 -11.35468 20.69995 24.47256 -11.4103 19.97495 24.4571 -12.11798 20.65494 24.33212 -11.94398 20.65258 24.08772 -11.41995 20.67495 24.7834 -11.49943 19.97495 24.75559 -12.0794 20.04208 24.35913 -11.91311 20.03501 24.10934 -15.99163 19.97495 24.45811 -15.4538 20.655 24.08633 -11.32988 20.97495 24.76063 -12.48988 20.97495 24.46063 -12.48988 20.97495 24.76063 -12.48988 19.75896 24.72861 -14.90988 19.74646 24.72452 -11.67488 23.68411 24.80758 -11.62711 24.03591 24.76063 -10.97488 23.69924 24.7862 -10.794 23.43604 24.46063 -10.84967 23.41073 24.76063 -10.73712 23.64024 24.76063 -10.91334 23.71204 24.46063 -10.97488 22.20495 24.46063 -10.97488 22.20495 24.76063 -11.67488 22.20495 24.46063 -11.67488 22.20495 24.76063 -11.8202 23.41708 24.46063 -11.76633 23.40115 24.76063 -11.90073 23.64759 24.46063 -11.91303 23.63505 24.76063 -11.67488 23.84774 24.49636 -10.97488 23.92481 24.48131 -11.02266 23.91353 24.9726 -11.01095 24.02239 24.76063 -11.63882 23.90339 24.96675 -15.72489 23.82156 24.49326 -15.59212 23.41051 24.46063 -15.59967 23.41073 24.76063 -15.48711 23.64024 24.76063 -15.50152 23.64638 24.46063 -15.72488 22.20495 24.46063 -15.72488 22.20495 24.76063 -16.42488 22.20495 24.46063 -16.42488 22.20495 24.76063 -16.57019 23.41708 24.46063 -16.51633 23.40114 24.76063 -16.65073 23.64759 24.46063 -16.66303 23.63504 24.76063 -16.42488 23.83915 24.50741 -16.42488 23.68448 24.80187 -15.72489 23.69924 24.7862 -15.77265 23.91353 24.9726 -16.38883 23.90339 24.96674 -15.76094 24.02239 24.76063 -16.37712 24.03591 24.76063 -13.28988 20.57495 24.46063 -11.99688 23.76846 24.12565 -12.09717 23.86313 24.06952 -11.98589 21.17496 24.13289 -12.00978 23.80686 23.64231 -12.21212 23.84836 23.6538 -11.96613 21.17496 23.68836 -14.81488 21.17496 23.64063 -14.81488 23.8027 23.61023 -12.58488 23.86261 23.66737 -12.58488 23.45249 23.73034 -14.81488 23.87586 23.79954 -14.81488 23.46462 23.74852 -14.43643 24.20113 22.61063 -13.68988 24.67496 22.61063 -13.75193 23.90313 22.61063 -14.36161 21.74623 22.61063 -13.70988 24.67496 22.61063 -14.50426 21.8696 22.61063 -13.76417 22.0459 22.61063 -13.76778 23.89479 22.41063 -13.68989 24.41245 22.33563 -14.42757 24.1975 22.41063 -14.48989 23.87495 22.37063 -14.50988 23.87495 22.34396 -15.19988 23.87495 22.3392 -13.34989 23.87495 22.3773 -15.19988 24.32495 22.36518 -13.34989 24.32495 22.35063 -13.70988 24.32495 22.38563 -13.70988 24.67496 22.31063 -13.70988 21.67495 22.38563 -13.77805 22.0532 22.41063 -14.43868 21.75131 22.41063 -6.625 -16.15 23.19844 -7.575001 -16.15 23.19844 -6.625 -17.85 23.19844 -7.575001 -17.85 23.19844 -13.05 -17.05 23.19844 -14 -17.05 23.19844 -13.05 -18.75 23.19844 -14 -18.75 23.19844 -8.399997 -8.775001 23.19844 -8.399997 -7.825 23.19844 -10.1 -8.775001 23.19844 -10.1 -7.825 23.19844 -12.175 -8.624999 23.19844 -12.175 -7.674997 23.19844 -13.875 -8.624999 23.19844 -13.875 -7.674997 23.19844 -10 -19.65 23.59844 -8.200001 -19.65 23.59844 -10 -16.25 23.59844 -8.200001 -16.25 23.59844 7.599998 -18.8 23.19844 7.599998 -17.85 23.19844 5.9 -18.8 23.19844 5.9 -17.85 23.19844 3.575001 -18.8 23.19844 3.575001 -17.85 23.19844 1.874995 -18.8 23.19844 1.874995 -17.85 23.19844 -10.275 -11.525 23.29844 -10.275 -14.525 23.29844 -5.275 -11.525 23.29844 -5.275 -14.525 23.29844 -12.3 -19.65 23.59844 -10.5 -19.65 23.59844 -12.3 -16.25 23.59844 -10.5 -16.25 23.59844 -6.900001 5.775 23.19844 -6.900001 6.725 23.19844 -8.6 5.775 23.19844 -8.6 6.725 23.19844 -8.399997 -7.425001 23.19844 -8.399997 -6.475007 23.19844 -10.1 -7.425001 23.19844 -10.1 -6.475007 23.19844 -11.45 14.625 23.19844 -12.4 14.625 23.19844 -11.45 12.925 23.19844 -12.4 12.925 23.19844 -12.8 14.625 23.19844 -13.75 14.625 23.19844 -12.8 12.925 23.19844 -13.75 12.925 23.19844 -5.300004 -16.15 23.19844 -6.250005 -16.15 23.19844 -5.300004 -17.85 23.19844 -6.250005 -17.85 23.19844 -16.09016 10.51308 23.19844 -14.88808 11.71516 23.19844 -16.76192 11.18483 23.19844 -15.55983 12.38691 23.19844 18.85 -21.25 22.89844 15.45 -21.25 22.89844 18.85 -23.05 22.89844 15.45 -23.05 22.89844 -49.18961 81.61692 11.98899 -51.11668 82.10938 12.0009 -50.59585 81.12246 11.9908 -52.04684 80.21002 12.00235 -50.84682 79.69053 11.98815 -50.9591 78.06848 12.00235 -49.73552 78.73419 11.98903 -48.89705 77.69468 12.00102 -48.35148 79.21878 11.9883 -47.39413 78.69367 12.0009 -46.94553 80.76042 12.00235 -48.07856 80.65956 11.9883 -47.97905 82.20744 12.00025 -49.41836 82.71965 12.00102 -46.77434 80.95845 9 -47.59637 80.72253 8.999633 -47.96961 82.54431 9 -48.67742 81.82689 8.984345 -49.60341 82.9398 9 -51.19059 78.01319 9 -50.07265 78.54674 8.967817 -49.98777 77.45791 9 -48.6647 77.52522 9 -48.84535 78.47899 8.985499 -47.52447 78.19966 9 -47.9293 79.32726 8.968361 -46.82826 79.32678 9 -50.8497 81.40244 8.980747 -51.14814 82.41163 9 -52.2071 80.73168 9 -51.26441 79.44245 8.999664 -51.99756 79.06382 9 -50.98426 80.1604 8.713478 -50.96755 79.94548 -2.746942 -50.80828 80.87992 -2.750917 -50.83201 80.89689 8.781973 -50.20293 81.53613 8.772007 -50.14247 81.53343 -2.750777 -49.27207 81.72863 8.840395 -49.00044 81.64044 -2.763262 -48.11985 80.8818 -2.750459 -48.01647 80.64733 8.712978 -47.96001 79.96215 -2.749779 -48.11516 79.4628 8.716983 -48.38374 79.10181 -2.746325 -48.6519 78.85683 8.782939 -49.23309 78.67462 -2.750751 -50.1271 78.79158 8.713264 -50.3529 78.92427 -2.763713 -50.4352 79.28873 -3.005136 -50.66842 80.62211 -3.001961 -48.31552 79.52281 -3.001471 -49.30092 78.92304 -3.000546 -48.3928 80.8884 -3.001961 -49.60863 81.48347 -3.005136 -51.96476 78.99023 11.75254 -51.12735 77.96327 11.75253 -49.90856 77.44309 11.75253 -48.58769 77.54891 11.75253 -47.46729 78.25643 11.75253 -46.80401 79.40363 11.75253 -46.74983 80.72763 11.75253 -47.31716 81.92515 11.75254 -48.376 82.72184 11.75254 -50.02994 82.9175 11.75555 -51.70558 81.85181 11.75555 -52.22901 80.28871 11.75253 -48.62657 81.10434 11.87579 -49.84904 81.36413 11.8758 -50.68527 80.43531 11.8758 -50.29723 79.2451 11.87587 -49.07651 78.98691 11.8758 -48.24028 79.91574 11.8758 -49.11964 81.56188 10.73433 -49.46277 80.17552 9.978313 -49.84838 81.36425 10.67698 -50.55531 81.09543 10.73448 -50.82382 79.71274 10.76476 -48.08908 80.6007 10.77152 -48.40969 79.19603 10.75803 -49.76547 78.76468 10.80094 -47.8873 80.21794 8.866542 -48.0683 81.12866 8.934292 -51.12523 79.76477 8.928236 -48.45111 81.33589 8.742899 -50.775 79.37127 8.742441 -49.38154 78.64169 8.78565 -19.51332 21.85709 16.5 -19.48529 22.79273 21.5 -19.71229 23.68442 16.5 -20.1843 24.49277 21.5 -20.50107 24.75081 16.5 -21.61542 25.39684 16.5 -21.74398 25.43302 21.5 -23.43656 25.408 16.5 -23.58057 25.35762 21.5 -24.75081 24.49893 16.5 -24.81187 24.42798 21.5 -25.39684 23.38458 16.5 -25.43302 23.25602 21.5 -25.408 21.56344 16.5 -25.35762 21.41943 21.5 -24.12564 19.91332 16.5 -23.99448 19.83539 21.5 -22.34046 19.47532 16.5 -22.20727 19.48529 21.5 -20.62532 20.0877 16.5 -20.98697 19.89758 21.5 -19.83539 21.00552 21.5 -24.15316 22.41189 16.5 -23.77364 23.48549 16.5 -21.01232 23.16406 16.5 -20.99525 21.80975 16.5 -22.0201 20.94313 16.5 -23.36659 21.08942 16.5 -21.82681 23.98357 16.5 -22.9799 24.05687 16.5 -20.85702 22.70328 21.5 -21.73398 23.96763 21.5 -23.27268 23.96413 21.5 -24.08111 22.89277 21.5 -24.01189 21.94545 21.5 -23.26603 21.03238 21.5 -21.92508 20.97566 21.5 -21.18476 21.57076 21.5 -11.96346 15.92885 16.5 -11.96346 15.92074 18.67826 -12.67732 12.83471 16.5 -12.40023 14.10259 18.90073 -12.67165 12.84545 18.68457 -12.27255 14.59442 18.8995 -14.25419 12.32411 18.9056 -12.58736 13.68027 18.9 -13.02987 13.01236 18.89656 -15.71386 11.90585 16.5 -15.70186 11.90631 18.68485 -14.9366 12.25073 18.9 -14.94354 12.25036 18.9034 -16.46882 12.61712 18.88777 -18.03654 14.07115 16.5 -18.03458 14.06735 18.66958 -17.73808 15.33428 18.9139 -17.6502 15.78281 18.89862 -17.32427 13.52777 18.90465 -17.5537 13.97966 18.9 -17.75473 14.63902 18.89785 -17.32268 17.16529 16.5 -17.32407 17.16259 18.69053 -15.81556 17.6667 18.89476 -17.30466 16.51809 18.9004 -16.84857 17.036 18.9 -16.4855 17.31426 18.9 -14.28614 18.09415 16.5 -14.2892 18.094 18.69051 -13.71785 17.43341 18.90212 -12.92358 16.8039 18.90122 -15.0634 17.74927 18.9 -14.60679 17.72174 18.9 -14.16106 17.61891 18.9 -12.8744 16.74374 18.91364 -12.25317 15.1363 18.90321 -12.25304 15.12935 18.9 -12.92023 16.79919 18.9 -16.3051 14.09566 18.89687 -13.48822 15.36016 18.89851 -13.74744 14.13428 18.89939 -12.58736 13.68027 18.9 -16.3726 15.71597 18.89865 -17.7304 15.32779 18.9 -14.78358 13.46254 18.89858 -17.5537 13.97966 18.9 -17.41264 16.31973 18.9 -14.48707 16.4612 18.89867 -15.0634 17.74927 18.9 -15.54393 16.40781 18.89984 -14.16106 17.61891 18.9 -16.4855 17.31426 18.9 -17.16049 16.7014 18.9 -13.84347 15.52679 18.6265 -13.85483 14.48163 18.62896 -14.59613 13.79917 18.62637 -15.44581 13.84294 18.62883 -16.15653 14.47321 18.6265 -16.18519 15.36841 18.62884 -15.80345 15.95554 18.62701 -14.8536 16.26943 18.62625 -14.55552 16.19059 16.7735 -15.45053 16.15647 16.77116 -16.00947 15.73454 16.77299 -16.25606 14.76501 16.77375 -15.44448 13.80941 16.7735 -14.54947 13.84353 16.77116 -13.99053 14.26547 16.77299 -13.74394 15.23497 16.77375 -15.60636 13.57329 16.50243 -14.19003 13.68158 16.50211 -13.45212 14.89186 16.50237 -13.92907 16.09418 16.50067 -15.12772 16.54812 16.50232 -16.21129 15.92266 16.50088 -16.528 14.72736 16.50231 -14.42272 13.6519 -2.98874 -13.8481 12.5265 -2.947659 -14.93752 12.28308 -2.94141 -15.8786 13.82563 -2.989515 -13.54303 14.82826 -2.988995 -12.4808 14.13231 -3.001437 -14.12279 16.1759 -2.988995 -12.40695 15.84855 -2.933669 -15.57975 16.34764 -2.988995 -15.37848 17.69768 -2.960467 -13.3114 17.06104 -3.001437 -17.14392 16.58205 -3.001437 -17.59917 14.26287 -3.003272 -16.45697 15.17174 -2.988995 -16.03697 12.47616 -2.947659 -16.51868 12.70738 0 -15.8913 13.66314 0 -16.94909 13.06002 0 -16.31405 14.0754 0 -17.29971 13.49208 0 -17.55618 13.98587 0 -16.55931 14.61251 0 -17.708 14.52119 0 -17.74895 15.0761 0 -16.5991 15.05381 0 -17.67736 15.6279 0 -16.52974 15.49143 0 -17.49616 16.154 0 -17.21276 16.63285 0 -16.24891 16.01086 0 -16.83877 17.04485 0 -16.38951 17.37314 0 -15.79942 16.39375 0 -15.88336 17.60426 0 -15.24195 16.58842 0 -15.34104 17.72877 0 -14.78476 17.74156 0 -14.65181 16.56856 0 -14.23729 17.64212 0 -13.72105 17.4345 0 -14.10869 16.33685 0 -13.25717 17.12722 0 -12.86464 16.73284 0 -13.782 16.03754 0 -12.55953 16.26753 0 -13.53844 15.6674 0 -12.35434 15.75032 0 -12.25746 15.20239 0 -13.39604 15.09435 0 -12.27286 14.64618 0 -13.47026 14.50857 0 -12.3999 14.10445 0 -12.6334 13.59939 0 -13.66875 14.11243 0 -12.96379 13.15167 0 -13.95809 13.77688 0 -13.37753 12.77962 0 -13.85771 12.49847 0 -14.4703 13.48309 0 -14.38464 12.31973 0 -14.93677 12.25073 0 -15.05403 13.39417 0 -15.49149 12.29428 0 -16.02609 12.4486 0 -15.48937 13.47668 0 -13.98751 13.84711 0.0720514 -14.09627 13.79766 5.935148 -13.60712 14.51113 5.961894 -13.51195 14.68072 0.06716728 -13.5695 15.32085 5.951858 -13.5646 15.50235 0.06881189 -13.77225 15.8844 5.850426 -14.03799 16.17949 0.06649833 -14.40251 16.35793 5.936767 -14.80139 16.50929 0.06597012 -15.25934 16.43869 5.986041 -15.62431 16.38866 0.06544977 -15.96856 16.16187 5.851049 -16.26112 15.85348 0.06494551 -16.38742 15.5016 5.946149 -16.52168 15.0634 0.06445759 -16.44221 14.66616 5.930368 -16.32812 14.25418 0.06399238 -15.91051 13.79205 5.91505 -15.4626 13.54941 0.06473731 -15.00081 13.52014 5.939349 -14.77254 13.50469 0.06312894 -14.09424 12.32968 -1.04079e-5 -12.83566 13.23845 -2.851103 -12.44053 13.81673 -1.04145e-5 -12.24757 14.6429 -2.855019 -12.27822 15.48125 -8.95631e-7 -12.83569 16.75634 -3.68975e-6 -12.85642 16.73952 -2.847527 -13.95447 17.59973 -2.858142 -14.22695 17.67794 -3.68784e-6 -16.17127 17.56499 -1.04189e-5 -16.75139 17.17257 -2.851103 -17.53 16.16964 -3.69094e-6 -17.50577 16.15845 -2.847527 -17.78964 14.9268 -2.851102 -17.7565 14.79658 -8.89509e-7 -17.18952 13.2232 -1.04118e-5 -17.1758 13.23433 -2.858141 -15.76659 12.34443 -8.96858e-7 -14.88115 16.24415 -2.875808 -13.86311 15.51915 -2.875808 -13.98197 14.27501 -2.875798 -15.12123 13.75611 -2.875862 -16.13684 14.48088 -2.875773 -16.01803 15.72499 -2.875798 -15.78093 13.81116 -1.742882 -15 15 -0.9783121 -16.43711 15.12907 -1.782641 -15.60384 16.3107 -1.783531 -14.15565 16.16816 -1.765801 -13.56476 14.85545 -1.787682 -14.38893 13.70101 -1.78942 -15.34783 13.43385 -0.008423328 -14.75859 13.41395 -0.008423089 -13.85336 13.88583 -0.003898322 -13.58828 14.23644 -0.006250441 -15.8901 13.66525 -0.008423328 -16.31396 14.08203 -0.01150023 -16.50846 14.4702 -0.003897786 -16.60156 14.90595 -0.00842154 -16.52798 15.49116 -0.006249845 -16.33184 15.8845 -0.003897607 -16.04021 16.22139 -0.008422851 -15.52874 16.51468 -0.008422911 -14.94587 16.6034 -0.008422493 -14.37032 16.47558 -0.008423328 -13.87925 16.14887 -0.00625205 -13.61457 15.79796 -0.003897428 -13.44299 15.38673 -0.00842303 -13.40843 14.79816 -0.008424282 -14.20194 13.60826 -0.008421957 -24.37738 24.25972 25.30034 -23.78589 23.20486 25.28673 -25.03772 22.42754 25.29911 -23.75399 21.73858 25.28743 -24.25972 20.62262 25.30034 -22.46664 21.03316 25.2873 -22.73116 19.99679 25.29863 -21.33368 20.24511 25.2992 -21.24601 23.26142 25.28743 -22.29471 25.06513 25.30018 -22.53241 23.9667 25.28743 -21.21404 21.79557 25.28677 -20.04487 21.72906 25.30018 -20.36664 23.93874 25.30034 -19.74627 22.75429 22.29844 -20.26723 24.1786 22.29844 -21.37143 23.84348 22.26753 -21.80094 25.20449 22.29844 -20.82141 20.26723 22.29844 -21.16259 21.39666 22.26174 -19.90864 21.5343 22.29844 -20.75238 22.63533 22.26254 -22.43144 24.22994 22.26835 -23.36068 25.12811 22.29844 -24.41574 24.49441 22.29844 -23.42902 23.96809 22.25913 -25.20449 23.19906 22.29844 -24.32523 22.76795 22.28194 -25.12811 21.63933 22.29844 -24.49441 20.58426 22.29844 -23.83969 21.35393 22.27057 -23.4657 19.90864 22.29844 -22.59409 20.74941 22.26317 -22.24572 19.74627 22.29844 -22.92966 21.04132 22.01205 -22.73307 20.99793 12.55117 -23.54062 21.39643 12.54768 -23.5558 21.37187 22.07982 -23.98966 22.13818 22.01274 -24.02733 22.37265 12.53636 -24.05542 22.49096 22.09948 -23.6843 23.45288 12.55117 -23.54842 23.60144 22.01205 -22.93541 23.95299 12.54768 -22.94305 23.96693 22.01143 -22.06852 23.97099 22.01274 -21.84662 23.88638 12.53636 -21.34994 23.50692 22.00634 -21.08263 23.0492 12.55117 -21.02192 22.85725 22.01205 -21.02397 22.15058 12.54768 -21.00808 22.15022 22.01143 -21.44183 21.39083 22.01274 -21.62606 21.24097 12.53636 -21.79528 21.35578 12.28911 -21.23809 22.73722 12.29808 -23.43273 21.57901 12.29423 -21.76116 23.52286 12.29799 -22.83124 23.76827 12.29423 -23.73863 22.83346 12.29683 -22.17155 19.75348 25.05051 -20.73708 20.33311 25.05282 -19.88296 21.60425 25.05051 -19.75348 22.82845 25.05051 -20.33311 24.26292 25.05282 -21.60425 25.11704 25.05051 -22.82845 25.24652 25.05051 -24.26292 24.6669 25.05282 -25.11704 23.39575 25.05051 -25.24652 22.17156 25.05051 -24.6669 20.73708 25.05282 -23.39575 19.88296 25.05051 -23.1249 23.58236 25.17424 -23.7498 22.5 25.17424 -23.1249 21.41765 25.17424 -21.87303 21.41883 25.17432 -21.2502 22.5 25.17424 -21.8751 23.58236 25.17424 -22.5 21.05707 24.08592 -22.5 22.5 23.27675 -21.25279 23.22515 24.08268 -22.5 23.94293 24.08592 -23.75117 21.78182 24.07153 -23.74722 23.22514 24.08267 -21.24881 21.78184 24.07153 -23.92157 23.09161 22.08353 -22.16324 20.99921 22.0458 19.04565 -12.92416 47.00064 19.21403 -14.29669 46.98818 18.19311 -14.00646 47.00008 17.98474 -15.3126 47.00064 19.24601 -15.76142 46.98899 18.71168 -16.80667 47.00108 20.53336 -16.46684 46.98886 21.75399 -14.23858 46.98899 20.88463 -12.46086 47.00196 20.46759 -13.5333 46.98899 21.78656 -15.70318 46.98891 23.00338 -15.20494 47.00008 22.68408 -13.64944 47.00214 20.45083 -17.5596 47.00115 22.38564 -16.74315 47.00214 22.1739 -12.79803 44 20.80192 -12.22383 44 20.97854 -13.33925 43.96832 19.74771 -13.32764 43.98456 19.3386 -12.48967 44 21.38318 -17.62119 44 22.40216 -17.00809 44 21.9421 -15.97204 43.97183 23.19075 -15.74709 44 17.80925 -15.74709 44 18.76067 -15.48082 43.98545 18.59784 -17.00809 44 19.45093 -16.65191 43.99952 19.89969 -17.72725 44 22.29987 -14.94225 43.98566 23.09421 -13.96638 44 21.86498 -13.91284 43.9688 18.18865 -13.43286 44 18.8668 -14.41021 43.96839 17.78623 -14.5551 44 21.06893 -16.65512 43.96658 20.09359 -16.46452 43.71369 20.48315 -16.54452 36.25202 19.50139 -16.13952 36.24933 19.50012 -16.15842 43.71302 18.96833 -15.20039 36.25197 18.97425 -14.84286 43.77379 19.23116 -14.17172 36.2493 19.28141 -14.02491 43.79007 20.63451 -13.46283 43.78032 20.09042 -13.51979 36.24318 21.14144 -13.6271 36.24926 21.28337 -13.698 43.71314 21.77753 -14.15627 43.71469 21.88604 -14.35302 36.23896 21.95619 -15.42969 36.25271 21.92968 -15.55607 43.7741 21.48751 -16.14901 36.24934 21.51246 -16.14721 43.71264 20.769 -16.51918 43.78137 20.74 -13.71343 35.99907 21.17254 -16.15562 35.99229 21.76741 -14.6845 35.99652 19.43158 -14.24876 35.99652 19.45186 -15.83016 35.99229 19.49775 -17.61002 46.75977 18.30329 -16.68714 46.74691 17.80423 -15.6355 46.75268 17.78654 -14.44485 46.75268 18.27044 -13.35681 46.75268 19.16647 -12.57251 46.75268 20.60392 -12.20616 46.75482 22.02716 -12.68917 46.7544 22.86625 -13.56025 46.74691 23.24868 -14.65967 46.75268 23.13516 -15.85328 46.7544 22.32586 -17.1179 46.74525 20.98863 -17.72622 46.75268 19.87512 -13.91766 46.87578 19.25025 -15 46.87577 19.8751 -16.08236 46.8758 21.12696 -16.08115 46.87586 21.74975 -15 46.87577 21.1249 -13.91764 46.8758 20.55019 -16.42571 45.7153 20.5 -15 44.97831 21.74451 -14.27374 45.76333 20.44649 -13.57451 45.72504 19.25549 -15.72626 45.76333 19.24852 -14.28094 45.80541 21.75148 -15.71906 45.80541 19.60006 -16.46719 43.9341 19.03683 -15.48699 43.78078 22.03922 -14.91977 43.77984 19.91195 -13.57939 43.78407 -41 -0.1942541 7.003636 -26 0.6493976 6.870015 -41 0.7266608 6.830647 -26 1.330647 6.22666 -41 1.370015 6.149397 -26 1.503636 5.305746 -41 1.490071 5.220098 -26 0.818308 4.132707 -41 1.040971 4.397713 -41 0.1565487 4.023029 -26 0 4 -26 -0.008755564 4.000042 -41 -0.6372135 4.101772 -26 -1.04097 4.397712 -41 -1.487825 5.082599 -26 -1.490071 5.220098 -26 -1.286021 6.356736 -41 -1.212206 6.458334 -26 -0.2799015 6.990071 -41 0 4 -47.14379 27.77011 -2 -30.09992 33.55859 -2 -47.14379 27.77011 0 -30.09992 33.55859 0 -55.18335 51.44215 -2 -55.18335 51.44215 0 -38.13948 57.23063 -2 -38.13948 57.23063 0 25 17.5 7 25 17.5 8.5 25 15 7 25 15 8.5 25 -17.5 8.5 25 -17.5 7 25 -15 8.5 25 -15 7 -15.50475 -13.43624 8.5 -13.89812 -13.78099 8.5 -18 -11 8.5 -18 11 8.5 -13.78099 13.89812 8.5 -15.34475 13.39337 8.5 -13.43624 15.50475 8.5 15.50475 13.43624 8.5 13.89812 13.78099 8.5 18 -11 8.5 13.78099 -13.89812 8.5 15.34475 -13.39337 8.5 -16.38564 15.8 8.5 -25 17.5 8.5 -16.56376 14.49525 8.5 -25 15 8.5 16.56376 15.50475 8.5 18 11 8.5 16.38564 14.2 8.5 16.56376 -14.49525 8.5 16.38564 -15.8 8.5 -15.50475 16.56376 8.5 13.39337 15.34475 8.5 14.49525 16.56376 8.5 15.8 16.38564 8.5 -14.2 16.38564 8.5 -13.39337 -15.34475 8.5 -14.49525 -16.56376 8.5 -25 -17.5 8.5 -15.8 -16.38564 8.5 -16.56376 -15.50475 8.5 -25 -15 8.5 -16.38564 -14.2 8.5 15.50475 -16.56376 8.5 14.2 -16.38564 8.5 13.43624 -15.50475 8.5 -13.43624 14.49525 7 -13.61436 15.8 7 13.43624 15.50475 7 -25 -17.5 7 -25 -15 7 -16.56376 -14.49525 7 16.38564 15.8 7 16.56376 14.49525 7 18 11 7 15.8 13.61436 7 14.49525 -16.56376 7 18 -11 7 15.50475 -13.43624 7 -18 -11 7 -15.8 -13.61436 7 -25 17.5 7 -16.56376 15.50475 7 -25 15 7 -18 11 7 -16.38564 14.2 7 -15.50475 13.43624 7 -16.38564 -15.8 7 -15.50475 -16.56376 7 15.8 -16.38564 7 16.56376 -15.50475 7 16.38564 -14.2 7 15.50475 16.56376 7 14.2 16.38564 7 -14.49525 16.56376 7 -15.8 16.38564 7 -14.2 -16.38564 7 13.43624 -14.49525 7 13.61436 -15.8 7 -13.43624 -15.50475 7 -13.61436 -14.2 7 14.2 -13.61436 7 -14.49525 -13.43624 7 13.61436 14.2 7 14.49525 13.43624 7 -14.2 13.61436 7 -12.32698 13.53215 7 -12.10799 14.10965 4 -11.98904 15.48346 7 -12.06696 15.83481 4 -12.92087 17.23088 7 -13.02293 17.29078 4 -14.35151 17.95566 4 -14.72951 18.03751 7 -15.60827 17.94714 4 -16.65222 17.56316 7 -16.73534 17.47893 4 -17.58025 16.54853 4 -17.76017 16.24014 7 -17.99912 15.4022 4 -18.00891 15.0453 7 -17.88684 14.15043 4 -17.69084 13.56508 7 -17.32715 13.06588 4 -16.68364 12.50582 7 -15.90534 12.08796 4 -15.27048 11.96249 7 -14.39174 12.05286 4 -13.58355 12.32603 7 -13.05732 12.64934 4 -16.48883 15.65176 4 -15.59439 16.53716 4 -16.53716 14.40561 4 -15.3233 13.35425 4 -13.79753 13.87297 4 -13.37582 15.05877 4 -13.99465 16.3425 4 -13.72719 13.95304 7 -13.38182 15.15135 7 -14.08901 16.40824 7 -15.6925 16.49553 7 -16.52359 15.56574 7 -16.54393 14.49237 7 -15.89058 13.64049 7 -14.84865 13.38182 7 17.75 -16.58771 38.5 17.74991 -16.58757 36.34135 20.5 -18.17543 38.5 18.74513 -17.16506 36.09427 20.48828 -18.17225 36.31544 21.48999 -17.61173 36.10071 20.26944 -17.74066 36.09862 20.72872 -17.74047 36.1 23.25 -16.58768 36.34086 23.25 -16.58771 38.5 22.40002 -17.06968 36.11362 23.24421 -15.56951 36.11279 23.23837 -14.7364 36.09217 23.25 -13.41229 38.5 23.23813 -14.7159 36.09572 23.24787 -13.41005 36.31869 22.45195 -13.06213 36.09784 21.41341 -12.35653 36.10894 23.10313 -14.02903 36.1021 22.75896 -13.43169 36.1 20.50014 -11.82458 36.34135 20.5 -11.82457 38.5 19.64425 -12.32624 36.11355 18.56252 -13.04651 36.09482 17.75 -13.41229 38.5 17.75862 -13.40372 36.31544 17.75683 -14.71026 36.08607 17.76201 -14.73322 36.09261 18.24104 -13.43169 36.1 17.89693 -14.02898 36.10215 17.75599 -15.57294 36.11264 21.91856 -15.62119 36.10133 19.20569 -15.86021 36.10149 19.08144 -14.37881 36.10133 18.24104 -13.43169 36.1 20.35076 -13.43314 36.1029 21.79431 -14.13979 36.10149 22.75896 -13.43169 36.1 20.64925 -16.56686 36.1029 20.72872 -17.74047 36.1 19.32605 -15.48673 36.3735 20.09829 -16.19112 36.37104 21.10297 -16.11425 36.37363 21.65032 -15.46291 36.37117 21.67395 -14.51327 36.3735 20.90172 -13.80889 36.37104 19.89704 -13.88575 36.37363 19.34968 -14.53709 36.37117 19.32605 -14.51327 38.2265 19.96132 -13.88187 38.22884 20.65107 -13.76075 38.22701 21.52835 -14.24147 38.22625 21.67395 -15.48673 38.2265 21.03869 -16.11813 38.22884 20.34894 -16.23925 38.22701 19.47165 -15.75853 38.22625 22.04937 -15.33752 38.49488 20.91206 -16.49147 38.49789 19.52363 -16.20594 38.49763 18.95063 -14.66248 38.49488 20.08794 -13.50853 38.49789 21.47638 -13.79406 38.49763 -71.3628 78.34281 17.75108 -72.27062 79.20208 17 -71.68598 79.56987 17.00281 -72.63292 78.46927 17.00264 -70.94706 79.52165 17 -70.40848 79.1714 17.00695 -70.10372 78.35475 17.00117 -70.30359 77.65042 17.00168 -71.03961 77.11576 17.00281 -71.77851 77.16397 17 -72.34113 77.53496 17.00392 -79.58805 87.64846 17.75108 -80.66968 88.29677 17.00505 -80.10789 88.78524 17 -79.42805 88.90724 17.00281 -78.47878 88.28369 17.01715 -80.8474 87.38716 17.00339 -78.36983 87.33487 17.00194 -78.82874 86.63182 17.00281 -80.20796 86.54129 17.00281 -79.53192 86.39972 17 -69.01838 94.17012 17.75107 -69.76158 95.2004 16.99954 -68.85839 95.4289 17.00281 -68.02886 94.96446 17.00281 -70.23883 94.47247 17.00232 -67.75914 94.17328 17.00096 -67.95918 93.47772 17.00168 -68.70246 92.93897 17.00329 -69.63829 93.06295 17.00281 -70.21701 93.76709 17.00259 -60.79312 84.86447 17.75108 -61.85232 85.55688 17.00168 -61.31296 86.00125 17 -60.63311 86.12326 17.00281 -59.8036 85.65882 17.00281 -62.05236 84.86135 17.00096 -59.53387 84.86759 17.00096 -59.86579 83.98675 17.01732 -60.90963 83.60552 17.00823 -61.77146 84.05662 17.00392 -85.18434 85.95542 13.59365 -84.84348 85.90007 12.81053 -84.36688 87.70511 12.40773 -83.6197 85.71815 12.01772 -83.62961 88.3207 12.0799 -84.93318 89.02523 13.67892 -84.69583 88.98977 13.02826 -82.64183 90.62826 12.00618 -83.75162 90.79182 12.42953 -84.38897 90.88694 13.3846 -72.60028 78.62107 12 -72.09072 79.38516 12 -71.41893 79.59156 12 -70.68139 79.41403 12 -70.14991 78.70935 12 -70.15578 77.9807 12 -70.63487 77.30047 12 -71.30666 77.09407 12 -72.312 77.47228 12 -80.73337 88.26295 12 -79.77874 88.89676 12 -78.93188 88.73741 12 -78.35794 87.91934 12 -78.39917 87.24282 12 -78.86013 86.60611 12 -80.14205 86.48574 12 -80.80093 87.28193 12 -70.10868 94.83531 12 -69.30281 95.40927 12 -68.36221 95.25907 12 -67.80551 94.53666 12 -67.88088 93.56491 12 -68.7644 92.92621 12 -69.67455 93.08117 12 -70.23126 93.8036 12 -61.93062 85.46968 12 -60.98381 86.11277 12 -60.13694 85.95342 12 -59.58025 85.23103 12 -59.58609 84.50238 12 -60.1487 83.77851 12 -61.34712 83.70175 12 -62.00598 84.49794 12 -57.29014 81.81844 12.03097 -56.84871 83.76372 12.06942 -55.26456 86.57273 13.22365 -55.27383 84.62198 13.76099 -55.47792 84.74938 13.0562 -56.07769 84.46833 12.38369 -56.62218 86.77326 12.04514 -56.27061 81.6688 12.81115 -55.92455 81.62413 13.5548 -65.4161 83.01782 12 -55.92395 81.59305 15.49986 -65.39339 82.97826 15.5 -68.47632 80.76795 12 -67.36724 81.23223 15.5 -66.97812 81.47185 12 -68.4763 80.76796 15.5 -69.83416 71.60041 12.85509 -69.67475 72.68141 12.04778 -69.86665 71.21743 15.49978 -69.88685 71.25559 13.68622 -73.42233 81.50059 15.5 -73.42234 81.50061 12 -74.62863 73.35604 12.03097 -74.77826 72.3365 12.81114 -74.85754 71.97034 15.49976 -74.82339 71.99657 13.54815 -75.69966 84.54274 15.5 -75.73212 84.50968 12 -74.65215 82.60858 15.5 -74.34918 82.26644 12 -85.20802 85.93344 15.49989 -74.96508 89.49513 12 -84.45723 90.91984 15.49985 -74.94646 89.48821 15.5 -71.9058 91.78975 15.5 -71.90488 91.74497 12 -73.29853 91.1177 12 -73.9915 90.59989 15.5 -70.54701 100.9125 12.85508 -70.70642 99.83153 12.04778 -70.51453 101.2955 15.49978 -70.49432 101.2573 13.68622 -67.6454 86.31581 12 -71.41182 84.02262 12 -69.34767 83.8542 12 -68.08036 84.91596 12 -72.72045 85.80925 12.00008 -72.21413 87.78151 12 -70.51565 88.78151 12 -66.95883 91.01234 12 -65.93171 90.14951 12 -68.5316 88.1876 12 -64.65122 87.97528 12 -66.95884 91.01235 15.5 -65.75254 99.15691 12.03097 -65.60292 100.1764 12.81114 -65.52363 100.5426 15.49976 -65.55778 100.5164 13.54815 -65.84714 90.05735 15.5 -64.67353 87.98828 15.5 -55.17252 86.56951 15.49989 -62.71386 73.2228 15.5 -59.75588 75.44467 15.5 -65.91654 71.84894 15.5 -57.31553 78.50552 15.5 -72.68336 72.91461 12.06942 -71.97869 72.14357 12.38369 -72.00296 71.43935 13.29583 -84.15701 80.70818 15.5 -84.92195 83.43034 15.5 -78.55003 73.77056 15.5 -81.20286 76.03031 15.5 -82.90099 78.29119 15.5 -79.21488 98.27064 15.5 -75.79833 100.1817 15.5 -73.51087 100.8844 15.5 -81.8769 95.70147 15.5 -83.47013 93.23168 15.5 -67.69786 99.59835 12.06942 -68.40249 100.3694 12.38369 -68.37815 101.0736 13.29583 -56.59629 92.59642 15.5 -55.55956 89.6168 15.5 -62.7724 99.29375 15.5 -60.52097 97.76052 15.5 -57.87952 94.87132 15.5 -55.68049 82.35944 23.69962 -62.52571 73.32997 23.7 -59.59961 75.59458 23.7 -70.03987 71.24467 23.69991 -73.33608 71.56228 23.70003 -76.80168 72.76409 23.7 -79.1573 74.23157 23.7 -85.0904 88.47917 23.70012 -57.43043 78.32196 23.7 -66.12516 71.79099 23.7 -81.34743 76.19154 23.7 -83.46854 79.22268 23.7 -85.03562 83.64649 23.7 -76.33076 99.97873 23.7 -79.38841 98.14111 23.7 -82.01352 95.53347 23.7 -68.83976 101.2231 23.70004 -66.2969 100.7379 23.69982 -64.43369 100.1078 23.7 -58.89893 96.14875 23.7 -57.4802 94.22178 23.7 -56.08453 91.39242 23.7 -55.22227 85.32372 23.69992 -83.83049 92.55973 23.7 -72.44417 101.1124 23.7 -61.83116 98.7424 23.7 -55.26721 88.00888 23.7 -72.65818 97.0026 23.7 -74.76519 96.26012 23.7 -77.08295 94.85151 23.7 -79.24023 92.54004 23.7 -62.3494 94.011 23.7 -65.14202 96.04888 23.7 -67.93248 97.04856 23.7 -70.15686 97.25642 23.7 -59.41306 88.58312 23.7 -60.51768 91.5483 23.7 -59.79568 82.58367 23.7 -59.19773 85.42449 23.7 -67.52967 75.56541 23.7 -65.61598 76.25283 23.7 -63.45075 77.53047 23.7 -61.30491 79.72488 23.7 -75.42082 76.55014 23.7 -73.34709 75.71909 23.7 -70.87673 75.25204 23.7 -81.10083 84.85411 23.7 -80.44287 82.22286 23.7 -78.87507 79.47716 23.7 -77.46871 78.00852 23.7 -80.64387 89.73347 23.7 -81.18772 87.00169 23.7 -59.21352 85.2563 25.9 -59.85721 82.4082 25.9 -61.41792 79.57749 25.9 -63.59733 77.41645 25.9 -66.47087 75.87707 25.9 -68.64553 75.36553 25.9 -71.06212 75.26296 25.9 -74.42046 76.08359 25.9 -76.20987 77.04951 25.9 -78.15968 78.63664 25.9 -79.51153 80.41525 25.9 -80.67319 82.86614 25.9 -81.20295 85.9591 25.9 -81.07186 87.86827 25.9 -80.4085 90.37378 25.9 -78.83334 93.08892 25.9 -76.53694 95.26221 25.9 -73.71781 96.69381 25.9 -71.73564 97.14742 25.9 -69.02414 97.21178 25.9 -67.03414 96.79387 25.9 -64.54476 95.71712 25.9 -62.22151 93.87633 25.9 -60.42799 91.38568 25.9 -59.37324 88.40172 25.9 -72.11896 87.88617 25.9 -70.96258 88.65822 25.9 -69.62197 88.70639 25.9 -68.53648 88.13102 25.9 -67.91014 87.33534 25.9 -67.68415 85.99391 25.9 -68.18375 84.74054 25.9 -69.33315 83.89211 25.9 -70.5569 83.78345 25.9 -71.43161 84.06894 25.9 -72.4228 85.09775 25.9 -72.69436 86.6119 25.9 -67.72258 85.77355 35.2 -68.39012 84.50042 35.2 -69.637 83.80311 35.2 -70.97728 83.85949 35.2 -71.8447 84.38193 35.2 -72.55068 85.38736 35.2 -72.61386 87.05741 35.2 -69.31867 88.61553 35.2 -70.54173 88.73168 35.2 -71.41819 88.45156 35.2 -68.1745 87.76008 35.2 -67.78237 86.92768 35.2 -72.64319 85.52459 15.50049 -72.36169 87.57453 15.50041 -70.71181 88.74842 15.5 -68.68745 88.31124 15.5 -67.65781 86.51437 15.5 -68.08036 84.91596 15.5 -69.16267 83.92734 15.5 -71.23367 83.93409 15.5 -12.06665 15.75473 8.5 -12.41261 16.62451 13.5 -12.68728 16.92697 8.5 -13.91817 17.85714 8.5 -14.06215 17.90759 13.5 -16.0078 17.88409 8.5 -15.88331 17.89723 13.5 -16.99795 17.25168 13.5 -17.46368 16.76195 8.5 -17.90759 15.93785 13.5 -18.05484 15.03939 8.5 -17.83018 13.84947 13.5 -17.6122 13.50391 8.5 -16.76195 12.53632 8.5 -16.87054 12.64141 13.5 -15.4187 11.97373 13.5 -15.29406 11.98542 8.5 -13.98024 12.16769 8.5 -13.89267 12.20077 13.5 -12.87971 12.837 8.5 -12.58852 13.12426 13.5 -12.08228 14.18694 8.5 -11.97539 14.83913 13.5 -16.55142 14.50274 8.5 -16.42017 15.85078 8.5 -13.44859 15.49726 8.5 -13.509 14.34343 8.5 -14.02881 16.28457 8.5 -15.67339 13.48763 8.5 -14.31936 13.51983 8.5 -15.10657 16.65208 8.5 -13.39807 15.41776 13.5 -14.08551 16.32554 13.5 -15.22162 16.64061 13.5 -16.47609 15.74958 13.5 -16.45541 14.21101 13.5 -15.37509 13.41461 13.5 -14.22945 13.56459 13.5 -13.5739 14.25195 13.5 52.89406 71.59523 12.95167 52.87049 70.41548 13.00353 53.63994 71.89987 12.92653 54.88791 71.2918 13.00118 54.27189 72.39526 12.95314 55.5046 72.7633 13.00015 54.25337 73.76119 12.9883 55.07243 74.55309 13.00358 52.96747 74.46605 12.9883 53.10593 75.54683 13.00127 51.34098 74.93146 13.00105 51.71411 73.70486 12.9883 50.46484 73.26564 13.00127 51.74663 72.23882 12.9883 50.96819 71.46553 13.00105 54.629 70.75788 9.999999 54.12861 71.67361 9.963526 55.6696 72.13259 9.999991 54.70057 72.73352 9.969599 55.63578 73.85641 9.999999 54.64077 73.55191 9.971602 54.6499 75.27091 9.999992 54.10673 74.43341 9.977449 53 75.77143 9.999999 52.76719 74.79668 9.985197 51.66484 75.42861 9.999999 50.66002 74.48502 9.999999 51.88472 74.31682 9.968184 50.23405 73.17403 9.999999 51.32936 73.54012 9.965358 50.49235 71.81999 9.999999 51.57644 71.80355 9.981778 51.64773 70.54022 9.999992 53.34736 70.25044 9.999999 53.0595 71.26815 9.968522 52.65761 71.48826 9.781834 52.77244 71.49758 -3.750085 51.87406 71.97138 -3.746064 51.54281 72.49276 9.781169 51.48285 72.89361 -3.751035 51.47411 73.25943 9.773597 51.73564 73.84504 -3.750928 51.95606 74.12834 9.711534 52.51816 74.44227 -3.750854 53.48581 74.47245 9.781703 53.47722 74.43903 -3.753787 54.25663 73.89733 9.737279 54.24474 73.8695 -3.750474 54.52169 72.95575 -3.74615 54.53359 72.90841 9.708405 54.24026 72.28168 -3.910141 54.17999 72.00824 9.750432 53.74077 71.67359 -3.750499 53.49154 71.56137 9.71047 51.9814 72.15006 -4.001885 53.36584 71.76394 -4.002416 54.20163 73.46666 -4.002416 53.26657 74.2612 -4.002416 51.92984 73.776 -4.006337 51.85267 70.4333 12.75534 50.40042 71.92815 12.76029 50.3764 74.01193 12.74421 51.76703 75.52716 12.76029 53.85981 75.67793 12.74916 55.23636 74.64563 12.74603 55.81093 73.05473 12.75534 55.08653 71.11567 12.75534 53.56754 70.28233 12.75372 52.3751 74.08236 12.8758 51.7502 73.00001 12.8758 53.6249 74.08236 12.8758 51.76139 72.26679 11.77999 53 73 10.97831 53.02218 71.56242 11.74896 51.74308 73.68522 11.75395 52.96492 74.43112 11.75392 54.23364 73.73917 11.75578 54.25433 72.29145 11.78046 51.94915 71.87489 9.789763 52.68131 74.50373 9.785609 53.10593 -71.59523 12.95167 53.12951 -70.41548 13.00353 52.36005 -71.89987 12.92653 51.1121 -71.2918 13.00118 51.72811 -72.39526 12.95314 50.4954 -72.7633 13.00015 51.74663 -73.76119 12.9883 50.92757 -74.55309 13.00358 53.03252 -74.46605 12.9883 52.89407 -75.54683 13.00127 54.90909 -74.74745 13.00324 54.28589 -73.70486 12.9883 55.52441 -72.64086 13.00088 54.25337 -72.23882 12.9883 54.77887 -71.22106 13.00015 50.3304 -72.13258 9.999991 51.24408 -72.82872 9.965066 50.46016 -74.19515 9.999992 51.89143 -74.46083 9.983746 51.66484 -75.42861 9.999999 53 -75.77143 9.999999 53.71782 -74.59996 9.964968 54.33516 -75.42861 9.999999 55.33998 -74.48502 9.999999 54.68906 -73.49087 9.966698 55.76595 -73.17403 9.999999 55.50765 -71.81999 9.999999 54.54415 -72.20535 9.968204 54.62899 -70.75787 9.999999 53.27133 -71.06793 9.999559 53.34736 -70.25044 9.999999 51.64773 -70.54022 9.999992 51.76005 -71.67112 9.980438 53.34239 -71.48826 9.781834 53.22756 -71.49758 -3.750085 54.12594 -71.97138 -3.746064 54.40917 -72.41645 9.715975 54.51715 -72.89361 -3.751035 54.51972 -73.08559 9.712512 54.26436 -73.84504 -3.750929 54.28038 -73.85089 9.711318 53.48183 -74.44227 -3.750853 53.50217 -74.45268 9.710549 52.49512 -74.48058 9.824409 52.52278 -74.43903 -3.753787 51.72057 -73.87393 9.77985 51.75526 -73.8695 -3.750473 51.47831 -72.95575 -3.746149 51.49771 -73.32581 9.793117 51.53042 -72.55033 9.712489 51.96402 -71.82178 -3.735584 52.50846 -71.56137 9.710469 54.01496 -72.15309 -4.006336 51.74335 -72.85755 -4.000118 52.42816 -71.80819 -4.006336 52.01499 -73.83153 -4.002416 53.36788 -74.26968 -4.006335 54.21553 -73.3472 -4.000673 54.14733 -70.4333 12.75534 55.59959 -71.92815 12.76029 55.6236 -74.01193 12.74421 54.23297 -75.52716 12.76029 52.14019 -75.67793 12.74916 50.76364 -74.64564 12.74603 50.18907 -73.05473 12.75534 50.91347 -71.11567 12.75534 52.43246 -70.28233 12.75372 53.6249 -74.08236 12.8758 54.2498 -73.00001 12.8758 52.3751 -74.08236 12.8758 54.2386 -72.26679 11.77999 53 -73 10.97831 52.97782 -71.56242 11.74896 54.25691 -73.68523 11.75395 53.03508 -74.43112 11.75392 51.76636 -73.73917 11.75578 51.74567 -72.29145 11.78046 53.32299 -71.27897 9.93651 54.05085 -71.87489 9.789763 51.95592 -71.86952 9.788521 50.06879 74.43994 8 50.02516 74.3475 9 49.70158 72.54202 8 49.72175 72.69941 9 50.48106 70.88052 9 50.62673 70.75778 8 51.98116 69.86963 8 52.14334 69.82141 9 54.27013 69.92168 8 54.4471 70.0008 9 55.93999 71.51887 8 55.82658 71.36585 9 56.29184 72.96741 9 56.26126 73.15541 8 55.6617 75.00117 8 55.88198 74.53433 9 54.76893 75.77636 9 53.9869 76.11224 8 52.51712 76.29487 9 52.37165 76.23149 8 50.88085 75.48379 8 50.79226 75.40538 9 51.37402 73.54611 8 51.92741 74.33851 8 51.33689 72.58036 8 53.17869 71.29409 8 51.98667 71.58211 8 53.08588 74.74066 8 54.0726 71.6615 8 54.66311 73.41966 8 54.62598 72.45389 8 54.17221 74.25219 8 48.69403 75.57157 9 49.31264 76.44064 11.5 49.7623 76.83037 9 51.04471 77.61858 11.5 51.18146 77.67411 9 52.65028 78.00321 11.5 53.24435 78.03736 9 54.29375 77.84568 11.5 55.61243 77.31391 9 55.79706 77.16304 11.5 57.24055 75.7299 11.5 57.35075 75.55061 9 57.95724 73.76168 11.5 57.97751 73.61547 9 57.93596 72.11079 11.5 57.90766 71.96592 9 57.37979 70.55626 11.5 57.30597 70.42844 9 56.07077 68.99938 11.5 56.2377 69.16963 9 54.81853 68.32589 9 54.16845 68.12259 11.5 53.20236 67.98867 9 52.1364 68.03122 11.5 51.5642 68.1945 9 50.20294 68.83697 11.5 50.08165 68.92108 9 48.75944 70.27011 11.5 48.91534 70.08969 9 48.0568 72.00028 9 48.04276 72.23832 11.5 48.1195 74.27096 11.5 48.09234 74.03409 9 55.67858 71.48204 11.5 50.07961 72.02516 11.5 55.27139 75.07842 11.5 53.63666 75.94674 11.5 51.49116 70.35932 11.5 53.66426 69.99372 11.5 55.99925 73.30507 11.5 52.04717 75.88825 11.5 50.32142 74.51797 11.5 55.58237 71.32358 10 56.00858 73.19248 10 55.39237 74.93794 10 53.74662 75.92082 10 52.20199 75.93479 10 50.41764 74.67643 10 50.02623 72.2027 10 51.35296 70.44324 10 53.4821 69.95919 10 53.97735 71.55707 10 54.65204 72.53868 10 52.7785 71.29913 10 54.63919 73.50507 10 54.10591 74.31112 10 51.89409 71.68889 10 51.85964 74.28127 10 51.34796 73.46132 10 52.9579 74.74227 10 51.3608 72.49495 10 55.86083 -71.37966 8 55.78458 -71.24433 9 54.67834 -70.19944 8 54.26598 -69.96116 9 53.13416 -69.71073 8 52.65977 -69.75282 9 51.23107 -70.22364 8 51.09076 -70.3182 9 49.96208 -71.73181 8 49.90093 -71.88957 9 49.8292 -74.01752 8 49.89378 -74.2003 9 51.5529 -75.99921 8 51.72987 -76.07833 9 53.55075 -76.21819 8 53.66696 -76.19612 9 55.04073 -75.58316 8 55.44559 -75.26019 9 56.26618 -73.64916 8 56.28937 -73.13178 9 54.60232 -72.31455 8 54.6392 -73.50507 8 53.73321 -71.44937 8 51.3608 -72.49494 8 51.89408 -71.6889 8 52.77851 -71.29913 8 54.10592 -74.31111 8 51.34796 -73.46133 8 51.85964 -74.28127 8 52.95789 -74.74227 8 57.37979 -70.55626 9 57.90766 -71.96593 11.5 57.93597 -72.11079 9 57.9432 -73.99972 11.5 57.89719 -74.20508 9 57.08466 -75.91033 11.5 56.99725 -76.02927 9 55.61243 -77.31391 11.5 55.79706 -77.16304 9 54.29376 -77.84568 9 53.62529 -77.97629 11.5 52.20344 -77.97998 9 51.9756 -77.90969 11.5 50.0988 -77.12525 11.5 50.31114 -77.23373 9 49.08216 -76.13129 9 48.69403 -75.57157 11.5 48.1195 -74.27096 9 48.09234 -74.03408 11.5 48.0568 -72.00029 11.5 48.10282 -71.79492 9 48.91534 -70.08969 11.5 49.00274 -69.97076 9 50.08166 -68.92108 11.5 50.20294 -68.83697 9 51.5642 -68.1945 11.5 51.70624 -68.15433 9 53.20236 -67.98867 11.5 53.34974 -67.9968 9 54.81853 -68.32589 11.5 54.95529 -68.38143 9 56.2377 -69.16963 11.5 56.34901 -69.26657 9 57.30598 -70.42844 11.5 49.99787 -72.51317 11.5 50.17324 -74.04786 11.5 51.07732 -75.35651 11.5 55.54713 -71.38732 11.5 54.39069 -70.29524 11.5 52.20361 -70.02599 11.5 53.16065 -76.07461 11.5 55.14262 -75.15847 11.5 50.67914 -71.07589 11.5 56.07456 -73.16161 11.5 50.13596 -73.94122 10 50.9548 -75.25099 10 52.9753 -76.07871 10 55.27139 -75.07841 10 55.99925 -73.30508 10 55.78394 -71.77547 10 54.53247 -70.37297 10 52.98985 -69.98529 10 51.49116 -70.35932 10 50.07961 -72.02516 10 51.33689 -72.58036 10 51.37402 -73.54611 10 51.92741 -74.33851 10 51.82779 -71.74781 10 53.08587 -74.74066 10 52.69087 -71.31285 10 54.66311 -73.41966 10 54.54769 -72.19879 10 54.17221 -74.25219 10 53.65206 -71.41354 10 -50.06879 -74.43994 8 -50.02516 -74.3475 9 -49.70158 -72.54202 8 -49.72175 -72.69941 9 -50.48106 -70.88052 9 -50.62673 -70.75778 8 -51.98116 -69.86963 8 -52.14334 -69.82141 9 -54.27013 -69.92168 8 -54.4471 -70.0008 9 -55.93999 -71.51887 8 -55.82658 -71.36585 9 -56.29184 -72.96741 9 -56.26126 -73.15541 8 -55.6617 -75.00117 8 -55.88198 -74.53433 9 -54.76893 -75.77636 9 -53.9869 -76.11224 8 -52.51712 -76.29487 9 -52.37165 -76.23149 8 -50.88085 -75.48379 8 -50.79226 -75.40538 9 -51.37402 -73.54611 8 -51.92741 -74.33851 8 -51.33689 -72.58036 8 -53.17869 -71.29409 8 -51.98667 -71.58211 8 -53.08588 -74.74066 8 -54.0726 -71.6615 8 -54.66311 -73.41966 8 -54.62598 -72.45389 8 -54.17221 -74.25219 8 -48.69403 -75.57157 9 -49.31264 -76.44064 11.5 -49.7623 -76.83037 9 -51.04471 -77.61858 11.5 -51.18146 -77.67411 9 -52.65028 -78.00321 11.5 -53.24435 -78.03736 9 -54.29375 -77.84568 11.5 -55.61243 -77.31391 9 -55.79706 -77.16304 11.5 -57.24055 -75.7299 11.5 -57.35075 -75.55061 9 -57.95724 -73.76168 11.5 -57.97751 -73.61547 9 -57.93596 -72.11079 11.5 -57.90766 -71.96592 9 -57.37979 -70.55626 11.5 -57.30597 -70.42844 9 -56.07077 -68.99938 11.5 -56.2377 -69.16963 9 -54.81853 -68.32589 9 -54.16845 -68.12259 11.5 -53.20236 -67.98867 9 -52.1364 -68.03122 11.5 -51.5642 -68.1945 9 -50.20294 -68.83697 11.5 -50.08165 -68.92108 9 -48.75944 -70.27011 11.5 -48.91534 -70.08969 9 -48.0568 -72.00028 9 -48.04276 -72.23832 11.5 -48.1195 -74.27096 11.5 -48.09234 -74.03409 9 -55.67858 -71.48204 11.5 -50.07961 -72.02516 11.5 -55.27139 -75.07842 11.5 -53.63666 -75.94674 11.5 -51.49116 -70.35932 11.5 -53.66426 -69.99372 11.5 -55.99925 -73.30507 11.5 -52.04717 -75.88825 11.5 -50.32142 -74.51797 11.5 -55.58237 -71.32358 10 -56.00858 -73.19248 10 -55.39237 -74.93794 10 -53.74662 -75.92082 10 -52.20199 -75.93479 10 -50.41764 -74.67643 10 -50.02623 -72.2027 10 -51.35296 -70.44324 10 -53.4821 -69.95919 10 -53.97735 -71.55707 10 -54.65204 -72.53868 10 -52.7785 -71.29913 10 -54.63919 -73.50507 10 -54.10591 -74.31112 10 -51.89409 -71.68889 10 -51.85964 -74.28127 10 -51.34796 -73.46132 10 -52.9579 -74.74227 10 -51.3608 -72.49495 10 -52.89406 -71.59523 12.95167 -52.87049 -70.41548 13.00353 -53.63994 -71.89987 12.92653 -54.88791 -71.2918 13.00118 -54.27189 -72.39526 12.95314 -55.5046 -72.7633 13.00015 -54.25337 -73.76119 12.9883 -55.07243 -74.55309 13.00358 -52.96747 -74.46605 12.9883 -53.10593 -75.54683 13.00127 -51.34098 -74.93146 13.00105 -51.71411 -73.70486 12.9883 -50.46484 -73.26564 13.00127 -51.74663 -72.23882 12.9883 -50.96819 -71.46553 13.00105 -54.629 -70.75788 9.999999 -54.12861 -71.67361 9.963526 -55.6696 -72.13259 9.999991 -54.70057 -72.73352 9.969599 -55.63578 -73.85641 9.999999 -54.64077 -73.55191 9.971602 -54.6499 -75.27091 9.999992 -54.10673 -74.43341 9.977449 -53 -75.77143 9.999999 -52.76719 -74.79668 9.985197 -51.66484 -75.42861 9.999999 -50.66002 -74.48502 9.999999 -51.88472 -74.31682 9.968184 -50.23405 -73.17403 9.999999 -51.32936 -73.54012 9.965358 -50.49235 -71.81999 9.999999 -51.57644 -71.80355 9.981778 -51.64773 -70.54022 9.999992 -53.34736 -70.25044 9.999999 -53.0595 -71.26815 9.968522 -52.65761 -71.48826 9.781834 -52.77244 -71.49758 -3.750085 -51.87406 -71.97138 -3.746064 -51.54281 -72.49276 9.781169 -51.48285 -72.89361 -3.751035 -51.47411 -73.25943 9.773597 -51.73564 -73.84504 -3.750928 -51.95606 -74.12834 9.711534 -52.51816 -74.44227 -3.750854 -53.48581 -74.47245 9.781703 -53.47722 -74.43903 -3.753787 -54.25663 -73.89733 9.737279 -54.24474 -73.8695 -3.750474 -54.52169 -72.95575 -3.74615 -54.53359 -72.90841 9.708405 -54.24026 -72.28168 -3.910141 -54.17999 -72.00824 9.750432 -53.74077 -71.67359 -3.750499 -53.49154 -71.56137 9.71047 -51.9814 -72.15006 -4.001885 -53.36584 -71.76394 -4.002416 -54.20163 -73.46666 -4.002416 -53.26657 -74.2612 -4.002416 -51.92984 -73.776 -4.006337 -51.85267 -70.4333 12.75534 -50.40042 -71.92815 12.76029 -50.3764 -74.01193 12.74421 -51.76703 -75.52716 12.76029 -53.85981 -75.67793 12.74916 -55.23636 -74.64563 12.74603 -55.81093 -73.05473 12.75534 -55.08653 -71.11567 12.75534 -53.56754 -70.28233 12.75372 -52.3751 -74.08236 12.8758 -51.7502 -73.00001 12.8758 -53.6249 -74.08236 12.8758 -51.76139 -72.26679 11.77999 -53 -73 10.97831 -53.02218 -71.56242 11.74896 -51.74308 -73.68522 11.75395 -52.96492 -74.43112 11.75392 -54.23364 -73.73917 11.75578 -54.25433 -72.29145 11.78046 -51.94915 -71.87489 9.789763 -52.68131 -74.50373 9.785609 -53.78723 -64.23677 0 -53.78713 -64.23693 -2.158656 -56.53709 -62.64907 -2.158651 -56.53723 -62.64906 0 -54.78233 -63.65945 -2.405725 -55.66105 -63.16161 -2.387336 -57.5591 -63.21575 -2.396921 -59.28723 -64.23681 -2.159142 -59.28723 -64.23677 0 -58.16403 -63.59912 -2.412847 -58.19782 -63.63251 -2.41388 -59.28144 -65.25495 -2.387208 -59.27492 -66.09992 -2.404691 -59.28723 -67.4122 0 -59.27958 -67.42076 -2.194079 -58.148 -68.05502 -2.404339 -59.18479 -66.56806 -2.4 -58.92913 -67.20427 -2.403158 -58.50496 -67.74556 -2.4 -56.53734 -68.99991 -2.158652 -56.53723 -68.99991 0 -57.4134 -68.48737 -2.387335 -55.51536 -68.43322 -2.396915 -53.78723 -67.4122 0 -53.79584 -67.42076 -2.184565 -53.8451 -66.44667 -2.413419 -53.80014 -66.10416 -2.404341 -54.71093 -67.8873 -2.394969 -54.14645 -67.2059 -2.402906 -53.79322 -65.25154 -2.387359 -57.95579 -65.20331 -2.398667 -55.24292 -64.96428 -2.398513 -55.11867 -66.44568 -2.398667 -54.27827 -67.3928 -2.4 -54.56949 -67.74556 -2.4 -56.38799 -67.39134 -2.397096 -53.88966 -66.56806 -2.4 -54.04955 -66.99665 -2.4 -57.83153 -66.68471 -2.398513 -58.79618 -67.3928 -2.4 -59.0249 -66.99665 -2.4 -59.18479 -66.56806 -2.4 -58.50496 -67.74556 -2.4 -56.68647 -64.25762 -2.397096 -54.91516 -68.04517 -2.4 -55.36328 -65.33777 -2.1265 -56.1355 -64.63338 -2.128956 -57.1402 -64.71025 -2.126378 -57.68755 -65.36158 -2.128828 -57.71117 -66.31123 -2.126501 -56.93894 -67.0156 -2.128958 -55.93427 -66.93874 -2.126374 -55.3869 -66.28738 -2.128827 -55.36328 -66.31123 -0.2734995 -55.99854 -66.94261 -0.2711588 -56.6883 -67.06375 -0.2729892 -57.56558 -66.58303 -0.2737491 -57.71118 -65.33777 -0.2734987 -57.07592 -64.70636 -0.271159 -56.38615 -64.58524 -0.2729915 -55.50888 -65.06594 -0.2737509 -58.06783 -65.86171 -6.71589e-4 -57.58251 -64.67543 -0.002317667 -56.38615 -64.30934 -8.75127e-4 -55.29589 -64.89273 -0.002307295 -55.08019 -66.35383 -0.002432227 -56.12517 -67.31596 -0.00210607 -57.51362 -67.03042 -0.002366304 -40.13159 -14.67648 -2.98874 -40.70434 -13.62328 -3.001437 -38.73971 -13.38359 -2.945321 -38.66985 -14.7909 -2.989515 -40.96274 -15.88762 -2.988995 -42.05238 -15.23542 -3.001437 -40.3287 -17.21058 -2.988995 -41.90208 -17.30671 -2.944126 -38.86595 -17.32296 -2.988995 -39.60041 -18.66255 -3.001437 -41.0561 -18.24501 -2.927002 -37.59411 -17.96318 -2.94434 -36.78931 -15.84498 -2.956768 -38.03726 -16.11238 -2.988995 -36.98667 -17.06219 -2.947659 -37.59647 -14.03399 -2.940221 -38.07575 -13.64755 0 -38.66377 -14.62802 0 -37.63136 -13.9824 0 -38.32518 -14.91382 0 -37.26347 -14.39986 0 -38.06676 -15.27375 0 -36.98715 -14.88282 0 -36.8137 -15.41152 0 -37.92934 -15.69498 0 -36.75023 -15.96432 0 -37.89912 -16.13703 0 -36.79933 -16.51857 0 -36.95901 -17.0516 0 -38.05672 -16.70608 0 -37.2227 -17.54157 0 -37.57964 -17.96843 0 -38.31005 -17.06959 0 -38.01519 -18.3147 0 -38.64459 -17.36011 0 -38.51153 -18.56621 0 -39.19369 -17.57727 0 -39.04833 -18.71266 0 -39.60364 -18.74805 0 -39.63645 -17.59417 0 -40.15469 -18.67093 0 -40.06991 -17.50227 0 -40.67895 -18.48447 0 -41.15493 -18.19629 0 -40.45523 -17.28356 0 -41.56317 -17.8182 0 -40.77537 -16.97725 0 -41.88693 -17.36567 0 -42.11298 -16.85723 0 -40.98786 -16.58844 0 -42.23205 -16.31369 0 -41.0988 -16.15946 0 -42.23927 -15.75731 0 -41.04845 -15.57115 0 -42.13434 -15.21087 0 -41.92156 -14.69673 0 -40.86622 -15.16727 0 -41.60965 -14.23595 0 -40.59075 -14.82022 0 -41.21136 -13.84739 0 -40.74302 -13.54696 0 -40.09091 -14.50587 0 -40.22378 -13.34696 0 -39.67491 -13.25557 0 -39.51128 -14.3933 0 -39.11888 -13.27654 0 -38.57845 -13.40901 0 -39.07294 -14.45805 0 -40.55853 -14.88923 0.07205384 -40.45185 -14.83539 5.935148 -40.91159 -15.56815 5.961895 -40.9998 -15.74148 0.06716579 -40.91628 -16.37873 5.951858 -40.9138 -16.56028 0.06881308 -40.69079 -16.93357 5.850426 -40.41328 -17.21761 0.06649893 -40.04181 -17.38109 5.936767 -39.63711 -17.51612 0.0659691 -39.23817 -17.43466 5.98368 -38.81976 -17.36214 0.06545126 -38.49833 -17.09041 5.930177 -38.20524 -16.80152 0.064947 -38.05984 -16.33296 5.948991 -37.97701 -16.00152 0.064462 -38.03813 -15.61279 5.85148 -38.20329 -15.20082 0.06399357 -38.3973 -15.05454 5.962274 -38.80849 -14.65227 5.850342 -39.09675 -14.5318 0.06473433 -39.55935 -14.52133 5.939351 -40.51354 -13.3687 -1.0394e-5 -41.00114 -13.65982 -2.84589 -42.10545 -14.92173 -1.03761e-5 -42.02502 -14.81183 -2.851102 -42.26137 -16.18324 -2.850361 -42.19997 -16.59146 -8.81425e-7 -41.41604 -18.06878 -1.03777e-5 -40.02895 -18.71643 -2.85036 -39.88307 -18.73733 -8.93085e-7 -38.63871 -18.65436 -2.851103 -38.49813 -18.601 -3.67795e-6 -37.017 -17.33633 -1.03979e-5 -36.75405 -15.68469 -8.89505e-7 -36.92011 -14.99854 -2.85036 -37.3845 -14.13568 -1.04107e-5 -38.84197 -13.31547 -9.01939e-7 -39.80851 -13.2498 -2.850359 -39.56818 -17.24796 -2.875808 -40.61485 -16.56492 -2.875808 -40.54665 -15.31698 -2.875799 -39.42943 -14.75221 -2.875863 -38.3852 -15.4351 -2.875774 -38.45335 -16.68302 -2.875799 -38.76804 -14.7804 -1.742881 -39.5 -16 -0.9783121 -38.05884 -16.07056 -1.782641 -38.84339 -17.28507 -1.783531 -40.29618 -17.20151 -1.765801 -40.93992 -15.9139 -1.787682 -40.16336 -14.72692 -1.78942 -39.21611 -14.421 -0.008422791 -39.64255 -14.41893 -0.02759134 -40.58898 -14.82188 -0.008422136 -40.94103 -15.29483 -0.008423805 -38.66488 -14.63018 -0.008423924 -38.22444 -15.02937 -0.0115022 -38.01432 -15.40932 -0.003898799 -37.90291 -15.84099 -0.006250917 -37.9259 -16.27992 -0.003898143 -38.05897 -16.70517 -0.008424282 -38.41102 -17.17812 -0.008423924 -38.90999 -17.4926 -0.006248652 -39.33845 -17.59061 -0.003897964 -39.78411 -17.57964 -0.006251633 -40.2 -17.43741 -0.003897368 -40.5726 -17.19304 -0.008421719 -40.93115 -16.725 -0.008421182 -41.09708 -16.15901 -0.006250023 -41.0741 -15.72008 -0.003897547 -40.09001 -14.5074 -0.006249606 -47.14379 -27.77011 0 -30.09992 -33.55859 0 -47.14379 -27.77011 -2 -30.09992 -33.55859 -2 -55.18335 -51.44215 0 -55.18335 -51.44215 -2 -38.13948 -57.23063 0 -38.13948 -57.23063 -2 -46.82993 -68.39445 11.98899 -48.35518 -69.98642 12.00235 -47.25662 -69.8227 11.9908 -47.09997 -71.66467 12.0009 -46.24579 -70.86752 11.98815 -44.9996 -71.9119 12.00235 -44.81885 -70.53073 11.98903 -43.48501 -70.46352 12.00102 -44.39722 -69.12622 11.9883 -43.35418 -68.98556 12.00025 -44.0591 -67.63013 12.0009 -45.40232 -68.05846 11.98829 -45.71837 -66.92036 12.0009 -47.69288 -67.67768 12.00257 -44.87738 -66.82769 9 -45.61241 -67.72947 8.963834 -46.86296 -66.86235 9 -46.98755 -68.14035 8.968295 -48.14333 -67.95149 9 -44.19386 -71.73912 9 -44.58219 -70.69277 8.965364 -43.09445 -70.08533 9 -44.09518 -69.59187 8.96865 -43.36819 -68.11844 9 -44.41863 -68.41652 8.968361 -48.58004 -69.20223 9 -47.53442 -69.22209 8.961218 -48.38549 -70.51266 9 -47.31743 -70.36772 8.962645 -47.37468 -71.79463 9 -46.12714 -71.19867 8.965065 -45.75098 -72.22966 9 -46.70668 -70.70249 8.713486 -46.52299 -70.81532 -2.746941 -47.1853 -70.13716 -2.750908 -47.20279 -70.13814 8.712887 -47.32254 -69.21437 -2.750779 -47.34049 -69.22589 8.71177 -46.92671 -68.39408 8.713596 -46.73776 -68.2276 -2.763262 -45.60634 -67.96121 -2.750461 -45.08179 -68.10231 8.711045 -44.76844 -68.37255 -2.749783 -44.45571 -68.79161 8.716982 -44.32157 -69.2211 -2.746325 -44.30469 -69.40655 8.712418 -44.47529 -70.1593 -2.750748 -44.45002 -70.14427 8.711148 -45.09543 -70.81374 8.71326 -45.33556 -70.91842 -2.763719 -46.27173 -70.66984 -3.000453 -44.93777 -70.43528 -3.005136 -44.62557 -68.91999 -3.005136 -45.97021 -68.15481 -3.005136 -47.06241 -69.81001 -3.001961 -46.93284 -68.85742 -3.000546 -46.97269 -71.982 11.75254 -45.67045 -72.22705 11.75254 -44.10107 -71.66958 11.75555 -43.18523 -70.29896 11.75254 -43.14996 -68.63389 11.75555 -44.10676 -67.29154 11.75254 -45.31252 -66.74198 11.75253 -46.63558 -66.81571 11.75254 -48.02594 -67.73255 11.75555 -48.58715 -69.2825 11.75254 -48.22292 -70.90763 11.75555 -46.08427 -68.24029 11.87579 -47.01309 -69.07651 11.8758 -46.75331 -70.29901 11.8758 -45.56237 -70.68479 11.87587 -44.63587 -69.84904 11.8758 -44.89566 -68.62655 11.8758 -46.74427 -68.37021 10.73433 -45.82448 -69.46278 9.978313 -47.01279 -69.0759 10.67698 -47.21092 -69.80581 10.73447 -46.25023 -70.83586 10.76476 -45.36088 -68.10157 10.77152 -44.41305 -69.18669 10.75803 -44.86112 -70.53704 10.80094 -46.16846 -67.96224 8.7429 -45.94527 -70.9971 8.742444 -70.75352 -93.52175 1.011005 -70.78395 -92.00127 0.9974345 -69.48007 -92.74692 1.009202 -68.6983 -91.7972 0.9990947 -68.21315 -93.45987 1.01185 -67.49253 -92.66188 0.9997467 -66.9246 -94.0802 0.999095 -68.17721 -94.92558 1.010974 -67.30558 -95.51422 0.999696 -68.43027 -96.54819 0.999095 -69.42895 -95.68947 1.011705 -70.33092 -96.75975 1.066193 -70.79048 -96.3958 0.9990949 -70.71664 -94.98789 1.011704 -71.89768 -94.97068 0.9990948 -71.871 -93.48712 0.9997467 -71.93119 -95.48047 4 -71.21001 -94.23984 4.031361 -72.23285 -94.19052 4 -71.90051 -92.90811 4 -66.78586 -94.9179 4 -67.67744 -93.96344 4.015468 -68.40052 -95.62545 4.028554 -67.61428 -96.32465 4 -69.16436 -96.97497 4 -69.76446 -95.94593 4.035564 -70.77347 -96.69921 4 -70.80758 -95.32134 4.031349 -70.93649 -93.31513 4.030896 -71.01025 -91.92704 4 -69.90282 -92.42584 4.015678 -69.76605 -91.47206 4 -68.45292 -91.64743 4 -68.31369 -92.89011 4.028406 -67.3717 -92.41291 4 -66.77007 -93.59324 4 -68.60852 -92.93433 4.218325 -68.33392 -93.20496 15.74694 -69.15783 -92.73621 15.75091 -70.08529 -92.83737 15.75078 -70.08028 -92.80386 4.21883 -70.76572 -93.39373 4.256206 -70.89154 -93.65317 15.76326 -70.99317 -94.31249 4.293378 -70.86243 -94.81517 15.75046 -70.59295 -95.28684 4.288957 -70.25212 -95.52143 15.74978 -69.76746 -95.71773 4.283013 -69.31798 -95.7386 15.74633 -68.95858 -95.68632 4.217058 -68.44941 -95.35207 15.75075 -68.20904 -95.12827 4.216413 -67.93317 -94.32746 15.76372 -68.28565 -93.63985 16.00514 -68.43694 -94.99792 16.00045 -69.30415 -95.47609 16.00055 -70.40665 -95.14313 16.00514 -70.68098 -93.80529 16.00196 -69.65579 -92.92134 16.00514 -67.09276 -92.73636 1.244449 -66.69898 -94.3371 1.247463 -67.06862 -95.60961 1.247463 -67.98727 -96.56458 1.247463 -69.24451 -96.98326 1.247467 -71.13005 -96.43556 1.247469 -71.96734 -95.40848 1.247462 -72.23142 -94.10995 1.247463 -71.8618 -92.83745 1.247468 -70.94313 -91.88246 1.247466 -69.6859 -91.46378 1.247464 -68.3781 -91.67733 1.247465 -70.71361 -94.28211 1.124211 -70.14019 -93.17166 1.124199 -68.89174 -93.11305 1.124203 -68.21666 -94.16729 1.124127 -68.79025 -95.27539 1.124202 -70.03865 -95.33399 1.124201 -70.75525 -93.61074 2.265673 -69.4652 -94.22351 3.021688 -70.1407 -93.17211 2.323017 -69.48484 -92.79541 2.265522 -68.2449 -93.4636 2.235245 -70.66442 -95.01705 2.228475 -69.37448 -95.65884 2.24197 -68.18183 -94.88309 2.19906 -67.92513 -94.46035 4.148309 -68.01897 -93.68119 4.221113 -69.34052 -92.69182 4.21356 -52.21277 -81.76323 0 -52.21287 -81.76309 -2.158655 -49.46292 -83.35094 -2.158651 -49.46277 -83.35095 0 -51.21767 -82.34056 -2.405726 -50.33897 -82.83838 -2.387337 -48.44092 -82.78425 -2.396921 -46.71277 -81.7632 -2.159142 -46.71277 -81.76323 0 -47.83598 -82.40089 -2.412846 -47.80219 -82.3675 -2.413881 -46.71857 -80.74506 -2.387209 -46.72507 -79.90007 -2.40469 -46.71277 -78.5878 0 -46.72042 -78.57925 -2.194079 -47.85199 -77.94499 -2.404339 -46.81521 -79.43195 -2.4 -47.07087 -78.79573 -2.403155 -47.49504 -78.25444 -2.4 -49.46266 -77.00009 -2.158649 -49.46277 -77.00009 0 -48.5866 -77.51264 -2.387336 -50.48464 -77.56679 -2.396915 -52.21277 -78.5878 0 -52.20416 -78.57926 -2.184565 -52.15489 -79.55334 -2.413419 -52.19986 -79.89585 -2.404341 -51.28907 -78.1127 -2.394967 -51.85355 -78.7941 -2.402907 -52.20679 -80.74846 -2.387359 -48.04421 -80.79669 -2.398667 -50.75708 -81.03573 -2.398513 -50.88133 -79.55433 -2.398667 -51.72173 -78.6072 -2.4 -51.43051 -78.25444 -2.4 -49.61201 -78.60866 -2.397096 -52.11034 -79.43195 -2.4 -51.95045 -79.00336 -2.4 -48.16847 -79.3153 -2.398513 -47.20381 -78.6072 -2.4 -46.97509 -79.00336 -2.4 -46.81521 -79.43195 -2.4 -47.49504 -78.25444 -2.4 -49.31353 -81.74238 -2.397096 -51.08483 -77.95484 -2.4 -50.63673 -80.66224 -2.1265 -49.86449 -81.36663 -2.128955 -48.8598 -81.28977 -2.126377 -48.31245 -80.63842 -2.128828 -48.28883 -79.68878 -2.126501 -49.06107 -78.9844 -2.128962 -50.06573 -79.06127 -2.126376 -50.6131 -79.71263 -2.128828 -50.63672 -79.68878 -0.2734984 -50.00146 -79.0574 -0.2711547 -49.31169 -78.93627 -0.272987 -48.43442 -79.41699 -0.2737479 -48.28882 -80.66224 -0.2735005 -48.92409 -81.29365 -0.2711603 -49.61384 -81.41477 -0.2729929 -50.49112 -80.93406 -0.2737507 -47.9134 -80.51303 -0.005117237 -49.05072 -81.66699 -0.002105772 -50.43916 -81.38146 -0.002367079 -51.01214 -79.83799 -0.005117893 -49.87483 -78.68405 -0.00210613 -48.48638 -78.96959 -0.002366304 -48.39444 -79.17008 11.98899 -48.17668 -77.93422 12.00257 -49.8227 -78.74338 11.9908 -49.93997 -77.70522 12.00025 -51.53289 -78.62851 12.00235 -50.86752 -79.75421 11.98815 -51.91189 -81.0004 12.00235 -50.53072 -81.18115 11.98903 -50.46353 -82.51499 12.00102 -49.12622 -81.60279 11.98829 -48.34869 -82.50735 12.00235 -48.05846 -80.59769 11.9883 -47.15866 -81.18607 12.00025 -46.96883 -79.67013 12.0009 -46.82769 -81.12261 9 -47.75813 -80.59446 8.964501 -46.86234 -79.13705 9 -47.87451 -79.46055 8.974613 -47.9515 -77.85667 9 -51.87857 -81.52642 9 -50.54213 -81.53209 8.969173 -50.97404 -82.49437 9 -49.72332 -82.93109 9 -49.64918 -81.89583 8.972196 -48.11841 -82.63181 9 -48.79409 -81.77395 8.959937 -49.2891 -78.44453 8.967974 -49.20225 -77.41996 9 -50.80713 -77.71923 9 -50.79946 -78.8959 8.98223 -51.94689 -78.9548 9 -52.22965 -80.24902 9 -51.18426 -80.49526 8.967201 -50.74691 -79.33452 8.770378 -50.81531 -79.47702 -2.74694 -50.17682 -78.80076 8.772419 -50.13717 -78.81472 -2.750908 -49.21435 -78.67746 -2.750784 -49.22587 -78.65952 8.711767 -48.39406 -79.07331 8.713604 -48.2276 -79.26225 -2.763261 -47.96215 -79.87425 8.706627 -47.9612 -80.39363 -2.750462 -48.01541 -80.64409 8.712976 -48.37253 -81.23154 -2.74978 -48.79162 -81.54431 8.716994 -49.22107 -81.67844 -2.746323 -49.40655 -81.69531 8.712417 -50.15929 -81.52472 -2.750749 -50.14427 -81.54999 8.71116 -50.81373 -80.90457 8.713261 -50.91841 -80.66444 -2.763721 -50.98423 -80.01359 8.705645 -50.77074 -80.32125 -3.005136 -50.00555 -78.9766 -3.005136 -48.4874 -79.28622 -3.001471 -49.9095 -81.38112 -3.001961 -48.92191 -81.31674 -3.000546 -48.25717 -80.62225 -3.001961 -51.982 -79.02732 11.75254 -52.22703 -80.32955 11.75253 -51.83883 -81.59651 11.75253 -50.90628 -82.53797 11.75254 -49.64307 -82.93819 11.75253 -48.01791 -82.57396 11.75555 -46.79083 -81.01267 11.75555 -46.90766 -79.03031 11.75555 -48.01926 -77.81308 11.75253 -49.62752 -77.38034 11.75555 -51.15984 -77.9881 11.75254 -48.24029 -79.91574 11.87579 -49.07651 -78.98691 11.8758 -50.29901 -79.2467 11.8758 -50.68478 -80.43765 11.87587 -49.84904 -81.36414 11.8758 -48.62655 -81.10436 11.8758 -48.37021 -79.25573 10.73433 -49.46277 -80.17552 9.978313 -49.07589 -78.98722 10.67698 -49.8058 -78.78908 10.73448 -50.83586 -79.74977 10.76476 -48.10157 -80.63912 10.77152 -49.18669 -81.58696 10.75803 -50.53702 -81.13888 10.80094 -48.35187 -78.89491 8.933135 -48.25335 -81.1322 8.786177 -44.23677 -72.21278 0 -44.23693 -72.21289 -2.158655 -42.64907 -69.46292 -2.158652 -42.64906 -69.46278 0 -43.65942 -71.21765 -2.405725 -43.16161 -70.33896 -2.387336 -43.22217 -68.46526 -2.405725 -44.2368 -66.71279 -2.159144 -44.23677 -66.71278 0 -43.7548 -67.56276 -2.386382 -45.25494 -66.71858 -2.387211 -46.0999 -66.72507 -2.404688 -47.4122 -66.71278 0 -47.42076 -66.72043 -2.194078 -48.05499 -67.85198 -2.404333 -46.56805 -66.81521 -2.4 -47.20427 -67.07089 -2.403156 -47.74555 -67.49504 -2.4 -48.9999 -69.46264 -2.15865 -48.99991 -69.46278 0 -48.48735 -68.58659 -2.387336 -48.43321 -70.48464 -2.396923 -47.4122 -72.21278 0 -47.42076 -72.20416 -2.184567 -46.44662 -72.1549 -2.413422 -46.10417 -72.19986 -2.404342 -47.88733 -71.28903 -2.394956 -47.20587 -71.85358 -2.402913 -45.25156 -72.2068 -2.387359 -45.20329 -68.04423 -2.398667 -44.96429 -70.7571 -2.398512 -46.44566 -70.88134 -2.398667 -47.3928 -71.72174 -2.4 -47.74556 -71.43051 -2.4 -47.39134 -69.61203 -2.397096 -46.56805 -72.11034 -2.4 -46.99664 -71.95046 -2.4 -46.68471 -68.16848 -2.398513 -47.3928 -67.20382 -2.4 -46.99664 -66.9751 -2.4 -46.56805 -66.81521 -2.4 -47.74556 -67.49504 -2.4 -44.25762 -69.31353 -2.397096 -48.04516 -71.08484 -2.4 -45.33776 -70.63674 -2.126501 -44.63337 -69.8645 -2.128958 -44.71024 -68.85981 -2.126375 -45.36156 -68.31247 -2.128827 -46.31122 -68.28884 -2.126499 -47.0156 -69.06106 -2.128958 -46.93873 -70.06575 -2.126376 -46.28738 -70.61312 -2.128823 -46.31121 -70.63674 -0.2734992 -46.9426 -70.00148 -0.2711577 -47.06374 -69.31173 -0.2729915 -46.58305 -68.43446 -0.2737528 -45.33775 -68.28884 -0.2735006 -44.70636 -68.92409 -0.271157 -44.58523 -69.61383 -0.2729914 -45.06599 -70.49117 -0.2737502 -45.48699 -67.9134 -0.00511831 -44.33301 -69.05072 -0.002105712 -44.61853 -70.43914 -0.002365767 -46.16202 -71.01215 -0.005117237 -47.31596 -69.87483 -0.00210601 -47.03041 -68.48638 -0.002366721 -57.60556 -66.82993 11.98899 -56.66505 -68.33721 12.00025 -56.1773 -67.25662 11.9908 -54.89747 -67.82194 12.00235 -55.13248 -66.2458 11.98815 -54.05823 -66.25428 12.00025 -54.35687 -64.43759 12.00257 -55.46928 -64.81886 11.98903 -55.81177 -63.41537 12.00025 -56.87378 -64.39723 11.98829 -57.33955 -63.40964 12.0009 -58.53255 -64.2919 12.00025 -57.94154 -65.40232 11.98829 -59.11259 -66.03928 12.00235 -58.06877 -67.85648 12.00102 -59.24129 -65.23371 9 -58.26672 -65.76713 8.967735 -59.13766 -66.86296 9 -57.85825 -67.10719 8.981367 -58.04851 -68.14333 9 -54.12144 -64.47358 9 -55.75692 -64.14408 8.979701 -55.27941 -63.32277 9 -57.25468 -63.11784 9 -57.99235 -64.74366 8.984503 -58.657 -64.04473 9 -56.73211 -67.53994 8.971039 -56.79776 -68.58005 9 -55.19287 -68.28078 9 -55.71128 -67.35388 8.964409 -54.85806 -66.25032 8.962116 -54.05311 -67.04521 9 -53.77035 -65.751 9 -54.88405 -65.31114 8.969837 -55.29004 -66.72322 8.78694 -55.18469 -66.523 -2.746937 -55.86283 -67.18529 -2.750909 -55.86186 -67.20279 8.712886 -56.78565 -67.32255 -2.750781 -56.77413 -67.34049 8.71177 -57.58482 -66.96623 8.772481 -57.7724 -66.73777 -2.763262 -58.0388 -65.60638 -2.750457 -57.98459 -65.35591 8.71298 -57.62747 -64.76847 -2.749778 -57.20837 -64.4557 8.716989 -56.77892 -64.32157 -2.746326 -55.84071 -64.47529 -2.750746 -55.85386 -64.43669 8.780735 -55.19751 -65.05982 8.743253 -55.08159 -65.33557 -2.763721 -55.01578 -65.98642 8.705647 -55.25259 -65.87679 -3.001961 -55.99285 -67.02693 -3.001472 -55.73982 -64.81594 -3.001961 -57.08001 -64.62557 -3.005135 -57.7784 -65.59129 -3.000546 -57.50974 -66.71118 -3.005135 -54.018 -66.97269 11.75254 -53.77297 -65.67047 11.75253 -54.16117 -64.4035 11.75254 -55.38411 -63.27293 11.75555 -57.36611 -63.14997 11.75555 -58.70845 -64.10675 11.75254 -59.25802 -65.31252 11.75253 -59.09234 -66.9697 11.75555 -57.98074 -68.18693 11.75253 -56.71749 -68.58716 11.75254 -55.09236 -68.22293 11.75555 -57.75971 -66.08426 11.87579 -56.92349 -67.01309 11.8758 -55.701 -66.75331 11.8758 -55.31522 -65.56237 11.87587 -56.15096 -64.63587 11.8758 -57.37345 -64.89566 11.8758 -57.62979 -66.74427 10.73433 -56.53723 -65.82449 9.978313 -56.92411 -67.0128 10.67698 -56.1942 -67.21092 10.73447 -55.16414 -66.25024 10.76476 -57.89843 -65.36089 10.77152 -56.81331 -64.41305 10.75803 -55.46297 -64.86112 10.80094 -57.30272 -64.31232 8.931707 -57.75205 -64.8804 8.778816 -58.05108 -66.13368 8.779545 -56.58811 -64.28883 8.78618 -40.72695 -15.63706 4.000001 -41.06512 -14.00865 4.000001 -40.21008 -14.97127 4.000001 -39.2876 -14.73824 4.000001 -40.49568 -16.80359 4.000001 -41.73288 -17.19555 4.000001 -41.97896 -15.48057 4.000001 -39.93412 -13.53798 4.000001 -38.55799 -13.64889 4.000001 -38.56436 -15.1711 4.000001 -37.26712 -14.80446 4.000001 -38.21813 -16.04972 4.000001 -37.02104 -16.51943 4.000001 -38.56436 -16.8289 4.000001 -37.58489 -17.60697 4.000001 -39.40427 -17.27592 4.000001 -38.71036 -18.40656 4.000001 -40.44201 -18.35111 4.000001 -40.21008 -14.97127 38.5 -41.18933 -14.11287 38.5 -40.75508 -15.75117 38.5 -42.00712 -15.64025 38.5 -40.41775 -16.89156 38.5 -39.40427 -14.72408 38.5 -38.71036 -13.59344 38.5 -39.93412 -13.53798 38.5 -39.2876 -17.26176 38.5 -39.06588 -18.46202 38.5 -37.81068 -17.88714 38.5 -38.56436 -16.8289 38.5 -38.21813 -15.95028 38.5 -36.99288 -16.35975 38.5 -37.34819 -14.66404 38.5 -38.56436 -15.1711 38.5 -41.65181 -17.33597 38.5 -40.28964 -18.40656 38.5 -39.91757 -14.59421 42.98874 -40.73496 -13.55458 42.92678 -41.68728 -14.37536 42.94532 -40.92629 -15.65828 42.98952 -38.48917 -14.93677 42.98899 -39.12714 -13.36178 43.00144 -38.07379 -16.34379 42.98899 -37.33094 -14.4526 43.00144 -39.08463 -17.40702 42.98899 -37.64199 -17.90973 43.00144 -36.87589 -16.2361 43.00052 -39.33601 -18.62967 43.00046 -40.51083 -17.06324 42.98899 -41.10634 -18.12578 43.00144 -42.14746 -16.30032 43.00144 -42.26845 -15.4645 39.99999 -41.7955 -17.6376 39.99999 -40.16726 -18.70623 40 -38.22889 -18.51701 39.99999 -37.0679 -17.31323 40 -36.69821 -15.68218 39.99999 -37.42385 -14.17537 40 -38.55337 -14.79146 39.97613 -38.56237 -13.37516 40 -39.95024 -13.27292 40 -40.01925 -14.53166 39.98036 -41.23159 -13.81584 40 -39.21746 -14.54537 34.05341 -39.82682 -14.58246 34.04506 -39.19403 -14.50636 39.97753 -38.58862 -14.78879 34.1532 -38.20423 -15.33271 34.0399 -38.0678 -15.45254 39.97579 -37.99048 -15.89557 34.14958 -37.9846 -16.26127 39.97457 -38.17674 -16.65288 34.05413 -38.36829 -17.03539 39.97632 -38.73997 -17.27088 34.06991 -38.86109 -17.3841 39.97534 -39.41028 -17.53306 39.97853 -39.5024 -17.51263 34.14895 -40.21437 -17.35849 39.97481 -40.28884 -17.29045 34.14874 -40.73286 -16.89871 39.97788 -40.84482 -16.6917 34.14852 -41.04779 -16.12573 39.97776 -40.93666 -16.16928 34.00852 -40.91621 -15.46249 34.14966 -40.79254 -15.17076 39.97665 -40.44607 -14.87304 34.05173 -39.94377 -17.33414 33.99686 -39.53935 -13.23283 42.85036 -38.04195 -13.59911 42.8451 -36.83634 -15.13017 42.85814 -36.90601 -17.07769 42.8451 -38.00462 -18.33821 42.85502 -39.45856 -18.79029 42.8511 -41.19347 -18.24106 42.8451 -42.08642 -16.98448 42.85036 -42.26186 -15.60053 42.8511 -38.61345 -16.88095 42.87581 -38.2938 -15.6727 42.8758 -39.18035 -14.79177 42.8758 -40.38819 -15.12076 42.87586 -40.70614 -16.32728 42.87577 -39.81965 -17.20823 42.8758 -40.86042 -15.58472 41.74288 -39.5 -16 40.97831 -40.52282 -17.01773 41.78264 -39.12677 -17.39401 41.78353 -38.10402 -16.35884 41.7658 -38.48851 -14.97156 41.78768 -39.86019 -14.61038 41.78942 + + + + + + + + + + -0.006056427 -0.01114732 -0.9999195 -0.006029665 -0.006760418 -0.9999591 -0.00972706 -0.003371655 -0.9999471 -0.00858128 -0.00111413 -0.9999626 -0.01291793 0.005518853 -0.9999014 -0.005087435 0.01177775 -0.9999178 -0.005484938 0.00858134 -0.9999482 0.002378702 0.01189738 -0.9999264 0.005012571 0.008328557 -0.9999528 0.008048832 0.008594751 -0.9999307 0.01277703 9.17608e-4 -0.999918 0.01099354 -7.61023e-4 -0.9999394 0.01200407 -0.007376372 -0.9999008 0.003846824 -0.008946657 -0.9999526 0.002390384 -0.01278555 -0.9999154 -0.03478014 0.02378642 0.9991119 -0.0211932 0.02268105 0.9995182 -0.004955649 0.03536349 0.9993622 0.004256486 -0.03037351 0.9995296 -0.003322064 -0.0225898 0.9997393 -0.01027572 -0.02029901 0.9997411 -0.008737146 -0.02763819 0.9995799 -0.02676397 -0.02219849 0.9993954 -0.03105872 0.01023906 0.9994651 0.02247506 0.002300977 0.9997448 -0.001104891 0.03199821 0.9994874 0.01964926 0.03578734 0.9991663 0.02569162 0.01409286 0.9995706 0.03283786 0.02764093 0.9990785 0.03067904 -0.005493581 0.9995143 0.03693914 -0.003161966 0.9993125 0.02066445 -0.02422738 0.999493 0.02001154 -0.02406424 0.9995101 0.9366485 -0.3502365 -0.004899263 0.9961494 -0.08740079 0.006886005 0.990567 0.1370136 -0.00209552 0.8389701 0.5441576 0.004673182 0.8585162 0.512784 0.001697063 0.4105902 0.9118195 9.55721e-4 0.3427098 0.939417 0.006770491 -0.1903777 0.9816985 -0.004955053 -0.4394028 0.8982311 0.01030403 -0.7307969 0.6825677 -0.006113231 -0.9096014 0.4153822 0.009116828 -0.979768 -0.200011 0.007102847 -0.9986737 0.05130034 -0.004383563 -0.9024912 -0.4307016 -0.002430438 -0.6500889 -0.7598461 0.004299044 -0.6611135 -0.7502795 0.003118276 -0.1250163 -0.9921534 0.001642107 -0.03701788 -0.9992802 0.008302628 0.4989023 -0.8666372 -0.00603348 0.6981371 -0.715875 0.01129698 0.004462122 -0.003186404 0.999985 0.001993834 0.001292884 0.9999972 0.001640915 -0.001331865 0.9999979 0.002202928 -7.56276e-4 0.9999973 0.7363168 -0.6759123 -0.031309 0.64858 -0.7604348 0.0329082 0.1387667 -0.9901738 -0.01730966 0.1865719 -0.982316 0.01569736 -0.3298162 -0.9436344 -0.02784788 -0.4514915 -0.8919135 0.02540946 -0.7695292 -0.6382699 -0.02089309 -0.7600769 -0.6497127 -0.01251232 -0.9947192 -0.1018616 0.01257294 -0.9977403 -0.06676858 -0.007496595 -0.9015488 0.4326145 0.007386088 -0.8973435 0.4413244 0.002711594 -0.6050476 0.7961857 0.002449095 -0.5894724 0.8077636 -0.006343901 -0.1387784 0.9902921 0.007884383 -0.1029447 0.9946085 -0.01250612 0.4812427 0.8764972 0.01257622 0.5118355 0.8590509 -0.007500171 0.8767278 0.4809224 0.007884383 0.8934703 0.4489482 -0.01250898 0.9842451 -0.176249 0.01407307 0.9846395 -0.173893 0.01569879 -0.7517841 0.3697218 -0.5460096 -0.7824823 -0.05123406 -0.6205614 -0.5625238 -0.09217596 -0.8216269 -0.5844212 -0.5712612 -0.5762921 -0.4879624 -0.4189211 -0.7657662 -0.2723038 -0.7791085 -0.5646598 -0.08918434 -0.5694897 -0.8171461 0.1593747 -0.8442695 -0.5116726 0.2249365 -0.4648682 -0.8563302 0.7075511 -0.6488931 -0.279838 0.53291 -0.1771154 -0.8274281 0.7834469 -0.1395025 -0.6055989 0.5479825 0.1637229 -0.820311 0.7813122 0.3935519 -0.4844257 0.3166698 0.5037333 -0.8037245 0.329881 0.5509548 -0.7665686 -0.09085077 0.8693976 -0.4856891 -0.1540758 0.529031 -0.8344981 -0.4838653 0.6630524 -0.5711706 -0.4444717 0.3286119 -0.8333423 0.5722603 -0.5752072 0.5845126 0.08053511 -0.562314 0.8229929 -0.03694432 -0.8290481 0.5579555 -0.5120564 -0.5766335 0.6366257 -0.4143844 -0.2686143 0.8695586 -0.8175433 -0.1688856 0.5505458 -0.6899973 0.3145646 0.6518842 -0.3825306 0.3102982 0.870279 -0.3989763 0.8048146 0.4394216 0.1819054 0.5608589 0.8076806 0.2351571 0.6210089 0.7476959 0.6947894 0.415096 0.5873356 0.5403626 0.1407399 0.8295786 0.8287897 -0.0750128 0.5545095 0.5110772 -0.3781306 0.7718921 0.4320813 -0.8834958 -0.180945 -0.5519763 -0.8162132 -0.1706404 -0.9625113 0.07938778 -0.259364 -0.431406 0.8835958 -0.1820641 0.5496283 0.8156125 -0.1807901 0.9815191 -0.06792378 -0.1789042 -0.523315 0.05211186 -0.8505445 -0.3382951 -0.3604125 -0.8692868 -0.1866012 -0.4576735 -0.8693188 0.2698082 -0.4534085 -0.8494848 0.5336307 -0.02494508 -0.8453497 0.2665857 0.468645 -0.8422018 -0.2275854 0.490352 -0.8412847 0.4186105 -0.9071566 -0.04280376 0.4744266 -0.8802938 -0.001527249 0.4644123 -0.8856042 0.005141139 -0.580762 -0.8140736 -1.09394e-4 -0.5425056 -0.8394988 -0.03048992 -0.5739966 -0.8166232 -0.06045329 -0.4978514 -0.8672624 -5.05711e-5 -0.9988881 0.04483503 -0.01457422 -0.992071 0.1207498 -0.03485125 -0.9979191 0.06446146 -0.001545369 -0.4630689 0.8863201 -0.002049088 -0.4157711 0.9090996 -0.0259304 -0.4566762 0.8896288 0.002770185 0.5356875 0.8444103 0.003209412 0.5784464 0.8150573 -0.03288674 0.5349081 0.8449062 0.002620816 0.9991194 -0.04191875 0.001843035 0.9949027 -0.09093165 -0.04359006 0.9994803 -0.03191888 -0.004512965 -0.7620794 -0.1785354 0.6223828 -0.01891601 0.04840642 0.9986487 -0.9293726 -0.2065518 0.3059464 -0.6810643 0.03030669 0.7315963 -0.8368989 0.4195764 0.3515051 -0.5044504 0.4669694 0.726271 -0.4533651 0.755097 0.4735913 0.9454993 -0.05854183 0.3203188 0.6431819 -0.2314617 0.7298922 0.6277806 -0.6755511 0.3866813 0.7418994 0.1001361 0.6629918 0.6308605 0.4080591 0.6599264 0.6989192 0.651974 0.2940098 0.2705156 0.6043493 0.7493886 0.05929714 0.9187798 0.3902916 -0.1271432 0.6846736 0.7176744 -0.6755688 -0.3170936 0.6656264 -0.4708211 -0.6354331 0.6120069 -0.491311 -0.7909713 0.3646613 -0.1042705 -0.5543324 0.825738 0.1966018 -0.8062697 0.5579221 0.3059075 -0.5854071 0.7508122 -0.9775292 0.2107951 -0.001498639 -0.9738716 0.2270977 -8.46324e-4 -0.9744033 0.2248066 4.95147e-4 -0.9677168 0.251168 0.02095288 -0.579259 0.2580305 0.7732267 -0.3957851 0.2667295 0.8787546 -0.2733967 0.4753624 0.8362325 -0.3133752 0.9496216 0.003858804 -0.2774717 0.9607329 -0.001323103 -0.292495 0.9562012 -0.01122689 -0.06048214 0.6220424 0.7806442 -0.2619037 0.8580392 0.4417867 0.09841859 0.3699277 0.923833 0.6791867 0.7339554 0.003884017 0.6047186 0.7964388 -8.49147e-4 0.7288393 0.6841662 -0.0266444 0.6814323 0.7309621 0.03666627 0.4539484 0.2215897 0.8630346 0.4479655 0.1336963 0.883998 0.628533 0.002894043 0.7777777 0.9737434 -0.2276449 0.001274883 0.973194 -0.2299858 -3.33159e-4 0.9743997 -0.2248052 0.002840995 0.9812219 -0.1914277 -0.0236485 0.3220925 -0.2843459 0.9029972 0.2946732 -0.5715121 0.76586 0.287987 -0.3757689 0.8808299 0.5314236 -0.2477805 0.8100579 0.2696222 -0.9629662 -3.09917e-4 0.3170629 -0.9484041 9.66682e-4 0.2924749 -0.9561372 -0.0161252 0.07513284 -0.6356513 0.7683115 -0.02843803 -0.4717136 0.8812932 -0.09770387 -0.4234852 0.9006189 -0.1786516 -0.4369251 0.8815783 -0.6707706 -0.7416598 0.002763152 -0.7648448 -0.6401176 0.07253915 -0.7561682 -0.6543765 0.001102387 -0.681349 -0.7308734 0.0398454 -0.6206759 -0.783183 -0.0372281 -0.3585439 -0.1325692 0.9240518 -0.648953 0.02437692 0.760438 -0.8710714 0.1921241 0.452021 6.8425e-4 7.6295e-4 0.9999995 0.005351305 0.008560478 0.999949 0.1977469 -0.07702839 0.977222 9.7451e-4 -9.18786e-4 0.9999992 -6.58019e-4 -0.00233078 0.9999971 0.005006074 0.00666666 0.9999653 0.001025199 0.001270294 0.9999987 -1.3329e-4 -0.00301516 0.9999955 -0.001295387 0.001043081 0.9999987 -6.05438e-4 0.002131819 0.9999976 0.002025127 0.003810107 0.9999907 4.86406e-4 0.003103673 0.9999951 -0.002147018 -0.003913938 0.9999901 -0.00148487 -0.01105034 0.9999378 1.57622e-4 0.002507507 0.9999969 -0.003104746 -0.007612407 0.9999663 6.51992e-5 0.001063704 0.9999995 -0.001137197 5.25755e-4 0.9999993 -0.04622226 0.2186356 0.9747112 0.001030743 0.002735853 0.9999958 0.004705309 -1.74274e-4 0.9999889 2.4642e-4 0.001081347 0.9999995 0.003680288 -0.004458308 0.9999833 -0.01179432 0.007461488 0.9999027 0.00352478 0.005765616 0.9999772 0.0090034 -0.005161106 0.9999462 6.96267e-4 8.96368e-4 0.9999994 -6.17379e-4 8.03781e-4 0.9999995 -7.98333e-4 7.39774e-4 0.9999995 -9.39457e-4 6.21756e-4 0.9999995 0.007233083 -0.002472579 0.9999708 -0.005110919 -0.005136311 0.9999738 0.6473888 0.5873748 0.4856735 0.6054224 -0.008450448 0.7958596 0.8184299 -0.1734485 0.5478029 0.4324689 -0.4668431 0.7713808 0.4537945 -0.6993026 0.5523102 -0.03405284 -0.616883 0.7863178 -0.361159 -0.8688498 0.3386211 -0.3821224 -0.433907 0.815909 -0.8544073 -0.03502422 0.518422 -0.8360233 -0.02532166 0.5481095 -0.5167091 0.3334953 0.7885383 -0.5333766 0.6398352 0.5532814 -0.1942949 0.5860376 0.7866445 -0.04320263 0.8433862 0.5355682 0.3503044 0.4762097 0.8065428 0.5912256 0.8042038 -0.06089878 -0.03792971 0.9980992 0.04857385 -0.3134576 0.9486238 -0.04309719 -0.6023109 0.7977647 0.02816259 -0.8379986 0.5449451 -0.02816349 -0.9682525 0.2462312 0.04309916 -0.9983043 -0.03207939 -0.04857426 -0.7608045 -0.6461182 0.0608927 -0.6634595 -0.7480986 -0.01304584 -0.05139482 -0.998516 -0.01801061 0.03803169 -0.9990133 0.02293586 0.602491 -0.7981161 0.003933966 0.6767956 -0.7352828 -0.03615283 0.9682918 -0.2462464 0.04211807 0.9984111 -0.01071614 -0.05532205 0.7608107 0.6461102 0.06089937 0.05901032 -0.7699209 -0.6354051 0.03330928 -0.8359937 -0.5477272 0.368735 -0.4919009 -0.7887129 0.765628 -0.4668965 -0.4425172 0.5754017 -0.1469804 -0.8045557 0.8203222 0.3260691 -0.4698411 0.418646 0.3557626 -0.8355648 0.3192857 0.8415275 -0.4357618 -0.02421867 0.5792577 -0.8147847 -0.4177656 0.7224875 -0.5508936 -0.4249446 0.5659911 -0.7064533 -0.7202759 0.1916452 -0.6666895 -0.7072634 0.1804226 -0.6835395 -0.5337469 -0.4534938 -0.7137631 -0.5897233 -0.4708812 -0.6561231 0.001612782 6.23e-4 -0.9999985 3.45556e-4 -0.001480579 -0.9999989 4.91629e-4 -0.001607894 -0.9999986 9.47567e-4 -7.93699e-4 -0.9999992 0.001893579 -4.37085e-4 -0.9999982 -5.50824e-4 0.001798391 -0.9999983 -0.001144409 -3.20311e-4 -0.9999993 -6.27865e-4 1.44471e-4 -0.9999999 -0.002314627 0.001812636 -0.9999957 4.74241e-4 0.001599133 -0.9999986 3.74364e-4 4.02729e-4 -1 -0.00104469 -0.001118957 -0.9999989 -0.00181216 -0.001341462 -0.9999975 0.1921491 0.980893 0.0304594 -0.1082126 0.9937925 -0.02582055 -0.3801547 0.9245625 0.02582073 -0.5945515 0.8038028 -0.02024096 -0.8650566 0.5015091 0.01287066 -0.8563941 0.5162744 0.007077872 -0.9999563 0.006129562 -0.00707823 -0.9991188 -0.04102301 0.008886158 -0.8223977 -0.5688554 -0.008096933 -0.7980706 -0.6025509 0.003966391 -0.5015487 -0.8651226 -0.003448367 -0.4682934 -0.8835551 0.005647242 -0.006126642 -0.9999563 -0.007078826 0.04102092 -0.9991189 0.008886456 0.6135941 -0.7895619 -0.009715616 0.6522472 -0.7579441 0.009716331 0.9711556 -0.2382811 -0.008886337 0.9813237 -0.1922339 0.00707817 0.9417468 0.3362482 -0.007078409 0.9473102 0.3200591 -0.0128709 0.72044 0.6931444 0.02274018 0.5317653 0.8461236 -0.03606361 0 0 -1 -1.89993e-6 0 -1 7.69361e-7 0 -1 1.63942e-6 0 -1 -2.76357e-6 0 -1 1.88541e-6 0 -1 -1.0939e-6 0 -1 8.70598e-7 0 -1 0.01259672 -0.999474 0.02988398 0.5697237 -0.8213931 -0.02699017 0.704885 -0.7092376 0.0109201 0.9979835 -0.0634424 -0.002004384 0.9998279 0.002272486 -0.01841241 0.8114367 0.5841265 0.01915282 0.6021865 0.7980437 -0.02231115 0.333235 0.9426631 0.01846325 -0.07284986 0.9971139 -0.0213769 -0.5110488 0.8592332 0.02339828 -0.6326106 0.774425 -0.008359074 -0.9941074 0.1080112 0.00916928 -0.9990802 0.04225498 -0.007303059 -0.7635717 -0.6456819 0.007302641 -0.7793334 -0.626464 0.01350772 -0.2779096 -0.9603291 -0.02311372 0 0 1 1.36945e-6 0 1 1.88472e-6 0 1 1.05377e-6 0 1 -1.55351e-6 0 1 -3.81084e-6 0 1 -8.3797e-7 0 1 -3.38353e-6 0 1 2.9543e-6 0 1 -1.57616e-6 0 1 0.1705164 0.9845809 0.03904837 0.02376216 0.9993045 -0.02873963 -0.4702943 0.881923 0.03217196 -0.5487678 0.8357921 -0.0174762 -0.8942639 0.4475324 0.00262928 -0.9129708 0.4071702 0.02639639 -0.9995815 -0.006782114 -0.02812552 -0.9700781 -0.2393271 0.04088062 -0.9233767 -0.3835904 -0.01529741 -0.6722742 -0.7403005 0.001634478 -0.6419115 -0.7665176 0.02001309 -0.343134 -0.9390507 -0.02104645 -0.2037665 -0.9787933 0.02104657 0.08933299 -0.9959052 -0.01387691 0.2100307 -0.9774271 0.0228753 0.4583609 -0.8882112 -0.03140461 0.6888254 -0.7244319 0.0267989 0.8234987 -0.5664014 -0.03224074 0.9327548 -0.3586202 0.03688085 0.9990512 -0.02316623 -0.03688091 0.9770504 0.2105544 0.03224164 0.9126187 0.4079325 -0.02679848 0.7207509 0.6918169 0.04367578 0.5445217 0.8376089 -0.04367506 -0.3350387 -0.9421127 0.01314437 -0.2769267 -0.9608341 -0.01046794 0.4342027 -0.9007406 0.01159864 0.4902896 -0.8714004 -0.01666444 0.9925182 -0.1207711 0.0179491 0.9983996 -0.054349 -0.01563251 0.7106277 0.7034455 0.01314336 0.6663957 0.7455248 -0.01046794 0.03875243 0.999194 0.01046895 0.01893895 0.9998168 0.002802312 -0.6084945 0.7934007 -0.01580721 -0.6781238 0.7348031 0.01457905 -0.9669337 0.2549865 -0.004615604 -0.9704962 0.2409342 -0.009376287 -0.9170559 -0.3986214 0.0104677 -0.8909913 -0.4538301 -0.01314288 -0.1705164 -0.9845809 0.03904837 -0.02376216 -0.9993045 -0.02873963 0.4702943 -0.881923 0.03217196 0.5487678 -0.8357921 -0.0174762 0.8942639 -0.4475324 0.00262928 0.9129708 -0.4071702 0.02639639 0.9995815 0.006782114 -0.02812552 0.9700781 0.2393271 0.04088062 0.9233767 0.3835904 -0.01529741 0.6722742 0.7403005 0.001634478 0.6419115 0.7665176 0.02001309 0.343134 0.9390507 -0.02104645 0.2037665 0.9787933 0.02104657 -0.08933299 0.9959052 -0.01387691 -0.2100307 0.9774271 0.0228753 -0.4583609 0.8882112 -0.03140461 -0.6888254 0.7244319 0.0267989 -0.8234987 0.5664014 -0.03224074 -0.9327548 0.3586202 0.03688085 -0.9990512 0.02316623 -0.03688091 -0.9770504 -0.2105544 0.03224164 -0.9126187 -0.4079325 -0.02679848 -0.7207509 -0.6918169 0.04367578 -0.5445217 -0.8376089 -0.04367506 0.3350387 0.9421127 0.01314437 0.2769267 0.9608341 -0.01046794 -0.4342027 0.9007406 0.01159864 -0.4902896 0.8714004 -0.01666444 -0.9925182 0.1207711 0.0179491 -0.9983996 0.054349 -0.01563251 -0.7106277 -0.7034455 0.01314336 -0.6663957 -0.7455248 -0.01046794 -0.03875243 -0.999194 0.01046895 -0.01893895 -0.9998168 0.002802312 0.6084945 -0.7934007 -0.01580721 0.6781238 -0.7348031 0.01457905 0.9669337 -0.2549865 -0.004615604 0.9704962 -0.2409342 -0.009376287 0.9170559 0.3986214 0.0104677 0.8909913 0.4538301 -0.01314288 -0.2107973 -0.9775287 -0.001498818 -0.2270961 -0.973872 -8.46645e-4 -0.224807 -0.9744033 4.95147e-4 -0.251164 -0.9677178 0.02095168 -0.2580226 -0.5792901 0.7732059 -0.2667366 -0.395772 0.8787583 -0.4753565 -0.2733981 0.8362355 -0.9496214 -0.3133754 0.003857493 -0.9607328 -0.277472 -0.001323401 -0.9562013 -0.292495 -0.01122689 -0.6220455 -0.06047934 0.7806419 -0.8580366 -0.2619209 0.4417812 -0.369926 0.09841585 0.9238339 -0.7339547 0.6791873 0.003884017 -0.7964383 0.6047193 -8.50588e-4 -0.6841658 0.7288396 -0.02664631 -0.7309627 0.6814317 0.03666847 -0.2215881 0.4539452 0.8630368 -0.1336962 0.4479646 0.8839983 -0.00289011 0.6285318 0.7777785 0.2276434 0.9737438 0.001275241 0.2299822 0.9731948 -3.31171e-4 0.2248059 0.9743995 0.002840638 0.1914306 0.9812211 -0.02365225 0.2843444 0.3220943 0.902997 0.5715131 0.2946746 0.7658588 0.3757675 0.2879865 0.8808307 0.2477846 0.5314291 0.8100531 0.9629663 0.2696221 -3.10683e-4 0.9484049 0.3170605 9.68321e-4 0.9561371 0.2924755 -0.01612496 0.635643 0.07512909 0.7683188 0.4717097 -0.02843308 0.8812955 0.4234886 -0.09770631 0.9006171 0.4369142 -0.1786518 0.8815836 0.7416577 -0.6707729 0.002762436 0.6401291 -0.7648339 0.07255196 0.6543767 -0.7561681 0.001101374 0.7308741 -0.6813483 0.0398454 0.7831816 -0.6206774 -0.03723126 0.1325682 -0.3585456 0.9240513 -0.02438253 -0.6489267 0.7604603 -0.1921248 -0.8711761 0.451819 -7.63773e-4 6.86329e-4 0.9999995 -0.008560061 0.005353569 0.999949 0.07704061 0.197713 0.9772279 9.19351e-4 9.751e-4 0.9999992 0.002324938 -6.57001e-4 0.9999971 -0.006663739 0.005010426 0.9999653 -0.001267373 0.00102657 0.9999988 0.003006756 -1.35348e-4 0.9999955 -0.001043498 -0.001295566 0.9999987 -0.00213176 -6.03439e-4 0.9999976 -0.003809869 0.002020537 0.9999907 -0.003103196 4.85738e-4 0.9999951 0.003915548 -0.002144634 0.9999901 0.01105421 -0.001481473 0.9999378 -0.002502918 1.53583e-4 0.999997 0.007613241 -0.003104746 0.9999663 -0.001063168 6.41316e-5 0.9999995 -5.27507e-4 -0.001138269 0.9999993 -0.218432 -0.04631012 0.9747528 -0.002735495 0.001030087 0.9999958 1.76242e-4 0.00470823 0.9999889 -0.00107938 2.49484e-4 0.9999995 0.004459083 0.003678143 0.9999833 -0.007461845 -0.01179623 0.9999026 -0.005765736 0.003523528 0.9999772 0.00515908 0.00900495 0.9999462 -8.97874e-4 6.94808e-4 0.9999994 -8.04461e-4 -6.16019e-4 0.9999995 -7.38207e-4 -7.93537e-4 0.9999994 -6.19939e-4 -9.41155e-4 0.9999995 0.002476274 0.00723201 0.9999708 0.005138337 -0.005112886 0.9999737 -0.5873765 0.6473843 0.4856773 0.008450448 0.6054198 0.7958615 0.1734476 0.8184326 0.5477992 0.466836 0.4324738 0.7713822 0.6993101 0.4537893 0.5523049 0.6168798 -0.03405272 0.7863204 0.8688508 -0.3611564 0.3386215 0.4339087 -0.3821228 0.8159078 0.03502404 -0.8544123 0.5184139 0.02532333 -0.83602 0.5481145 -0.333498 -0.5167115 0.7885357 -0.6398283 -0.5333781 0.5532881 -0.5860362 -0.1942952 0.7866455 -0.8433856 -0.04320442 0.535569 -0.4762126 0.3503023 0.8065419 -0.8042024 0.5912274 -0.06089878 -0.9980992 -0.0379315 0.04857355 -0.9486237 -0.3134575 -0.04309862 -0.7977671 -0.6023078 0.02816301 -0.5449454 -0.8379984 -0.02816438 -0.2462302 -0.9682527 0.04310005 0.03207927 -0.9983044 -0.04857414 0.6461199 -0.760803 0.06089353 0.7480973 -0.663461 -0.01304477 0.9985161 -0.05139356 -0.01801174 0.9990133 0.03803074 0.02293556 0.798115 0.6024923 0.003933966 0.7352849 0.6767932 -0.03615486 0.2462455 0.968292 0.04211825 0.01071721 0.9984112 -0.05532139 -0.6461116 0.7608096 0.06089848 0.7699189 0.05901175 -0.6354073 0.8359937 0.03330761 -0.5477272 0.4919048 0.3687415 -0.7887074 0.466902 0.7656248 -0.4425171 0.1469768 0.5754 -0.8045575 -0.3260728 0.8203217 -0.4698391 -0.3557615 0.4186511 -0.8355627 -0.8415243 0.3192902 -0.4357646 -0.5792597 -0.02421629 -0.8147833 -0.7224855 -0.4177695 -0.5508933 -0.5659965 -0.4249435 -0.7064495 -0.1916458 -0.7202718 -0.6666937 -0.1804203 -0.7072687 -0.6835347 0.453487 -0.533756 -0.7137607 0.470892 -0.5897172 -0.6561208 -6.23785e-4 0.001609146 -0.9999985 0.001483678 3.43482e-4 -0.9999989 0.001607716 4.91846e-4 -0.9999986 7.93005e-4 9.4767e-4 -0.9999992 4.37135e-4 0.001894474 -0.9999982 -0.001799643 -5.50121e-4 -0.9999983 3.21378e-4 -0.001145839 -0.9999993 -1.44621e-4 -6.26196e-4 -0.9999999 -0.001810669 -0.002318382 -0.9999957 -0.001597583 4.76073e-4 -0.9999987 -4.03428e-4 3.75441e-4 -0.9999999 0.001119554 -0.001043081 -0.9999989 0.00134015 -0.001814246 -0.9999976 -0.2377832 0.9709751 0.02582061 -0.4678141 0.8835951 -0.02024126 -0.7977216 0.602836 0.01513862 -0.7892929 0.6139401 0.009716868 -0.9998698 0.01289242 -0.00971651 -0.9999808 -0.005685627 -0.002487063 -0.865303 -0.5011452 0.01020312 -0.7918663 -0.6103435 -0.02070951 -0.5691137 -0.8219952 0.02082377 -0.3244543 -0.9454109 -0.0304585 0.03701734 -0.9986637 0.0360642 0.2769267 -0.960622 -0.02273947 0.6600344 -0.7511252 0.01287031 0.6219969 -0.7830098 -0.003932297 0.9084848 -0.4177978 0.01002007 0.9361798 -0.351351 -0.01094681 0.9905121 0.1374212 0.001110374 0.9891049 0.1471588 0.003965795 0.8543939 0.5196146 -0.003448665 0.8160354 0.5778506 0.01322984 0.5084986 0.8608088 -0.02091813 0.336575 0.9413564 0.02377736 0.009967386 0.9997489 -0.02007299 8.51781e-7 0 -1 -4.66057e-7 0 -1 -4.65031e-7 0 -1 -1.11212e-6 0 -1 1.03758e-6 0 -1 0.5932646 -0.8050066 -0.001299977 0.6037026 -0.7971991 -0.004094064 0.9464795 -0.3227382 0.004094719 0.9635982 -0.2672243 -0.008358895 0.853662 0.520731 0.01002448 0.8152315 0.5790486 -0.01002466 0.09689706 0.9952523 0.009169518 -0.01343971 0.9997403 -0.01841253 -0.6540093 0.7561171 0.02363908 -0.804697 0.5932151 -0.02363914 -0.9995892 -0.02377039 0.01601755 -0.9915184 -0.1298026 -0.006540298 -0.7013416 -0.7127954 0.006540238 -0.6901575 -0.723652 0.003234922 -0.1491264 -0.9887665 -0.01010471 -0.05228817 -0.9985724 0.01091969 -2.32012e-6 0 1 6.57926e-7 0 1 -9.29506e-7 0 1 -8.80601e-7 0 1 0.2107973 0.9775287 -0.001498818 0.2270961 0.973872 -8.46645e-4 0.224807 0.9744033 4.95147e-4 0.251164 0.9677178 0.02095168 0.2580226 0.5792901 0.7732059 0.2667366 0.395772 0.8787583 0.4753565 0.2733981 0.8362355 0.9496214 0.3133754 0.003857493 0.9607328 0.277472 -0.001323401 0.9562013 0.292495 -0.01122689 0.6220455 0.06047934 0.7806419 0.8580366 0.2619209 0.4417812 0.369926 -0.09841585 0.9238339 0.7339547 -0.6791873 0.003884017 0.7964383 -0.6047193 -8.50588e-4 0.6841658 -0.7288396 -0.02664631 0.7309627 -0.6814317 0.03666847 0.2215881 -0.4539452 0.8630368 0.1336962 -0.4479646 0.8839983 0.00289011 -0.6285318 0.7777785 -0.2276434 -0.9737438 0.001275241 -0.2299822 -0.9731948 -3.31171e-4 -0.2248059 -0.9743995 0.002840638 -0.1914306 -0.9812211 -0.02365225 -0.2843444 -0.3220943 0.902997 -0.5715131 -0.2946746 0.7658588 -0.3757675 -0.2879865 0.8808307 -0.2477846 -0.5314291 0.8100531 -0.9629663 -0.2696221 -3.10683e-4 -0.9484049 -0.3170605 9.68321e-4 -0.9561371 -0.2924755 -0.01612496 -0.635643 -0.07512909 0.7683188 -0.4717097 0.02843308 0.8812955 -0.4234886 0.09770631 0.9006171 -0.4369142 0.1786518 0.8815836 -0.7416577 0.6707729 0.002762436 -0.6401291 0.7648339 0.07255196 -0.6543767 0.7561681 0.001101374 -0.7308741 0.6813483 0.0398454 -0.7831816 0.6206774 -0.03723126 -0.1325682 0.3585456 0.9240513 0.02438253 0.6489267 0.7604603 0.1921248 0.8711761 0.451819 7.63773e-4 -6.86329e-4 0.9999995 0.008560061 -0.005353569 0.999949 -0.07704061 -0.197713 0.9772279 -9.19351e-4 -9.751e-4 0.9999992 -0.002324938 6.57001e-4 0.9999971 0.006663739 -0.005010426 0.9999653 0.001267373 -0.00102657 0.9999988 -0.003006756 1.35348e-4 0.9999955 0.001043498 0.001295566 0.9999987 0.00213176 6.03439e-4 0.9999976 0.003809869 -0.002020537 0.9999907 0.003103196 -4.85738e-4 0.9999951 -0.003915548 0.002144634 0.9999901 -0.01105421 0.001481473 0.9999378 0.002502918 -1.53583e-4 0.999997 -0.007613241 0.003104746 0.9999663 0.001063168 -6.41316e-5 0.9999995 5.27507e-4 0.001138269 0.9999993 0.218432 0.04631012 0.9747528 0.002735495 -0.001030087 0.9999958 -1.76242e-4 -0.00470823 0.9999889 0.00107938 -2.49484e-4 0.9999995 -0.004459083 -0.003678143 0.9999833 0.007461845 0.01179623 0.9999026 0.005765736 -0.003523528 0.9999772 -0.00515908 -0.00900495 0.9999462 8.97874e-4 -6.94808e-4 0.9999994 8.04461e-4 6.16019e-4 0.9999995 7.38207e-4 7.93537e-4 0.9999994 6.19939e-4 9.41155e-4 0.9999995 -0.002476274 -0.00723201 0.9999708 -0.005138337 0.005112886 0.9999737 0.5873765 -0.6473843 0.4856773 -0.008450448 -0.6054198 0.7958615 -0.1734476 -0.8184326 0.5477992 -0.466836 -0.4324738 0.7713822 -0.6993101 -0.4537893 0.5523049 -0.6168798 0.03405272 0.7863204 -0.8688508 0.3611564 0.3386215 -0.4339087 0.3821228 0.8159078 -0.03502404 0.8544123 0.5184139 -0.02532333 0.83602 0.5481145 0.333498 0.5167115 0.7885357 0.6398283 0.5333781 0.5532881 0.5860362 0.1942952 0.7866455 0.8433856 0.04320442 0.535569 0.4762126 -0.3503023 0.8065419 0.8042024 -0.5912274 -0.06089878 0.9980992 0.0379315 0.04857355 0.9486237 0.3134575 -0.04309862 0.7977671 0.6023078 0.02816301 0.5449454 0.8379984 -0.02816438 0.2462302 0.9682527 0.04310005 -0.03207927 0.9983044 -0.04857414 -0.6461199 0.760803 0.06089353 -0.7480973 0.663461 -0.01304477 -0.9985161 0.05139356 -0.01801174 -0.9990133 -0.03803074 0.02293556 -0.798115 -0.6024923 0.003933966 -0.7352849 -0.6767932 -0.03615486 -0.2462455 -0.968292 0.04211825 -0.01071721 -0.9984112 -0.05532139 0.6461116 -0.7608096 0.06089848 -0.7699189 -0.05901175 -0.6354073 -0.8359937 -0.03330761 -0.5477272 -0.4919048 -0.3687415 -0.7887074 -0.466902 -0.7656248 -0.4425171 -0.1469768 -0.5754 -0.8045575 0.3260728 -0.8203217 -0.4698391 0.3557615 -0.4186511 -0.8355627 0.8415243 -0.3192902 -0.4357646 0.5792597 0.02421629 -0.8147833 0.7224855 0.4177695 -0.5508933 0.5659965 0.4249435 -0.7064495 0.1916458 0.7202718 -0.6666937 0.1804203 0.7072687 -0.6835347 -0.453487 0.533756 -0.7137607 -0.470892 0.5897172 -0.6561208 6.23785e-4 -0.001609146 -0.9999985 -0.001483678 -3.43482e-4 -0.9999989 -0.001607716 -4.91846e-4 -0.9999986 -7.93005e-4 -9.4767e-4 -0.9999992 -4.37135e-4 -0.001894474 -0.9999982 0.001799643 5.50121e-4 -0.9999983 -3.21378e-4 0.001145839 -0.9999993 1.44621e-4 6.26196e-4 -0.9999999 0.001810669 0.002318382 -0.9999957 0.001597583 -4.76073e-4 -0.9999987 4.03428e-4 -3.75441e-4 -0.9999999 -0.001119554 0.001043081 -0.9999989 -0.00134015 0.001814246 -0.9999976 -0.9808933 0.1921477 0.03045845 -0.9937925 -0.1082119 -0.02582031 -0.9245618 -0.3801563 0.02582025 -0.8038027 -0.5945516 -0.02024096 -0.5015102 -0.8650562 0.01287037 -0.5162739 -0.8563944 0.007077753 -0.006126642 -0.9999562 -0.007078826 0.04102098 -0.9991189 0.008886456 0.5688567 -0.8223969 -0.008096933 0.6025491 -0.798072 0.003966152 0.8651232 -0.5015477 -0.003448367 0.8835552 -0.4682929 0.005647599 0.9999563 -0.006129562 -0.00707823 0.9991188 0.04102301 0.008886098 0.7895621 0.6135939 -0.009716749 0.7579439 0.6522474 0.009716868 0.2382799 0.9711559 -0.008886098 0.1922335 0.9813238 0.00707823 -0.3362477 0.941747 -0.007077991 -0.3200588 0.9473103 -0.01287072 -0.693143 0.7204415 0.02274018 -0.8461238 0.5317651 -0.03606355 9.49974e-7 0 -1 -1.53872e-6 0 -1 1.11446e-6 0 -1 1.56853e-6 0 -1 -1.39964e-6 0 -1 -1.48078e-6 0 -1 0.9994741 0.01259648 0.02988314 0.8213909 0.5697267 -0.02699011 0.7092369 0.7048857 0.01091986 0.06344413 0.9979834 -0.002004683 -0.002270519 0.999828 -0.01841199 -0.584127 0.8114364 0.01915287 -0.7980439 0.6021863 -0.02231168 -0.942663 0.3332353 0.01846355 -0.9971137 -0.07285159 -0.02137666 -0.8592336 -0.5110481 0.02339851 -0.7744247 -0.632611 -0.008359074 -0.1080093 -0.9941076 0.009168982 -0.04226022 -0.99908 -0.007303237 0.6456835 -0.7635704 0.007302641 0.6264638 -0.7793335 0.0135073 0.9603281 -0.2779133 -0.0231142 -1.45461e-6 0 1 7.96622e-7 0 1 2.24084e-6 0 1 -2.10753e-6 0 1 1.90543e-6 0 1 -7.88208e-7 0 1 -1.47714e-6 0 1 1.57616e-6 0 1 3.18619e-6 0 1 0.8710378 -0.4912161 2.76839e-5 0.8649961 -0.5017634 -0.003939688 0.8660219 -0.4999983 -0.002841413 0.847109 -0.5308175 0.02528274 0.486338 0.002820491 -0.8737662 0.5336615 -0.125944 -0.8362677 0.5184938 0.08849495 -0.8504899 0.8698713 0.493279 -1.26568e-5 0.8690382 0.4947451 -3.48979e-5 0.859054 0.5118094 -0.008796513 0.8660218 0.4999983 0.002841413 0.2021245 0.3582984 -0.9114648 -0.005689144 0.9999839 0 0.01037043 0.9999461 6.86503e-4 -0.007019519 0.9999753 5.67982e-4 0 0.9999884 -0.004828989 -0.01387828 0.9998252 -0.01253664 -0.1313912 0.632384 -0.763431 -0.2310316 0.4063955 -0.8840063 -0.3155965 0.3940261 -0.8632163 -0.8722978 0.4889753 2.66728e-5 -0.8538903 0.5204517 -0.001234114 -0.8659781 0.4999718 0.01050049 -0.4863346 -0.002830207 -0.8737682 -0.5201054 -0.09308189 -0.8490148 -0.5548885 0.1950011 -0.8087481 -0.8670927 -0.4981394 -0.00273925 -0.8647066 -0.5022774 -3.72779e-5 -0.9059079 -0.4212521 0.04333239 -0.8597218 -0.5107426 0.004524946 -0.8660148 -0.4999927 -0.005067169 -0.199222 -0.3685718 -0.9080008 -0.4465975 -0.4209609 -0.7895205 -0.1181039 -0.6499196 -0.7507702 -0.008640468 -0.8921052 -0.4517451 0.02242666 -0.9997477 0.001264035 -0.0232042 -0.9997305 7.4616e-4 0 -0.9998699 0.01613306 0.1159324 -0.6385908 -0.7607638 0.03378689 -0.8398514 -0.5417639 -0.5373269 0.7664311 -0.3519423 0.2224745 -0.3159153 -0.9223355 3.25911e-4 -0.002625346 -0.9999966 4.47478e-4 -0.006637096 -0.999978 0.02467572 0.009603202 -0.9996495 -0.02860176 0.01402515 -0.9994926 -3.47358e-4 9.82539e-4 -0.9999995 0.01158326 0.002482295 -0.9999299 -0.001923739 0.003904521 -0.9999905 7.34755e-4 6.18647e-4 -0.9999996 -1.24728e-4 0.009939789 -0.9999506 4.87669e-4 0.01242506 -0.9999228 -0.004791021 -0.003522396 -0.9999824 0.003107786 7.34675e-4 -0.999995 -0.01390534 -7.04758e-4 -0.9999031 0.002108097 -0.004771471 -0.9999864 0.005442619 -0.00364381 -0.9999786 0.008062958 0.004379212 -0.9999579 -0.00251168 5.22748e-4 -0.9999967 -0.002675056 0.003005564 -0.999992 0.005540132 0.008859753 -0.9999455 0.007130622 0.004072844 -0.9999663 0.002830862 -0.005218148 -0.9999824 0.002675056 -0.003005623 -0.999992 -0.009125232 0.008739173 -0.9999202 0.01838874 -0.001569211 -0.9998297 -0.01028221 0.0116744 -0.9998791 -0.07300537 0.8710827 -0.4856803 -0.4485908 0.4066498 -0.7958658 -0.846427 0.4146823 -0.3340656 -0.5416321 -0.03927952 -0.8396975 -0.7593653 -0.5661297 -0.3207204 -0.4227869 -0.5064942 -0.7514751 -0.01924252 -0.7034167 -0.7105173 0.07300597 -0.8710896 -0.4856677 0.4485911 -0.4066521 -0.7958644 0.8464327 -0.414677 -0.334058 0.5416321 0.03928101 -0.8396975 0.759365 0.5661315 -0.3207181 0.4227839 0.5064868 -0.7514819 0.01923769 0.7034272 -0.710507 0.02483373 0.9996064 0.0130459 0.6432827 0.765417 0.01801067 0.7090389 0.7047963 -0.02293694 0.9849214 0.1729577 -0.003932774 0.9964272 0.07632756 0.03615349 0.8761764 -0.480147 -0.04211926 0.7375994 -0.6729686 0.05532217 0.1159275 -0.9913888 -0.06090205 -0.02483922 -0.9996063 0.01304882 -0.643288 -0.7654127 0.01800739 -0.7090377 -0.7047975 -0.02293795 -0.9849215 -0.1729572 -0.003932893 -0.9964271 -0.07632893 0.03615343 -0.8761743 0.4801506 -0.0421189 -0.7375981 0.67297 0.05532109 -0.1159203 0.9913899 -0.06089782 -0.6014208 -0.6088383 0.5173094 -0.5944159 -0.5887777 0.5477322 -0.6051414 -0.108368 0.788708 -0.8783981 0.1805593 0.4425103 -0.5211094 0.2848498 0.8045531 -0.3242401 0.8716272 0.3676064 -0.06564515 0.5629035 0.8239117 0.6014136 0.6088461 0.5173086 0.5944191 0.5887809 0.5477252 0.6051426 0.108362 0.7887079 0.8783985 -0.180555 0.4425109 0.5211117 -0.2848501 0.8045515 0.3242444 -0.8716273 0.3676022 0.0656439 -0.5628978 0.8239157 0.00211358 -8.79135e-4 0.9999974 0 -0.004263818 0.999991 -0.001233339 6.69594e-5 0.9999992 -0.001681387 9.71347e-4 0.9999982 0.001230239 -6.69536e-5 0.9999994 0.001681387 -9.71346e-4 0.9999982 -0.003359019 -7.6224e-4 0.9999941 -0.001457571 -8.40723e-4 0.9999986 -0.002112329 8.79134e-4 0.9999974 0 0.004263818 0.999991 0.003361701 7.62229e-4 0.9999942 0.001457095 8.40721e-4 0.9999986 0.4889763 0.8722971 2.82781e-5 0.5249384 0.8511317 -0.003832936 0.4999724 0.8659778 0.01050096 -0.002803802 0.4863414 -0.8737644 0.1949885 0.5548858 -0.8087529 -0.09442472 0.5205628 -0.8485862 -0.4985712 0.8668436 -0.003004908 -0.4854969 0.8742384 -3.454e-5 -0.5342144 0.8449679 -0.02538043 -0.499984 0.8659963 0.008153796 0.7504354 -0.5242786 -0.4024659 -0.3179541 0.221374 -0.9218996 -0.8370156 0.03921186 -0.5457722 -0.6465467 0.117742 -0.7537335 -0.9995637 -0.02934515 -0.003367781 -0.9997333 0.02308249 7.70954e-4 -0.9998707 0 0.01607978 -0.4355379 -0.165278 -0.8848673 -0.6314116 -0.1150037 -0.7668726 -0.3957393 -0.4290386 -0.811983 -0.3583093 -0.2923896 -0.8866357 -0.5028728 -0.8643605 2.89005e-5 -0.4999995 -0.8660241 0.001635968 -0.49479 -0.8689844 -0.007005989 0.002808213 -0.486337 -0.8737668 0.09309369 -0.5201022 -0.8490155 -0.191603 -0.5539067 -0.8102319 0.5022822 -0.8647038 -3.7278e-5 0.4940344 -0.8694407 -0.00173819 0.5116451 -0.8591823 0.005016386 0.4999923 -0.8660126 -0.005476474 0.7429468 -0.07483381 -0.6651542 0.3970941 -0.4479515 -0.8010342 0.3474096 -0.2771594 -0.8958176 0.4264968 -0.1340668 -0.894498 0.9999959 -0.002510786 0.001397669 0.9999998 0 6.09464e-4 0.9999995 8.66733e-4 -6.39529e-4 0.6612832 0.1082763 -0.7422808 0.4390071 0.1725205 -0.8817651 0.372854 0.2928916 -0.8804513 -0.001031875 1.95632e-5 -0.9999995 -0.002285063 -2.97662e-4 -0.9999973 0.007751464 -0.02242314 -0.9997186 -0.001086652 -6.25382e-4 -0.9999992 -0.001134872 -4.23752e-4 -0.9999993 -0.001116812 -2.15619e-4 -0.9999994 -8.09885e-4 6.77489e-4 -0.9999995 -0.001526355 3.81121e-4 -0.9999988 0.01312524 -0.02028924 -0.999708 -0.002907574 0.007642805 -0.9999666 -0.001057684 2.04992e-4 -0.9999995 -0.001040399 3.89637e-4 -0.9999995 -9.61389e-4 5.54088e-4 -0.9999995 -0.00364536 -0.005443394 -0.9999786 0.004378259 -0.008070468 -0.9999579 -0.004776298 -0.002104938 -0.9999865 8.97809e-4 -0.002414226 -0.9999967 0.001666367 0.006580591 -0.999977 0.008696079 8.3233e-4 -0.9999619 0.005407452 0.009036839 -0.9999446 -0.02009719 0.01416105 -0.9996978 -0.001329779 0.002243161 -0.9999966 -0.006205379 -0.002893149 -0.9999766 -0.002984583 -0.002677023 -0.999992 0.01044481 -0.001375317 -0.9999446 0.002992808 -0.002352833 -0.9999927 0.005222022 0.002826869 -0.9999824 0.002984523 0.002676486 -0.999992 0.008075892 0.009203612 -0.9999251 7.64698e-4 0.01213532 -0.9999261 -0.008169889 -0.007560193 -0.9999381 -0.8710799 -0.07300841 -0.4856847 -0.4066445 -0.4485996 -0.7958635 -0.4146728 -0.8464346 -0.3340584 0.0392735 -0.5416299 -0.8396992 0.5661361 -0.7593532 -0.3207376 0.5064756 -0.4227979 -0.7514817 0.7034265 -0.01923882 -0.7105076 0.8710799 0.07300841 -0.4856847 0.4066475 0.4486009 -0.7958613 0.4146724 0.8464349 -0.3340581 -0.03927928 0.5416328 -0.839697 -0.5661392 0.7593573 -0.3207225 -0.5064659 0.4227989 -0.7514876 -0.7034259 0.01923751 -0.7105082 -0.9996065 0.02483379 0.0130462 -0.7654161 0.6432836 0.01801127 -0.7048015 0.7090338 -0.02293515 -0.1729508 0.9849227 -0.003931045 -0.07632666 0.9964273 0.03615283 0.4801492 0.8761751 -0.04211914 0.6729663 0.7376016 0.05532139 0.9913899 0.1159207 -0.06089848 0.9996065 -0.02483379 0.01304626 0.7654151 -0.6432849 0.01801073 0.7047986 -0.7090366 -0.02293521 0.1729558 -0.9849218 -0.003932535 0.07632762 -0.9964272 0.03615492 -0.4801498 -0.8761749 -0.04211777 -0.6729652 -0.7376024 0.05532228 -0.9913901 -0.1159191 -0.06089764 0.6088405 -0.6014174 0.5173107 0.5887706 -0.5944238 0.5477313 0.1083647 -0.6051375 0.7887116 -0.1805583 -0.8783968 0.4425134 -0.2848629 -0.5211021 0.8045532 -0.8716354 -0.324232 0.367594 -0.5628905 -0.0656473 0.8239203 -0.6088417 0.6014186 0.517308 -0.5887706 0.5944288 0.5477258 -0.1083641 0.6051399 0.7887098 0.1805604 0.8783956 0.4425145 0.2848564 0.5211036 0.8045545 0.8716297 0.3242358 0.3676043 0.5628985 0.06564837 0.8239148 8.77454e-4 0.002110779 0.9999974 0.004266381 0 0.999991 -7.14558e-5 -0.001234054 0.9999992 -9.70477e-4 -0.0016824 0.9999982 6.67955e-5 0.001234054 0.9999992 9.72944e-4 0.0016824 0.9999982 7.63665e-4 -0.003362774 0.999994 8.44162e-4 -0.001456141 0.9999986 -8.80033e-4 -0.002110779 0.9999974 -0.004262387 0 0.999991 -7.63666e-4 0.003362774 0.9999941 -8.40322e-4 0.001456141 0.9999986 -0.1921491 -0.980893 0.0304594 0.1082126 -0.9937925 -0.02582055 0.3801547 -0.9245625 0.02582073 0.5945515 -0.8038028 -0.02024096 0.8650566 -0.5015091 0.01287066 0.8563941 -0.5162744 0.007077872 0.9999563 -0.006129562 -0.00707823 0.9991188 0.04102301 0.008886158 0.8223977 0.5688554 -0.008096933 0.7980706 0.6025509 0.003966391 0.5015487 0.8651226 -0.003448367 0.4682934 0.8835551 0.005647242 0.006126642 0.9999563 -0.007078826 -0.04102092 0.9991189 0.008886456 -0.6135941 0.7895619 -0.009715616 -0.6522472 0.7579441 0.009716331 -0.9711556 0.2382811 -0.008886337 -0.9813237 0.1922339 0.00707817 -0.9417468 -0.3362482 -0.007078409 -0.9473102 -0.3200591 -0.0128709 -0.72044 -0.6931444 0.02274018 -0.5317653 -0.8461236 -0.03606361 1.89993e-6 0 -1 -7.69361e-7 0 -1 -1.63942e-6 0 -1 2.76357e-6 0 -1 -1.88541e-6 0 -1 1.0939e-6 0 -1 -8.70598e-7 0 -1 -0.01259672 0.999474 0.02988398 -0.5697237 0.8213931 -0.02699017 -0.704885 0.7092376 0.0109201 -0.9979835 0.0634424 -0.002004384 -0.9998279 -0.002272486 -0.01841241 -0.8114367 -0.5841265 0.01915282 -0.6021865 -0.7980437 -0.02231115 -0.333235 -0.9426631 0.01846325 0.07284986 -0.9971139 -0.0213769 0.5110488 -0.8592332 0.02339828 0.6326106 -0.774425 -0.008359074 0.9941074 -0.1080112 0.00916928 0.9990802 -0.04225498 -0.007303059 0.7635717 0.6456819 0.007302641 0.7793334 0.626464 0.01350772 0.2779096 0.9603291 -0.02311372 -1.36945e-6 0 1 -1.88472e-6 0 1 -1.05377e-6 0 1 1.55351e-6 0 1 3.81084e-6 0 1 8.3797e-7 0 1 3.38353e-6 0 1 -2.9543e-6 0 1 1.57616e-6 0 1 0.2377832 -0.9709751 0.02582061 0.4678141 -0.8835951 -0.02024126 0.7977216 -0.602836 0.01513862 0.7892929 -0.6139401 0.009716868 0.9998698 -0.01289242 -0.00971651 0.9999808 0.005685627 -0.002487063 0.865303 0.5011452 0.01020312 0.7918663 0.6103435 -0.02070951 0.5691137 0.8219952 0.02082377 0.3244543 0.9454109 -0.0304585 -0.03701734 0.9986637 0.0360642 -0.2769267 0.960622 -0.02273947 -0.6600344 0.7511252 0.01287031 -0.6219969 0.7830098 -0.003932297 -0.9084848 0.4177978 0.01002007 -0.9361798 0.351351 -0.01094681 -0.9905121 -0.1374212 0.001110374 -0.9891049 -0.1471588 0.003965795 -0.8543939 -0.5196146 -0.003448665 -0.8160354 -0.5778506 0.01322984 -0.5084986 -0.8608088 -0.02091813 -0.336575 -0.9413564 0.02377736 -0.009967386 -0.9997489 -0.02007299 -8.51781e-7 0 -1 4.66057e-7 0 -1 4.65031e-7 0 -1 1.11212e-6 0 -1 -1.03758e-6 0 -1 -0.5932646 0.8050066 -0.001299977 -0.6037026 0.7971991 -0.004094064 -0.9464795 0.3227382 0.004094719 -0.9635982 0.2672243 -0.008358895 -0.853662 -0.520731 0.01002448 -0.8152315 -0.5790486 -0.01002466 -0.09689706 -0.9952523 0.009169518 0.01343971 -0.9997403 -0.01841253 0.6540093 -0.7561171 0.02363908 0.804697 -0.5932151 -0.02363914 0.9995892 0.02377039 0.01601755 0.9915184 0.1298026 -0.006540298 0.7013416 0.7127954 0.006540238 0.6901575 0.723652 0.003234922 0.1491264 0.9887665 -0.01010471 0.05228817 0.9985724 0.01091969 2.32012e-6 0 1 -6.57926e-7 0 1 9.29506e-7 0 1 8.80601e-7 0 1 0.009851992 0.005428731 0.9999368 0.005450546 0.01327174 0.9998971 -6.80755e-4 0.009462177 0.999955 -0.005985915 0.01230674 0.9999064 -0.009222447 0.005159318 0.9999442 -0.009635925 0.005064308 0.9999408 -0.01155954 -0.002459228 0.9999302 0.0107733 -0.006374597 0.9999217 0.01037186 -0.005687117 0.9999301 0.01268279 0.004979014 0.9999072 -0.008375227 -0.004674196 0.9999541 -0.00886166 -0.01096659 0.9999006 7.08646e-4 -0.01151108 0.9999336 0.001982092 -0.0131433 0.9999117 -0.01250112 0.03418189 -0.9993375 -0.01598495 0.02312606 -0.9996048 -0.0287649 0.01924127 -0.999401 0.02287518 0.03175556 -0.9992339 0.009386897 0.03028243 -0.9994974 0.004821419 0.03622984 -0.999332 -0.02537357 0.0084818 -0.9996421 -0.03187221 -0.001560628 -0.9994907 -0.02065545 -0.01240587 -0.9997098 -0.06156045 -0.006929755 -0.9980794 -0.01830428 -0.0300551 -0.9993807 0.003656148 -0.020554 -0.9997821 9.43168e-4 -0.01922422 -0.9998148 0.006691515 -0.01114225 -0.9999156 0.004680395 -0.0370413 -0.9993029 0.02322494 -0.01525396 -0.999614 0.0238009 -0.01748609 -0.9995638 0.03683567 -0.00490278 -0.9993094 0.03117758 0.01140403 -0.9994488 0.02883869 0.01204127 -0.9995116 0.8840707 -0.467319 -0.005655586 0.8967596 -0.4425079 -0.003015339 0.4928514 -0.8701095 -0.002656102 0.4462389 -0.8948826 -0.00748372 0.1831021 -0.9830937 -6.2216e-4 -0.2173548 -0.9760769 -0.005555987 -0.3027843 -0.9529804 -0.01224511 -0.5908302 -0.8067927 0.002310156 -0.8560539 -0.5168516 -0.006019115 -0.8316128 -0.5553534 -0.001672983 -0.9999881 -0.004644751 -0.001476764 -0.9981104 0.0609892 -0.007484078 -0.840012 0.5425429 0.005203723 -0.6739194 0.7387116 -0.01173961 -0.4507382 0.8926497 0.003416359 -0.01957553 0.9997903 -0.006019055 -0.06514811 0.9978742 -0.001673102 0.4959771 0.8683344 -0.001476764 0.5518748 0.8338935 -0.007483899 0.878754 0.4772526 0.004619061 0.9766935 0.2142615 -0.01272714 0.9984793 -0.05502134 0.003436625 -0.007356107 -0.002127647 -0.9999707 -0.002623975 0.004113554 -0.9999882 0.00314629 3.79606e-4 -0.999995 -0.002213358 5.85971e-4 -0.9999974 0.9391281 0.3435 -0.006795644 0.9271234 0.3746035 0.01070654 0.5844689 0.8113435 -0.01086181 0.5576972 0.8300197 0.006431519 0.1319309 0.9912415 -0.005895733 0.1051824 0.9944381 0.005442619 -0.3434995 0.9391283 -0.006793379 -0.3746016 0.9271241 0.01070588 -0.831134 0.5559396 -0.01214939 -0.8299431 0.5576853 -0.01348274 -0.994165 0.1051505 0.02407628 -0.9982426 -0.04888421 -0.03349697 -0.926698 -0.374396 0.03253298 -0.8569855 -0.5147286 -0.02510923 -0.5200251 -0.8540225 0.01481592 -0.5576856 -0.8299427 -0.0134837 -0.1051523 -0.9941647 0.02407568 0.04888474 -0.9982426 -0.03349608 0.3743969 -0.9266977 0.03253251 0.5147275 -0.8569861 -0.02510976 0.8357893 -0.5489194 0.01199597 0.8300192 -0.5576977 0.006431639 0.9912415 -0.1319305 -0.00589478 0.9944382 -0.1051812 0.00544089 -0.8902945 0.0941652 0.4455431 -0.4629956 0.2704166 0.8441031 -0.5415799 0.3625186 0.7584666 -0.3183577 0.7899762 0.5240097 -0.07025122 0.4828508 0.8728802 0.08627402 0.8156623 0.5720595 0.4311147 0.6433154 0.6326812 0.3490032 0.4012058 0.8468947 0.8043988 0.3242213 0.4978185 0.583591 0.1033724 0.8054413 0.8001567 -0.08463174 0.5937903 0.5291767 -0.2157382 0.8206272 0.7330773 -0.4917172 0.4699062 0.2375884 -0.5524606 0.7989613 0.2431541 -0.6047956 0.7583524 -0.08507663 -0.8043772 0.5879961 -0.1778299 -0.4949824 0.850511 -0.4917167 -0.7330722 0.4699149 -0.5505257 -0.2128387 0.8072307 -0.5217866 -0.2094991 0.8269516 0.8404796 0.177679 -0.5118832 0.4198353 0.6462501 -0.6372591 0.188556 0.481273 -0.8560508 -0.05566316 0.8187085 -0.571505 -0.3557029 0.5344001 -0.7667411 -0.5335314 0.5962619 -0.5998467 -0.5651178 0.1324616 -0.8143069 -0.8158548 0.04392778 -0.576586 -0.6372244 -0.4285224 -0.6405574 -0.3786017 -0.3924455 -0.8382406 -0.2711145 -0.8329581 -0.4823669 0.1226869 -0.5103655 -0.851161 0.3698929 -0.7285172 -0.5765779 0.68972 -0.3375878 -0.6405629 0.4696613 -0.06678253 -0.8803173 0.840546 0.5107779 0.1805225 -0.02147942 0.9832725 0.1808702 -0.8624302 0.4725955 0.1812946 -0.8400449 -0.5112235 0.1815908 0.02152597 -0.9832142 0.1811809 0.8621354 -0.4726568 0.1825324 0.4711011 -0.2689419 0.8400799 -0.4718193 0.2636306 0.8413594 0.00797367 0.539434 0.8419901 0.4711034 0.2689371 0.8400802 0.007989466 -0.5394316 0.8419916 -0.4718177 -0.2636312 0.84136 0.8682649 0.4960994 0.00130552 0.8412514 0.5397433 0.03119856 0.8667107 0.4988107 -7.44232e-4 0.005188584 0.9999843 0.002137362 -0.04588574 0.9984067 0.03284204 0.002739608 0.9999962 5.37196e-4 -0.8637288 0.5039469 0.003194153 -0.8879127 0.4588527 0.03263777 -0.8653143 0.5012285 0.001107752 -0.8678132 -0.4968712 0.004407405 -0.8408782 -0.5402929 0.03174084 -0.8653134 -0.50123 0.001116693 -0.004690289 -0.999974 0.005486547 0.04660874 -0.9984895 0.02909559 0.002760767 -0.9999961 5.34788e-4 0.8635148 -0.5043116 0.003475904 0.8882502 -0.4584231 0.02932322 0.8667125 -0.4988076 -7.46066e-4 -0.4878568 -0.6676113 -0.5623976 0.7219215 -0.3539032 -0.5946275 -0.5991236 -0.3624536 -0.7139176 -0.5096058 -0.7698607 -0.384209 -0.01408606 0.6868768 -0.7266374 -0.4009701 0.7786532 -0.4826202 -0.399561 0.7991571 -0.4491092 0.8204513 -0.4685672 -0.3275736 0.6538701 -0.002615928 -0.7566023 0.3551707 -0.5057665 -0.7861642 0.2342538 -0.6980649 -0.6766318 0.1851975 -0.9826671 0.008205235 -0.08732998 -0.4949772 -0.8645063 -0.8681012 -0.2237729 -0.4430869 -0.7009496 -0.002183079 -0.7132075 -0.8516787 0.3101793 -0.4224123 -0.5840604 0.3707648 -0.7220852 0.2956165 0.893312 -0.3385331 0.3584538 0.6254709 -0.6930347 0.7961548 0.4118826 -0.4432722 0.8878884 0.4012392 -0.2250805 -0.9845806 0.1705179 0.03904855 -0.9993045 0.02376127 -0.02873951 -0.8819231 -0.4702942 0.03217256 -0.8357927 -0.5487672 -0.01747655 -0.4475328 -0.8942637 0.00262928 -0.4071704 -0.9129708 0.02639663 0.006779551 -0.9995814 -0.0281257 0.2393283 -0.9700778 0.04088038 0.3835906 -0.9233766 -0.01529717 0.7402998 -0.672275 0.001634478 0.7665168 -0.6419126 0.02001368 0.9390513 -0.3431323 -0.02104586 0.9787931 -0.2037677 0.02104669 0.9959049 0.08933532 -0.01387834 0.9774273 0.2100301 0.02287656 0.8882118 0.4583598 -0.03140538 0.7244315 0.6888257 0.02679836 0.5664008 0.8234992 -0.03224152 0.3586212 0.9327544 0.03688067 0.02316641 0.9990511 -0.03688114 -0.2105541 0.9770504 0.03224104 -0.4079352 0.9126175 -0.02679848 -0.691816 0.7207518 0.04367613 -0.8376098 0.5445201 -0.04367578 0.9421131 -0.335038 0.01314336 0.9608342 -0.2769263 -0.01046794 0.9007411 0.4342016 0.01159864 0.8713994 0.4902913 -0.01666444 0.1207708 0.9925182 0.01794928 0.05435132 0.9983995 -0.01563262 -0.7034451 0.710628 0.01314288 -0.7455271 0.6663932 -0.01046693 -0.999194 0.03875398 0.01046788 -0.9998168 0.01893895 0.002802968 -0.7933991 -0.6084964 -0.01580721 -0.7348052 -0.6781215 0.01457941 -0.2549849 -0.966934 -0.00461632 -0.2409342 -0.9704962 -0.009376704 0.3986212 -0.917056 0.01046794 0.45383 -0.8909914 -0.01314288 -0.005430519 0.009850859 0.9999368 -0.01327502 0.005452513 0.9998971 -0.009462893 -6.83257e-4 0.999955 -0.01230591 -0.005984127 0.9999065 -0.00515896 -0.009223639 0.9999442 -0.005063176 -0.009638786 0.9999408 0.00245881 -0.011559 0.9999303 0.006369948 0.0107727 0.9999217 0.005690276 0.01037311 0.99993 -0.004976689 0.01268094 0.9999073 0.004670023 -0.008374929 0.9999541 0.01096504 -0.008860051 0.9999007 0.01151216 7.05133e-4 0.9999336 0.01314598 0.001984655 0.9999117 -0.03418475 -0.01250243 -0.9993374 -0.02312403 -0.01598429 -0.9996049 -0.01924061 -0.02876585 -0.999401 -0.03175562 0.02287584 -0.9992339 -0.03028035 0.009385108 -0.9994975 -0.03623384 0.004822134 -0.9993318 -0.008482694 -0.0253756 -0.9996421 0.001561999 -0.03186815 -0.9994909 0.01240521 -0.02065503 -0.9997097 0.006927788 -0.06155776 -0.9980795 0.03005677 -0.01830095 -0.9993807 0.02055084 0.003654897 -0.9997822 0.01923096 9.41345e-4 -0.9998147 0.01114785 0.00669229 -0.9999155 0.03703546 0.00468105 -0.9993031 0.01525771 0.0232259 -0.9996139 0.01748496 0.02380239 -0.9995638 0.004902005 0.03683674 -0.9993093 -0.01140505 0.03117853 -0.9994488 -0.01204258 0.02884024 -0.9995115 0.4673203 0.88407 -0.005655288 0.4425104 0.8967584 -0.003015816 0.8701089 0.4928525 -0.002655625 0.8948813 0.4462414 -0.007483839 0.9830963 0.1830887 -6.22441e-4 0.9760785 -0.2173473 -0.005555987 0.9529792 -0.3027884 -0.01224523 0.8067978 -0.5908232 0.002309799 0.5168475 -0.8560564 -0.006018579 0.5553567 -0.8316106 -0.00167346 0.004641056 -0.9999881 -0.001476764 -0.06098872 -0.9981104 -0.007484138 -0.5425457 -0.8400102 0.005203723 -0.7387095 -0.6739218 -0.01173979 -0.89265 -0.4507376 0.00341624 -0.9997903 -0.01957678 -0.006018877 -0.9978743 -0.06514614 -0.001673221 -0.868335 0.495976 -0.001476764 -0.8338947 0.5518729 -0.007483959 -0.4772475 0.8787568 0.004618763 -0.2142629 0.9766932 -0.01272684 0.05501782 0.9984795 0.003436505 0.002127707 -0.00735557 -0.9999707 -0.004115343 -0.002622187 -0.9999881 -3.79921e-4 0.003147423 -0.999995 -5.85808e-4 -0.002213716 -0.9999974 -0.3434989 0.9391285 -0.00679332 -0.374604 0.9271231 0.01070564 -0.8113433 0.5844693 -0.01086181 -0.8300176 0.5577002 0.006431102 -0.9912415 0.1319305 -0.005895495 -0.9944383 0.105181 0.005440831 -0.9391281 -0.3435 -0.006795167 -0.9271234 -0.3746035 0.0107057 -0.5559441 -0.8311309 -0.01214939 -0.557684 -0.8299439 -0.01348364 -0.1051518 -0.9941647 0.02407556 0.04888463 -0.9982426 -0.03349602 0.3743964 -0.9266979 0.03253167 0.514729 -0.8569853 -0.02510869 0.8540244 -0.520022 0.01481688 0.8299431 -0.5576853 -0.01348364 0.994165 -0.1051505 0.02407622 0.9982426 0.04888421 -0.03349691 0.9266983 0.3743954 0.03253293 0.8569856 0.5147286 -0.02510809 0.5489192 0.8357895 0.01199376 0.5576953 0.8300209 0.006432354 0.1319304 0.9912415 -0.005895793 0.1051819 0.9944381 0.005442619 -0.09416687 -0.8902961 0.4455397 -0.2704166 -0.462998 0.8441017 -0.3625198 -0.5415772 0.7584679 -0.789967 -0.3183583 0.5240232 -0.4828545 -0.07025092 0.8728783 -0.8156602 0.08627218 0.5720626 -0.643314 0.4311016 0.6326915 -0.4011938 0.349011 0.8468973 -0.3242252 0.8043943 0.4978234 -0.1033732 0.5835936 0.8054394 0.08463424 0.8001667 0.5937764 0.2157351 0.5291722 0.8206309 0.491724 0.7330748 0.4699031 0.5524534 0.2375923 0.7989651 0.6048014 0.2431551 0.7583475 0.8043701 -0.08507591 0.5880058 0.4949976 -0.1778268 0.8505029 0.7330762 -0.4917186 0.4699066 0.2128366 -0.5505247 0.8072319 0.2094985 -0.5217796 0.8269562 -0.1776809 0.8404741 -0.5118915 -0.6462462 0.4198391 -0.6372606 -0.4812768 0.1885577 -0.8560484 -0.8187051 -0.05566591 -0.5715097 -0.5344 -0.3557031 -0.7667412 -0.5962651 -0.5335304 -0.5998444 -0.1324628 -0.5651125 -0.8143105 -0.0439248 -0.8158543 -0.5765869 0.428525 -0.6372219 -0.6405581 0.3924474 -0.3786055 -0.8382381 0.8329575 -0.2711148 -0.4823678 0.5103709 0.1226893 -0.8511576 0.7285184 0.3698914 -0.5765774 0.3375906 0.6897193 -0.6405622 0.06678044 0.4696581 -0.8803191 -0.5107645 0.8405568 0.1805104 -0.9832666 -0.02148127 0.1809015 -0.4726026 -0.8624295 0.1812793 0.5112382 -0.840038 0.1815816 0.9832094 0.02152836 0.1812065 0.4726688 0.862129 0.1825314 0.2689417 0.4711013 0.8400799 -0.2636312 -0.4718186 0.8413596 -0.5394362 0.00797367 0.8419888 -0.2689394 0.4711024 0.8400799 0.5394328 0.007991671 0.8419907 0.2636306 -0.4718202 0.8413589 -0.4961025 0.8682631 0.00130552 -0.5397473 0.8412489 0.03119844 -0.4988056 0.8667137 -7.41802e-4 -0.9999843 0.005190193 0.002133905 -0.9984067 -0.04588848 0.03283768 -0.9999962 0.002741336 5.38928e-4 -0.5039485 -0.863728 0.003194153 -0.45885 -0.8879141 0.03263771 -0.5012279 -0.8653147 0.001110196 0.4968717 -0.8678129 0.004407405 0.5402914 -0.8408793 0.03174078 0.5012303 -0.8653132 0.001118481 0.999974 -0.004695057 0.005485236 0.9984898 0.04660284 0.02909421 0.9999961 0.002763032 5.35366e-4 0.5043129 0.863514 0.00347799 0.4584249 0.8882495 0.02931982 0.4988072 0.8667128 -7.44243e-4 0.667617 -0.4878487 -0.5623978 0.3538966 0.7219259 -0.5946263 0.3624549 -0.5991182 -0.7139215 0.7698621 -0.5096159 -0.3841928 -0.6868817 -0.01408714 -0.7266327 -0.7786496 -0.400972 -0.4826245 -0.7991638 -0.3995544 -0.4491032 0.4685764 0.8204413 -0.3275857 0.002616763 0.6538682 -0.756604 0.5057629 0.3551676 -0.7861679 0.698068 0.2342505 -0.6766298 0.9826655 0.1852054 0.008227348 0.4949607 -0.08733797 -0.8645149 0.2237719 -0.8681008 -0.4430884 0.002184629 -0.7009553 -0.7132018 -0.3101842 -0.8516851 -0.4223959 -0.37077 -0.5840612 -0.7220818 -0.8933067 0.295618 -0.3385455 -0.6254652 0.3584535 -0.69304 -0.4118798 0.7961578 -0.4432697 -0.4012339 0.8878903 -0.2250829 -0.009851992 -0.005428731 0.9999368 -0.005450546 -0.01327174 0.9998971 6.80755e-4 -0.009462177 0.999955 0.005985915 -0.01230674 0.9999064 0.009222447 -0.005159318 0.9999442 0.009635925 -0.005064308 0.9999408 0.01155954 0.002459228 0.9999302 -0.0107733 0.006374597 0.9999217 -0.01037186 0.005687117 0.9999301 -0.01268279 -0.004979014 0.9999072 0.008375227 0.004674196 0.9999541 0.00886166 0.01096659 0.9999006 -7.08646e-4 0.01151108 0.9999336 -0.001982092 0.0131433 0.9999117 0.01250112 -0.03418189 -0.9993375 0.01598495 -0.02312606 -0.9996048 0.0287649 -0.01924127 -0.999401 -0.02287518 -0.03175556 -0.9992339 -0.009386897 -0.03028243 -0.9994974 -0.004821419 -0.03622984 -0.999332 0.02537357 -0.0084818 -0.9996421 0.03187221 0.001560628 -0.9994907 0.02065545 0.01240587 -0.9997098 0.06156045 0.006929755 -0.9980794 0.01830428 0.0300551 -0.9993807 -0.003656148 0.020554 -0.9997821 -9.43168e-4 0.01922422 -0.9998148 -0.006691515 0.01114225 -0.9999156 -0.004680395 0.0370413 -0.9993029 -0.02322494 0.01525396 -0.999614 -0.0238009 0.01748609 -0.9995638 -0.03683567 0.00490278 -0.9993094 -0.03117758 -0.01140403 -0.9994488 -0.02883869 -0.01204127 -0.9995116 -0.8840707 0.467319 -0.005655586 -0.8967596 0.4425079 -0.003015339 -0.4928514 0.8701095 -0.002656102 -0.4462389 0.8948826 -0.00748372 -0.1831021 0.9830937 -6.2216e-4 0.2173548 0.9760769 -0.005555987 0.3027843 0.9529804 -0.01224511 0.5908302 0.8067927 0.002310156 0.8560539 0.5168516 -0.006019115 0.8316128 0.5553534 -0.001672983 0.9999881 0.004644751 -0.001476764 0.9981104 -0.0609892 -0.007484078 0.840012 -0.5425429 0.005203723 0.6739194 -0.7387116 -0.01173961 0.4507382 -0.8926497 0.003416359 0.01957553 -0.9997903 -0.006019055 0.06514811 -0.9978742 -0.001673102 -0.4959771 -0.8683344 -0.001476764 -0.5518748 -0.8338935 -0.007483899 -0.878754 -0.4772526 0.004619061 -0.9766935 -0.2142615 -0.01272714 -0.9984793 0.05502134 0.003436625 0.007356107 0.002127647 -0.9999707 0.002623975 -0.004113554 -0.9999882 -0.00314629 -3.79606e-4 -0.999995 0.002213358 -5.85971e-4 -0.9999974 -0.9391281 -0.3435 -0.006795644 -0.9271234 -0.3746035 0.01070654 -0.5844689 -0.8113435 -0.01086181 -0.5576972 -0.8300197 0.006431519 -0.1319309 -0.9912415 -0.005895733 -0.1051824 -0.9944381 0.005442619 0.3434995 -0.9391283 -0.006793379 0.3746016 -0.9271241 0.01070588 0.831134 -0.5559396 -0.01214939 0.8299431 -0.5576853 -0.01348274 0.994165 -0.1051505 0.02407628 0.9982426 0.04888421 -0.03349697 0.926698 0.374396 0.03253298 0.8569855 0.5147286 -0.02510923 0.5200251 0.8540225 0.01481592 0.5576856 0.8299427 -0.0134837 0.1051523 0.9941647 0.02407568 -0.04888474 0.9982426 -0.03349608 -0.3743969 0.9266977 0.03253251 -0.5147275 0.8569861 -0.02510976 -0.8357893 0.5489194 0.01199597 -0.8300192 0.5576977 0.006431639 -0.9912415 0.1319305 -0.00589478 -0.9944382 0.1051812 0.00544089 0.8902945 -0.0941652 0.4455431 0.4629956 -0.2704166 0.8441031 0.5415799 -0.3625186 0.7584666 0.3183577 -0.7899762 0.5240097 0.07025122 -0.4828508 0.8728802 -0.08627402 -0.8156623 0.5720595 -0.4311147 -0.6433154 0.6326812 -0.3490032 -0.4012058 0.8468947 -0.8043988 -0.3242213 0.4978185 -0.583591 -0.1033724 0.8054413 -0.8001567 0.08463174 0.5937903 -0.5291767 0.2157382 0.8206272 -0.7330773 0.4917172 0.4699062 -0.2375884 0.5524606 0.7989613 -0.2431541 0.6047956 0.7583524 0.08507663 0.8043772 0.5879961 0.1778299 0.4949824 0.850511 0.4917167 0.7330722 0.4699149 0.5505257 0.2128387 0.8072307 0.5217866 0.2094991 0.8269516 -0.8404796 -0.177679 -0.5118832 -0.4198353 -0.6462501 -0.6372591 -0.188556 -0.481273 -0.8560508 0.05566316 -0.8187085 -0.571505 0.3557029 -0.5344001 -0.7667411 0.5335314 -0.5962619 -0.5998467 0.5651178 -0.1324616 -0.8143069 0.8158548 -0.04392778 -0.576586 0.6372244 0.4285224 -0.6405574 0.3786017 0.3924455 -0.8382406 0.2711145 0.8329581 -0.4823669 -0.1226869 0.5103655 -0.851161 -0.3698929 0.7285172 -0.5765779 -0.68972 0.3375878 -0.6405629 -0.4696613 0.06678253 -0.8803173 -0.840546 -0.5107779 0.1805225 0.02147942 -0.9832725 0.1808702 0.8624302 -0.4725955 0.1812946 0.8400449 0.5112235 0.1815908 -0.02152597 0.9832142 0.1811809 -0.8621354 0.4726568 0.1825324 -0.4711011 0.2689419 0.8400799 0.4718193 -0.2636306 0.8413594 -0.00797367 -0.539434 0.8419901 -0.4711034 -0.2689371 0.8400802 -0.007989466 0.5394316 0.8419916 0.4718177 0.2636312 0.84136 -0.8682649 -0.4960994 0.00130552 -0.8412514 -0.5397433 0.03119856 -0.8667107 -0.4988107 -7.44232e-4 -0.005188584 -0.9999843 0.002137362 0.04588574 -0.9984067 0.03284204 -0.002739608 -0.9999962 5.37196e-4 0.8637288 -0.5039469 0.003194153 0.8879127 -0.4588527 0.03263777 0.8653143 -0.5012285 0.001107752 0.8678132 0.4968712 0.004407405 0.8408782 0.5402929 0.03174084 0.8653134 0.50123 0.001116693 0.004690289 0.999974 0.005486547 -0.04660874 0.9984895 0.02909559 -0.002760767 0.9999961 5.34788e-4 -0.8635148 0.5043116 0.003475904 -0.8882502 0.4584231 0.02932322 -0.8667125 0.4988076 -7.46066e-4 0.4878568 0.6676113 -0.5623976 -0.7219215 0.3539032 -0.5946275 0.5991236 0.3624536 -0.7139176 0.5096058 0.7698607 -0.384209 0.01408606 -0.6868768 -0.7266374 0.4009701 -0.7786532 -0.4826202 0.399561 -0.7991571 -0.4491092 -0.8204513 0.4685672 -0.3275736 -0.6538701 0.002615928 -0.7566023 -0.3551707 0.5057665 -0.7861642 -0.2342538 0.6980649 -0.6766318 -0.1851975 0.9826671 0.008205235 0.08732998 0.4949772 -0.8645063 0.8681012 0.2237729 -0.4430869 0.7009496 0.002183079 -0.7132075 0.8516787 -0.3101793 -0.4224123 0.5840604 -0.3707648 -0.7220852 -0.2956165 -0.893312 -0.3385331 -0.3584538 -0.6254709 -0.6930347 -0.7961548 -0.4118826 -0.4432722 -0.8878884 -0.4012392 -0.2250805 -0.9709751 -0.2377828 0.02582025 -0.8835949 -0.4678147 -0.02024072 -0.6028357 -0.7977218 0.01513862 -0.6139407 -0.7892924 0.00971657 -0.01289296 -0.9998698 -0.009716391 0.005686879 -0.9999808 -0.002487301 0.5011452 -0.8653032 0.01020312 0.6103436 -0.7918661 -0.02070909 0.8219937 -0.5691158 0.02082335 0.9454112 -0.3244534 -0.03045809 0.9986637 0.03701788 0.03606367 0.9606218 0.2769272 -0.02273994 0.751125 0.6600347 0.01287037 0.7830089 0.6219981 -0.003931999 0.4177985 0.9084845 0.01002031 0.3513514 0.9361797 -0.01094657 -0.1374224 0.990512 0.00111097 -0.1471579 0.9891052 0.003965139 -0.519616 0.8543931 -0.003448665 -0.5778493 0.8160364 0.01322972 -0.8608092 0.5084979 -0.02091783 -0.9413566 0.3365746 0.02377742 -0.9997488 0.009967625 -0.02007281 -9.21011e-7 0 -1 -1.96606e-6 0 -1 1.0169e-6 0 -1 4.77764e-7 0 -1 -5.18787e-7 0 -1 8.14926e-7 0 -1 0.8050064 0.5932649 -0.001299619 0.7971992 0.6037024 -0.004094362 0.322736 0.9464803 0.004095733 0.2672265 0.9635975 -0.008359074 -0.5207322 0.8536612 0.01002472 -0.5790476 0.8152321 -0.0100252 -0.9952523 0.0968964 0.009169578 -0.9997402 -0.0134387 -0.01841253 -0.7561165 -0.65401 0.02363967 -0.5932167 -0.8046957 -0.02363967 0.02377092 -0.9995892 0.01601725 0.1298026 -0.9915183 -0.006540298 0.7127946 -0.7013424 0.006540596 0.7236508 -0.6901587 0.003234505 0.9887667 -0.1491249 -0.01010471 0.9985724 -0.05228853 0.0109201 -1.34645e-6 0 1 1.32597e-6 0 1 -9.12769e-7 0 1 -8.99251e-7 0 1 -1.31585e-6 0 1 1.85901e-6 0 1 2.1137e-6 0 1 -9.48374e-7 0 1 -1.66796e-6 0 1 1.10626e-6 0 1 -1.44517e-6 0 1 0.007019698 0.00822544 -0.9999415 0.009945154 0.008907794 -0.9999109 0.009854316 0.001009464 -0.999951 0.01161712 -5.80162e-4 -0.9999324 0.008497297 -0.01049822 -0.9999089 0.004050672 -0.009656488 -0.9999452 -4.78196e-4 -0.01447248 -0.9998952 -0.005012273 -0.008328914 -0.9999528 -0.008049428 -0.00859493 -0.9999307 -0.01277756 -9.1757e-4 -0.9999181 -0.01099365 7.60999e-4 -0.9999393 -0.0122593 0.009046971 -0.999884 -0.003816306 0.008886098 -0.9999533 -3.53734e-4 0.01456612 -0.9998939 0.01833897 -0.0255503 0.9995054 0.01638048 -0.02504545 0.9995521 -6.42174e-4 -0.03416585 0.999416 0.008226037 0.02676701 0.9996079 0.006858527 0.02573406 0.9996454 0.01075869 0.02191805 0.9997019 0.02411097 0.022165 0.9994636 0.02747201 0.007179677 0.9995968 0.03394341 0.003475487 0.9994177 0.02980494 -0.01359575 0.9994633 0.02371883 -0.01545363 0.9995992 -0.008364915 -0.02431321 0.9996694 -0.01550734 -0.02536278 0.999558 -0.02233982 -0.01225394 0.9996754 -0.02597022 -0.01902478 0.9994817 -0.02941691 0.004134058 0.9995587 -0.0406146 -0.00188744 0.9991731 -0.03200036 0.02533203 0.9991668 -0.01582485 0.02745443 0.9994979 -0.01330393 0.03322166 0.9993595 -0.9961349 0.08741235 0.008623778 -0.9918216 -0.1276122 -0.002242505 -0.8482708 -0.5295444 0.004414081 -0.8585139 -0.5127825 0.002841711 -0.3999661 -0.9165281 0.001877844 -0.3426978 -0.9394214 0.006769239 0.1903817 -0.9816977 -0.004956662 0.4394013 -0.8982319 0.01030355 0.730796 -0.6825686 -0.006113171 0.9096114 -0.4153603 0.009116053 0.9797676 0.2000125 0.007102727 0.9986731 -0.05131262 -0.00438416 0.9024826 0.4307197 -0.002430081 0.6500866 0.7598481 0.004299044 0.6611291 0.7502657 0.003118693 0.1059077 0.9943748 0.001581966 0.0369904 0.9992911 0.007007479 -0.4768078 0.8789933 -0.005026996 -0.6981316 0.7158905 0.01063394 -0.884156 0.4671693 -0.004593491 -0.001345157 -8.60811e-4 0.9999988 5.34768e-4 0.002337038 0.9999972 1.13065e-4 0.002111196 0.9999979 -6.88957e-4 0.002223908 0.9999973 -0.7656481 0.6432284 -0.006342053 -0.3717374 0.9283046 0.007877409 -0.3790109 0.9253102 0.01232445 0.1379856 0.9899393 -0.031309 0.2573804 0.96575 0.03289842 0.7360747 0.6766791 -0.01730608 0.7329468 0.6801392 -0.01413577 0.9947211 0.101843 0.01256936 0.9977399 0.06677532 -0.00749588 0.9097926 -0.4150071 0.006837248 0.8768003 -0.4801396 -0.02621769 0.5825856 -0.8116637 0.04238128 0.4157976 -0.9084163 -0.04350191 -0.01878285 -0.9994331 0.02794146 -0.09442305 -0.995512 -0.006343066 -0.5216459 -0.8531348 0.006837129 -0.5823183 -0.8125382 -0.02621382 -0.8759723 -0.4804958 0.04238194 -0.9519144 -0.3032602 -0.04350173 -0.9898811 0.1391201 0.02794712 -0.97687 0.2137402 -0.00634545 -0.78404 0.6206727 0.006833195 0.7419761 -0.4052541 -0.5340791 0.7824813 0.05124843 -0.6205617 0.5625234 0.09217178 -0.8216276 0.5844213 0.5712568 -0.5762963 0.5446401 0.5054021 -0.6692802 0.05359745 0.6889606 -0.7228145 0.07341557 0.5374951 -0.840065 -0.3495332 0.8533611 -0.3867834 -0.3895539 0.4044848 -0.8274297 -0.5533962 0.4649041 -0.6910984 -0.6928448 0.1066471 -0.7131568 -0.5490688 0.120136 -0.8270979 -0.9064506 -0.2882509 -0.3086405 -0.3324299 -0.2936868 -0.8962358 -0.4916691 -0.6876395 -0.534241 -0.07415366 -0.7818179 -0.6190816 0.04007649 -0.502906 -0.8634116 0.3745107 -0.8199517 -0.4329217 0.38395 -0.3119413 -0.8690656 -0.5383289 0.5391018 0.6477432 0.03974592 0.6795948 0.7325102 0.03301018 0.6649498 0.7461583 0.5380693 0.6065217 0.5853314 0.4740905 0.3036819 0.8264477 0.8229227 0.1699585 0.5421369 0.5504053 -0.250006 0.7965871 0.5514072 -0.251177 0.7955252 0.4089092 -0.8264272 0.3870549 -0.02460694 -0.4621068 0.8864828 -0.2895573 -0.7761159 0.5601792 -0.6628465 -0.3960359 0.6354449 -0.5024833 -0.1632498 0.8490349 -0.8279739 0.07494217 0.5557365 -0.4836293 0.3970338 0.7800429 -0.4320707 0.8834833 -0.1810309 0.5519745 0.8162233 -0.1705983 0.9625014 -0.07938724 -0.2594011 0.4313996 -0.8836005 -0.1820569 -0.549638 -0.8156155 -0.1807467 -0.9815198 0.0679174 -0.1789025 0.5233185 -0.05210894 -0.8505424 0.3382955 0.3604064 -0.869289 0.1865983 0.4576717 -0.8693203 -0.2698053 0.4534043 -0.849488 -0.5336388 0.02494537 -0.8453446 -0.2665812 -0.4686399 -0.8422062 0.2275815 -0.4903408 -0.8412923 -0.4186075 0.9071579 -0.04280447 -0.4744224 0.880296 -0.001522421 -0.4644192 0.8856006 0.005133152 0.5807709 0.8140671 -1.09395e-4 0.5425116 0.8394945 -0.03049796 0.5739784 0.8166362 -0.06045132 0.4978522 0.867262 -5.89995e-5 0.9988881 -0.04483449 -0.01457434 0.992073 -0.1207337 -0.03485167 0.9979181 -0.06447666 -0.001541137 0.4630911 -0.8863083 -0.002040565 0.4157549 -0.9091066 -0.02594822 0.456676 -0.8896288 0.002775132 -0.5357092 -0.8443964 0.003217697 -0.5784345 -0.8150651 -0.0329042 -0.5349046 -0.8449085 0.002625703 -0.9991187 0.04193526 0.001843035 -0.9949074 0.09088051 -0.04359126 -0.99948 0.03192824 -0.004512965 -0.9010352 0.1388965 0.4109058 0.8973832 0.1952601 0.3956981 0.6755863 -0.02998375 0.736671 0.8077061 -0.4386008 0.3940057 0.5079967 -0.4703027 0.7216334 0.4472647 -0.7773151 0.44242 -0.5912451 0.2419062 0.7693573 -0.6044101 0.7236725 0.3331466 -0.6885442 -0.02230221 0.7248515 -0.675274 -0.4327569 0.597266 -0.7220674 -0.5014343 0.4766364 -0.2941203 -0.5307735 0.7948414 -0.1870301 -0.9235895 0.3346676 0.1210411 -0.6543315 0.7464579 0.6678224 0.3133017 0.6751706 0.4674541 0.5173459 0.7168263 0.5180253 0.6779455 0.5215742 0.04466223 0.8543314 0.5178062 0.1238078 0.6594724 0.7414633 -0.3331751 0.6266411 0.7044965 -0.8710383 0.4912153 2.76841e-5 -0.864995 0.5017653 -0.003940999 -0.8660212 0.4999994 -0.002841174 -0.8471096 0.5308166 0.02528101 -0.4863264 -0.002818405 -0.8737728 -0.5336419 0.12594 -0.8362808 -0.5184856 -0.08848917 -0.8504955 -0.8698721 -0.4932774 -1.06226e-5 -0.869038 -0.4947454 -3.56738e-5 -0.8590562 -0.5118059 -0.008796513 -0.8660218 -0.4999985 0.002840399 -0.2021249 -0.358299 -0.9114645 0.005689144 -0.9999839 0 -0.002659797 -0.9999904 -0.003494918 0.007019519 -0.9999752 5.64104e-4 0 -0.9999884 -0.004828453 0.0138759 -0.9998253 -0.01252382 0.6237316 -0.4444019 -0.6430132 0.124904 -0.5980259 -0.7916843 0.2115254 -0.3726667 -0.9035357 0.3426231 -0.3513535 -0.8712981 0.8671062 -0.4981204 -0.001728951 0.866024 -0.4999998 0.001634895 0.8672441 -0.4978798 -0.001893818 0.6883333 0.3137353 -0.6540393 0.4363415 0.09683519 -0.8945553 0.5944368 -0.2169325 -0.7743289 0.4393731 -0.06631851 -0.8958534 0.8667045 0.4988217 3.46037e-4 0.8660252 0.5 6.10241e-4 0.8653998 0.5010806 -0.001188039 0.4446536 0.3931188 -0.8048234 0.2248547 0.3661785 -0.9029694 0.1147041 0.6325488 -0.7659798 0.1655012 0.443636 -0.8807931 -0.02242666 0.9997477 0.001264631 0.02580153 0.9996667 -9.77624e-4 0 0.9998699 0.01613301 -0.1159335 0.6385821 -0.760771 -0.03375184 0.8398363 -0.5417897 0.5370534 -0.7665252 -0.352155 -0.2224817 0.3159111 -0.9223352 -3.25911e-4 0.002625346 -0.9999966 -4.47478e-4 0.006637096 -0.999978 -0.02467572 -0.009603142 -0.9996495 0.02860176 -0.01402509 -0.9994926 -6.7657e-4 -8.20639e-4 -0.9999995 -3.79835e-4 -0.001522123 -0.9999989 -0.006979525 -3.88943e-4 -0.9999756 -3.87542e-4 -0.001044452 -0.9999994 -5.51843e-4 -9.59705e-4 -0.9999995 -7.35582e-4 -6.18649e-4 -0.9999996 1.24727e-4 -0.00993973 -0.9999506 -4.87668e-4 -0.01242512 -0.9999227 0.004784405 0.003519237 -0.9999824 -0.003107786 -7.34656e-4 -0.999995 0.01390534 7.04712e-4 -0.9999031 -0.003623843 -0.001287758 -0.9999926 -9.72259e-5 0.001027286 -0.9999995 -2.16563e-4 0.003652155 -0.9999933 -9.02555e-4 7.84093e-4 -0.9999993 -7.85267e-4 9.60303e-4 -0.9999992 0.002503275 -5.17801e-4 -0.9999967 0.002675056 -0.002997279 -0.999992 -0.005540072 -0.008859753 -0.9999454 -0.007133901 -0.004072844 -0.9999663 -0.002443552 -4.11101e-4 -0.9999969 -0.002472698 0 -0.999997 -0.002344489 3.94431e-4 -0.9999973 0.009130656 -0.008740544 -0.9999201 0.00154972 -0.001895904 -0.9999971 -0.00422734 0.001134693 -0.9999904 -0.002262234 -7.83789e-4 -0.9999971 0.07300531 -0.8710806 -0.4856838 0.4485929 -0.4066517 -0.7958636 0.8464335 -0.4146744 -0.3340592 0.5416431 0.03927975 -0.8396904 0.7593613 0.566134 -0.3207222 0.4227862 0.5064907 -0.751478 0.01924246 0.7034173 -0.7105166 -0.07300597 0.8710896 -0.4856677 -0.4485915 0.4066504 -0.7958651 -0.8464339 0.4146735 -0.3340594 -0.541631 -0.03927904 -0.8396981 -0.7593613 -0.566134 -0.3207222 -0.4227813 -0.5064877 -0.7514828 -0.01923763 -0.7034246 -0.7105095 -0.02483361 -0.9996066 0.01304584 -0.6432864 -0.7654138 0.01801073 -0.7090345 -0.7048008 -0.0229361 -0.9849225 -0.1729515 -0.003933787 -0.9964272 -0.0763275 0.03615307 -0.8761767 0.4801462 -0.0421189 -0.7376005 0.6729673 0.05532157 -0.1159265 0.9913889 -0.06090241 0.02483928 0.9996063 0.01304996 0.6432908 0.7654103 0.01800858 0.7090343 0.7048009 -0.02293664 0.9849223 0.1729528 -0.00393325 0.9964272 0.07632786 0.03615295 0.8761743 -0.4801508 -0.04211807 0.7376024 -0.6729652 0.05532258 0.1159197 -0.99139 -0.06089752 0.6014165 0.6088434 0.5173084 0.5944133 0.5887833 0.547729 0.6051452 0.1083618 0.788706 0.8783938 -0.1805632 0.4425171 0.5211133 -0.2848488 0.8045508 0.3242397 -0.8716292 0.367602 0.06564491 -0.5629025 0.8239124 -0.6014184 -0.6088433 0.5173062 -0.5944236 -0.5887787 0.5477229 -0.6051444 -0.1083616 0.7887066 -0.8783949 0.1805583 0.4425169 -0.5211035 0.2848516 0.8045563 -0.3242436 0.8716281 0.3676013 -0.0656439 0.5628978 0.8239157 -0.00211358 8.7914e-4 0.9999974 0 0.004263818 0.9999909 0.001233339 -6.69592e-5 0.9999992 0.001681387 -9.71347e-4 0.9999982 -0.001233339 6.69563e-5 0.9999992 -0.001681387 9.71347e-4 0.9999982 0.003361701 7.62229e-4 0.9999941 0.001457095 8.40724e-4 0.9999986 0.002112329 -8.79141e-4 0.9999974 0 -0.004263818 0.999991 -0.003361701 -7.62229e-4 0.9999942 -0.001456141 -8.40723e-4 0.9999986 0.008650958 0.00461626 0.999952 0.006649196 0.01057744 0.999922 -7.90537e-4 0.01103442 0.9999389 -2.03222e-4 0.01024633 0.9999475 -0.006844222 0.009751379 0.9999291 -0.008153557 0.004575252 0.9999563 0.008982419 -0.008438706 0.9999241 0.00800985 -0.004390299 0.9999583 0.01154309 -8.87939e-4 0.999933 0.009430587 0.004423856 0.9999458 -0.006011962 -0.01164209 0.9999142 2.63017e-4 -0.009071707 0.9999589 0.003740012 -0.01176267 0.9999238 -0.01096701 0.003676831 0.9999332 -0.01165807 -0.005430996 0.9999173 -0.009404122 -0.005768239 0.9999392 -0.02477741 0.01146376 -0.9996273 -0.02490139 0.0117138 -0.9996214 -0.03014552 0 -0.9995456 -0.02171033 -0.01004278 -0.9997139 0.02926206 0.002142488 -0.9995695 0.01756626 0.02590501 -0.9995101 0.008339464 -0.02092719 -0.9997462 0.009993314 -0.01237732 -0.9998735 0.01534712 -0.01002001 -0.9998321 0.007728755 0.02263432 -0.999714 -0.001707434 0.03150427 -0.9995023 -0.01460558 0.01853513 -0.9997216 -0.01521986 0.0430743 -0.998956 -0.01189321 -0.01227933 -0.9998539 -0.01128178 -0.01327848 -0.9998482 -0.0175026 -0.01370126 -0.999753 -0.006633281 -0.02782154 -0.9995909 0.01322323 -0.001437604 -0.9999116 0.01691406 -0.004817843 -0.9998455 0.01561462 0.005906939 -0.9998607 0.9044826 -0.4263719 -0.01088303 0.9244279 -0.3813369 -0.003898978 0.5373116 -0.8433756 -0.00375247 0.4936004 -0.8696403 -0.009187221 0.08080744 -0.996699 0.00783807 -0.3513322 -0.9361159 -0.01590567 -0.2475482 -0.9688743 0.001638054 -0.7965684 -0.6044394 -0.01147913 -0.816652 -0.5770854 -0.007203161 -0.9872302 -0.1592494 0.004033923 -0.9947095 0.101648 -0.01485586 -0.9345346 0.3558545 0.003567636 -0.7160589 0.6979143 -0.01324391 -0.6224209 0.7826825 -7.41514e-4 -0.2774668 0.9607294 0.003343224 -0.06484162 0.9978029 -0.01360708 0.08813357 0.9961035 -0.003223359 0.5958459 0.8030421 -0.009543776 0.5458982 0.8378474 -0.002669215 0.889927 0.4561011 -0.001310467 0.9304063 0.3663568 -0.01126283 0.9991844 0.04022306 0.003576576 0.00105977 0.00495857 -0.9999873 4.08052e-4 4.30741e-5 -1 -0.001534521 8.33965e-4 -0.9999986 -0.003614008 6.22089e-4 -0.9999933 0.9935823 -0.1080529 -0.03345036 0.8876065 -0.4595426 0.03123092 0.8370995 -0.546778 -0.01727098 0.4630724 -0.886201 0.01454985 0.3699266 -0.9284449 -0.03382915 0.01484674 -0.9994081 0.03103387 -0.2316213 -0.9722479 -0.0329492 -0.4062796 -0.9135346 0.01978617 -0.6472256 -0.7619686 -0.02243095 -0.752312 -0.6585098 0.01978713 -0.9073465 -0.4197846 -0.02243089 -0.9685769 -0.2468897 0.0300706 -0.9994365 0 -0.03356921 -0.9466443 0.3212758 0.02542942 -0.9074911 0.4198547 -0.01349598 -0.693668 0.7202116 0.01095587 -0.6185687 0.785291 -0.02628558 -0.3285313 0.9440238 0.02976864 -0.05408883 0.9976372 -0.04236173 0.09464418 0.9953754 0.01644134 0.5083455 0.8611505 -0.002216219 0.5608932 0.827252 -0.0324468 0.8217241 0.5691075 0.02976906 0.9347009 0.353905 -0.03294807 0.989892 0.1384573 0.03071993 -0.8256604 -0.2112055 0.5231418 -0.5235236 -0.2667475 0.8091779 -0.592889 -0.5189641 0.6157588 -0.333369 -0.495668 0.8019841 -0.3255324 -0.7319704 0.5985383 0.009698867 -0.6335942 0.7736048 0.009398639 -0.6328078 0.7742519 0.3817455 -0.725459 0.5726951 0.3512138 -0.4788455 0.8045842 0.7257496 -0.379843 0.5735914 0.5584032 -0.2161977 0.8009024 0.8407705 0.1195639 0.5280241 0.4613825 0.1942477 0.8656756 0.6436191 0.4493425 0.6195529 0.40842 0.6845042 0.6038603 0.2079573 0.5206168 0.8280774 0.07374614 0.7846842 0.6154936 -0.1152381 0.5666619 0.815852 -0.260788 0.7403641 0.6195569 -0.5502748 0.5766566 0.6038749 -0.4460071 0.3396648 0.8280735 -0.7813106 0.2653285 0.5649377 -0.568463 0.06150615 0.8204066 0.5363237 0.1573651 -0.8292124 0.6267288 0.2448215 -0.7397794 0.430454 0.6650503 -0.6102602 0.1496892 0.5340089 -0.8321225 -0.05043101 0.8700471 -0.4903825 -0.4217364 0.438448 -0.7936635 -0.4847943 0.4623672 -0.7424224 -0.8033766 0.08543258 -0.589311 -0.5685608 -0.06053555 -0.820411 -0.6727907 -0.5142329 -0.5318997 -0.2939452 -0.4687294 -0.833 -0.2096064 -0.8256753 -0.5237607 0.3361993 -0.5125144 -0.790126 0.2507718 -0.4460434 -0.8591618 0.8628655 -0.3549644 -0.3598104 0.8408856 0.5119512 0.1755492 -0.0215668 0.9830936 0.1818298 -0.8624299 0.4726049 0.1812711 -0.8402645 -0.5120415 0.1782396 0.02186369 -0.9827209 0.183798 0.8621341 -0.4726685 0.1825087 0.4547233 -0.2699977 0.8487215 -0.4491963 0.2742228 0.8503085 0.02182376 0.5424709 0.8397912 0.4317613 0.3113963 0.8465309 -0.02182364 -0.5424692 0.8397922 -0.4270905 -0.3148089 0.8476374 0.840386 0.5416777 0.01835286 0.8615171 0.5077058 -0.004815042 0.8673058 0.4977669 0.002967119 0.004432201 0.9999613 0.007608532 -0.004779577 0.9999873 0.001593768 -0.04666471 0.9984681 0.02973353 -0.8655519 0.4996259 0.03455567 -0.8882778 0.4583887 0.02902442 -0.8794419 0.4757187 0.01654171 -0.8401013 -0.5420619 0.01997667 -0.8620613 -0.5067878 -0.004073202 -0.8674143 -0.497577 0.003106832 -0.004431962 -0.9999612 0.007610559 0.004779517 -0.9999873 0.001591324 0.04739379 -0.9984188 0.03022861 0.8654112 -0.4997275 0.0365529 0.8882778 -0.4583887 0.02902442 0.8800395 -0.4745828 0.01736783 0.07580161 -0.2711375 0.9595512 0.347388 0.9376425 0.01217252 0.5194752 -0.2498412 -0.8171443 0.7798891 -0.235567 -0.5798975 0.6045277 -0.01865839 -0.7963657 -0.3128751 -0.6551019 -0.6877141 0.02397674 -0.7891554 -0.6137256 0.05862444 -0.7450622 -0.6644138 0.3723378 -0.7955225 -0.4780256 0.3585768 0.6773806 -0.6423225 0.2023296 0.8074364 -0.5541743 0.3718634 -0.44525 -0.8145368 -0.3747194 -0.7031498 -0.6042894 -0.4393568 -0.3184309 -0.8399806 -0.8023818 -0.2409685 -0.5460016 -0.6295155 -0.1055515 -0.7697852 -0.5785734 0.2222173 -0.7847753 -0.7452095 0.4101749 -0.525756 -0.4589813 0.4475211 -0.7675031 -0.2753919 0.7179639 -0.6392863 -0.2505335 0.8604756 -0.443638 0.7570382 0.3579506 -0.5465936 0.6623182 0.3574932 -0.6584324 -0.01085317 -0.005952239 0.9999234 -0.002937316 -0.01442229 0.9998917 7.79568e-4 -0.01049119 0.9999447 0.006443321 -0.01132589 0.9999152 0.008153557 -0.004575252 0.9999563 -0.008982419 0.008438706 0.9999241 -0.00800985 0.004390299 0.9999583 -0.01154893 8.87948e-4 0.999933 -0.008789539 -0.006018519 0.9999433 0.006011962 0.01164209 0.9999142 -2.63016e-4 0.009071648 0.9999588 -0.003740012 0.01176267 0.9999238 0.01096922 -0.003676831 0.9999331 0.01165801 0.005430996 0.9999174 0.009404122 0.005768239 0.9999392 0.03229498 -0.007108509 -0.9994531 0.01964646 0.01196968 -0.9997354 0.01642543 0.003615796 -0.9998586 -0.02871358 -0.01727777 -0.9994384 -0.006843864 -0.0263195 -0.9996302 -0.008935153 -0.0142768 -0.9998582 -0.002815306 0.01715141 -0.999849 -0.01113313 0.01518172 -0.9998229 -2.77489e-4 -0.01460254 -0.9998934 -0.01047688 -0.02594453 -0.9996085 0.009809613 -0.02737075 -0.9995773 0.01303625 -0.02204197 -0.9996721 0.02673512 -0.0219258 -0.9994021 0.02252382 -0.002310693 -0.9997437 0.02340984 0.01919025 -0.9995418 1.5732e-4 0.02633577 -0.9996532 0.005571782 0.01751875 -0.9998311 -3.65685e-4 0.01504582 -0.9998868 -0.01133751 0.007651686 -0.9999065 -0.01560884 0.005906701 -0.9998608 -0.01402294 -0.001525163 -0.9999006 -0.03106462 0.009197831 -0.9994751 -0.9048917 0.4255037 -0.01085525 -0.9244269 0.3813377 -0.004075586 -0.5529943 0.8331793 -0.003084182 -0.493588 0.8696296 -0.01074123 -0.03251183 0.9994513 0.006338477 0.2474878 0.968783 -0.01446908 0.4972811 0.8675788 0.004329621 0.7965665 0.6044369 -0.01174581 0.8369686 0.547234 -0.004323363 0.989142 0.1469296 0.003130197 0.9947099 -0.101645 -0.01485586 0.9345356 -0.3558519 0.003567576 0.7160599 -0.6979133 -0.01324409 0.611954 -0.7908932 5.79217e-4 0.09638553 -0.9953339 -0.004535377 0.0649107 -0.9978528 -0.008740127 -0.5202634 -0.8540046 -0.001470029 -0.5458875 -0.8378449 -0.004775345 -0.8996315 -0.4366481 -0.00128591 -0.9304223 -0.3663696 -0.009373188 -0.998829 -0.04823076 0.003820717 0.003726005 -0.002501547 -0.9999899 1.40211e-4 4.13706e-4 -1 -5.20502e-4 4.93426e-4 -0.9999998 -0.9343507 0.3537717 -0.04283052 -0.7904262 0.611151 0.04148429 -0.5910558 0.8059411 -0.03335016 -0.4287338 0.90323 0.01905268 -0.161742 0.9865782 -0.02243095 -0.01485002 0.9996939 0.01978784 0.3028289 0.9526386 -0.02782738 0.4389106 0.8980237 0.03017836 0.7727751 0.6338335 -0.03276848 0.8578497 0.5132497 0.02586084 0.9763692 0.2149149 -0.02269273 0.9978345 0.0623604 0.02092248 0.9763582 -0.2149123 -0.02317905 0.9319296 -0.3621191 0.01941561 0.7728831 -0.6339216 -0.028198 0.6935703 -0.7201696 0.0177735 0.3285182 -0.9444906 -0.003638386 0.3375437 -0.9413095 8.86974e-4 -0.0193113 -0.9997237 -0.01340925 -0.09464299 -0.9953756 0.01643908 -0.539001 -0.8422967 -0.003781855 -0.5302204 -0.8478567 0.002355635 -0.8566874 -0.5154504 -0.01994246 -0.9099132 -0.4140669 0.02462947 -0.9938879 -0.1080918 -0.02243143 -0.9965175 0.07752597 0.03070592 0.8051338 0.04675382 0.5912477 0.5363403 0.3199484 0.7810072 0.5392331 0.3231239 0.7777009 0.3697154 0.7571207 0.5385897 0.1009686 0.4820871 0.8702859 -0.01167643 0.7861422 0.6179354 -0.3365445 0.7019147 0.627737 -0.3182702 0.4723026 0.8219698 -0.6614004 0.516872 0.5435007 -0.4896093 0.1896445 0.8510686 -0.8898586 0.06721085 0.4512587 -0.521236 -0.2195264 0.8246946 -0.5735744 -0.2652357 0.7750241 -0.4658035 -0.7220857 0.5114874 -0.2079628 -0.5206178 0.8280754 -0.07374024 -0.7846741 0.6155071 0.1152386 -0.566665 0.8158498 0.260789 -0.7403681 0.6195516 0.5502754 -0.5766555 0.6038755 0.4460008 -0.339668 0.8280755 0.7349018 -0.2814459 0.6170151 0.6057125 -0.06550639 0.7929826 -0.7558107 -0.2960765 -0.5840281 -0.4135714 -0.6394028 -0.6481689 -0.1678815 -0.4945935 -0.8527563 0.05027657 -0.8682578 -0.4935591 0.4372792 -0.411974 -0.7994151 0.4316976 -0.4097647 -0.8035735 0.8837113 -0.09287965 -0.4587242 0.4321196 0.2032275 -0.878619 0.6012945 0.4608539 -0.6527316 0.2208265 0.8687922 -0.4432109 -0.1038687 0.4285746 -0.8975161 -0.3729633 0.6603031 -0.6518422 -0.8249253 0.3390656 -0.4522534 -0.4683359 -0.02303725 -0.8832502 -0.840887 -0.5119506 0.1755439 0.0215668 -0.9830956 0.1818185 0.8624321 -0.4726033 0.1812659 0.8402665 0.5120317 0.1782578 -0.02186357 0.9827212 0.1837969 -0.8621359 0.4726673 0.1825034 -0.4547225 0.2699977 0.8487219 0.4491984 -0.274222 0.8503077 -0.02182364 -0.5424706 0.8397913 -0.4317584 -0.3113967 0.8465324 0.02182364 0.5424699 0.8397918 0.427091 0.3148102 0.8476366 -0.8403878 -0.5416749 0.01835089 -0.8615159 -0.5077078 -0.004815042 -0.8673048 -0.4977687 0.002968132 -0.004433274 -0.9999613 0.007608532 0.004779577 -0.9999873 0.001593768 0.04666465 -0.9984681 0.02973347 0.8655539 -0.4996221 0.03455722 0.8882757 -0.458393 0.02902299 0.87944 -0.4757223 0.01654285 0.8401004 0.5420632 0.01997464 0.8620607 0.5067889 -0.004073798 0.8674135 0.4975783 0.003108978 0.004431962 0.9999613 0.007608532 -0.004779517 0.9999873 0.001591324 -0.04739379 0.9984189 0.03022742 -0.8654145 0.4997218 0.03655219 -0.8882767 0.458391 0.02902191 -0.8800396 0.4745827 0.0173695 -0.01092398 0.7006812 -0.7133909 -0.03218692 0.7485068 -0.6623456 -0.252047 -0.4774187 -0.8417504 -0.007252275 -0.771604 -0.6360619 -0.4991623 0.2342472 -0.8342454 -0.7476587 -0.102935 -0.6560571 0.05277281 -0.6178019 -0.784561 -0.976872 -0.018525 -0.2130209 -0.6520016 0.5356105 -0.5366707 -0.3062032 0.4380344 -0.8452014 0.3272347 0.4439224 -0.8341765 0.3659904 0.7340569 -0.5720241 0.6059867 0.376854 -0.7005435 0.6992897 0.3794899 -0.6057899 0.5544192 0.08835607 -0.827534 0.8221432 -0.1323115 -0.5536915 0.5484151 -0.2107941 -0.8092013 0.5102505 -0.6091866 -0.6070719 0.5397255 -0.6944489 -0.4758542 -0.6261069 -0.6007207 -0.4971166 -0.5857715 -0.3236128 -0.7430657 -0.005131602 0.009487748 0.9999418 -0.01152205 0.007440745 0.999906 -0.009933054 -7.74067e-4 0.9999504 -0.0101757 -0.00102663 0.9999478 -0.009750127 -0.006843268 0.9999291 -0.004578292 -0.008154928 0.9999564 0.007267236 0.01084482 0.9999148 0.0054605 0.009964942 0.9999355 -0.003945231 0.0136221 0.9998995 0.01163864 -0.00601691 0.9999142 0.009065568 2.61624e-4 0.9999589 0.01175916 0.003741145 0.999924 -0.003682374 -0.01097273 0.9999331 0.005437672 -0.01166045 0.9999173 0.005762457 -0.009400904 0.9999393 -0.01340901 -0.02649676 -0.999559 -0.005913913 -0.0325194 -0.9994537 0.009097576 -0.02202469 -0.9997161 0.008070468 -0.02143406 -0.9997377 -0.01363062 0.01336967 -0.9998178 -0.01209396 0.005111455 -0.9999138 -0.01616293 0.003266036 -0.9998641 0.03375703 0.006821811 -0.9994069 0.02132904 0.0178318 -0.9996135 0.022327 0.02356934 -0.9994729 -0.01615023 -0.005129933 -0.9998564 -0.04950237 0.006672501 -0.9987518 -0.02334696 -0.02846473 -0.9993221 0.0153802 -0.01741749 -0.9997301 0.01528972 -0.004858374 -0.9998713 0.02267849 -0.01403117 -0.9996443 0.005110859 0.03494191 -0.9993763 -0.01201903 0.0214529 -0.9996977 -0.006189644 0.01836317 -0.9998123 0.4288788 0.9032727 -0.01270657 0.3813343 0.9244227 -0.005196392 0.8594336 0.5111992 -0.00702095 0.8696412 0.4935988 -0.009186863 0.994912 0.1004993 0.007072567 0.8980484 -0.438808 -0.03092771 0.9688746 -0.2475438 -0.002049088 0.7972002 -0.603712 -0.001999497 0.6044261 -0.7965229 -0.01485478 0.5086929 -0.8609407 -0.003553748 0.146929 -0.9891421 0.003130495 -0.1016443 -0.9947099 -0.01485592 -0.3558507 -0.9345361 0.003567814 -0.6979165 -0.7160567 -0.01324433 -0.802414 -0.5967627 0.00247097 -0.9852025 -0.1713741 -0.002667069 -0.9978067 -0.06484991 -0.01327997 -0.981572 0.1910868 -0.001498401 -0.794559 0.6070532 -0.01275002 -0.8378443 0.5458918 -0.004364073 -0.4511401 0.8924488 -0.002834618 -0.3663517 0.9303968 -0.0121802 0.06381279 0.9979347 0.007368385 0.001579821 0.002693057 -0.9999951 0.003197968 0.001855015 -0.9999933 9.55891e-4 0.001451253 -0.9999985 -0.00126779 -3.20423e-4 -0.9999992 0.1446421 0.9885519 -0.04294216 0.4270039 0.9033051 0.04132592 0.6870626 0.7253234 -0.04302215 0.7897262 0.6132575 0.01574766 0.9733191 0.2294524 -0.001221656 0.9800438 0.1981052 -0.01638638 0.9796438 -0.2004283 0.01125079 0.9526518 -0.3028337 -0.02731651 0.7824871 -0.621544 0.0373767 0.6617453 -0.7492457 -0.02690845 0.3521267 -0.935952 -9.31939e-4 0.2834308 -0.9583315 0.03560853 -0.1786453 -0.9833725 -0.03262621 -0.3212709 -0.9466331 0.02590399 -0.6339208 -0.772884 -0.02819609 -0.7444629 -0.666902 0.03188985 -0.9524478 -0.3027679 -0.03427553 -0.9875212 -0.1555483 0.02462935 -0.9797961 0.1980538 -0.02782875 -0.94023 0.339202 0.03015959 -0.7136733 0.6997186 -0.03262501 -0.604232 0.7964032 0.0254091 -0.3192241 0.9474138 -0.02243202 -0.1384575 0.9898919 0.03071951 0.1695659 -0.5836646 0.7940927 0.1766887 -0.5955366 0.7836565 0.6598755 -0.5237599 0.5387392 0.496585 -0.2651342 0.826503 0.7719478 -0.1579325 0.6157549 0.5963448 0.03456264 0.8019841 0.7796898 0.1838049 0.5985814 0.5182074 0.3800516 0.7661735 0.5447444 0.4260582 0.7223075 0.3214201 0.6703141 0.6688557 0.2161859 0.5584178 0.8008954 -0.1195623 0.8407818 0.5280065 -0.1942552 0.4613741 0.8656783 -0.5150231 0.6800189 0.5218483 -0.5802124 0.231972 0.7807322 -0.6522473 0.2342312 0.7209087 -0.7055994 -0.1439213 0.6938416 -0.6236286 -0.1021184 0.775022 -0.6419985 -0.5711548 0.5114881 -0.2706511 -0.40988 0.8710606 -0.2744184 -0.8081427 0.5211526 -0.3016137 0.6401917 -0.7065295 -0.2162831 0.5546733 -0.803467 -0.7235436 0.4690623 -0.5064241 -0.5484659 -0.004796981 -0.8361592 -0.5995461 -0.02884978 -0.7998201 -0.6412563 -0.6632415 -0.3858772 -0.1200084 -0.4968646 -0.8594903 -0.0716955 -0.6598262 -0.7479901 0.5053778 -0.6609039 -0.5547966 0.438284 -0.3407831 -0.8317297 0.8220179 -0.2086517 -0.5298595 0.5480757 0.139285 -0.82475 0.7244631 0.4096706 -0.5543676 0.2863162 0.5708891 -0.7694862 0.2785454 0.6797285 -0.6785144 -0.5119484 0.8408899 0.1755371 -0.9830944 -0.02156472 0.1818255 -0.4725793 -0.8624438 0.1812721 0.5120469 -0.8402591 0.1782489 0.9827216 0.02186185 0.1837945 0.4726904 0.8621245 0.1824972 0.2699983 0.4547263 0.8487197 -0.274221 -0.4492008 0.8503068 -0.5424677 0.02183037 0.8397931 -0.3113933 0.4317573 0.8465341 0.5424677 -0.02183037 0.8397931 0.3148099 -0.4270867 0.8476389 -0.5416702 0.8403909 0.01835083 -0.5077064 0.8615168 -0.00481379 -0.4977703 0.8673039 0.002966046 -0.9999613 0.00443536 0.007608294 -0.9999874 -0.004780888 0.001593708 -0.9984682 -0.04666298 0.02973395 -0.4996257 -0.865552 0.03455311 -0.4583925 -0.8882759 0.02902305 -0.4757173 -0.8794427 0.01654171 0.5420587 -0.8401033 0.0199747 0.5067883 -0.862061 -0.004074454 0.4975839 -0.8674104 0.003107905 0.9999613 -0.00443536 0.007608354 0.9999874 0.004780888 0.001593708 0.9984192 0.04739028 0.03022313 0.4997242 0.8654131 0.03655123 0.4583905 0.8882768 0.02902525 0.4745836 0.880039 0.01736837 0.7085062 -0.2420616 0.6628915 -0.8815699 0.4545585 0.1273226 -0.6856476 0.4393233 -0.5804159 -0.683875 0.2238634 -0.6944064 -0.4671466 -0.1736882 -0.8669524 -0.02709925 0.8880411 -0.4589648 0.7311596 -0.04466766 -0.6807426 -0.9210997 -0.117357 -0.3712178 0.4260494 0.5851588 -0.6899791 0.00393176 0.8254082 -0.5645228 0.7187585 0.6557546 0.2310238 0.6882997 0.5143552 -0.5115489 0.6889289 -0.364756 -0.6263626 0.7915351 -0.4950372 0.3583437 0.255747 -0.3972693 -0.881346 0.1057429 -0.676206 -0.7290843 0.05405431 -0.8769662 -0.4775024 -0.2218616 -0.5775822 -0.7856057 -0.5321033 -0.7397375 -0.4118915 -0.4844399 -0.4394353 -0.7564488 -0.2340013 0.4514658 -0.8610588 -0.4454221 0.2866624 -0.8481886 -0.2466464 0.4640966 -0.8507525 -0.5250141 -0.02436357 -0.8507449 0.4331446 0.3086705 -0.8468225 0.1125992 0.5255432 -0.8432828 0.4269894 -0.322243 -0.8448904 0.05985885 -0.5430829 -0.8375428 0.5268701 0.008267879 -0.8499057 -0.4095621 -0.3560866 -0.8399174 -0.5176055 0.1371467 -0.8445563 -0.2812535 0.4570631 -0.8437949 0.08482891 0.5219668 -0.8487372 0.3312067 0.4100255 -0.8498126 0.5185873 0.1193081 -0.8466598 0.4462383 -0.3073559 -0.8404784 0.07781749 -0.5347229 -0.8414369 -0.470224 -0.2444357 -0.8480217 -0.2845605 -0.4426497 -0.850345 -0.4357281 0.3122594 -0.8441771 0.5152797 0.1391826 -0.8456448 0.2992789 0.4424671 -0.8453727 -0.08949798 0.5309224 -0.8426811 0.4526397 -0.3023082 -0.8388845 -0.5245081 -0.1094675 -0.8443389 -0.3112006 -0.438447 -0.8431598 0.08260136 -0.5324552 -0.8424183 -0.4269939 0.3222452 -0.8448871 -0.0895673 0.5291445 -0.8437914 -0.5268687 -0.008253216 -0.8499067 0.3182075 0.4377756 -0.8408904 0.5384128 0.03473651 -0.841965 -0.4381241 -0.2962078 -0.8487098 0.4283326 -0.3039562 -0.8509653 0.2433752 -0.4666321 -0.8503076 -0.1288643 -0.5245192 -0.8415901 0.5119522 0.1988484 -0.8356819 0.4079383 0.1025882 -0.9072278 0.9192618 0.1885282 -0.3455648 0.8943328 0.1956948 -0.4023336 0.7913438 0.1560911 -0.5911097 0.3580356 -0.01208287 -0.9336298 0.8313227 0.007888436 -0.5557342 0.9365634 0.06146234 -0.3450672 0.7266842 0.06621843 -0.6837729 0.481909 0.04097926 -0.8752626 0.1294172 0.01495981 -0.9914774 -0.9998834 -0.01048833 0.0110988 -0.7314305 0.6817765 0.01378798 -0.9991348 -0.04121196 0.0055992 -0.8466882 0.5320276 -0.008122205 -0.4609889 0.8873518 -0.009808421 -0.1079128 0.9940509 0.01475805 0.207714 0.9779965 -0.01943796 0.5810339 0.8137052 0.01683598 0.8122759 0.583089 -0.01466852 0.9764966 0.2150201 0.01486134 0.9998487 0.01407819 -0.01022619 0.7970137 -0.6039415 0.004902899 0.8035237 -0.5952668 0.002680361 0.109702 -0.9939573 -0.003793954 0.1353654 -0.9907494 -0.009580373 -0.6060674 -0.7952326 0.01695251 -0.7546281 -0.6558383 -0.02031213 -0.9700511 0.2428126 0.00655806 0.2885764 0.9573163 0.01641136 0.8895758 0.4564214 0.01828342 -0.9649994 0.2622395 0.002591967 -0.5240751 0.8516656 -0.003368616 -0.4966577 0.8679431 0.002455949 0.1544117 0.9880024 -0.002916216 0.6355992 0.7719421 -0.01091402 0.9742558 0.2250775 -0.01287907 -0.2589675 -0.9656907 0.01942402 -0.5354512 -0.8445011 -0.01049149 -0.8532841 -0.5213935 0.007432162 0.9569303 -0.2897824 0.01762336 0.8239805 -0.566203 -0.02169317 0.4965744 -0.86781 0.01788032 0.1441866 -0.9893237 -0.02118968 -0.8863346 -0.4630399 -0.002249121 -0.9099784 0.4136466 0.0289117 -0.1567751 0.987623 0.004747331 0.5895345 0.8077337 -0.003952443 0.9844853 0.1749601 0.01333522 -0.8109392 0.5850731 -0.008197724 -0.1700804 0.9854283 0.0019176 0.5618944 0.8272057 0.002374351 0.9645743 0.2637938 -0.003044068 0.01437723 -0.9996119 0.02386653 -0.8619643 -0.506334 0.02536749 0.8299318 -0.5577749 -0.01002538 0.7913314 -0.6113823 0.002524852 0.1596127 -0.9871739 -0.003425657 -0.5823724 -0.8125735 -0.0238099 -0.9788809 -0.2038589 -0.01529121 -0.9998492 -0.01404476 -0.0102272 -0.7970072 0.60395 0.004902899 -0.8035317 0.595256 0.002683222 -0.1668979 0.9859684 -0.003371834 -0.1353864 0.9907899 0.002452731 0.5886464 0.8083828 -0.003583908 0.5811193 0.8138 -0.005480468 0.9593073 0.2822059 0.009458184 0.9446197 -0.3278198 0.01509934 0.8190483 -0.5736362 -0.01007276 0.4876704 -0.8729949 0.007589161 -0.668828 -0.7432785 0.01436626 0.9976753 0.06572306 -0.01801162 0.4554629 -0.8902519 0.002258479 -0.2375521 -0.9713688 -0.003425478 -0.1748391 -0.98447 -0.01582008 -0.8264296 -0.5629431 -0.01045948 -0.9821643 -0.1876782 0.01142078 -0.9347766 -0.1952995 -0.2967337 -0.7273786 -0.1916473 -0.6589324 -0.6172586 -0.2342774 -0.7510699 -0.4444963 -0.04888457 -0.894446 -0.6064106 -0.01474452 -0.7950151 -0.9496231 -0.09806019 -0.2976583 -0.9031519 -0.07083696 -0.4234368 -0.7779619 -0.08093416 -0.623077 -0.4002875 -0.08156216 -0.9127528 -0.1789582 -0.03172492 -0.9833451 -0.1491221 0.9888163 0.002235174 -0.1468158 0.9891169 -0.009648799 -0.1501712 0.988635 0.007050275 -0.1480597 0.9889785 -3.09453e-4 -0.6692804 0.7428649 -0.01468461 -0.8758887 0.4824979 -0.003830313 -0.6369802 0.7708802 0 -0.8542082 0.5194149 0.02316784 -0.9887612 -0.1494712 0.003135263 -0.9892189 -0.1464436 4.60331e-4 -0.9892069 -0.1465255 1.5421e-5 -0.9892518 -0.1462202 -8.33908e-4 0.9888026 0.1491029 0.006165981 0.9894429 0.144114 -0.01529973 0.9889032 0.1484359 0.006104052 0.9891351 0.1470055 0.001119792 0.7536639 0.6570791 -0.0154255 0.68276 0.7300736 0.02883523 0.4891414 0.8716727 -0.03045785 0.4037218 0.9148326 0.009489715 -0.1470274 0.9891121 0.006352424 -0.1465547 0.9892022 8.66145e-4 -0.1443387 0.9894778 -0.01000362 -0.1449715 0.9893474 -0.0132361 0.1441922 -0.9894933 -0.01057171 0.1465207 -0.9892077 -1.57927e-6 0.1466383 -0.9891899 -8.01499e-4 0.1465029 -0.9892082 0.001991748 0.7354086 -0.6775828 -0.007462978 0.919264 -0.3936144 0.004619717 0.7238551 -0.6899397 0.004153132 0.9148712 -0.4037461 -1.48734e-6 0.988765 0.1494455 0.003156542 0.9894105 0.1451426 -6.91347e-4 0.9893181 0.1457693 9.70485e-4 0.9894137 0.1451198 -8.31741e-4 -0.005676388 0.01234012 -0.9999079 0.004267096 0.005600392 -0.9999752 -9.83186e-4 0.007201373 -0.9999737 -0.00486952 0.009147167 -0.9999463 -0.008751332 0.006483197 -0.9999407 -0.01548558 0.00361526 -0.9998736 0.008787393 0.005140781 -0.9999483 0.001767456 0.006593823 -0.9999767 0.001041948 0.008028805 -0.9999672 2.90918e-6 -2.05628e-6 -1 -7.29067e-7 -9.15272e-7 -1 -6.53154e-7 -1.48705e-6 -1 -3.92377e-7 2.61101e-7 -1 -4.88129e-7 8.06623e-7 -1 0.001192927 -0.002636969 -0.9999958 0.001273572 -0.002225816 -0.9999967 0.002003312 -5.01528e-4 -0.9999979 0.004850625 0.002791166 -0.9999845 0.004722177 0.00288546 -0.9999847 0 3.00931e-6 -1 -0.02040797 -0.003626763 -0.9997851 -0.005700886 -0.00470823 -0.9999727 -0.004129052 -0.005657613 -0.9999755 0.001146554 -0.007228314 -0.9999733 0.004872322 -0.0091632 -0.9999462 0.01117688 -0.005080819 -0.9999247 0.01428639 -0.003847539 -0.9998906 -0.005944073 0.01064115 -0.9999258 -0.008517384 0.002955675 -0.9999594 -0.01365381 -0.005076706 -0.9998939 -0.0147016 -0.004324436 -0.9998826 -0.007986426 -0.01118427 -0.9999057 0.004478931 -0.03278076 -0.9994525 -0.003092527 -0.01684361 -0.9998534 -0.9878118 -0.1544755 0.01911813 -0.9894424 -0.1441179 -0.01529979 -0.9889041 -0.1484297 0.006105959 -0.9891355 -0.1470025 0.001117706 -0.7585311 -0.6516153 -0.005312919 -0.697274 -0.7160851 0.03210991 -0.501995 -0.8644009 -0.02849638 -0.4103946 -0.911781 0.01522952 0.1464418 -0.9892189 -8.62548e-4 0.1463651 -0.9892305 -6.80813e-4 0.147263 -0.9890874 -0.004476785 -6.5237e-5 -9.84437e-6 -1 1.80298e-7 0 -1 2.1796e-5 2.03542e-5 -1 7.33346e-7 0 -1 -3.04295e-7 0 -1 1.2076e-5 4.50351e-5 -1 -0.2586897 0.8864851 -0.3836976 -0.1659832 0.7741247 -0.6108852 -0.1966719 0.5678004 -0.7993265 -0.04888528 0.4445033 -0.8944424 -0.01474416 0.6064115 -0.7950143 -0.0529952 0.9059773 -0.4199962 -0.08622133 0.7900495 -0.6069495 -0.08147823 0.4004083 -0.9127073 -0.03152304 0.1759459 -0.9838951 -1.62026e-5 3.19735e-5 -1 -5.30182e-7 0 -1 5.60483e-5 -1.70332e-5 -1 3.16513e-7 0 -1 2.76797e-7 0 -1 -2.86503e-5 -2.27717e-5 -1 6.60693e-5 9.79539e-6 -1 -2.11394e-7 0 -1 -9.12398e-6 -4.19782e-5 -1 0.2586875 -0.8864778 -0.3837158 0.1659855 -0.7741231 -0.6108864 0.1966723 -0.5677945 -0.7993308 0.04888188 -0.4444827 -0.8944528 0.01474452 -0.6064129 -0.7950132 0.05299401 -0.9059768 -0.4199973 0.08622145 -0.7900486 -0.6069507 0.08147776 -0.4004093 -0.9127069 0.0315209 -0.1759346 -0.9838971 1.60424e-5 -3.0153e-5 -1 -6.03733e-5 1.65368e-5 -1 2.9277e-7 0 -1 -0.9974986 -0.07044357 -0.005855143 -0.9922595 -0.1234643 -0.0133391 -0.996401 -0.08475953 -0.001013159 -0.5291544 0.848373 -0.01608675 -0.6315655 0.77527 0.009034872 -0.7401394 0.6723657 -0.01086366 -0.7503184 0.661062 -0.004426956 -0.875498 0.483056 0.01265597 -0.915951 0.4009417 -0.01672309 -0.9888002 0.1483732 -0.01611489 -0.9998044 0.01728624 0.009613215 -0.3576118 0.9338703 -4.58576e-4 0.03967618 0.9991177 0.01377278 0.1588193 0.9871633 -0.01688808 0.2600017 0.9655703 0.008562743 0.3828069 0.9238218 -0.003498017 0.5305774 0.8475916 -0.008734643 0.5988165 0.8008488 0.007748365 0.6911583 0.7226951 -0.003496646 0.808602 0.5882589 -0.01069182 0.9777165 0.2096188 -0.01142138 0.9775159 0.2105656 -0.0111742 -0.9643956 0.2639746 0.01608031 -0.4255348 0.9047889 0.01665693 0.4332994 0.9012053 0.008986115 0.7300412 0.6833441 0.008986294 0.8621798 0.5064747 0.01138579 0.9127736 0.4083278 -0.01062059 0.9586881 0.2841848 0.01250213 -0.4720114 0.8815903 0.001939237 -0.2064396 0.9784564 -0.002402245 -0.196758 0.980452 -5.27934e-4 -0.09771198 0.9951247 -0.01339131 -0.1168223 0.9930188 -0.0163235 0.999264 0.01505243 -0.03528445 0.998928 0.04625546 -0.00184077 0.5138047 -0.8578613 -0.00888288 0.8111152 -0.5847439 -0.01291531 0.8785691 -0.4775038 0.01031094 0.928964 -0.3699288 -0.01336222 0.3576076 -0.9338719 -4.60704e-4 -0.01810783 -0.9997896 0.009636282 -0.1512064 -0.9884567 -0.009480237 -0.5305711 -0.8475956 -0.008736014 -0.5988202 -0.8008461 0.007748365 -0.6911558 -0.7226974 -0.003497302 -0.801328 -0.5981615 -0.008736491 -0.8547605 -0.5189204 0.0103116 -0.9116714 -0.4107419 -0.01209855 -0.9966658 -0.07127577 -0.03971362 -0.9578332 -0.2873171 -0.002133548 0.9998873 -0.005362153 0.01402962 0.991572 -0.1289539 -0.01249045 0.9628372 -0.2695984 0.01616805 0.7342936 -0.6786317 0.01649552 0.6632102 -0.7483834 -0.00863564 0.5601106 -0.8284106 0.003496825 0.4028427 -0.9152046 0.01087808 -0.1879251 -0.9821792 0.002894699 -0.3761611 -0.9265515 -0.002288877 -0.4169239 -0.908864 0.01186168 -0.7300424 -0.6833428 0.008986294 -0.9522027 -0.3052064 0.01262325 0.4723078 -0.8814316 0.001928091 0.2064321 -0.9784581 -0.002400755 0.1967593 -0.9804517 -5.29703e-4 0.09771263 -0.9951246 -0.01339244 0.116822 -0.9930189 -0.01631486 -7.33917e-7 0 1 1.37045e-6 0 1 -1.69751e-6 0 1 1.52259e-6 0 1 -1.24182e-5 2.47666e-6 1 0 7.49244e-6 1 -1.45863e-6 7.63761e-6 1 4.96079e-5 -2.43955e-5 1 -2.66101e-5 -2.92568e-5 1 -6.2041e-7 0 1 5.35121e-7 0 1 6.16025e-7 0 1 -6.40835e-7 0 1 5.01839e-7 0 1 -5.76032e-5 -1.6814e-4 1 -1.25142e-4 -1.22753e-5 1 -2.00455e-5 2.84473e-4 1 -7.03069e-7 -5.29238e-7 1 -1.0399e-6 1.53989e-6 1 -6.92319e-7 0 1 -1.45263e-6 0 1 1.13542e-6 0 1 8.97057e-7 0 1 8.27401e-6 -4.26671e-6 1 0 -7.40169e-6 1 -3.91992e-5 4.83399e-6 1 -1.00424e-5 2.17059e-5 1 1.82556e-5 1.53371e-5 1 2.35134e-7 0 1 7.62702e-7 0 1 -6.26811e-7 0 1 3.43966e-7 0 1 -1.19816e-5 -2.80756e-5 1 -2.89627e-5 -2.65687e-6 1 -2.86062e-5 -1.08918e-5 1 -7.50529e-6 2.95564e-5 1 -0.9987875 -0.04814004 0.01030713 -0.9825458 0.1857842 -0.009391427 -0.9741122 0.2230567 0.03675901 -0.8739216 0.4852175 0.0287227 -0.7994424 0.6000246 -0.0293681 -0.7261572 0.6869708 0.02769458 -0.5691688 0.8216508 0.03061097 -0.05438637 0.9977893 0.03819531 0.8998019 0.4341743 0.04300552 -0.9944471 -0.09752058 -0.03955751 -0.9032141 0.4280968 -0.03061848 -0.6298714 0.7756813 -0.03975701 -0.3775795 0.9252369 -0.03701752 -0.3421618 0.939592 0.009611606 -0.09395235 0.995506 -0.01186734 0.2093348 0.9768553 -0.04396361 0.2247408 0.9742192 -0.0197134 0.4603516 0.8866808 0.04328751 0.5676526 0.8211575 -0.05891478 0.622065 0.7829192 0.008533239 0.8032622 0.5954735 -0.01346331 0.7891876 0.6124244 -0.04603809 0.9379253 0.3451089 -0.03458189 0.9791473 0.1997475 0.0370351 0.9729413 -0.2298897 0.02315193 0.9369387 -0.3482582 -0.02936244 0.8913655 -0.4524388 0.02768856 0.7873306 -0.6160963 0.02314817 0.7050738 -0.708526 -0.0293591 0.6200644 -0.7840623 0.02768856 0.4453787 -0.8948189 0.03061044 0.1867815 -0.9815965 0.03976094 -0.2551251 -0.9663623 0.032485 -0.6363084 -0.7708271 0.0306161 -0.8286287 -0.5579862 0.04501003 -0.9322409 -0.3570215 -0.05884361 -0.9677745 -0.2494804 0.03423821 0.9947903 0.09100067 -0.04594689 0.9988167 -0.03692847 0.03164619 0.985583 -0.16769 -0.0225045 0.8323875 -0.5532412 -0.03248405 0.5120488 -0.8580357 -0.03976058 0.2610641 -0.9648361 -0.03061121 0.05689424 -0.9979963 -0.02768898 -0.05682295 -0.9979524 0.02936255 -0.1796892 -0.9834511 -0.02314758 -0.3661532 -0.9301425 -0.02769392 -0.4694005 -0.8824968 0.02936834 -0.5855512 -0.8101266 -0.02871805 -0.7903116 -0.6115142 -0.03818702 -1.5474e-6 0 1 3.52329e-6 0 1 -3.58964e-7 0 1 2.27433e-6 0 1 -6.67544e-7 0 1 -6.43546e-7 0 1 -3.32058e-7 0 1 8.05775e-7 0 1 -2.22202e-7 0 1 -3.12274e-6 0 1 3.33777e-7 0 1 3.76276e-7 0 1 -5.44726e-7 0 1 -2.89201e-6 0 1 6.1022e-7 0 1 -3.89341e-6 0 1 3.33222e-7 0 1 4.74094e-7 0 1 0 0 1 3.52056e-6 0 1 -6.30307e-7 0 1 -9.70521e-7 0 1 3.73566e-7 0 1 3.5899e-7 0 1 0 0 1 -0.9818656 0.1894263 0.007602751 -0.7365853 0.6763157 0.006269335 -0.526589 0.8500971 -0.006253421 -0.3221108 0.9466836 0.005912423 0.08843278 0.9960572 0.007057726 0.9112714 0.4115821 0.01359385 -0.9968137 0.07954055 -0.006003916 -0.8183835 0.5746343 -0.00664246 -0.09453338 0.9954968 -0.007057249 0.3163046 0.9486393 -0.005913197 0.5523149 0.8335952 0.008209049 0.7466152 0.6651514 -0.01180368 1.05048e-6 0 1 -1.34241e-6 0 1 0.9962546 -0.08628267 0.005661725 0.8739724 -0.4859244 0.007057368 -0.03848373 -0.9991662 0.01363843 -0.9228611 -0.3850222 0.009241878 -0.913647 -0.4064664 0.00585556 0.9885876 0.1504074 -0.00850141 0.9437668 -0.3305559 -0.006079673 0.7379733 -0.674804 -0.005912005 0.5232163 -0.8521518 0.009064018 0.28693 -0.9578568 -0.01347386 -0.2810642 -0.9596566 -0.007882177 -0.5523144 -0.8335955 0.00820893 -0.7140411 -0.7000567 -0.008119404 -0.8259356 -0.5636873 0.009334444 -0.9968133 -0.07762354 -0.01838362 -0.9994156 0.02669423 0.0213533 -0.825536 0.5640073 -0.0196501 -0.7348875 0.6771888 0.03682237 -0.3946364 0.918057 -0.03786027 -0.09734177 0.9945308 0.03785723 0.3308407 0.9428633 -0.03941231 0.4569002 0.8893375 0.01792037 0.922571 0.3852517 -0.02107149 0.9498358 0.3120386 0.02106928 0.9036164 -0.4278244 -0.02106541 0.9102059 -0.4130856 -0.02975833 0.541401 -0.8398246 0.03974682 0.3424541 -0.9386935 -0.03974676 -0.2204014 -0.9749553 0.02975791 -0.2046791 -0.9786024 0.0210675 -0.7874301 -0.6161436 -0.01792025 7.61008e-4 -2.12052e-4 -0.9999997 0.001917421 0.01064234 0.9999416 0.002530872 0.009394645 0.9999527 -0.006190419 0.008409023 0.9999455 -0.006153762 0.00897777 0.9999408 -0.01680088 0.002684235 0.9998553 -0.01003658 -0.002982735 0.9999452 -0.01089519 -0.009538829 0.9998952 -0.003267586 -0.009155213 0.9999529 6.84244e-4 -0.01495009 0.999888 0.008085668 -0.00858891 0.9999305 0.007710278 -0.008531808 0.9999339 0.01254385 -0.001140952 0.9999207 0.009293138 0.002676725 0.9999533 0.01149529 0.008954226 0.9998939 -0.03850662 -6.71822e-4 -0.9992582 -0.02152013 -0.01112371 -0.9997066 -0.01971352 -0.01676982 -0.9996651 0.02312713 0.01622396 -0.999601 0.02314627 0.02163046 -0.9994981 0.009667038 0.02768325 -0.9995701 0.007339239 0.02632218 -0.9996266 -0.005074322 0.02721005 -0.9996169 0.006895601 0.05206996 -0.9986197 -0.02840763 0.02429491 -0.9993011 -0.02691042 0.01976847 -0.9994424 -0.01663178 -0.01662296 -0.9997235 -0.01059508 -0.03034383 -0.9994834 0.005919814 -0.03174299 -0.9994785 0.01392203 -0.01500898 -0.9997904 0.01625317 -0.01499289 -0.9997555 0.01566064 -0.003421545 -0.9998716 0.02758485 -0.01602852 -0.999491 0.03352558 0.00921452 -0.9993954 0.683451 -0.7299795 -0.004971504 0.6987 -0.7154074 -0.003269731 0.1470211 -0.9891319 -0.001705467 0.1471131 -0.9891182 -0.001696348 -0.4453979 -0.8953323 -9.5429e-4 -0.5097551 -0.860293 -0.006768107 -0.8801892 -0.4745972 0.004953742 -0.9733534 -0.229079 -0.01030325 -0.9976105 0.06901407 0.003210246 -0.8976572 0.4406616 -0.005383193 -0.898549 0.4388387 -0.005504131 -0.4659581 0.8847783 -0.007102429 -0.6078645 0.7940407 5.58066e-4 -0.2384534 0.9711509 0.002429723 0.1932596 0.9811371 -0.004572629 0.1616731 0.9868424 -0.001964569 0.694064 0.719913 -6.77144e-4 0.7497464 0.6616882 -0.007006585 0.9821751 0.1879011 0.005027115 0.9961833 -0.08663636 -0.01063281 0.9440557 -0.3297824 0.001527249 -0.002162992 0.001230657 -0.999997 -0.002164959 0.001236081 -0.9999969 -0.001482546 7.73028e-4 -0.9999986 0.002127528 2.27501e-7 -0.9999977 0.9827339 -0.184916 0.00634402 0.9642242 0.2650002 -0.006837308 0.9561027 0.2929631 0.006345808 0.7306202 0.6827499 -0.006841361 0.7104495 0.7037196 0.006343185 0.3296418 0.9440814 -0.006841421 0.3020253 0.9532788 0.006347775 -0.1833106 0.9830235 -0.007877469 -0.2186554 0.975722 0.01250976 -0.7598996 0.6498883 -0.01406639 -0.7861518 0.6178721 0.01413321 -0.999749 -0.0174427 -0.01407122 -0.9981679 -0.0588321 0.01413708 -0.7616352 -0.6478841 -0.01257306 -0.7383903 -0.674332 0.00750041 -0.3296361 -0.9440833 -0.006832957 -0.259788 -0.9653098 0.02621662 0.1831505 -0.9821708 -0.04238462 0.3684092 -0.9286453 0.04350405 0.7347436 -0.6777692 -0.0279445 0.784236 -0.6204304 0.00634253 0.9769335 -0.2134346 -0.006834328 -0.6251711 0.5622109 0.5413687 -0.498287 0.39162 0.773527 -0.1903396 0.8532993 0.4854393 -0.001276314 0.5044932 0.8634148 0.2559633 0.8079029 0.5308257 0.4296964 0.4116167 0.8036994 0.3993276 0.3955451 0.8270922 0.8817118 0.2701662 0.3867745 0.5074422 -0.08108359 0.8578625 0.5523646 -0.1039314 0.8270984 0.7232124 -0.572163 0.3867731 0.2808048 -0.4863355 0.8274216 0.294417 -0.7393033 0.6055983 -0.0710718 -0.5556074 0.8284016 -0.2205777 -0.8160367 0.5342562 -0.5782235 -0.5295886 0.6206398 -0.4181451 -0.2901206 0.8608047 -0.9261358 -0.05458003 0.3732204 -0.5758877 0.07246339 0.8143111 0.8987981 -0.0841214 -0.4302158 0.4555909 0.3726315 -0.8084447 0.4935896 0.4467964 -0.7461518 0.1284052 0.8005753 -0.5853131 -0.04003691 0.5965029 -0.8016117 -0.377234 0.7207614 -0.5815476 -0.4303575 0.4135597 -0.802347 -0.7506849 0.3689496 -0.5480405 -0.596637 -0.1031048 -0.7958604 -0.6610182 -0.1473115 -0.7357679 -0.4250532 -0.7286856 -0.5369796 -0.0996527 -0.4783077 -0.8725201 0.1201075 -0.8080673 -0.5767161 0.5429533 -0.552151 -0.6327173 0.4280356 -0.2435782 -0.870319 0.957292 0.2253875 0.1810875 0.2818646 0.9441733 0.1705553 -0.6711657 0.6944268 0.259438 -0.9569779 -0.2259898 0.181995 -0.2828755 -0.9419645 0.1807882 0.6743595 -0.7164216 0.1788281 -0.3718488 0.3718904 0.8505446 0.06456226 0.4900824 0.8692819 0.2359015 0.4343217 0.8693189 0.5217465 0.07847881 0.8494832 0.3573616 -0.3970916 0.8453468 -0.1937237 -0.5031545 0.8422034 -0.5235742 -0.1345471 0.841289 0.9670902 0.2508074 0.04280537 0.9816678 0.1905941 0.001522421 0.9794356 0.2016915 -0.005145192 0.2619633 0.9650779 1.09394e-4 0.3058643 0.9515865 0.03049874 0.2682344 0.9614542 0.06046664 0.3556352 0.9346249 5.89991e-5 -0.6674847 0.7444812 0.01455783 -0.7219023 0.6911175 0.03483933 -0.6820763 0.7312793 0.00155735 -0.9791386 -0.2031837 0.002036392 -0.9667922 -0.2542438 0.02594506 -0.9776434 -0.2102516 -0.002770185 -0.3139694 -0.9494276 -0.003225922 -0.2642124 -0.9639037 0.03288638 -0.3148653 -0.9491328 -0.002615928 0.6653978 -0.7464868 -0.001841962 0.7006172 -0.7122042 0.04359853 0.6578848 -0.7531051 0.004523694 -0.1191126 -0.1722283 0.977829 -0.7479651 0.6565653 -0.09731566 0.3469607 -0.3738647 -0.8601415 0.7807425 -0.1934252 -0.5941616 -0.5430667 0.6129739 -0.5738829 -0.6745734 0.4199009 -0.6071524 -0.7033807 0.05450284 -0.7087208 -0.8930773 -0.09558659 -0.4396319 0.936695 -0.3365612 -0.09658819 0.2667543 -0.880223 -0.3924917 0.1515904 -0.7384563 -0.6570409 -0.3156012 -0.7058137 -0.6342104 -0.3759934 -0.7534272 -0.5394225 -0.5208542 -0.3836365 -0.7625839 -0.7669815 -0.4178503 -0.4869708 -0.1807551 0.7156524 -0.6746623 -0.1111643 0.8342373 -0.5400838 0.1399334 0.7163079 -0.6836093 0.3340446 0.8238531 -0.4579088 0.4863303 0.5021185 -0.7150944 0.7916309 0.4909612 -0.3636999 0.6552976 0.1317578 -0.7437909 -0.3215824 -0.9468816 0 -0.3215824 -0.9468816 0 0.9468816 -0.3215826 0 0.9468817 -0.3215823 0 0.3215824 0.9468816 0 0.3215824 0.9468816 0 -0.9468817 0.3215825 0 -0.9468817 0.3215823 0 0 0 1 0 0 1 -0.5049892 -0.8631258 2.53603e-5 -0.5018933 -0.8649296 -3.686e-5 -0.4928305 -0.8701052 -0.005934536 -0.4999989 -0.8660255 0.001008689 0.00671631 -0.3978548 -0.9174239 0.4937196 -0.8696213 -1.64147e-5 0.4849187 -0.8745592 -3.62925e-5 0.5346438 -0.8446882 -0.02564734 0.4999824 -0.8659948 0.008411705 0.4390805 -0.468169 -0.7668286 0.3290719 -0.2046304 -0.9218666 0.999984 0.005679547 0 0.9999895 -0.002967715 -0.003495752 0.9999698 0.007725119 8.6873e-4 0.999987 0 -0.005115866 0.4269277 0.1671512 -0.8887032 0.6015163 0.1237216 -0.789222 0.4012272 0.451646 -0.7968895 0.3557684 0.2839872 -0.890382 0.5049841 0.8631287 2.43661e-5 0.5072436 0.8618021 0.001134335 0.4999988 0.8660246 0.001633822 0.4908083 0.8711624 -0.01353871 -0.006718754 0.3978466 -0.9174275 -0.4849351 0.8745502 -2.41956e-5 -0.5072581 0.8617932 0.001371145 -0.4999807 0.8659957 0.008413732 -0.4795147 0.7047241 -0.5229049 -0.3596314 0.3081875 -0.8807303 -0.4353294 0.1849803 -0.8810622 -0.9999819 0.00601232 4.45792e-5 -0.9987633 -0.04954671 -0.004130303 -0.9999666 0.008134603 9.49175e-4 -0.9997126 0 -0.02397418 -0.9864524 0.1320821 0.09729343 -0.345916 -0.2043393 -0.9157443 0.004238128 2.51167e-4 -0.999991 -0.004386723 -2.63535e-4 -0.9999904 0.009444653 -0.02061164 -0.9997431 -0.006166577 0.007704257 -0.9999514 -0.01161825 -0.01981711 -0.9997361 8.2216e-4 -6.78303e-4 -0.9999995 0.001522362 -3.82156e-4 -0.9999989 0.00197792 0.008974611 -0.9999579 0.001046061 -3.90132e-4 -0.9999995 9.61191e-4 -5.54811e-4 -0.9999995 0.003144085 0.004417955 -0.9999854 0.01037782 -0.0186119 -0.999773 -0.001083135 -6.25246e-4 -0.9999992 -0.001135706 -4.23692e-4 -0.9999994 -2.39179e-4 0.009973466 -0.9999503 -0.01154506 0.0197038 -0.9997392 -0.002751767 -0.003616511 -0.9999897 0.007056415 -0.005881726 -0.9999579 -9.60434e-4 -7.9269e-4 -0.9999992 -0.004926979 -0.004294991 -0.9999787 0.0082165 0.0109499 -0.9999064 -0.007582306 0.008515894 -0.999935 0.004924952 0.004297792 -0.9999787 -0.01709395 -0.01448571 -0.999749 0.00130409 -0.00150454 -0.999998 0.003261148 0.002904951 -0.9999905 0.8710874 0.07301056 -0.4856709 0.4066545 0.4485898 -0.7958641 0.4146721 0.8464213 -0.334093 -0.03928077 0.5415954 -0.8397212 -0.5661487 0.7593677 -0.3206812 -0.5064833 0.4227907 -0.7514804 -0.7034139 0.01924264 -0.71052 -0.8710824 -0.07301872 -0.4856787 -0.4066433 -0.4485983 -0.7958648 -0.4146714 -0.8464297 -0.3340729 0.03928065 -0.5416451 -0.839689 0.5661327 -0.7593603 -0.3207268 0.5064761 -0.4227948 -0.751483 0.70342 -0.01923835 -0.7105141 0.9996066 -0.02483195 0.01304334 0.7654134 -0.643287 0.01801526 0.7048034 -0.709032 -0.02293246 0.1729562 -0.9849217 -0.003928124 0.07632869 -0.9964275 0.03614306 -0.4801529 -0.8761731 -0.0421198 -0.6729665 -0.7376009 0.05532652 -0.9913883 -0.115933 -0.06090021 -0.9996061 0.02484738 0.01305115 -0.7654215 0.6432775 0.01800644 -0.7048168 0.7090185 -0.02293664 -0.172942 0.9849241 -0.003939747 -0.0763266 0.9964268 0.03616666 0.4801402 0.8761799 -0.04212427 0.672976 0.737592 0.05533009 0.9913892 0.1159238 -0.06090295 -0.8332586 0.3402817 0.435762 -0.4071902 0.4126908 0.8147898 -0.2435996 0.7982449 0.5508759 -0.1242281 0.6967533 0.7064716 0.3509548 0.6575164 0.6667106 0.3503088 0.6403852 0.6835135 0.6956671 0.08119016 0.7137615 0.7465391 0.1102601 0.6561419 0.5229169 -0.5681544 0.63542 0.5887799 -0.5944293 0.5477154 0.1083644 -0.6051413 0.7887087 -0.1805624 -0.878403 0.4424992 -0.2848523 -0.5211021 0.8045569 -0.7978688 -0.3776704 0.4698622 -0.5456994 -0.06363785 0.8355612 -0.001493811 7.41683e-4 0.9999987 -5.508e-4 0 1 -0.001553118 -7.52199e-4 0.9999985 3.21214e-4 5.56359e-4 0.9999998 2.54912e-4 0.002931356 0.9999957 -6.64355e-5 -0.001234412 0.9999992 -9.71868e-4 -0.001683294 0.9999982 -9.40455e-4 0.001628875 0.9999983 0.001016139 6.19618e-4 0.9999994 0.001529395 0 0.9999989 0.002219378 4.13166e-4 0.9999974 8.4894e-4 -0.001261055 0.9999989 8.40887e-4 -0.001456439 0.9999986 -0.8631226 0.5049946 2.92113e-5 -0.8649239 0.5019031 -3.68584e-5 -0.8701062 0.4928285 -0.005934774 -0.8660255 0.4999991 0.001010656 -0.4017487 -0.003998577 -0.9157413 -0.8698659 -0.4932883 -1.08866e-5 -0.8671169 -0.4981046 -3.68616e-5 -0.8611201 -0.5083513 -0.007146894 -0.8660246 -0.5000005 0.001006662 -0.2021316 -0.3583012 -0.9114621 0.00568664 -0.9999839 -6.94103e-6 -0.002953827 -0.9999896 -0.003502309 0.007701396 -0.9999701 8.58585e-4 0 -0.999987 -0.005107522 0.1671627 -0.4269309 -0.8886994 0.1237182 -0.601507 -0.7892296 0.4516495 -0.401211 -0.7968956 0.2839823 -0.35578 -0.890379 0.8631174 -0.5050035 2.65061e-5 0.8618033 -0.5072413 0.001138091 0.8660243 -0.4999992 0.001640379 0.8711646 -0.4908037 -0.01356101 0.3978542 0.006712734 -0.9174242 0.874552 0.4849318 -3.62924e-5 0.8617933 0.5072578 0.001376807 0.8659961 0.49998 0.008409678 0.7046949 0.479502 -0.522956 0.3082129 0.3596196 -0.8807262 0.1849776 0.4353677 -0.881044 0.006011605 0.9999819 4.50714e-5 -0.04952895 0.9987642 -0.004135429 0.008152782 0.9999663 9.67692e-4 0 0.9997125 -0.02397739 0.132089 0.9864525 0.0972836 -0.2043393 0.3459111 -0.9157462 2.50883e-4 -0.004239201 -0.999991 -2.63852e-4 0.004384875 -0.9999904 -0.02060663 -0.009442687 -0.9997432 0.007704019 0.006166756 -0.9999514 -0.01981955 0.01161932 -0.9997361 -6.78867e-4 -8.21687e-4 -0.9999995 -3.82467e-4 -0.001522421 -0.9999988 0.008979499 -0.001978754 -0.9999577 -3.90047e-4 -0.001045703 -0.9999995 -5.54665e-4 -9.60903e-4 -0.9999995 0.004417896 -0.003143966 -0.9999854 -0.01861327 -0.01037847 -0.9997729 -6.2507e-4 0.001082658 -0.9999992 -4.2356e-4 0.001135289 -0.9999994 0.009966433 2.3964e-4 -0.9999504 0.01969712 0.01153761 -0.9997394 -0.003611505 0.002749562 -0.9999898 -0.005874097 -0.007045328 -0.999958 -7.91818e-4 9.59834e-4 -0.9999992 2.85873e-4 0.009823203 -0.9999518 -0.005536913 -0.008857429 -0.9999455 -0.007127344 -0.004072427 -0.9999664 0.004294037 -0.00492829 -0.9999787 0.01745027 -0.01113021 -0.9997859 -0.001504242 -0.001303851 -0.999998 0.002892971 -0.003256022 -0.9999906 0.07300984 -0.8710941 -0.485659 0.4485947 -0.4066455 -0.7958657 0.8464345 -0.4146881 -0.3340398 0.5416272 0.03927904 -0.8397008 0.7593541 0.5661394 -0.3207297 0.4228026 0.5064935 -0.7514668 0.0192489 0.7034277 -0.7105061 -0.07301121 0.8710898 -0.4856666 -0.4485964 0.4066485 -0.7958632 -0.8464339 0.4146723 -0.3340606 -0.5416221 -0.03927981 -0.8397039 -0.759357 -0.5661457 -0.3207117 -0.4228245 -0.5065003 -0.7514498 -0.01923453 -0.7034489 -0.7104856 -0.02483218 -0.9996065 0.01304608 -0.6432904 -0.7654107 0.01800584 -0.7090317 -0.7048036 -0.02293479 -0.9849193 -0.1729703 -0.003937005 -0.9964262 -0.07633966 0.03615671 -0.8761792 0.4801419 -0.04211825 -0.7376011 0.6729667 0.05532312 -0.1159424 0.9913864 -0.06091463 0.02484697 0.9996061 0.01304548 0.6432833 0.7654166 0.01800179 0.709032 0.7048034 -0.02293407 0.9849232 0.1729475 -0.003932595 0.9964268 0.07633084 0.03615725 0.8761726 -0.4801539 -0.04211908 0.7375988 -0.6729692 0.05532175 0.1159076 -0.9913917 -0.0608924 0.6014138 0.6088533 0.5173 0.5944359 0.5887905 0.5476967 0.6051418 0.108372 0.7887072 0.8783916 -0.1805549 0.4425247 0.5210949 -0.2848516 0.8045619 0.3242509 -0.8716545 0.367532 0.06564122 -0.5629237 0.8238983 -0.6014089 -0.608832 0.5173308 -0.594437 -0.5887961 0.5476896 -0.6051239 -0.108375 0.7887205 -0.8784006 0.180561 0.4425045 -0.5211246 0.2848526 0.8045422 -0.3242251 0.8715889 0.3677105 -0.06565481 0.5628776 0.8239287 -0.002109587 8.80364e-4 0.9999974 0 0.004263043 0.9999909 0.001234173 -6.64995e-5 0.9999992 0.001682937 -9.71661e-4 0.9999982 -0.001234471 6.61107e-5 0.9999993 -0.001683592 9.72045e-4 0.9999981 0.00336188 7.6229e-4 0.9999941 0.001456201 8.4076e-4 0.9999986 0.002109229 -8.79905e-4 0.9999974 0 -0.004262089 0.9999909 -0.003360986 -7.62485e-4 0.9999942 -0.001456439 -8.40883e-4 0.9999987 -0.02815395 -0.003259181 -0.9995983 -0.00193417 -0.03148341 -0.9995024 -0.00818336 0.005404889 -0.9999519 -0.008735895 0.007304728 -0.9999352 0.02769291 0.01327252 -0.9995284 0.005374133 0.02804797 -0.9995921 -6.84637e-4 -0.008912384 -0.9999601 0.0567528 0.01991277 -0.9981898 0.02594023 0.04161679 -0.9987969 -0.02429348 0.01663035 -0.9995666 -0.02481657 0.0204128 -0.9994837 -0.03116381 0.007802724 -0.999484 0.008299469 0.004366278 -0.9999561 -0.00910449 0.03342396 -0.9993999 -0.03504705 -0.03310614 -0.9988372 -0.0146631 -0.05930411 -0.9981324 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.8468531 -0.5317228 0.01052635 0.8880259 -0.4597935 -2.31999e-4 0.999875 -0.005589842 0.01479727 0.9945257 0.1044553 0.002804219 0.9256431 0.3782295 0.0112822 0.7955976 0.6057669 -0.008424639 0.5688161 0.8223606 0.01309287 0.3589578 0.9333481 -0.003277957 0.06756031 0.9975477 0.01828676 -0.185137 0.9827123 0.001046597 -0.4229067 0.9059783 0.01879709 -0.6739563 0.7387663 -0.002709686 -0.8650959 0.5012637 0.01853996 -0.9616293 0.2743453 -0.001915693 -0.999518 0.02843242 0.01246821 -0.9622789 -0.2719445 -0.008102774 -0.8421865 -0.5389958 0.01433384 -0.9904055 -0.1350664 0.0292266 -0.6958849 -0.7177799 0.02315914 -0.4950312 -0.8688505 -0.006572484 -0.173144 -0.9848249 0.0118795 -0.2002131 -0.9796521 0.01402044 0.3319535 -0.9430661 0.0208131 0.4567396 -0.8896005 1.41264e-4 -0.0162853 -0.02626669 0.9995224 0.01342052 -0.01373374 0.9998157 0.009685516 -0.01414614 0.9998531 -0.03138786 0.002099692 0.9995052 -0.1135795 0.09032601 0.9894145 0.02664577 0.01222312 0.9995703 0.06276941 0.06974953 0.9955878 0.6975618 -0.7150228 0.04636955 0.7474543 -0.664298 0.004518091 0.9852502 -0.1697956 -0.02125048 0.9979642 -0.05649745 0.02958869 0.9527825 0.3027936 -0.02284145 0.8830695 0.4686027 0.02449148 0.7412731 0.6692739 -0.05086076 0.4173375 0.9087452 0.003391087 0.3997133 0.9165372 0.01373881 -0.04459756 0.9989589 -0.009605705 -0.0979529 0.9950955 0.01379328 -0.5510576 0.8343873 -0.0115565 -0.6489614 0.7600337 0.03461062 -0.8282982 0.5586023 -0.04342567 -0.9905482 0.1371418 -0.002560377 -0.987428 0.1572053 -0.0165112 -0.9255837 -0.3767142 0.0371648 -0.8477956 -0.5282114 -0.04728162 -0.4823723 -0.8759646 0.00172609 -0.4904305 -0.8714748 -0.003126859 -0.1225526 -0.992286 -0.0186944 0.03180515 -0.9989225 0.03379929 0.3249847 -0.9448313 -0.04097461 -0.1476825 0.3480777 -0.9257602 -0.04334884 0.9735672 -0.2242498 0.2059832 0.5772596 -0.7901534 0.4093491 0.05490279 -0.9107245 0.9442676 -0.1625903 -0.2862225 0.3944987 -0.3298721 -0.8576452 0.4620056 -0.4141678 -0.7842296 0.3030291 -0.8773521 -0.3720573 0.02653574 -0.4289119 -0.9029566 -0.651975 -0.3699467 -0.6618672 -0.746885 0.06270861 -0.6619899 -0.1798651 -0.4300237 0.8847193 -0.4415694 -0.1073029 0.8907876 0.3235501 0.2957986 0.8987873 -0.07531976 -0.9803338 -0.1824079 -0.8866566 -0.4249426 -0.1823844 -0.8116939 0.5569972 -0.1758043 0.07686096 0.9806805 -0.1798843 0.886323 0.4243552 -0.1853496 0.8113237 -0.5553785 -0.1825062 -0.4540674 0.2982963 -0.8395488 -0.00770384 0.5344551 -0.8451618 -0.4873175 -0.2293156 -0.842577 -0.02068829 -0.5384271 -0.8424182 0.4547264 -0.2943568 -0.840582 0.4821169 0.2390432 -0.8428651 -0.05038082 -0.9986919 -0.008743286 -0.1008685 -0.9943476 -0.03314143 -0.05737179 -0.9983443 -0.004144728 -0.8899697 -0.4559671 -0.006932139 -0.9121111 -0.4090344 -0.02728116 -0.8944466 -0.4471747 -3.31482e-4 -0.8391472 0.5439041 -6.46543e-4 -0.8103365 0.5852862 -0.02819585 -0.8368203 0.5474738 0.002116084 0.03683483 0.9983973 -0.04296743 0.1137737 0.9926305 0.041718 0.05020028 0.9987292 0.004456102 0.8894916 0.4569516 -6.9968e-5 0.8764186 0.4812108 -0.01807314 0.9080668 0.4132617 -0.06804054 0.8403492 -0.5420439 -0.001306891 0.8107906 -0.5843036 -0.0347585 0.8399839 -0.5426108 -8.63177e-4 -0.2720593 -0.7169163 0.6418838 -0.2127866 -0.2274531 0.9502563 -0.6490638 -0.3722288 0.663447 -0.4402122 -0.108748 0.8912841 -0.5036748 -0.1428369 0.8520032 -0.7280598 0.03443366 0.6846482 -0.4233323 0.1419958 0.8947777 -0.5194661 0.1476842 0.841632 -0.6217923 0.4628584 0.6317725 -0.3148977 0.3443811 0.884444 -0.4059321 0.6395402 0.6528457 -0.129148 0.544699 0.8286277 -0.08880102 0.4684009 0.8790421 0.02155989 0.7285485 0.6846548 0.1771374 0.5316932 0.8282057 0.1715162 0.4475283 0.8776679 0.4112899 0.6146562 0.6730814 0.4426406 0.3390941 0.8301112 0.4445722 0.3414293 0.8281193 0.7407861 0.2196003 0.634832 0.3535079 -0.01348888 0.9353343 0.7001631 0.07210612 0.7103326 0.6437464 -0.2092857 0.736064 0.3966037 -0.6246102 0.6727314 -0.009263575 -0.1899636 0.9817475 0.6254049 -0.4655409 0.6262112 0.4040071 -0.2040675 0.8917033 0.03571707 -0.5235891 0.851222 -4.46963e-7 0 -1 -1.50897e-7 0 -1 7.5287e-7 0 -1 2.18463e-7 0 -1 0 0 -1 7.02041e-6 0 1 -2.32542e-6 0 1 -2.33452e-6 0 1 -3.39632e-6 0 1 -1.69502e-6 0 1 -3.96016e-6 0 1 1.3095e-6 0 1 0.978743 0.2050852 0.001465141 0.6669805 0.7450737 -0.001465201 0.6179345 0.7862284 0.001465201 0.0320084 0.9994866 -0.00146526 0.0452696 0.9989727 -0.002072274 -0.4164019 0.9091763 0.002829611 -0.5791683 0.8152033 -0.002829611 -0.8877692 0.4602842 0.002072274 -0.881585 0.4720231 0.001465201 -0.9898602 -0.1420379 -0.00146526 -0.9787438 -0.2050819 0.00146526 -0.6669771 -0.7450768 -0.001465141 -0.6179355 -0.7862275 0.001465082 -0.08033877 -0.9967669 -0.001247465 -0.04527103 -0.9989748 0 0.3842108 -0.9232454 0 0.4164082 -0.909177 0.001247286 0.8495763 -0.5274638 -0.00146526 0.8815844 -0.4720243 0.001465141 0.9898607 0.1420336 -0.001465201 -0.9809067 -0.1944743 0.001442849 -0.9589254 -0.283655 -0.001442909 -0.3971729 -0.9177428 0.001442849 -0.3112908 -0.9503136 -0.00144279 0.4698227 -0.8827599 0.001226246 0.5135425 -0.8580643 0 0.913846 -0.4060611 0 0.9303677 -0.3666266 -0.001056551 0.9303677 0.3666266 0.001056611 0.913846 0.406061 0 0.5135408 0.8580653 0 0.4698212 0.8827609 -0.001226246 -0.2449169 0.9695433 0.001226186 -0.2932742 0.9560284 0 -0.7899054 0.6132289 0 -0.8196884 0.5728084 -0.001226305 0.04888427 -0.02106779 0.9985823 0.01898968 -0.04459321 0.9988248 0.02186763 -0.02146053 0.9995305 0.006366014 0.01047742 0.9999249 0.002298653 0.008830666 0.9999585 0.00936228 0.002901971 0.999952 0.009565591 0.002823114 0.9999504 0.006470859 -0.006159543 0.9999602 0.01008796 -0.005164325 0.9999359 -0.002150952 -0.00893855 0.9999578 0.005000591 -0.01040881 0.9999334 -0.008616447 -0.002176284 0.9999606 -0.01035809 -0.005906224 0.999929 -0.00335431 -0.009833812 0.9999461 0.006359457 -0.03065729 0.9995098 0.02064454 0.004491746 -0.9997768 0.01612335 0.006723821 -0.9998475 0.01426422 0.009401619 -0.9998542 0.01254326 0.01912307 -0.9997385 -5.77173e-4 0.0186659 -0.9998256 -0.001900851 0.01952153 -0.9998077 -7.05411e-5 0.02171373 -0.9997643 -0.01247406 0.01480281 -0.9998127 -0.01509612 0.0145545 -0.9997802 -0.01602995 0.0102052 -0.9998195 -0.02200478 0.004992723 -0.9997455 -0.01824116 -0.003389775 -0.9998279 -0.0192151 -0.009260237 -0.9997726 -0.01488608 -0.01144617 -0.9998238 -0.0119028 -0.01692211 -0.999786 -0.005334615 -0.01688122 -0.9998433 -0.001404643 -0.01907575 -0.9998171 0.003925681 -0.01581686 -0.9998672 0.006764292 -0.01597279 -0.9998496 0.007451236 -0.01481443 -0.9998626 0.01806855 -0.01136958 -0.9997721 0.01645177 -0.003232359 -0.9998595 0.06059908 -0.9981069 -0.01050692 0.0306642 -0.9995089 -0.006459951 -0.3620295 -0.9321359 -0.00756973 -0.4065624 -0.9136208 -0.002042174 -0.8161844 -0.5777727 -0.004675626 -0.8059319 -0.5919718 -0.006572782 -0.9356914 -0.3525261 -0.01438909 -0.994735 -0.1023377 0.005419135 -0.9713992 0.2369228 -0.01585507 -0.8959831 0.4440881 2.96579e-4 -0.7387061 0.6737421 -0.01962321 -0.5776265 0.8162924 -0.003803133 -0.3014759 0.9534394 -0.008104681 -0.2616764 0.9650663 -0.01313555 0.2718631 0.9623047 -0.007762134 0.2121616 0.9772347 -7.18299e-5 0.7327584 0.6804141 -0.01008927 0.6634765 0.7481971 -2.56269e-4 0.9260803 0.3773013 0.004388034 0.9839681 0.1775304 -0.01702314 0.9992887 -0.03266829 -0.01884216 0.9660567 -0.2582195 0.007574796 0.7828785 -0.622005 -0.01452559 0.637055 -0.770817 0.001478195 0.4248932 -0.9049876 -0.02152103 0.03206759 -0.04542392 -0.998453 -0.05737835 -0.05888444 -0.9966145 -0.01038789 0.0349875 -0.9993338 -0.01468575 0.01046758 -0.9998375 -0.01283705 -0.0140385 -0.999819 -0.004467308 -0.02290636 -0.9997277 -0.07344424 -0.9969958 -0.02460992 -0.2375878 -0.9708068 0.0329591 -0.5745444 -0.8174585 -0.04074907 -0.7846701 -0.6182603 0.04524427 -0.9002394 -0.4335337 -0.04022282 -0.9978244 0.03606748 0.05518931 -0.9745888 0.2208971 -0.03716534 -0.719685 0.6941044 0.01651293 -0.7536675 0.6570079 -0.01805627 -0.296628 0.9542968 0.03646355 -0.09701883 0.9938482 -0.05341738 0.3016283 0.9522713 0.04690212 0.5476662 0.8344627 -0.06110483 0.8140444 0.5786886 0.04951262 0.9758585 0.2123816 -0.05093532 0.9920551 0.1257496 -0.003707647 0.9058127 -0.4230921 0.02227932 0.8461319 -0.5321388 -0.0298199 0.6517692 -0.7571973 0.04300308 0.3900866 -0.9206393 -0.01598966 0.2583811 -0.9657533 0.02366393 -0.1955185 0.4612208 0.8654755 -0.7529729 0.655805 0.05433028 -0.3953334 0.1804718 0.9006339 -0.9993607 0.03575325 -1.04547e-4 -0.403901 -0.1025858 0.9090326 -0.7704254 -0.6049314 -0.2012532 -0.2065469 -0.3401126 0.9174213 -0.2344729 -0.9560199 0.176206 0.1080015 -0.5911898 0.7992687 0.4155495 -0.1256015 0.9008569 0.9781665 0.1240888 0.1667104 0.4058209 0.2314514 0.8841604 0.6099448 0.436196 0.6615894 0.2295191 0.7178568 0.6572691 0.169912 0.5984178 0.7829599 -0.23197 0.7513864 0.6177447 0.4219762 -0.1892623 -0.8866317 0.3625331 0.3001729 -0.8823072 0.4122923 0.383148 -0.8265669 0.2572771 0.9109446 -0.3224723 -0.0790292 0.526084 -0.8467527 -0.4563748 8.6302e-5 -0.8897877 -0.2885857 -0.3864206 -0.8760123 0.7125813 -0.6774684 0.1823862 0.9429985 0.2783822 0.1823657 0.2296254 0.9572708 0.1757983 -0.713958 0.6766917 0.1798681 -0.9423628 -0.2785868 0.1853159 -0.2304091 -0.9558249 0.1825114 0.1373441 0.5256364 0.8395493 -0.3522745 0.4020032 0.8451604 0.5154479 0.1561473 0.8425744 0.376016 -0.3859294 0.8424195 -0.1404718 -0.5231565 0.8405802 -0.5180994 -0.1454368 0.8428649 0.7063599 -0.707799 0.008747458 0.7409415 -0.6707512 0.03314346 0.7113177 -0.7028585 0.004147112 0.966234 0.2575732 0.006933271 0.9512373 0.3072512 0.02728331 0.9636698 0.2670962 3.38113e-4 0.2587596 0.9659417 6.46547e-4 0.209649 0.9773702 0.02819383 0.254639 0.9670339 -0.00211364 -0.6961033 0.7166548 0.04296863 -0.749373 0.6608327 -0.04171788 -0.7062515 0.7079471 -0.00445193 -0.966541 -0.2565123 6.7357e-5 -0.9730838 -0.2297416 0.01807439 -0.9510644 -0.3014082 0.06804156 -0.2608859 -0.9653688 0.001305818 -0.2106342 -0.9769469 0.03475648 -0.2602457 -0.9655421 8.64395e-4 -0.2832831 0.4438257 -0.8501585 -0.4753711 0.2380685 -0.8469627 0.2780709 0.4444696 -0.8515417 0.03763717 0.5274878 -0.8487285 0.5019732 0.18133 -0.8456609 0.3152456 -0.4321925 -0.8448846 -0.2851756 -0.4414669 -0.8507537 -0.0376451 -0.5274752 -0.8487361 0.5074298 -0.1433632 -0.8496836 -0.5129293 -0.1590364 -0.8435705 -0.3339396 0.4085326 -0.8494619 0.2748327 0.4652447 -0.841436 -0.09639948 0.5176261 -0.8501591 -0.5243335 0.1115515 -0.8441746 0.5051777 0.1564885 -0.8487089 0.3069981 -0.4423816 -0.842645 -0.07963114 -0.5271726 -0.8460189 0.5066437 -0.1448289 -0.849904 -0.4314514 -0.3267367 -0.8408882 0.2621709 0.468261 -0.8437998 -0.1343324 0.5188974 -0.8442158 0.5040168 0.169854 -0.8468274 -0.4454132 0.2952508 -0.8452421 0.3151576 -0.4322834 -0.8448709 -0.5257456 -0.01595407 -0.8504922 -0.4134232 -0.3394961 -0.8448809 -0.07077676 -0.5310446 -0.844383 -0.3339448 0.4085429 -0.849455 0.2621749 0.468256 -0.8438013 -0.09639763 0.5176241 -0.8501605 -0.5066341 0.1448251 -0.8499103 0.504019 0.16984 -0.846829 -0.2524701 -0.4742816 -0.8433955 0.5042627 -0.1743017 -0.8457766 0.1797494 -0.5121824 -0.8398569 -0.5037614 -0.1727311 -0.8463973 0.5476161 0.04190105 -0.83568 0.420161 -0.02007746 -0.9072275 0.9344412 -0.08604854 -0.3455651 0.9126609 -0.07196575 -0.4023323 0.8026087 -0.08001518 -0.5911151 0.3391537 -0.1153494 -0.9336323 0.7979228 -0.2334355 -0.5557223 0.9141618 -0.2126758 -0.3450759 0.7146766 -0.1472792 -0.6837736 0.473088 -0.1004791 -0.8752667 0.1282058 -0.02320003 -0.9914762 0.2339991 0.9721997 0.00849384 0.5450528 0.8383307 -0.01091581 0.7982962 0.6020945 0.01433598 -0.8964014 0.4431781 -0.007598161 -0.8319234 0.5548073 0.009619116 -0.5324965 0.8463496 -0.0118336 -0.2936625 0.9558396 0.01153504 0.06514239 0.9978455 -0.007804512 0.9368038 0.3494834 -0.01612764 0.9999195 -0.008055567 0.009805619 -0.3520309 -0.9357718 0.02013957 -0.9698395 -0.2433582 0.01371443 0.9619691 -0.2729602 -0.01040297 0.8174976 -0.5757653 0.01386064 0.5876412 -0.8089286 -0.01767623 0.2936725 -0.9558366 0.01153063 -0.0651434 -0.9978455 -0.007800519 -0.5504476 -0.8348383 -0.007253646 -0.9545299 -0.2981098 0.001822412 -0.5617645 0.8270897 0.01853305 0.8184406 0.5741968 0.02128732 -0.9786086 0.2053961 -0.01173931 -0.6358711 0.7717874 0.003500819 -0.1766685 0.9842163 -0.01032346 0.184896 0.9826433 0.01501977 0.5083103 0.8609133 -0.02118647 0.9541317 0.2992044 -0.01046156 0.9993045 -0.03647321 0.007773041 0.09344232 -0.9951445 0.03091889 0.9609989 -0.2763661 -0.01014912 0.8174937 -0.5757707 0.01386225 0.5687188 -0.8222922 -0.01986211 -0.1495859 -0.9887077 -0.009006142 -0.7977135 -0.6030246 0.003815531 -0.7703959 -0.6375352 -0.006252944 -0.9969471 0.07731819 0.01088577 -0.8361257 0.5482423 -0.01801222 -0.5800122 0.8143815 0.01920258 -0.2452837 0.9692845 -0.01798707 0.1576527 0.9873328 0.01787745 0.4884403 0.8723942 -0.01882731 0.791979 0.6103163 0.0168308 0.9464244 0.3225923 -0.01466625 0.9968951 -0.07732611 0.01486188 0.5858399 -0.8104103 0.005186319 -0.1678423 -0.9858033 -0.004588246 -0.9928682 0.1179595 0.01727455 0.9609974 -0.2763686 -0.0102263 0.5868678 -0.8096679 0.004928529 -0.1313295 -0.9913352 0.002662301 -0.772549 -0.6349466 -0.003284394 -0.7920888 -0.610402 0.002198874 -0.9995198 -0.03087729 -0.002620518 -0.5617637 0.8270903 0.01853281 -0.9609941 0.27638 -0.01022648 -0.6358796 0.7717804 0.003500819 -0.1766654 0.9842169 -0.01032108 0.184902 0.9826422 0.01501953 0.4884459 0.8723911 -0.01882517 0.7919827 0.6103117 0.01682972 0.9464247 0.3225914 -0.01466739 0.9999195 -0.008005678 0.009855628 0.7894241 -0.6135525 0.0190491 0.06389367 -0.9976497 0.02475202 0.935747 -0.352311 -0.01595818 0.3428388 -0.9391889 -0.0196467 -0.463706 -0.8856778 -0.02348858 -0.7702564 -0.6374173 0.02011656 -0.9440423 -0.3294743 -0.01518887 -0.996896 0.07731419 0.01486223 -0.6581274 -0.04508209 -0.7515558 -0.4395754 0.08207041 -0.8944485 -0.5846431 0.1616817 -0.7950168 -0.9057375 0.260568 -0.3342813 -0.9048562 0.2351759 -0.354863 -0.9608131 0.1820042 -0.2090758 -0.7458688 0.1504743 -0.6488739 -0.9336158 0.09494316 -0.345467 -0.8048397 0.07428395 -0.5888251 -0.4067456 0.03797906 -0.9127517 -0.1804752 0.02151632 -0.9833442 0.1435086 0.9896317 -0.005880296 0.1443434 0.9894746 -0.01024776 0.1457506 0.9893194 -0.002023518 0.1460203 0.989281 0.001081585 -0.4251886 0.9049857 -0.01468938 -0.7033893 0.7106932 -0.01259958 -0.3861553 0.9224338 -3.62612e-6 -0.662389 0.7488258 0.02237755 -0.9896366 0.1435597 0.003178 -0.9891961 0.1465981 4.78656e-4 -0.989569 0.1440599 -6.3241e-6 -0.9887177 0.1491211 -0.01415163 0.9887342 -0.1488983 -0.0152983 0.9893082 -0.1458406 4.53866e-6 0.9891118 -0.1469888 0.007231414 0.9892064 -0.1465187 0.001742422 0.851025 0.5246481 -0.02237939 0.8792499 0.4761927 0.01265215 0.6692826 0.7428629 0.01468139 0.6369653 0.7708926 0 0.1483619 0.9889189 0.00532037 0.1514561 0.9884393 -0.006989777 0.1499109 0.9886414 0.01072818 0.1447086 0.9893863 -0.0132001 -0.1488425 -0.9888043 -0.01058375 -0.1462739 -0.9892435 0.001177787 -0.1459409 -0.9892928 -0.001130521 -0.1460241 -0.9892809 5.91128e-4 0.4104096 -0.9118254 -0.01177185 0.4952925 -0.868195 0.0303781 0.6972258 -0.7161327 -0.03209811 0.7585436 -0.6516007 0.00531882 0.9896298 -0.1436065 0.00318408 0.9891915 -0.1466143 -0.002135992 0.9890757 -0.1474085 -2.40163e-4 0.9893605 -0.1448034 -0.01407361 -0.002029061 0.01207065 -0.9999251 0.002335429 0.006208419 -0.999978 -0.002020537 0.01007968 -0.9999472 -0.0029881 0.00972259 -0.9999483 -0.011339 0.007985889 -0.9999039 -0.01300263 0.007834911 -0.9998849 0.008768022 0.002503275 -0.9999585 0.009244859 0.002319872 -0.9999547 0.003413617 0.007618367 -0.9999653 1.71876e-5 -2.93266e-5 -1 -1.96239e-5 -1.21816e-5 -1 -1.5437e-5 -2.27064e-5 -1 -1.17164e-5 7.91872e-6 -1 -7.6091e-6 1.59337e-5 -1 -1.2655e-5 4.81206e-7 -1 -9.74366e-4 -0.005178034 -0.9999862 4.53731e-4 -0.002375781 -0.9999971 0.001140892 -0.001679956 -0.999998 0.004921138 0.001370906 -0.999987 0.006568968 -5.0952e-4 -0.9999784 0.004308402 0.003565311 -0.9999845 2.12156e-5 3.29334e-5 -1 -0.018269 0.0014171 -0.9998322 -0.007464289 -0.002696454 -0.9999686 -0.005517959 -0.004251003 -0.9999758 -0.001144826 -0.007177174 -0.9999736 0.002008736 -0.01016604 -0.9999463 0.006276845 -0.008811712 -0.9999415 0.01364266 -0.007929801 -0.9998755 -9.25202e-4 0.01444751 -0.9998952 -0.007066369 0.005492329 -0.99996 -0.01453906 -9.00981e-4 -0.999894 -0.01532334 1.22837e-4 -0.9998826 -0.01088607 -0.008388817 -0.9999057 -0.005732178 -0.03046476 -0.9995194 -0.007971525 -0.01569682 -0.999845 -0.9887342 0.1488987 -0.01529836 -0.9893082 0.1458405 3.61929e-6 -0.989112 0.146988 0.007226765 -0.9892067 0.1465168 0.0017457 -0.8616443 -0.5074582 -0.007456839 -0.6432051 -0.7656801 0.004614889 -0.8698117 -0.49337 0.003709435 -0.6516222 -0.7585436 0 -0.1480687 -0.9889754 -0.00180757 -0.1476895 -0.98903 -0.00273019 -0.148452 -0.9889078 -0.004844784 6.23081e-7 0 -1 -5.47654e-5 -1.55027e-5 -1 8.64916e-7 0 -1 -3.17153e-7 0 -1 2.80666e-5 6.43618e-5 -1 0.009398043 0.923412 -0.3836953 0.06555122 0.7889969 -0.6108904 -0.02362775 0.6004385 -0.7993218 0.08207052 0.4395753 -0.8944485 0.1616761 0.5846438 -0.7950174 0.211912 0.8824424 -0.4199865 0.1465032 0.7811091 -0.6069643 0.03809839 0.4068372 -0.912706 0.02083796 0.1775234 -0.983896 -5.2161e-6 4.32189e-5 -1 4.89788e-5 -3.27529e-5 -1 -4.22561e-7 0 -1 1.3915e-6 0 -1 7.21649e-5 1.28334e-5 -1 2.11747e-7 0 -1 5.59422e-7 0 -1 -2.82404e-7 0 -1 -2.31485e-5 -5.28015e-5 -1 -0.00939846 -0.9234107 -0.3836983 -0.06555157 -0.7889932 -0.610895 0.02362543 -0.6004304 -0.7993279 -0.08207148 -0.4395823 -0.8944449 -0.1616763 -0.5846437 -0.7950173 -0.2119136 -0.8824243 -0.4200238 -0.1465045 -0.7811107 -0.6069617 -0.03809708 -0.4068318 -0.9127084 -0.02083826 -0.177537 -0.9838936 -2.64502e-7 0 -1 6.44664e-6 -3.61095e-5 -1 -7.19028e-5 3.60593e-5 -1 -0.9509704 0.3085025 -0.02194398 -0.5203146 0.8539218 -0.009509503 -0.6166795 0.7871232 0.01198512 -0.7014043 0.7125727 -0.01649743 -0.9194089 0.393283 -0.004002451 -0.9667743 0.2555055 0.008029699 0.3276077 0.9447135 0.01377147 0.4381663 0.8987353 -0.01688987 0.528744 0.8487381 0.008559167 0.648445 0.7612437 -0.005225419 0.9964984 -0.08282828 -0.01142489 0.9965829 -0.08183944 -0.01117426 -0.9831914 0.1824208 -0.007577896 -0.9649858 0.2622115 0.006911337 -0.9006477 0.4345058 0.006214678 -0.8487217 0.528778 -0.00810182 -0.7825791 0.6224172 0.01291376 -0.3796973 0.9250345 0.0118848 -0.3960779 0.91821 0.003586888 -0.157865 0.9874563 -0.002962172 -0.138213 0.9903832 0.006208419 0.6668627 0.745175 0.002893388 0.7995806 0.6005544 -0.002288818 0.8192912 0.5733159 0.008420586 0.8873014 0.4611017 -0.009034037 0.9424421 0.3338493 0.01864796 0.9626944 0.2705195 -0.006213068 0.9934754 0.1135367 -0.01077789 0.9997764 0.01133167 0.01785886 0.6024627 0.7980836 -0.01007562 0.08607071 0.9962862 -0.002402305 0.09591257 0.9953896 -5.28806e-4 0.1949551 0.9807208 -0.01339274 0.1760698 0.9842428 -0.01630139 0.9607223 -0.2752597 -0.03528332 0.9694433 -0.2453088 -0.001841604 0.4881499 -0.8727015 -0.01009386 0.5151188 -0.8571148 0.002636373 0.6944421 -0.719541 -0.003329694 0.7047402 -0.70946 0.00279504 0.8403228 -0.5420788 -0.002894639 -0.320385 -0.9472566 0.007647633 -0.413328 -0.9105579 -0.006653726 -0.7379759 -0.6746948 -0.01336169 -0.8052594 -0.5928722 0.007748186 -0.870981 -0.4913043 -0.003496646 -0.9444098 -0.3285968 -0.01069188 -0.9782638 0.2021673 -0.04613476 -0.9999954 -0.003030419 3.13776e-4 0.955398 -0.2949879 0.01402908 0.9196445 -0.3926654 -0.008236885 0.8533084 -0.5213804 0.005224227 0.2936429 -0.9559042 0.004597246 0.2800118 -0.9599473 0.009728908 0.1359317 -0.9906691 -0.009869515 0.03069514 -0.999415 0.01509034 -0.4645685 -0.8855154 0.006212472 -0.562856 -0.8265056 -0.009034872 -0.6624507 -0.7489311 0.01616901 -0.8967871 -0.4423713 0.008985042 -0.9719797 -0.2347893 0.0113849 -0.9919739 -0.1259925 -0.01066118 -0.9999264 0.002221405 0.01193547 -0.1373678 -0.9903318 -0.01931554 -0.08456695 -0.9963619 -0.0105682 -0.1942903 -0.9809288 -0.005476951 -0.187415 -0.98225 -0.007796406 -0.0924592 -0.9956036 -0.01499587 -4.85004e-7 0 1 1.40971e-6 0 1 -5.33709e-7 0 1 1.0112e-6 0 1 -6.6167e-7 0 1 7.11804e-5 -8.02007e-5 1 -8.77272e-5 -1.00252e-5 1 0 9.32732e-6 1 -1.5915e-6 9.95209e-6 1 1.10264e-5 -5.51937e-7 1 8.82154e-7 0 1 -6.16392e-7 0 1 -5.01354e-7 0 1 3.47259e-6 6.85114e-6 1 6.1038e-6 -1.24862e-6 1 6.29254e-6 4.4037e-7 1 -9.65786e-7 -6.5065e-6 1 5.48521e-7 0 1 -6.51884e-7 0 1 5.30091e-6 -7.32499e-6 1 0 -7.34503e-6 1 -3.72661e-5 1.80236e-5 1 -2.38394e-6 2.34373e-5 1 2.31929e-5 8.61763e-6 1 -5.13071e-7 0 1 -1.05501e-6 0 1 4.06787e-7 0 1 6.15207e-7 0 1 6.97076e-7 0 1 -2.02664e-5 -2.31173e-5 1 -2.79496e-5 5.70017e-6 1 -2.95823e-5 -1.26502e-6 1 -7.99654e-6 2.47784e-5 1 -0.975353 0.2204304 -0.009850025 -0.8756458 0.4827886 0.01263707 -0.7040627 0.7100463 -0.01140677 -0.4719603 0.8810049 0.03292196 -0.3379172 0.9407176 -0.02936929 -0.2288906 0.9730585 0.02768266 -0.02372163 0.9992496 0.03062123 0.2472691 0.9681307 0.039761 0.631122 0.7753382 0.02314537 0.7219471 0.691325 -0.02936404 0.7958319 0.6048842 0.02768856 0.9032118 0.4281021 0.03061079 0.9848967 0.1686913 0.03900903 -0.9784983 0.2059652 0.0109356 -0.884261 0.4668255 -0.01250731 -0.7149282 0.6991049 0.01140224 -0.5081681 0.8611905 -0.0107752 -0.09970033 0.9942225 -0.03976958 0.1728962 0.9844639 -0.03062087 0.371851 0.9278795 -0.0276885 0.4748089 0.8795993 0.02935475 0.5799175 0.8143462 -0.02315348 0.8677185 0.4954634 -0.03976118 0.9696747 0.2424739 -0.0306198 0.998843 0.04041355 -0.02606773 0.9973254 -0.06847834 0.02555119 0.9662885 -0.2558327 0.028921 0.8644564 -0.5015046 0.03476238 0.686948 -0.7258638 0.03498941 0.4524239 -0.8909162 0.03976106 0.02371746 -0.9991906 0.03249031 -0.3968071 -0.9173914 0.0306158 -0.6209831 -0.783734 0.01188135 -0.811442 -0.584322 -0.01139771 -0.9986524 -0.05070948 0.01104563 0.9804406 -0.1951895 -0.02524751 0.8938481 -0.4470422 -0.03447943 0.7306225 -0.6818841 -0.03499805 0.5191109 -0.8541585 -0.03061628 0.3322249 -0.9427937 -0.02768903 0.2229814 -0.9743805 0.02936238 0.1009293 -0.9946241 -0.02315562 -0.09300285 -0.9952808 -0.0276913 -0.2054323 -0.9782307 0.02936911 -0.3371215 -0.9410231 -0.02871751 -0.589043 -0.8071988 -0.03819113 -0.8023371 -0.5967624 0.01139771 -0.9370138 -0.3490725 -0.01239871 -0.9427821 -0.3332468 0.01041555 -0.9976072 -0.06800872 -0.01244658 2.86844e-7 0 1 -2.58384e-7 0 1 -4.44145e-7 0 1 3.3315e-7 0 1 2.89783e-6 0 1 -8.322e-7 0 1 3.53897e-6 0 1 -9.16545e-7 0 1 -5.89148e-7 0 1 -3.05603e-7 0 1 5.60774e-7 0 1 -8.84614e-7 0 1 5.56527e-7 0 1 1.9879e-7 0 1 -7.04188e-7 0 1 -2.84756e-7 0 1 4.44346e-7 0 1 7.19833e-7 0 1 -4.02856e-7 0 1 -0.9591104 0.2827 0.01371616 -0.9192624 0.3936348 -0.002895355 -0.5173213 0.855727 0.0104959 0.3491301 0.9370714 0.002347707 0.7437254 0.6684819 -0.002102196 0.7933797 0.6086741 0.008044242 0.9992307 0.037799 0.01046037 -0.6166644 0.78721 -0.005066752 -0.2454559 0.9693897 -0.005912244 -0.02136766 0.9997522 0.006249964 0.2691968 0.9630584 -0.007201015 0.9842633 0.1765257 -0.008037447 7.89107e-7 0 1 -4.99935e-6 0 1 5.17432e-7 0 1 2.13505e-6 0 1 0.9113317 -0.411503 -0.01182448 0.7589524 -0.6509078 0.017618 -0.09453874 -0.995499 0.00664252 -0.5987806 -0.8008667 0.008637368 0.5552436 -0.8316421 -0.008721232 0.304427 -0.9525152 0.006249725 0.03590339 -0.9993356 -0.006270587 -0.4683161 -0.8835361 -0.006641268 -0.7857428 -0.6185253 -0.005912184 -0.9269583 -0.3750512 0.009220123 -0.9880097 -0.1538376 -0.01307034 -0.9901651 0.1359771 -0.03291356 -0.9682597 0.2485781 0.02611964 -0.5795702 0.8145768 -0.0237348 -0.5072513 0.8615595 0.02028775 0.2110494 0.9772484 -0.02106279 0.2867082 0.9577864 0.02106291 0.8674542 0.4970709 -0.02106767 0.903618 0.427821 0.02106541 0.9666314 -0.2555434 -0.01792407 0.9549646 -0.2967201 0 0.6744288 -0.7383399 0 0.642103 -0.7664089 0.01792037 -0.003259479 -0.9997729 -0.02106297 -0.08130812 -0.9964665 0.02106732 -0.7482277 -0.6630996 -0.02131313 -0.8063704 -0.5906376 0.0302335 2.42502e-4 8.23617e-6 -1 3.11049e-4 -3.37853e-5 -1 -7.64928e-7 0 -1 0.004330694 -0.008672356 0.9999531 0.008241415 -0.009329378 0.9999225 0.008224427 -0.003290295 0.9999608 0.01462095 0.001092612 0.9998926 0.007907509 0.01010459 0.9999177 0.008100986 0.01156377 0.9999004 -0.00187397 0.01221394 0.9999237 -0.002878069 0.009731769 0.9999485 -0.01015752 0.008072137 0.9999158 -0.0100907 0.001910924 0.9999473 -0.01119309 0.001156568 0.9999368 -0.01074379 -0.007917165 0.999911 -0.006448686 -0.008213877 0.9999455 -0.002096891 -0.01621025 0.9998664 0.03438651 0.01320433 -0.9993214 0.03781914 0.0123437 -0.9992083 0.02540612 0.03179508 -0.9991714 0.005696892 0.02948504 -0.999549 -0.01163202 -0.02785742 -0.9995443 -0.01420962 -0.02913564 -0.9994745 0.008359789 -0.03331947 -0.9994099 0.007530033 -0.03515213 -0.9993537 0.02830916 -0.02885729 -0.9991827 0.02989953 -0.008426308 -0.9995174 0.04336613 -0.02396506 -0.9987719 -0.001279711 0.02324438 -0.999729 -0.007918059 0.02629536 -0.9996229 -0.01728552 0.01761966 -0.9996954 -0.01881462 0.03609454 -0.9991713 -0.03123313 0.01006239 -0.9994615 -0.02411973 -0.001420915 -0.9997081 -0.02683603 -0.004652321 -0.9996291 -0.02364408 -0.01815962 -0.9995556 -0.01849573 -0.0190674 -0.9996472 -0.9674341 0.2529453 -0.009500026 -0.9857839 0.1680029 -0.002275109 -0.6934584 0.7204924 -0.002486646 -0.7004703 0.7136796 -0.001696407 -0.1660298 0.9861203 -9.52843e-4 -0.09335899 0.9956095 -0.006769478 0.4118937 0.9112211 0.004454076 0.6527379 0.7575023 -0.01111489 0.8775499 0.4794433 0.006350874 0.9851931 0.1712059 -0.009117066 0.8970655 -0.4418407 -0.00710237 0.9790556 -0.2035462 0.004383146 0.7638245 -0.6454195 0.002429187 0.4204547 -0.907302 -0.004571676 0.4493294 -0.8933641 -0.001964151 -0.1382545 -0.9903966 -6.77104e-4 -0.217516 -0.9760317 -0.007004618 -0.6840873 -0.7293828 0.005027353 -0.8568077 -0.5155264 -0.01063281 -0.9514673 -0.3077493 5.21266e-4 -0.002202153 -0.004773378 -0.9999862 -0.005007028 0.002056479 -0.9999853 0.001758754 -0.001741647 -0.999997 0.001593887 -0.001747548 -0.9999972 -0.7925292 -0.6087194 -0.03685653 -0.5978056 -0.7998368 0.05375719 -0.3849385 -0.9219157 -0.04351764 0.03939688 -0.9982522 0.04405355 0.2431675 -0.9692061 -0.03884798 0.5701352 -0.820682 0.03777629 0.7000021 -0.7135533 -0.02896362 0.962363 -0.271216 0.0173071 0.961135 -0.2757169 0.0141344 0.9334575 0.3584679 -0.01257133 0.9203061 0.3911274 0.007498502 0.6242257 0.7812141 -0.006837308 0.601229 0.7990517 0.006343901 0.1896685 0.9818245 -0.006841361 0.1610167 0.9869313 0.006346344 -0.2883259 0.9575081 -0.006833076 -0.3160745 0.9487133 0.006341934 -0.7002826 0.7138331 -0.006837189 -0.7207636 0.6931519 0.006344139 -0.9518038 0.3066316 -0.006837248 -0.960327 0.2788044 0.006345391 -0.98528 -0.1708117 -0.006836414 -0.9698742 -0.2421911 0.02622061 0.5707915 -0.03618675 0.8202973 0.9067896 -0.2601225 0.3317664 0.4106817 -0.3495327 0.8421208 0.4940805 -0.7126787 0.4979695 0.1418927 -0.5342966 0.8333029 0.03652805 -0.9080678 0.4172273 -0.3317452 -0.4671069 0.8196075 -0.3794146 -0.5076357 0.7735312 -0.848443 -0.2110016 0.4854098 -0.5042527 -0.013493 0.8634508 -0.8139482 0.2363065 0.5307048 -0.4219321 0.4195342 0.8037191 -0.4052063 0.3896847 0.827015 -0.2914233 0.8747316 0.3871914 0.06879758 0.509364 0.8577967 0.09050118 0.5547273 0.8270956 0.5544365 0.73687 0.3868112 0.4793733 0.2925268 0.8274233 0.7319669 0.3122708 0.605567 -0.699401 -0.4113531 -0.5844885 -0.252111 -0.5211314 -0.8153908 -0.1806994 -0.8373258 -0.5159781 0.2855197 -0.5432958 -0.7894987 0.2719014 -0.5323023 -0.8017008 0.8016709 -0.3966236 -0.4472289 0.5533382 0.031933 -0.8323444 0.6745016 0.1166912 -0.7289931 0.5407369 0.6180352 -0.5706455 0.2250801 0.4552754 -0.861431 -0.090631 0.9239181 -0.3717007 -0.3637613 0.398879 -0.841768 -0.4093431 0.4172278 -0.8113934 -0.880024 0.1480715 -0.4512568 -0.5514433 -0.1838763 -0.8136951 -0.6419318 -0.7451054 0.1809462 0.3270446 -0.9294905 0.170556 0.951188 -0.1671948 0.2593982 0.6413072 0.7453929 0.1819739 -0.3249143 0.9282861 0.1808747 -0.9666772 0.1831133 0.1788986 0.5194292 -0.08224576 0.8505463 0.2358823 -0.4344028 0.8692834 0.06448882 -0.4900208 0.869322 -0.3759351 -0.3701987 0.8494856 -0.5225277 0.1111458 0.8453471 -0.1390733 0.5209104 0.8422061 0.3444492 0.4166332 0.8412917 -0.6349013 -0.7714062 0.04281324 -0.6820874 -0.7312691 0.001507997 -0.6737476 -0.7389437 -0.005145192 0.3554314 -0.9347024 1.17809e-4 0.3119872 -0.9495967 0.03049814 0.3482193 -0.9354608 0.06046843 0.2617382 -0.965139 5.89976e-5 0.9776235 -0.2098569 0.01457381 0.9902734 -0.1347002 0.03484982 0.9816667 -0.1905995 0.001545369 0.6726292 0.7399769 0.002040565 0.6326361 0.7740145 0.0259478 0.6672775 0.7448041 -0.002775073 -0.3041376 0.9526228 -0.003217637 -0.3529403 0.9350674 0.03289628 -0.3032585 0.9529048 -0.002640366 -0.9771137 0.2127103 -0.001842021 -0.9854515 0.1642721 0.04359006 -0.9749252 0.2224869 0.004514157 0.03092074 0.1046674 0.9940266 -0.7431707 0.02720123 0.6685488 -0.8252896 0.1566206 -0.5425561 0.8409454 -0.4423584 -0.311657 0.6647081 -0.1429857 -0.7332928 0.897691 0.2943295 -0.3279041 0.5615957 0.3320653 -0.7578541 -0.8035843 -0.1352596 -0.579618 -0.4629975 0.3947854 -0.7935855 -0.5067449 0.668995 -0.543742 -0.1015833 0.8078671 -0.5805442 -0.1253904 0.7523747 -0.6466912 0.3689225 0.7738922 -0.5147691 0.3971469 0.7963377 -0.4562026 0.5686784 -0.474186 -0.6721253 0.3201835 -0.6883202 -0.6509209 0.2850235 -0.8577515 -0.4278131 -0.09876686 -0.6958041 -0.7114083 -0.2391566 -0.8171617 -0.524453 -0.5641159 -0.5734664 -0.594062 -0.5210121 -0.5634281 -0.641167 -0.003965973 0.008845269 -0.9999531 -0.001998126 0.01228582 -0.9999226 0.002664506 0.008448481 -0.9999608 0.006272673 0.009501278 -0.9999352 0.0119872 0.004340529 -0.9999188 0.009725093 -3.59275e-4 -0.9999527 0.01120954 -0.002558946 -0.999934 0.007232308 -0.008448123 -0.9999382 0.005583286 -0.008191168 -0.9999509 0.03267723 0.02332979 -0.9991937 -0.06291568 0.1035565 -0.9926317 -0.004744589 -0.008706986 -0.9999508 -0.01079815 -0.008389115 -0.9999066 -0.01067316 2.08803e-4 -0.9999431 -0.01008206 -2.58194e-4 -0.9999492 -0.009803235 0.008728146 -0.9999139 0.02649176 0.009868025 0.9996004 0.03099447 0.007248282 0.9994933 0.03026753 -0.00784409 0.9995111 -0.01758366 -2.22255e-4 0.9998455 -0.02382576 0.01403087 0.9996178 -0.01163649 0.02773505 0.9995476 -0.01165717 0.02774673 0.9995471 0.006575405 0.03836989 0.999242 0.01792204 0.02318578 0.9995706 0.02457815 0.02334713 0.9994253 0.02828931 -0.008869707 0.9995605 0.02316039 -0.02101624 0.9995108 0.004231989 -0.02202773 0.9997485 0.006342351 -0.01734459 0.9998295 -0.002153694 -0.01612621 0.9998677 0.00137633 -0.02269852 0.9997415 -0.01757019 -0.02481639 0.9995377 -0.02395886 -0.01221197 0.9996384 -0.01768344 0.001569628 0.9998424 -0.01712697 2.03878e-4 0.9998533 -0.4945162 -0.8691256 0.008623957 -0.3144938 -0.9492586 -0.001327574 0.149701 -0.9887121 0.006177306 0.1084337 -0.9940997 0.002840459 0.6522242 -0.7580237 0.001919806 0.7111753 -0.7029684 0.00807178 0.9707328 -0.2401064 -0.005200564 0.9996305 0.02515715 0.01030367 0.9250035 0.3799096 -0.006113231 0.7565963 0.6538189 0.00911647 0.2264119 0.9740058 0.007103621 0.4627593 0.8864731 -0.0043841 -0.038531 0.9992519 -0.003329873 -0.4065369 0.9135947 0.008529484 -0.5971829 0.8020992 -0.003119468 -0.8929566 0.4500346 0.009876906 -0.9204726 0.3907737 0.005107939 -0.9928161 -0.1196486 -6.81578e-4 -0.9416604 -0.3363567 0.0118336 -0.7849177 -0.6195863 -0.004151105 -0.002727985 0.004755675 0.999985 -0.002167522 -0.002818524 0.9999937 7.67394e-4 0.002704381 0.9999961 0.001704454 0.00325644 0.9999933 -0.9703137 -0.2386147 -0.03942757 -0.9995076 0.01190423 0.02903246 -0.9599114 0.2788473 -0.02853834 -0.861034 0.5070521 0.03896927 -0.7201751 0.6927943 -0.03720068 -0.3867254 0.9217714 0.0279482 -0.315948 0.9487553 -0.006348431 0.1689043 0.985601 0.007884263 0.1999049 0.9797651 -0.009932935 0.3831812 0.92286 -0.0387541 0.7247433 0.6884521 0.02794486 0.7750689 0.6318448 -0.006347537 0.9737051 0.22771 0.006834268 0.9799207 0.199287 -0.006344079 0.9679982 -0.250864 0.006838321 0.9602871 -0.278942 -0.006341755 0.7405321 -0.6719862 0.006837248 0.7206631 -0.6932564 -0.006346046 0.3434236 -0.9391558 0.006833076 0.3159533 -0.9487536 -0.006339907 -0.1323675 -0.9911772 0.006833136 -0.1611552 -0.9869087 -0.006346344 -0.5778095 -0.816143 0.006837308 -0.6356317 -0.7715471 -0.02622199 -0.8903349 -0.453812 0.03685969 0.5058798 0.4124045 -0.7576333 0.4065249 0.6345117 -0.6573678 -0.03006649 0.5374118 -0.8427839 -0.2677916 0.8041402 -0.5307035 -0.4217128 0.4582596 -0.7824044 -0.5208945 0.5010756 -0.6910805 -0.6754316 0.1797463 -0.7151807 -0.6267491 0.1820551 -0.7576552 -0.8194406 -0.2005627 -0.5369282 -0.5387064 -0.2160923 -0.8143093 -0.4764526 -0.6639485 -0.5763379 -0.4078787 -0.4972217 -0.7657712 -0.13302 -0.8146049 -0.564557 0.0483061 -0.5007311 -0.864254 0.2646641 -0.7947537 -0.5461864 0.5659851 -0.5444519 -0.6190583 0.4453293 -0.3245022 -0.8344939 0.7882275 -0.2289606 -0.5712044 0.5789541 -0.01076954 -0.815289 0.8305611 0.1689026 -0.530698 0.4807912 0.3735345 -0.7932917 -0.8727957 -0.3171488 0.3710047 -0.4858841 0.05713135 0.8721541 -0.762368 0.3906404 0.5159412 -0.3064838 0.5556933 0.7728343 -0.2958328 0.6725186 0.6783818 0.2011909 0.6759551 0.7089478 0.1345885 0.5915649 0.7949447 0.6734497 0.5824013 0.4552739 0.5437477 0.1095167 0.8320724 0.757885 0.02616643 0.6518633 0.4495471 -0.5187603 0.7271832 0.4035783 -0.4113578 0.8172572 0.09661024 -0.8850914 0.4552798 -0.25124 -0.4790999 0.8410362 -0.2950587 -0.5117813 0.8068584 -0.9831612 -0.02465826 -0.1810693 -0.5120074 0.8418958 -0.1704697 0.4732304 0.8418964 -0.2593519 0.9830137 0.02400642 -0.1819553 0.5124084 -0.8394773 -0.1808751 -0.4707203 -0.8639607 -0.1788701 0.2654256 0.4540098 -0.8505435 -0.186683 0.457709 -0.8692824 -0.3382951 0.3603199 -0.8693251 -0.5245949 -0.0563544 -0.8494849 -0.245027 -0.4747082 -0.8453484 0.3149402 -0.4376099 -0.8422056 0.5405784 0.002570569 -0.8412898 -0.99908 -0.002532184 -0.04281228 -0.9979165 -0.0645014 -0.001528143 -0.9985731 -0.05315566 0.005150258 -0.4980425 0.8671526 -1.00977e-4 -0.5370854 0.8429762 -0.030505 -0.5032123 0.8620457 -0.06045335 -0.5809537 0.8139367 -4.21427e-5 0.4569582 0.8893687 -0.01458173 0.5231232 0.8515443 -0.03485268 0.4744155 0.8802998 -0.001547753 0.9986636 0.05164486 -0.002033174 0.9996631 -8.50818e-4 -0.02594441 0.9990073 0.04446107 0.002770185 0.5444011 -0.838819 0.003225922 0.4999142 -0.8654504 -0.0328865 0.5451823 -0.8383134 0.002635478 -0.4544256 -0.8907828 0.001850247 -0.4971823 -0.8665505 -0.04358971 -0.4454817 -0.8952797 -0.004523754 -0.8953846 0.3878269 0.2188076 -0.6931744 -0.4036877 0.5971143 0.3552606 0.6892991 0.6313927 0.4526626 0.7527529 0.4779747 0.7220385 0.2686728 0.6375542 0.7716442 0.3194649 0.5500069 -0.4635916 -0.36896 0.8055752 -0.2469493 -0.8576455 0.4510657 -0.2538803 -0.7776353 0.5751766 0.06914895 -0.4972567 0.8648436 0.4608643 -0.5781838 0.6732813 0.5151521 -0.6091187 0.6029865 0.7225716 -0.2140551 0.657321 0.7426817 -0.209598 0.6359973 -0.08355498 0.7320616 0.676095 -0.2163311 0.9131219 0.3455565 -0.3299416 0.4421824 0.8340345 -0.9203892 0.3834239 0.07661646 -0.5035136 0.02006232 0.8637544 0.5050006 0.863119 3.2509e-5 0.5018889 0.8649322 -4.30027e-5 0.492827 0.8701071 -0.005931556 0.5000008 0.8660244 0.001010656 -0.006713628 0.3978416 -0.9174296 -0.4937235 0.869619 -1.15909e-5 -0.4849295 0.8745533 -3.62931e-5 -0.5346202 0.8447033 -0.02564674 -0.4999825 0.8659947 0.008411705 -0.4390801 0.468236 -0.766788 -0.3290637 0.2046245 -0.921871 -0.9999839 -0.005682051 -1.70815e-6 -0.9999896 0.002967715 -0.003497481 -0.9999698 -0.007727921 8.65174e-4 -0.999987 0 -0.005115926 -0.4269273 -0.1671534 -0.8887029 -0.601526 -0.1237242 -0.789214 -0.4012278 -0.4516459 -0.7968892 -0.3557639 -0.2839788 -0.8903865 -0.5049954 -0.8631221 3.13308e-5 -0.5072273 -0.8618117 0.001126766 -0.4999977 -0.8660252 0.001629412 -0.4908147 -0.871159 -0.01353025 0.006719231 -0.3978314 -0.917434 0.4849331 -0.8745512 -2.41952e-5 0.5072615 -0.8617911 0.001367628 0.4999815 -0.8659953 0.008411705 0.479512 -0.7047168 -0.5229173 0.3596352 -0.3081928 -0.8807268 0.4353283 -0.1849753 -0.8810638 0.9999819 -0.00601226 4.63664e-5 0.9987636 0.04954004 -0.004130303 0.9999666 -0.008134603 9.5269e-4 0.9997127 0 -0.02397406 0.9864516 -0.1320883 0.09729349 0.3459208 0.2043453 -0.9157412 -0.004238009 -2.51163e-4 -0.9999911 0.004386007 2.63645e-4 -0.9999904 -0.009443819 0.02060979 -0.9997431 0.006166696 -0.007704794 -0.9999514 0.01161891 0.01981842 -0.9997361 -8.22171e-4 6.78312e-4 -0.9999994 -0.001522362 3.82154e-4 -0.9999988 -0.001978278 -0.008975148 -0.9999579 -0.001045644 3.90132e-4 -0.9999995 -9.61194e-4 5.54812e-4 -0.9999994 -0.003144264 -0.004418373 -0.9999853 -0.01037853 0.01861262 -0.9997729 0.001082658 6.25171e-4 -0.9999992 0.001135706 4.23586e-4 -0.9999994 2.39956e-4 -0.009972453 -0.9999504 0.01154386 -0.01970285 -0.9997393 0.002751767 0.003615796 -0.9999898 -0.007056117 0.005880832 -0.9999579 9.59984e-4 7.92516e-4 -0.9999992 0.004926621 0.004294455 -0.9999787 -0.008216321 -0.01095056 -0.9999064 0.007582783 -0.008516371 -0.999935 -0.00492382 -0.004297971 -0.9999787 0.0170955 0.01448589 -0.999749 -0.00130409 0.00150454 -0.999998 -0.003262341 -0.002905726 -0.9999905 -0.8710917 -0.07299858 -0.4856651 -0.4066497 -0.4485869 -0.795868 -0.4146745 -0.8464385 -0.3340466 0.03928595 -0.5416392 -0.8396927 0.5661506 -0.759366 -0.3206823 0.5064879 -0.4227893 -0.751478 0.7034006 -0.01924765 -0.710533 0.8710879 0.07302379 -0.4856682 0.4066408 0.4485889 -0.7958716 0.4146705 0.8464237 -0.3340889 -0.03928112 0.5416109 -0.8397111 -0.5661451 0.75937 -0.3206822 -0.5064675 0.4227843 -0.7514947 -0.7034161 0.01923817 -0.7105179 -0.9996063 0.02484267 0.01304548 -0.7654142 0.6432858 0.0180155 -0.704791 0.7090442 -0.02293568 -0.1729568 0.9849216 -0.003933966 -0.07633656 0.9964267 0.03615123 0.4801576 0.8761711 -0.04210776 0.6729623 0.7376052 0.05532157 0.9913884 0.115933 -0.06089937 0.9996066 -0.02483028 0.01305103 0.7654183 -0.6432814 0.01800131 0.7048074 -0.709028 -0.02293401 0.1729333 -0.9849257 -0.003939807 0.07632648 -0.9964277 0.03614223 -0.480143 -0.876178 -0.04212868 -0.6729711 -0.7375968 0.0553258 -0.9913892 -0.1159238 -0.06090372 0.6088336 -0.6014029 0.5173357 0.5887987 -0.5944288 0.5476956 0.108352 -0.605134 0.7887159 -0.1805614 -0.8783888 0.4425277 -0.2848472 -0.5211083 0.8045547 -0.8716176 -0.3242316 0.3676366 -0.5629017 -0.0656464 0.8239129 -0.608831 0.6014071 0.5173339 -0.5887667 0.59443 0.5477288 -0.108368 0.6051452 0.7887051 0.180566 0.878414 0.4424758 0.2848621 0.5211239 0.8045393 0.871609 0.3242318 0.3676571 0.5629071 0.06565135 0.8239088 8.80212e-4 0.00210911 0.9999974 0.004262149 0 0.999991 -6.5663e-5 -0.001234471 0.9999992 -9.72212e-4 -0.00168389 0.9999982 6.64651e-5 0.001234412 0.9999992 9.71865e-4 0.001683294 0.9999982 7.62385e-4 -0.003361046 0.9999941 8.4079e-4 -0.00145626 0.9999986 -8.80671e-4 -0.00210911 0.9999974 -0.004262685 0 0.999991 -7.6248e-4 0.003361463 0.9999942 -8.40909e-4 0.001456499 0.9999987 -0.01263648 0.003717541 0.9999133 -0.01081126 0.001967847 0.9999397 -0.009577214 -0.00630176 0.9999344 -0.009091198 -0.006260216 0.9999392 -0.00106126 -0.01486194 0.9998891 0.002985715 -0.01003789 0.9999452 0.009538233 -0.01089549 0.9998952 0.009156703 -0.00326842 0.9999527 0.01167249 -0.001550793 0.9999307 0.01065206 0.006020307 0.9999251 0.007221937 0.006795942 0.9999508 0.005378484 0.01257276 0.9999065 -0.00290662 0.01027208 0.9999431 -0.005542337 0.01225858 0.9999096 7.09898e-4 -0.04064971 -0.9991733 0.01097226 -0.02586936 -0.9996051 0.02299773 -0.02703559 -0.99937 -0.03193271 0.02122747 -0.9992646 -0.02691435 0.008922457 -0.999598 -0.03361463 -0.004678308 -0.9994239 -0.02799254 -0.007457256 -0.9995803 -0.02260267 -0.02642786 -0.9993953 -0.01828563 -0.02518296 -0.9995156 0.02594155 -0.009058058 -0.9996225 0.03657782 -0.02502739 -0.9990174 0.03716868 0.005518257 -0.9992939 0.03391349 0.007668137 -0.9993954 0.03156822 0.02489125 -0.9991917 0.01579374 0.02553355 -0.9995493 0.01005333 0.03752857 -0.9992451 -0.009568691 0.03037726 -0.9994927 -0.009831845 0.0294373 -0.9995183 0.7510423 0.6602311 -0.005537867 0.715411 0.6987029 -0.001151204 0.9887958 0.149267 -0.001521527 0.9891181 0.1471146 -0.001696944 0.8953363 -0.4453899 -9.54634e-4 0.8602965 -0.5097493 -0.006768941 0.4950094 -0.8688763 0.004453301 0.2290483 -0.9733517 -0.01111441 -0.1280195 -0.9917513 0.006349623 -0.4406604 -0.8976276 -0.009118616 -0.8847913 -0.4659333 -0.0071038 -0.7402122 -0.6723591 0.00438404 -0.9711474 -0.2384675 0.002429187 -0.9811349 0.1932705 -0.004572629 -0.9868415 0.1616786 -0.001963555 -0.7199237 0.6940529 -6.77854e-4 -0.6616936 0.7497416 -0.007005572 -0.2110559 0.9774636 0.00450015 0.08665925 0.9961727 -0.01140385 0.360965 0.9325733 0.003395557 0.003642141 -7.50433e-4 -0.9999932 9.9181e-4 0.001742899 -0.9999981 -0.003068506 -0.001067996 -0.9999948 0.003735363 0.001413941 -0.999992 0.1849246 0.9827324 0.00633496 -0.3004593 0.9537621 -0.007880926 -0.3346751 0.9422506 0.01250797 -0.8326935 0.5535556 -0.01407176 -0.8313465 0.5555327 -0.01569902 -0.9992843 0.02122944 0.03130894 -0.9890841 -0.1376518 -0.05258184 -0.8134769 -0.5799261 0.04405963 -0.649021 -0.7588639 -0.05382806 -0.4144462 -0.9093131 0.03720641 0.01744335 -0.9992741 -0.03386914 0.0556367 -0.9983751 -0.01232188 0.5501882 -0.8344536 0.03130877 0.6475826 -0.7612847 -0.03290164 0.9440104 -0.3296176 0.01402729 0.9402385 -0.340434 0.00749737 0.9891344 0.1468546 -0.006838262 0.9754672 0.2185784 0.02621972 0.784557 0.6186064 -0.04238474 0.6510689 0.7577709 0.04350519 0.2586928 0.9655556 -0.0279383 -0.2706809 -0.5938894 0.7576459 -0.6864166 -0.4904731 0.5369065 -0.5151026 -0.2674924 0.8143201 -0.8140943 0.07176387 0.5762817 -0.6429557 0.01500672 0.7657564 -0.7019335 0.4678389 0.5370441 -0.3345596 0.3490473 0.8753491 -0.3208805 0.9048529 0.2797805 0.06338888 0.5335888 0.8433652 0.120692 0.6413962 0.7576571 0.549099 0.6404815 0.5369114 0.386799 0.2900506 0.8753612 0.9369324 0.2094742 0.2797827 0.4940134 -0.1416384 0.85784 0.6043086 -0.2173172 0.7665406 0.4804757 -0.7302345 0.4856961 0.1800349 -0.4712795 0.8634138 0.04715812 -0.8462506 0.530694 -0.2394494 -0.5597706 0.7932976 0.079764 0.8284135 -0.5544086 -0.08497822 0.5004793 -0.8615679 -0.6177131 0.6936872 -0.3704439 -0.5281593 0.1088215 -0.8421435 -0.5904411 0.0929647 -0.8017088 -0.7921451 -0.41535 -0.4472032 -0.2637211 -0.463433 -0.8459794 -0.2675461 -0.5436799 -0.7955069 0.2071645 -0.8984807 -0.3870598 0.3088806 -0.4176035 -0.8545175 0.7316193 -0.4268609 -0.5315291 0.5895826 -0.08138823 -0.8035972 0.8195537 0.1218154 -0.5599042 0.4606262 0.4249482 -0.7792577 0.4769899 0.4701874 -0.7425661 -0.2253993 0.9573242 0.180902 -0.9441832 0.2818576 0.1705119 -0.6944264 -0.6711981 0.259355 0.2259785 -0.9569844 0.1819746 0.941968 -0.2828647 0.1807867 0.7163931 0.6743547 0.1789603 -0.3718889 -0.3718474 0.8505459 -0.4900794 0.06454962 0.8692845 -0.4343158 0.2359034 0.8693213 -0.07847613 0.5217446 0.8494846 0.3970926 0.3573673 0.8453437 0.5031526 -0.1937198 0.8422057 0.1345492 -0.5235769 0.8412869 -0.2507988 0.967092 0.04281443 -0.1905868 0.9816692 0.001532018 -0.2017068 0.9794325 -0.005149126 -0.9650821 0.2619475 1.09394e-4 -0.9515873 0.3058609 0.03051018 -0.9614545 0.2682338 0.06046384 -0.9346222 0.3556421 5.05702e-5 -0.7444773 -0.6674885 0.01458227 -0.6911211 -0.7218984 0.03484672 -0.7312756 -0.6820804 0.001538157 0.2031835 -0.9791386 0.002040624 0.2542367 -0.9667939 0.02594769 0.2102422 -0.9776454 -0.002770185 0.949429 -0.3139656 -0.003223836 0.9639063 -0.2642025 0.03289073 0.9491333 -0.3148638 -0.002631843 0.7464922 0.6653916 -0.001842021 0.7122007 0.7006214 0.04358947 0.7531067 0.6578829 0.004523694 0.2760275 -0.9208285 -0.2754698 -0.4997864 -0.4475708 -0.7415484 -0.4868247 -0.8444097 -0.2235493 -0.05601513 -0.6136986 -0.7875509 0.5436353 0.4786322 -0.6894721 0.5478847 0.7856487 -0.2873651 0.2153359 0.6298733 -0.7462508 0.7817926 0.1488326 -0.6055158 0.850913 0.1290754 -0.5092021 0.7414331 -0.3784558 -0.5541194 0.7321601 -0.365482 -0.5747734 0.3304362 -0.6280129 -0.704565 -0.8280316 -0.2277479 -0.5123423 -0.8663653 -0.2160903 -0.4502401 -0.7146909 0.1396082 -0.685366 -0.8509454 0.3753399 -0.3674399 -0.4763781 0.4616229 -0.7483103 -0.2662115 0.8126698 -0.518362 -0.2119806 0.976575 0.0369566 -0.003945291 -0.009931564 0.9999429 -0.001192331 -0.008213043 0.9999656 0.004304349 -0.0106936 0.9999337 0.005402922 -0.008203804 0.9999518 0.0112096 -0.007338106 0.9999102 0.01129245 0.003128349 0.9999313 0.01106309 0.003225088 0.9999336 0.008701503 0.01012229 0.999911 0.003153026 0.008768856 0.9999566 -3.79273e-4 0.01258915 0.9999207 -0.006596207 0.009657382 0.9999317 -0.006753623 0.00717467 0.9999515 -0.01384884 0.003397047 0.9998984 -0.01040387 -0.002938926 0.9999416 -0.01213306 -0.006236374 0.999907 0.02104318 -0.02201676 -0.9995362 0.03428089 0.002180397 -0.9994099 0.01752227 0.01551067 -0.9997262 0.01738381 0.01478695 -0.9997397 -0.01661288 -0.02087414 -0.9996441 -0.01556336 -0.01566106 -0.9997562 -0.002417623 -0.02330315 -0.9997255 0.005355715 -0.01196134 -0.9999142 0.008997976 -0.01361334 -0.9998669 0.0153703 -0.007553279 -0.9998534 0.01501822 0.01522219 -0.9997714 0.009508311 0.02723228 -0.9995839 -0.005251765 0.02816426 -0.9995895 -4.57457e-4 0.0381149 -0.9992733 -0.02723926 0.0231381 -0.9993612 -0.02461564 0.02270644 -0.9994391 -0.03868132 0.008451223 -0.9992159 -0.03064984 -0.009064614 -0.9994891 -0.03036653 -0.008346259 -0.999504 -0.6431372 0.7657152 -0.00741744 -0.6987014 0.7154126 -0.001150786 -0.1492564 0.9887974 -0.001521289 -0.1471228 0.9891169 -0.001696169 0.4192082 0.9078896 -0.001000225 0.5097278 0.8602913 -0.0087502 0.8724653 0.4886553 0.004509031 0.9733455 0.2290552 -0.01151168 0.9963402 -0.08542853 0.002845346 0.8976557 -0.4406649 -0.005382478 0.898032 -0.4398969 -0.005433678 0.4659507 -0.8847823 -0.007103681 0.6155282 -0.7881143 0.001000106 0.2599588 -0.9656186 0.001559078 -0.1973732 -0.9803097 -0.006048679 -0.1616705 -0.9868399 -0.003118515 -0.6884695 -0.7252635 -0.001642107 -0.7497232 -0.6616995 -0.008303523 -0.9813307 -0.1922556 0.005278885 -0.9961818 0.08665359 -0.01063299 -0.937267 0.3486035 0.002509355 3.86234e-4 1.77139e-4 -1 -0.002299964 4.84445e-4 -0.9999973 0.00274384 0.002767682 -0.9999924 -0.003439903 -0.004922866 -0.999982 -0.9827319 0.1849262 0.006345152 -0.9642207 -0.2650128 -0.006837248 -0.9561055 -0.2929539 0.006344616 -0.704885 -0.7092779 -0.007884323 -0.678793 -0.7342231 0.01250666 -0.1031834 -0.9945629 -0.01406621 -0.06191444 -0.9979814 0.01413559 0.5513608 -0.8341723 -0.01257306 0.5804159 -0.8142858 0.007496058 0.8974642 -0.4410344 -0.006837248 0.9099211 -0.4147329 0.006344437 0.9979523 0.06347632 -0.007883787 0.9949635 0.09945458 0.01251077 0.7616333 0.6478864 -0.01256978 0.7383926 0.6743295 0.007497906 0.3296415 0.9440815 -0.006837129 0.3020238 0.9532794 0.006343901 -0.1833102 0.9830235 -0.00788784 -0.2186611 0.9757208 0.01250755 -0.734975 0.6779776 -0.01257294 -0.7584245 0.6517179 0.007495701 -0.976933 0.2134368 -0.006836473 0.6576997 -0.2997696 0.691064 0.4158361 -0.561769 0.7151895 0.4273509 -0.5974234 0.6785694 -0.002884387 -0.6869412 0.7267073 -0.05098474 -0.8218029 0.5674863 -0.3211402 -0.4589447 0.8283953 -0.5745455 -0.62007 0.5342385 -0.7508824 -0.2300742 0.6190652 -0.5438675 -0.08833926 0.8345084 -0.8066525 0.1517809 0.5712044 -0.4878004 0.2600235 0.8333299 -0.6899014 0.5918477 0.4168363 -0.1664518 0.5742523 0.8015785 -0.1582186 0.711607 0.6845307 0.2261099 0.6613656 0.7151712 0.1971365 0.6222143 0.7576192 0.6222447 0.569577 0.5370229 0.4189732 0.2413046 0.8753477 0.9553459 0.09500712 0.2798 0.532681 -0.1778157 0.8274253 -0.8897504 0.08359259 -0.4487277 -0.4815372 -0.2211607 -0.8480625 -0.6377072 -0.5705304 -0.5175177 -0.08823078 -0.6080102 -0.7890114 -0.0929625 -0.590449 -0.8017032 0.4153667 -0.7921349 -0.4472055 0.4686987 -0.3350709 -0.8173427 0.6644469 -0.3267181 -0.6721352 0.6789227 0.1599372 -0.7165781 0.6618701 0.1475226 -0.7349593 0.4239438 0.7268807 -0.5402927 0.09750366 0.4785396 -0.8726356 -0.1203674 0.8097864 -0.5742452 -0.5436319 0.5528554 -0.6315183 -0.4462214 0.2875576 -0.8474651 -0.9572979 -0.2253889 0.1810546 -0.2818565 -0.944176 0.1705538 0.6711753 -0.6944193 0.2594332 0.9569763 0.2259781 0.1820174 0.2828759 0.941964 0.1807903 -0.6743567 0.716413 0.1788728 0.3718493 -0.3718899 0.8505446 -0.06455665 -0.4900727 0.8692877 -0.2358999 -0.4343162 0.869322 -0.5217406 -0.07847845 0.849487 -0.3573638 0.397094 0.8453447 0.1937199 0.5031542 0.8422046 0.5235745 0.134545 0.8412892 -0.9670904 -0.2508068 0.04280376 -0.9816694 -0.1905857 0.001522421 -0.979436 -0.2016895 -0.005147099 -0.2619566 -0.9650797 9.25647e-5 -0.3058665 -0.9515858 0.03049892 -0.268229 -0.9614561 0.06045907 -0.3556434 -0.9346218 4.21421e-5 0.6674714 -0.7444931 0.0145654 0.7218973 -0.6911227 0.03484106 0.6820743 -0.7312813 0.00155735 0.9791374 0.2031897 0.002030014 0.9667875 0.2542619 0.02594047 0.9776456 0.2102414 -0.002772629 0.3139718 0.9494269 -0.003225922 0.2642045 0.9639059 0.03288674 0.3148608 0.9491342 -0.002625703 -0.6654025 0.7464826 -0.001850247 -0.7006152 0.7122066 0.04358965 -0.6578848 0.7531051 0.004518926 0.05251801 -0.2036371 0.9776369 0.3760916 -0.5063204 -0.7760121 0.5834481 -0.1694266 -0.7942814 0.8483557 0.2632559 -0.4593356 -0.7579213 0.5865731 -0.28546 0.5255938 -0.5825793 -0.6199617 0.8628203 -0.4530164 -0.2243152 0.6643944 0.00717771 -0.7473477 -0.5375182 0.5410494 -0.646792 -0.6307073 0.3131077 -0.7100507 -0.864107 -0.02804327 -0.5025264 -0.1371099 0.774261 -0.6178356 -0.1238826 0.8161259 -0.5644392 0.2461783 0.6228948 -0.7425621 0.3896169 0.7594372 -0.5210122 0.4931945 0.2691893 -0.8272222 0.146806 -0.791601 -0.5931408 0.09357666 -0.9472433 -0.306551 -0.1017417 -0.5360798 -0.8380138 -0.3675869 -0.4365663 -0.8211515 -0.7317785 -0.5507053 -0.4015274 -0.6589609 -0.1590833 -0.735162 -3.5086e-6 0 1 4.59108e-6 0 1 -1.20718e-6 0 1 6.02296e-6 0 1 -7.87593e-6 0 1 9.93726e-7 0 1 -4.58599e-6 0 1 0.978743 -0.2050852 -0.001465141 0.6669806 -0.7450737 0.001465201 0.6179345 -0.7862284 -0.001465201 0.0320084 -0.9994866 0.00146526 0.0452696 -0.9989727 0.002072274 -0.416402 -0.9091763 -0.002829611 -0.5791683 -0.8152031 0.002829611 -0.8877693 -0.4602842 -0.002072274 -0.881585 -0.4720231 -0.001465201 -0.9898602 0.1420379 0.00146526 -0.9787438 0.2050819 -0.00146526 -0.6669771 0.7450768 0.001465141 -0.6179355 0.7862275 -0.001465082 -0.08033877 0.9967669 0.001247465 -0.04527103 0.9989748 0 0.3842109 0.9232454 0 0.4164081 0.9091771 -0.001247286 0.8495764 0.5274638 0.00146526 0.8815844 0.4720243 -0.001465141 0.9898608 -0.1420336 0.001465201 -0.9809067 0.1944743 -0.001442849 -0.9589254 0.283655 0.001442909 -0.3971729 0.9177428 -0.001442849 -0.3112907 0.9503136 0.00144279 0.4698228 0.88276 -0.001226246 0.5135425 0.8580643 0 0.9303677 0.3666265 0.001056551 0.9303677 -0.3666266 -0.001056611 0.913846 -0.406061 0 0.5135408 -0.8580653 0 0.4698213 -0.8827608 0.001226246 -0.2449169 -0.9695433 -0.001226186 -0.2932742 -0.9560284 0 -0.7899054 -0.6132289 0 -0.8196884 -0.5728084 0.001226305 -0.3215824 0.9468816 0 -0.3215824 0.9468816 0 0.9468816 0.3215826 0 0.9468817 0.3215823 0 0.3215824 -0.9468816 0 -0.9468817 -0.3215825 0 -0.9468817 -0.3215823 0 -0.003583431 0.01015961 0.9999421 -0.004118561 0.008068084 0.9999591 -0.01081395 0.004534304 0.9999313 -0.01025652 0.003645479 0.9999408 -0.0151686 -0.0077039 0.9998553 -0.006365954 -0.008313894 0.9999452 -0.003207564 -0.01412177 0.9998952 0.00273931 -0.009327411 0.9999528 0.007180452 -0.01091802 0.9999147 0.01211255 -0.001928985 0.9999248 0.01261585 -0.002389192 0.9999176 0.01178359 0.006966471 0.9999064 0.005711138 0.007357358 0.9999567 0.00361514 0.01165276 0.9999257 -3.65687e-4 -2.76779e-4 -1 -0.01814234 -0.003918528 -0.9998278 -0.004264414 -0.01761227 -0.9998359 0.0141474 0.03064358 -0.9994304 -0.001497447 0.02942854 -0.9995658 -0.01370894 0.01260524 -0.9998266 -0.008087158 0.01367115 -0.9998739 -0.005457401 0.02608919 -0.9996448 -0.02871239 0.01773506 -0.9994305 -0.028723 9.49264e-4 -0.9995869 0.006424903 -0.02393913 -0.9996928 9.39992e-4 -0.01328432 -0.9999113 0.005922496 -0.01732349 -0.9998325 0.02059417 -0.01298207 -0.9997037 0.01051455 0.007426202 -0.9999172 4.30287e-4 5.4175e-5 -1 3.28002e-4 2.52525e-4 -1 0.02797579 0.001680433 -0.9996073 0.9791881 -0.2028878 -0.00523287 0.985782 -0.1680137 -0.002275586 0.7127664 -0.7013971 -0.002498269 0.700469 -0.7136725 -0.003843069 0.2024285 -0.9792962 -0.001292288 0.0933935 -0.9955815 -0.009753704 -0.4318662 -0.9019318 0.003253757 -0.6527508 -0.7574912 -0.01111388 -0.8456797 -0.5336809 0.003288745 -0.9852175 -0.1712239 -0.005382418 -0.9587333 -0.2840427 -0.01225578 -0.8970602 0.4418513 -0.007103741 -0.9573424 0.2889558 3.69746e-4 -0.7487506 0.6628435 0.003330647 -0.4493476 0.8933163 -0.008529841 -0.2828249 0.9591712 8.99849e-4 0.1966056 0.9804683 -0.005328953 0.217514 0.9760321 -0.007004857 0.6666644 0.7453444 0.004499435 0.856809 0.515508 -0.01140505 0.9666174 0.2562019 0.003395199 -3.75295e-4 -0.002446293 -0.999997 -0.003533959 0.001587212 -0.9999925 0.0065611 -0.003082334 -0.9999737 -0.001279771 0.005259692 -0.9999853 0.7930441 0.6091259 -0.006837308 0.7749868 0.6319457 0.006341993 0.4191337 0.9078988 -0.006841361 0.3925341 0.9197156 0.006349563 -0.05080467 0.9986853 -0.006837308 -0.07985031 0.9967868 0.006344616 -0.5090945 0.8606836 -0.00684154 -0.5339252 0.8455079 0.006345391 -0.8507608 0.5255088 -0.006837129 -0.8657019 0.5005198 0.006346046 -0.9994233 0.03303164 -0.007884144 -0.9990882 0.04087775 -0.01232254 -0.9033648 -0.427968 0.02784675 -0.7974219 -0.601017 -0.05382317 -0.6008212 -0.7985174 0.03720134 -0.2351803 -0.9715501 -0.02794086 -0.1174842 -0.9927287 0.02621638 0.3232383 -0.9453679 -0.04238867 0.5355941 -0.8421415 0.06274175 0.844294 -0.5322028 -0.06267231 0.9473739 -0.3171594 0.04350423 0.9918114 0.1246157 -0.02794635 0.9798961 0.1994076 0.006344437 -0.7847602 0.03210777 0.6189673 -0.492828 0.1075744 0.8634514 -0.7337555 0.4242371 0.5306844 -0.3370746 0.5070191 0.7932922 -0.3484972 0.5518646 0.7576247 -0.06590312 0.8226826 0.5646683 0.08918339 0.4950569 0.8642714 0.3288733 0.7705603 0.5459662 0.6086733 0.4963258 0.6190134 0.4121555 0.2093428 0.8867376 0.8209472 0.1670717 0.5460155 0.7439401 -0.2479231 0.6205542 0.4567669 -0.2243456 0.8608329 0.4978759 -0.7828351 0.3732144 0.1791792 -0.4984697 0.8481879 -0.1056584 -0.8862114 0.4510717 -0.1936563 -0.5429524 0.8171291 -0.4934961 -0.655882 0.5712097 -0.4492473 -0.3220792 0.8333318 -0.7571214 -0.3586848 0.5459969 0.7765461 0.4603357 -0.4301944 0.1809172 0.5712149 -0.8006139 0.1529539 0.7211629 -0.6756694 -0.3686868 0.6071158 -0.7039037 -0.2719064 0.532311 -0.8016932 -0.8016805 0.3966396 -0.4471976 -0.5530306 -0.03229099 -0.8325351 -0.6742615 -0.1166388 -0.7292235 -0.541184 -0.618577 -0.5696336 -0.2253127 -0.4547162 -0.8616656 0.09063786 -0.923927 -0.3716769 0.3543889 -0.4329766 -0.8288184 0.4657101 -0.4746406 -0.7468805 0.8007976 -0.1340034 -0.583752 0.5215939 0.08920902 -0.8485174 0.6419218 0.7451041 0.1809871 -0.3270446 0.9294826 0.1705988 -0.9511868 0.1671929 0.259404 -0.6412801 -0.7453623 0.1821948 0.324923 -0.9283004 0.1807857 0.966682 -0.1831177 0.178869 -0.519429 0.08224213 0.8505467 -0.2358828 0.4343902 0.8692898 -0.06448531 0.4900278 0.8693184 0.3759371 0.3701997 0.8494843 0.5225282 -0.1111467 0.8453465 0.1390742 -0.5209071 0.8422079 -0.3444552 -0.4166364 0.8412876 0.6348953 0.7714122 0.04279518 0.6820865 0.73127 0.001527249 0.6737466 0.7389445 -0.005157351 -0.3554332 0.9347017 1.09395e-4 -0.3119853 0.9495976 0.03049027 -0.348222 0.9354599 0.06046873 -0.2617397 0.9651386 4.21414e-5 -0.9776235 0.2098574 0.01456946 -0.9902735 0.1347 0.03485029 -0.9816666 0.1906002 0.001540541 -0.6726329 -0.7399736 0.002032101 -0.6326254 -0.7740235 0.02593898 -0.6672827 -0.7447994 -0.002775132 0.3041493 -0.952619 -0.003225862 0.3529294 -0.9350719 0.03288727 0.3032582 -0.9529048 -0.002635478 0.9771127 -0.2127143 -0.001844108 0.9854516 -0.1642704 0.04359322 0.9749249 -0.2224882 0.004515349 0.1905288 -0.9740425 0.1222294 -0.5769911 0.1195744 -0.8079501 -0.2355974 -0.1185836 -0.9645889 -0.5363739 -0.5158047 -0.6680184 0.6867712 -0.1384249 -0.7135713 0.1426392 0.1550328 -0.9775576 -0.5925674 -0.5585516 -0.5804172 0.8601989 -0.1602494 -0.484126 -0.7706115 0.1081424 -0.6280632 -0.9523296 -0.2060236 -0.2249949 -0.5724577 -0.3926225 -0.7198193 0.9501827 -0.2172147 -0.2235413 0.6196833 0.1922662 -0.7609379 0.3511648 -0.3319359 -0.875501 0.2025001 -0.9792823 -2.5057e-4 -0.1292608 -0.4849153 -0.864956 -0.5181259 0.5318324 -0.6698506 -0.5402239 0.5954099 -0.5946808 -0.1520928 0.5263456 -0.8365574 0.03714549 0.8214439 -0.5690783 0.07992106 0.7269085 -0.682068 0.5941033 0.6394497 -0.4880013 0.7554351 0.6540778 -0.03873199 0.006056427 0.01114732 -0.9999195 0.006029665 0.006760418 -0.9999591 0.00972706 0.003371655 -0.9999471 0.00858128 0.00111413 -0.9999626 0.01291793 -0.005518853 -0.9999014 0.005087435 -0.01177775 -0.9999178 0.005484938 -0.00858134 -0.9999482 -0.002378702 -0.01189738 -0.9999264 -0.005012571 -0.008328557 -0.9999528 -0.008048832 -0.008594751 -0.9999307 -0.01277703 -9.17608e-4 -0.999918 -0.01099354 7.61023e-4 -0.9999394 -0.01200407 0.007376372 -0.9999008 -0.003846824 0.008946657 -0.9999526 -0.002390384 0.01278555 -0.9999154 0.03478014 -0.02378642 0.9991119 0.0211932 -0.02268105 0.9995182 0.004955649 -0.03536349 0.9993622 -0.004256486 0.03037351 0.9995296 0.003322064 0.0225898 0.9997393 0.01027572 0.02029901 0.9997411 0.008737146 0.02763819 0.9995799 0.02676397 0.02219849 0.9993954 0.03105872 -0.01023906 0.9994651 -0.02247506 -0.002300977 0.9997448 0.001104891 -0.03199821 0.9994874 -0.01964926 -0.03578734 0.9991663 -0.02569162 -0.01409286 0.9995706 -0.03283786 -0.02764093 0.9990785 -0.03067904 0.005493581 0.9995143 -0.03693914 0.003161966 0.9993125 -0.02066445 0.02422738 0.999493 -0.02001154 0.02406424 0.9995101 -0.9366485 0.3502365 -0.004899263 -0.9961494 0.08740079 0.006886005 -0.990567 -0.1370136 -0.00209552 -0.8389701 -0.5441576 0.004673182 -0.8585162 -0.512784 0.001697063 -0.4105902 -0.9118195 9.55721e-4 -0.3427098 -0.939417 0.006770491 0.1903777 -0.9816985 -0.004955053 0.4394028 -0.8982311 0.01030403 0.7307969 -0.6825677 -0.006113231 0.9096014 -0.4153822 0.009116828 0.979768 0.200011 0.007102847 0.9986737 -0.05130034 -0.004383563 0.9024912 0.4307016 -0.002430438 0.6500889 0.7598461 0.004299044 0.6611135 0.7502795 0.003118276 0.1250163 0.9921534 0.001642107 0.03701788 0.9992802 0.008302628 -0.4989023 0.8666372 -0.00603348 -0.6981371 0.715875 0.01129698 -0.004462122 0.003186404 0.999985 -0.001993834 -0.001292884 0.9999972 -0.001640915 0.001331865 0.9999979 -0.002202928 7.56276e-4 0.9999973 -0.7363168 0.6759123 -0.031309 -0.64858 0.7604348 0.0329082 -0.1387667 0.9901738 -0.01730966 -0.1865719 0.982316 0.01569736 0.3298162 0.9436344 -0.02784788 0.4514915 0.8919135 0.02540946 0.7695292 0.6382699 -0.02089309 0.7600769 0.6497127 -0.01251232 0.9947192 0.1018616 0.01257294 0.9977403 0.06676858 -0.007496595 0.9015488 -0.4326145 0.007386088 0.8973435 -0.4413244 0.002711594 0.6050476 -0.7961857 0.002449095 0.5894724 -0.8077636 -0.006343901 0.1387784 -0.9902921 0.007884383 0.1029447 -0.9946085 -0.01250612 -0.4812427 -0.8764972 0.01257622 -0.5118355 -0.8590509 -0.007500171 -0.8767278 -0.4809224 0.007884383 -0.8934703 -0.4489482 -0.01250898 -0.9842451 0.176249 0.01407307 -0.9846395 0.173893 0.01569879 0.7517841 -0.3697218 -0.5460096 0.7824823 0.05123406 -0.6205614 0.5625238 0.09217596 -0.8216269 0.5844212 0.5712612 -0.5762921 0.4879624 0.4189211 -0.7657662 0.2723038 0.7791085 -0.5646598 0.08918434 0.5694897 -0.8171461 -0.1593747 0.8442695 -0.5116726 -0.2249365 0.4648682 -0.8563302 -0.7075511 0.6488931 -0.279838 -0.53291 0.1771154 -0.8274281 -0.7834469 0.1395025 -0.6055989 -0.5479825 -0.1637229 -0.820311 -0.7813122 -0.3935519 -0.4844257 -0.3166698 -0.5037333 -0.8037245 -0.329881 -0.5509548 -0.7665686 0.09085077 -0.8693976 -0.4856891 0.1540758 -0.529031 -0.8344981 0.4838653 -0.6630524 -0.5711706 0.4444717 -0.3286119 -0.8333423 -0.5722603 0.5752072 0.5845126 -0.08053511 0.562314 0.8229929 0.03694432 0.8290481 0.5579555 0.5120564 0.5766335 0.6366257 0.4143844 0.2686143 0.8695586 0.8175433 0.1688856 0.5505458 0.6899973 -0.3145646 0.6518842 0.3825306 -0.3102982 0.870279 0.3989763 -0.8048146 0.4394216 -0.1819054 -0.5608589 0.8076806 -0.2351571 -0.6210089 0.7476959 -0.6947894 -0.415096 0.5873356 -0.5403626 -0.1407399 0.8295786 -0.8287897 0.0750128 0.5545095 -0.5110772 0.3781306 0.7718921 -0.4320813 0.8834958 -0.180945 0.5519763 0.8162132 -0.1706404 0.9625113 -0.07938778 -0.259364 0.431406 -0.8835958 -0.1820641 -0.5496283 -0.8156125 -0.1807901 -0.9815191 0.06792378 -0.1789042 0.523315 -0.05211186 -0.8505445 0.3382951 0.3604125 -0.8692868 0.1866012 0.4576735 -0.8693188 -0.2698082 0.4534085 -0.8494848 -0.5336307 0.02494508 -0.8453497 -0.2665857 -0.468645 -0.8422018 0.2275854 -0.490352 -0.8412847 -0.4186105 0.9071566 -0.04280376 -0.4744266 0.8802938 -0.001527249 -0.4644123 0.8856042 0.005141139 0.580762 0.8140736 -1.09394e-4 0.5425056 0.8394988 -0.03048992 0.5739966 0.8166232 -0.06045329 0.4978514 0.8672624 -5.05711e-5 0.9988881 -0.04483503 -0.01457422 0.992071 -0.1207498 -0.03485125 0.9979191 -0.06446146 -0.001545369 0.4630689 -0.8863201 -0.002049088 0.4157711 -0.9090996 -0.0259304 0.4566762 -0.8896288 0.002770185 -0.5356875 -0.8444103 0.003209412 -0.5784464 -0.8150573 -0.03288674 -0.5349081 -0.8449062 0.002620816 -0.9991194 0.04191875 0.001843035 -0.9949027 0.09093165 -0.04359006 -0.9994803 0.03191888 -0.004512965 0.7620794 0.1785354 0.6223828 0.01891601 -0.04840642 0.9986487 0.9293726 0.2065518 0.3059464 0.6810643 -0.03030669 0.7315963 0.8368989 -0.4195764 0.3515051 0.5044504 -0.4669694 0.726271 0.4533651 -0.755097 0.4735913 -0.9454993 0.05854183 0.3203188 -0.6431819 0.2314617 0.7298922 -0.6277806 0.6755511 0.3866813 -0.7418994 -0.1001361 0.6629918 -0.6308605 -0.4080591 0.6599264 -0.6989192 -0.651974 0.2940098 -0.2705156 -0.6043493 0.7493886 -0.05929714 -0.9187798 0.3902916 0.1271432 -0.6846736 0.7176744 0.6755688 0.3170936 0.6656264 0.4708211 0.6354331 0.6120069 0.491311 0.7909713 0.3646613 0.1042705 0.5543324 0.825738 -0.1966018 0.8062697 0.5579221 -0.3059075 0.5854071 0.7508122 0.008204758 0.004166364 0.9999577 0.008796095 0.005773007 0.9999447 0.003277659 0.00892961 0.9999548 0.003431379 0.009026825 0.9999534 -0.003813207 0.01255935 0.9999139 -0.008568286 0.006584525 0.9999417 -0.009316205 0.006597697 0.9999349 -0.01183509 -1.56732e-4 0.99993 -0.008947074 -0.002604186 0.9999567 -0.009961962 -0.007707417 0.9999207 -0.001928508 -0.01211285 0.9999248 -0.002390921 -0.01261752 0.9999176 0.008297681 -0.01166599 0.9998975 0.007776618 -0.006072342 0.9999514 0.01297175 -0.001740992 0.9999144 -0.02673041 0.01268559 -0.9995622 -0.009025275 0.01089125 -0.9999001 -0.006277859 0.02811324 -0.9995851 -0.03859835 0.007821559 -0.9992242 0.03592932 1.4946e-4 -0.9993544 0.02765023 0.007376134 -0.9995905 0.02724975 0.01611834 -0.9994988 0.01877909 0.01899272 -0.9996433 0.01508873 0.02657735 -0.9995329 0.01009541 0.02503633 -0.9996356 -0.004586279 0.03650552 -0.999323 -0.01813924 -0.01705819 -0.9996899 -0.01547753 -0.008205056 -0.9998466 -0.03094452 -0.00331366 -0.9995157 -0.01611179 -0.0283789 -0.9994674 -0.01849877 -0.02922946 -0.9994016 0.007137238 -0.04352307 -0.999027 0.02424389 -0.008401215 -0.9996709 0.0133357 -0.01085644 -0.9998522 0.01861155 -0.02678304 -0.999468 -0.1679874 -0.9857634 -0.00713253 -0.3584849 -0.9335194 0.005491375 -0.7136661 -0.7004481 -0.007292747 -0.8184833 -0.5745289 0.001323819 -0.9942528 -0.1069066 -0.005691289 -0.9956095 -0.09335982 -0.006770312 -0.9062702 0.4226728 0.004708468 -0.7574809 0.6527551 -0.01155632 -0.457533 0.8891776 0.005182683 -0.1712052 0.9851932 -0.009117245 0.4418501 0.8970519 -0.008146882 0.1786605 0.9839047 0.003475129 0.6477066 0.7618863 0.002381086 0.9073101 0.4204375 -0.004571557 0.8933655 0.4493265 -0.00196439 0.9917705 -0.1280277 -7.02501e-4 0.9760244 -0.2175184 -0.007887244 0.7532151 -0.6577677 0.002948522 0.5155333 -0.8568041 -0.01059556 0.3176471 -0.9482049 0.002814829 -0.005957603 0.002504348 -0.9999791 0.002129375 -0.006305992 -0.999978 3.94757e-4 0.002450048 -0.999997 0.002463936 2.19903e-4 -0.999997 0.6335632 -0.7718977 0.05264645 0.7744429 -0.6304548 -0.05258101 0.9786714 -0.2006515 0.04405975 0.9992367 0.004158675 -0.03884571 0.948345 0.3159549 0.02853715 0.8603433 0.5088877 -0.02903068 0.6928846 0.7204836 0.0285387 0.4933426 0.8689616 -0.03897202 0.2786212 0.9596802 0.0372036 -0.1246153 0.9918115 -0.02794796 -0.1994129 0.9798951 0.006349742 -0.6380191 0.7699803 -0.007884383 -0.6653649 0.7464136 0.01251059 -0.9799821 0.1985878 -0.01407051 -0.9873625 0.1578467 0.01413565 -0.8834484 -0.4683601 -0.01256966 -0.8664523 -0.4992036 0.007497966 -0.4937011 -0.869596 -0.007884383 -0.5005007 -0.8656485 -0.01232159 0.003024756 -0.9995053 0.03130865 0.1616109 -0.9854526 -0.05258435 -0.183898 0.9036539 0.3867702 0.1145467 0.5250089 0.8433533 0.1819713 0.626794 0.7576383 0.5721185 0.5949066 0.5645942 0.4677695 0.3368266 0.8171533 0.7787404 0.2594497 0.5711824 0.5781223 0.03329485 0.8152706 0.8831309 -0.180327 0.4330844 0.4200333 -0.3009139 0.8561676 0.5985135 -0.729194 0.3317496 0.1394277 -0.5209399 0.8421293 0.001771152 -0.8672043 0.4979495 -0.1738791 -0.5523213 0.8152958 -0.4242243 -0.7337328 0.5307258 -0.5070279 -0.3370816 0.7932835 -0.6358383 -0.3677586 0.6785745 -0.6820756 0.09493076 0.7250938 -0.7336902 0.1172897 0.6692847 -0.4275889 0.5428729 0.7228118 -0.3598535 0.4059587 0.8400613 0.4220486 -0.7163732 -0.5555938 0.3635579 -0.3548662 -0.8613337 0.9074903 -0.1980273 -0.3704681 0.5497432 0.1834293 -0.8149455 0.6549937 0.3329702 -0.6783171 0.2725536 0.6504004 -0.7090091 0.2706286 0.5429788 -0.7949429 -0.1521233 0.8772787 -0.4552371 -0.3513435 0.4292184 -0.8320633 -0.5697868 0.5003618 -0.6519059 -0.6765099 -0.1165915 -0.7271457 -0.5728863 -0.06260991 -0.8172401 -0.6354603 -0.623595 -0.4553235 -0.1422225 -0.5420895 -0.8281979 -0.1095221 -0.6610989 -0.7422623 0.7450982 -0.6419087 0.1810578 0.9294929 0.3270379 0.1705554 0.1671954 0.9512221 0.2592728 -0.7453815 0.641308 0.1820179 -0.928307 -0.3249151 0.1807665 -0.1831156 -0.9666987 0.17878 0.08224666 0.5194292 0.8505463 0.4344071 0.2358755 0.8692831 0.4900282 0.06449681 0.8693174 0.3701967 -0.3759335 0.8494871 -0.1111515 -0.5225355 0.8453415 -0.5209043 -0.1390763 0.8422093 -0.4166359 0.3444569 0.8412871 0.7714151 -0.6348907 0.042809 0.7312676 -0.682089 0.001519978 0.7389459 -0.6737451 -0.005145251 0.9347065 0.3554207 1.13604e-4 0.9495996 0.3119788 0.03049468 0.9354657 0.3482086 0.06045526 0.9651408 0.2617314 5.89979e-5 0.2098526 0.9776245 0.01456815 0.1347033 0.9902725 0.03486466 0.1906021 0.9816663 0.001547753 -0.7399764 0.6726298 0.002032101 -0.7740147 0.6326364 0.02593016 -0.7448017 0.6672802 -0.002770185 -0.9526211 -0.3041427 -0.00321567 -0.9350699 -0.352934 0.03289115 -0.9529061 -0.3032543 -0.00263673 -0.2127071 -0.9771143 -0.001850247 -0.1642866 -0.9854496 0.04358083 -0.222491 -0.9749242 0.004533231 0.1947123 0.818843 -0.5399844 -0.2445195 0.5484886 -0.7996065 -0.6040972 0.3317726 -0.7245644 0.2212401 -0.6556966 -0.7218828 0.1847767 0.8054915 -0.563064 -0.4058826 0.7030348 -0.5839533 0.3085444 -0.7599061 -0.572139 -0.2495202 -0.7149162 -0.6531727 -0.3008728 -0.7669619 -0.5667849 -0.3998841 -0.3689889 -0.8390114 -0.7315825 -0.4533448 -0.5091814 -0.7076453 -0.05852168 -0.7041402 -0.8595865 -0.1391308 -0.4916847 -0.6121478 0.3424485 -0.7127441 0.3932258 0.5600385 -0.7291985 0.6400861 0.5679032 -0.5174708 0.636322 0.296195 -0.7122941 0.8880149 0.1238162 -0.4428308 0.6160036 -0.1382819 -0.7755113 0.7735776 -0.3924059 -0.4975896 0.4255144 -0.3758133 -0.8232265 -0.504984 -0.8631287 2.43661e-5 -0.5018867 -0.8649334 -4.30031e-5 -0.4928328 -0.8701038 -0.005928158 -0.4999982 -0.8660259 0.001010656 0.006718993 -0.3978527 -0.9174248 0.493719 -0.8696216 -1.0943e-5 0.4849431 -0.8745458 -3.02442e-5 0.5346297 -0.8446977 -0.02563071 0.4999799 -0.8659962 0.008407652 0.4389081 -0.4677531 -0.767181 0.3290622 -0.2046277 -0.9218708 0.9999839 0.005692422 0 0.9999896 -0.002967715 -0.003495693 0.9999698 0.007717728 8.68819e-4 0.999987 0 -0.005115926 0.4269278 0.1671437 -0.8887045 0.6015178 0.1237232 -0.7892205 0.4012194 0.4516476 -0.7968924 0.3557704 0.283987 -0.8903813 0.5049948 0.8631225 3.00652e-5 0.5072417 0.8618031 0.00113058 0.4999996 0.8660242 0.001638174 0.4908076 0.8711627 -0.01355206 -0.006714522 0.3978517 -0.9174253 -0.4849207 0.8745582 -3.02439e-5 -0.5072595 0.8617923 0.001375079 -0.499981 0.8659956 0.008409678 -0.479501 0.7046732 -0.5229862 -0.359619 0.3082065 -0.8807287 -0.4353355 0.1849751 -0.8810604 -0.9999819 0.00601226 4.4598e-5 -0.9987639 -0.04953515 -0.004130542 -0.9999666 0.008134543 9.49107e-4 -0.9997127 0 -0.02397412 -0.9864527 0.1320766 0.09729743 -0.3459168 -0.2043412 -0.9157436 0.004237115 2.50972e-4 -0.9999911 -0.004386305 -2.63787e-4 -0.9999904 0.009443879 -0.02060961 -0.999743 -0.0061661 0.00770545 -0.9999514 -0.01161855 -0.01981675 -0.9997361 8.22176e-4 -6.78212e-4 -0.9999995 0.001522243 -3.82134e-4 -0.9999988 0.00197798 0.008974134 -0.9999579 0.001045644 -3.90056e-4 -0.9999995 9.60276e-4 -5.54675e-4 -0.9999995 0.003144383 0.004418849 -0.9999853 0.01037883 -0.01861333 -0.9997729 -0.001082956 -6.2519e-4 -0.9999992 -0.001135706 -4.23635e-4 -0.9999993 -2.39179e-4 0.009972393 -0.9999504 -0.01153916 0.0196982 -0.9997395 -0.002749562 -0.003612935 -0.9999898 0.007047057 -0.005875766 -0.999958 -9.59528e-4 -7.92526e-4 -0.9999992 -0.004927337 -0.004294574 -0.9999787 0.008215427 0.01095032 -0.9999064 -0.007582485 0.008516252 -0.9999351 0.004928231 0.004294395 -0.9999787 -0.01709502 -0.01448518 -0.999749 0.001303732 -0.001504182 -0.999998 0.003256201 0.002894103 -0.9999906 0.8710765 0.0730139 -0.4856902 0.4066383 0.4485956 -0.7958691 0.414668 0.8464327 -0.3340692 -0.03928202 0.5416375 -0.8396939 -0.5661397 0.7593613 -0.3207122 -0.5064948 0.4228045 -0.7514649 -0.7034133 0.01924842 -0.7105205 -0.8710921 -0.0730158 -0.4856617 -0.4066541 -0.4485899 -0.7958642 -0.4146778 -0.8464233 -0.3340805 0.03928017 -0.5416193 -0.8397058 0.5661523 -0.7593648 -0.3206818 0.5064863 -0.4227986 -0.7514739 0.7034192 -0.01923751 -0.7105149 0.9996066 -0.02482926 0.01304697 0.7654176 -0.6432821 0.01800149 0.7048119 -0.7090233 -0.02293878 0.1729459 -0.9849236 -0.003933966 0.07632559 -0.9964271 0.03615802 -0.4801498 -0.8761748 -0.04212027 -0.6729764 -0.7375922 0.05532222 -0.9913883 -0.1159309 -0.06090402 -0.9996063 0.02484464 0.01304739 -0.7654075 0.6432939 0.01801532 -0.7048037 0.7090317 -0.022933 -0.1729504 0.9849227 -0.003927946 -0.07632964 0.9964274 0.03614354 0.4801559 0.8761712 -0.04212421 0.6729655 0.7376019 0.05532646 0.9913892 0.1159266 -0.06089782 -0.8332512 0.3402736 0.4357826 -0.4071963 0.4127117 0.8147763 -0.2436035 0.798259 0.5508537 -0.1242351 0.6967505 0.7064732 0.3509747 0.6575576 0.6666594 0.350296 0.6403343 0.6835676 0.6956785 0.0811972 0.7137495 0.7465389 0.1102688 0.6561406 0.5229217 -0.5681567 0.635414 0.5887957 -0.5944208 0.5477076 0.108356 -0.6051377 0.7887126 -0.1805621 -0.878395 0.4425152 -0.2848578 -0.5211233 0.8045413 -0.7978646 -0.3776798 0.4698619 -0.5456959 -0.06363314 0.8355639 -0.001494407 7.42133e-4 0.9999987 -5.50805e-4 0 1 -0.001552522 -7.51731e-4 0.9999985 3.21295e-4 5.56502e-4 0.9999998 2.54995e-4 0.002931296 0.9999957 -6.56172e-5 -0.001234412 0.9999992 -9.72209e-4 -0.00168389 0.9999982 -9.4011e-4 0.001628279 0.9999983 0.001015245 6.1966e-4 0.9999993 0.001529455 0 0.9999989 0.002218604 4.12685e-4 0.9999976 8.48828e-4 -0.001260757 0.9999989 8.40764e-4 -0.001456201 0.9999987 0.8641005 -0.5033193 2.47083e-5 0.914669 -0.404202 0.001219153 0.8653917 -0.4996317 -0.03828179 0.8277259 -0.5603355 0.02990335 0.4069613 -0.004593014 -0.9134339 0.8627334 0.5056591 -3.20634e-5 0.9100146 0.4145719 0.001909017 0.8660229 0.4999969 -0.002756536 0.8334976 0.5495845 -0.056912 0.1091166 0.3085849 -0.9449175 0.32943 0.3788135 -0.8648562 0.1128476 0.4162862 -0.9022036 0.001978695 0.9999905 -0.00389862 -0.001915276 0.9999922 -0.003473997 0 0.9999971 -0.002402365 -0.1671671 0.4269401 -0.8886942 -0.1291395 0.5820756 -0.8028146 -0.4516447 0.4012122 -0.7968977 -0.2839806 0.3557802 -0.8903795 -0.8631215 0.5049964 2.99887e-5 -0.8618071 0.507235 0.001130521 -0.8660244 0.4999992 0.001638174 -0.8711609 0.4908105 -0.01355677 -0.3978563 -0.006715476 -0.9174233 -0.8745554 -0.4849258 -3.93172e-5 -0.8599239 -0.5104196 -0.001707196 -0.8659944 -0.499983 0.008409678 -0.6977185 -0.474799 -0.5364279 -0.2911971 -0.3388907 -0.8946269 -0.1260398 -0.5566695 -0.8211171 -0.161832 -0.4121829 -0.8966135 3.15463e-4 -0.9999963 -0.002719521 0 -0.9999998 6.02607e-4 0.004509389 -0.9999725 -0.005885541 0.1153206 -0.4214453 -0.8994916 0.1352471 -0.3246359 -0.9361195 0.3323476 -0.3861163 -0.8604994 -7.63293e-4 0.01034522 -0.9999463 7.16198e-4 -0.009781479 -0.999952 1.65538e-4 -0.01013606 -0.9999486 0.001598536 0.008561074 -0.9999621 6.78849e-4 8.21665e-4 -0.9999995 3.82473e-4 0.001522541 -0.9999988 -0.02425086 0.003499209 -0.9996998 3.90047e-4 0.001045703 -0.9999995 5.54681e-4 9.60943e-4 -0.9999994 0.004435777 -0.001190483 -0.9999895 0.001400053 0.01302194 -0.9999142 -0.003351807 0.005022048 -0.9999818 6.2507e-4 -0.001082658 -0.9999992 4.2356e-4 -0.001135349 -0.9999994 -0.02410984 9.79777e-4 -0.9997089 -0.01969563 -0.01153695 -0.9997395 0.003611445 -0.002749621 -0.9999898 0.005873978 0.007044792 -0.999958 7.91829e-4 -9.59847e-4 -0.9999992 0.008044183 0.002465009 -0.9999646 -0.008535444 -6.27466e-4 -0.9999635 -0.006516516 -0.006092429 -0.9999603 -0.004293143 0.004928171 -0.9999787 0.01693195 -0.01146382 -0.9997909 0.001503527 0.00130397 -0.9999981 -0.002893269 0.003256142 -0.9999905 -0.07300937 0.8710961 -0.4856555 -0.4485998 0.4066542 -0.7958585 -0.846435 0.4146859 -0.3340414 -0.5416208 -0.03928142 -0.8397046 -0.7593576 -0.5661348 -0.3207295 -0.4227985 -0.5064831 -0.7514761 -0.01924908 -0.7034278 -0.7105061 0.07301092 -0.8710918 -0.4856631 0.4485901 -0.4066401 -0.795871 0.8464447 -0.4146737 -0.3340317 0.5416249 0.03927993 -0.8397022 0.7593488 0.5661386 -0.3207437 0.4228234 0.5065044 -0.7514477 0.01923477 0.7034409 -0.7104935 0.02483189 0.9996066 0.01304596 0.6432992 0.7654032 0.01800608 0.7090273 0.7048081 -0.02293485 0.9849216 0.172957 -0.003934025 0.9964268 0.07633185 0.03615695 0.8761811 -0.4801385 -0.04211658 0.7375973 -0.6729707 0.05532336 0.1159424 -0.9913864 -0.06091463 -0.02484691 -0.9996062 0.01304543 -0.6432861 -0.7654142 0.01800185 -0.7090319 -0.7048034 -0.02293354 -0.9849188 -0.1729722 -0.003934085 -0.9964274 -0.07632404 0.03615528 -0.876174 0.4801508 -0.04212492 -0.737598 0.6729702 0.05532169 -0.1159076 0.9913917 -0.0608924 -0.601418 -0.6088493 0.5172997 -0.5944254 -0.5887861 0.5477129 -0.605144 -0.1083735 0.7887054 -0.8783887 0.1805539 0.442531 -0.521095 0.2848489 0.8045627 -0.3242458 0.8716436 0.3675626 -0.06563919 0.5629161 0.8239035 0.6014074 0.6088312 0.5173333 0.5944385 0.5888051 0.5476784 0.6051339 0.1083695 0.7887136 0.8784046 -0.1805613 0.4424963 0.5211222 -0.2848457 0.8045462 0.3242249 -0.8715889 0.3677105 0.06565499 -0.5628798 0.8239271 0.002109587 -8.80364e-4 0.9999974 0 -0.004263043 0.9999909 -0.001234233 6.65791e-5 0.9999992 -0.001682937 9.71669e-4 0.9999982 0.001234471 -6.60254e-5 0.9999993 0.001683592 -9.72049e-4 0.9999981 -0.00336188 -7.6236e-4 0.9999941 -0.00145626 -8.40794e-4 0.9999986 -0.002109229 8.79899e-4 0.9999974 0 0.004262089 0.999991 0.003361046 7.62436e-4 0.9999942 0.00145632 8.40839e-4 0.9999986 -0.00897634 -0.004939079 -0.9999476 0.0217784 0.01428705 -0.9996607 -7.15973e-4 0.02840095 -0.9995964 -0.02794665 0.01811927 -0.9994452 -0.03054457 -0.0114606 -0.9994677 0.008791327 -0.004701733 -0.9999503 -0.02248412 -0.01397413 -0.9996495 -0.02972418 -0.006479501 -0.9995372 9.52796e-4 -0.02930986 -0.99957 -0.0389198 -0.03678876 -0.9985649 -0.02746051 -0.05279672 -0.9982277 0.02182936 -0.0120902 -0.9996886 0.01892089 -0.03321337 -0.9992693 0.004201352 -0.03200381 -0.9994789 -0.009250044 -0.00491333 -0.9999452 -0.005678176 -0.027287 -0.9996115 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.2615009 0.9650718 0.01592904 -0.1642143 0.9864223 -0.002203762 -0.1543675 0.9880133 -6.02821e-4 -0.6710385 0.7414182 0.00256592 -0.6723685 0.7402127 0.002389073 -0.8404383 0.5417526 0.01294898 -0.9589911 0.2833109 -0.008425354 -0.9999363 -6.49174e-4 0.01126927 -0.9648954 -0.2625001 -0.008405029 -0.8536093 -0.5207903 0.01135075 -0.6829459 -0.7304214 -0.008342981 -0.4580453 -0.8888555 0.01142042 -0.1971612 -0.9803363 -0.008272409 0.07121986 -0.9973946 0.01147979 0.3474537 -0.9376614 -0.008192539 0.6212088 -0.7834945 0.01536691 0.7883504 -0.6151407 -0.01028507 0.2958254 -0.9547999 -0.02906417 0.9905492 -0.1349264 0.0246427 0.9969723 0.07772243 -0.002342879 0.9115158 0.4109194 0.01686304 0.8203816 0.5718153 0.001167178 0.5796363 0.8147864 0.01204049 0.4671584 0.8841723 0.001535832 0.06066614 0.02531373 0.9978372 0.02542299 0.02985972 0.9992308 0.001483559 0.001004397 0.9999985 0.02304619 0.04805481 0.9985788 -0.009324073 0.0178641 0.9997969 -0.008505702 0.01813286 0.9997995 0.2772218 0.9594697 -0.05065453 0.03181493 0.9992466 0.0222271 -0.07950413 0.9967988 -0.008441925 -0.4903856 0.8713972 0.01373952 -0.4917356 0.8706488 0.0129106 -0.830164 0.5565288 -0.03321897 -0.925598 0.3767185 0.03676205 -0.9873045 0.1576285 -0.0195747 -0.9875581 -0.1572296 -0.002825736 -0.9867588 -0.1621063 -0.005357265 -0.8235933 -0.5654009 -0.04489952 -0.6747992 -0.7372167 0.03402477 -0.402157 -0.9146562 -0.04091542 -0.2297706 -0.9731749 0.01166999 0.03590387 -0.9986642 -0.03715932 0.3677579 -0.9294942 0.0281921 0.3969774 -0.9177311 0.01336443 0.7708237 -0.6361724 -0.03340297 0.8832249 -0.4686819 0.01584547 0.9179931 -0.3964697 -0.01002961 0.9983072 0.05651694 0.01373815 0.9956494 0.09299165 -0.005906403 0.7590472 0.6510091 -0.005876183 0.6975619 0.7150226 0.04636973 -0.3904362 0.1717632 -0.9044651 -0.6696642 0.4463811 -0.5935435 -0.3938184 0.7018748 -0.5935309 -0.1234173 0.3790752 -0.9170989 0.230356 0.6068704 -0.7606868 0.7251263 0.6246564 -0.289821 0.3426081 0.1844256 -0.9211987 0.9917674 0.09220999 -0.08885347 0.5054349 -0.1317318 -0.85275 0.2088553 -0.2915681 -0.9334707 0.3980169 -0.1412971 0.9064313 0.6132755 -0.7732263 0.1612894 0.05736786 -0.4817976 0.8744027 0.03994989 -0.5625382 0.8258057 -0.4335608 -0.8411603 0.3232252 -0.4034405 -0.2731407 0.8732869 -0.4834983 -0.2947412 0.8242312 -0.9458248 -5.42235e-4 0.324677 -0.5346728 0.2036363 0.8201569 -0.2044761 0.4388813 0.8749702 0.8350776 0.5190122 -0.1824061 0.8670185 -0.4636943 -0.1823911 0.03086686 -0.983946 -0.1757771 -0.8362741 -0.5179722 -0.1798626 -0.8663507 0.4637674 -0.1853548 -0.03194028 0.9826809 -0.1825323 0.02798253 -0.5425617 -0.8395498 -0.4264249 -0.3222829 -0.8451601 0.4731106 -0.2573561 -0.8425759 0.4464176 0.3017305 -0.8424193 -0.03154593 0.5407651 -0.840582 -0.477876 0.2474098 -0.8428659 0.835129 0.5499848 -0.008746385 0.8614884 0.5066946 -0.03314477 0.8389872 0.5441353 -0.004143536 0.8940004 -0.4480125 -0.006929218 0.8692446 -0.493629 -0.02728217 0.8895579 -0.4568224 -3.3329e-4 0.05765938 -0.9983362 -6.46536e-4 0.007252573 -0.9995762 -0.02819621 0.05340033 -0.998571 0.002117335 -0.8268846 -0.5607278 -0.0429697 -0.8677325 -0.4952776 0.04171717 -0.8350579 -0.5501441 0.004455149 -0.8945153 0.4470375 -6.57912e-5 -0.9063405 0.4221618 -0.01806843 -0.87026 0.4878714 -0.06803768 -0.05986016 0.998206 -0.001307904 -0.008305251 0.9993613 -0.03475666 -0.0591889 0.9982464 -8.61969e-4 0.689817 0.2197057 0.6898419 0.4411965 0.01900327 0.8972094 0.2428194 -0.03760075 0.9693426 0.5905306 -0.3342529 0.7345397 0.3653115 -0.2844129 0.8863729 0.5061013 -0.5583183 0.6573752 0.2194408 -0.5138833 0.8293189 0.1644334 -0.442249 0.8816903 0.09911453 -0.7279606 0.6784171 -0.1061394 -0.5462302 0.8308833 -0.1065491 -0.5323913 0.839766 -0.4128615 -0.6563192 0.6314986 -0.3196138 -0.3426361 0.8834295 -0.6073415 -0.4559103 0.6506013 -0.5335183 -0.1715736 0.8282034 -0.4623149 -0.1263558 0.8776668 -0.73887 -0.03183555 0.6730956 -0.5351984 0.1564112 0.8301194 -0.5382377 0.1565804 0.8281201 -0.6157115 0.4718715 0.63106 -0.3213019 0.3563375 0.8773761 -0.4059842 0.6662418 0.6255387 0.2455662 0.3903539 0.8873112 0.2997673 0.5499959 0.7795154 0.1684024 0.8666455 0.4696447 -0.09637498 0.5366756 0.8382669 -0.0835334 0.5063261 0.8582867 0.4961167 0.373587 0.7837737 0.4466927 0.3137235 0.8378803 -0.02822709 -0.002514958 0.9995984 -0.008276402 0.0304355 0.9995025 -0.006216824 -0.006222963 0.9999614 -0.0061329 -0.009211361 0.9999388 0.01942551 -0.004813253 0.9997998 0.01194757 -0.01926183 0.9997431 -0.002614915 0.009081482 0.9999554 0.03902894 -0.01504844 0.9991248 0.0275678 -0.02277171 0.9993606 0.006191134 0.006430506 0.9999603 0.004487335 0.01170349 0.9999215 0.009073138 -0.00260955 0.9999555 0.01018697 0.005240976 0.9999344 0.01702338 0.03436583 0.9992644 0.008500695 -0.0018875 0.9999622 -0.02333647 0.007773101 -0.9996975 -0.01791697 0.009406566 -0.9997953 -0.01710349 0.004220843 -0.9998449 -0.0217483 -0.004934489 -0.9997513 -0.0134266 -0.01294231 -0.9998261 -0.02080297 -0.013713 -0.9996896 -0.009167134 -0.0150128 -0.9998454 -0.001347661 -0.02160221 -0.9997658 0.001462638 -0.0183717 -0.9998302 0.005259692 -0.01621347 -0.9998548 0.01293301 -0.01601934 -0.9997881 0.01453197 -0.01027619 -0.9998417 0.01729649 -0.00696057 -0.9998262 0.01869499 -0.01114821 -0.9997631 0.01946938 0.004477798 -0.9998005 0.03081291 -5.89676e-4 -0.9995251 0.009342491 0.01664292 -0.9998179 0.01019084 0.01477289 -0.999839 0.009361624 0.01457154 -0.9998501 -1.03917e-4 0.02218699 -0.9997538 -0.009587764 0.01846778 -0.9997836 -0.007412075 0.02554178 -0.9996463 0.546694 0.8373314 0.001358449 0.7512418 0.6597014 -0.0207352 0.868309 0.4960007 -0.004788517 0.9911579 0.1318428 -0.01494759 0.9962449 0.08623409 -0.007729053 0.9310659 -0.3647893 0.006729006 0.7812057 -0.6242059 -0.009206354 0.7441381 -0.6677606 -0.01882797 0.251362 -0.967794 -0.01385664 0.3903434 -0.9206694 2.26282e-4 -0.02136158 -0.9997674 -0.00297594 -0.2439674 -0.9695793 -0.01990264 -0.5115432 -0.8592575 3.59593e-4 -0.6974387 -0.716473 -0.01567894 -0.8780272 -0.4785804 0.005411028 -0.9761378 -0.2166956 -0.01407772 -0.9977903 0.06610679 0.006660699 -0.9182733 0.3954583 -0.01967281 -0.8077888 0.5894607 0.003656685 -0.3998925 0.9164447 -0.01466798 -0.4327378 0.9014798 -0.008492469 0.1430692 0.9896215 -0.01343965 0.1370003 0.9904658 -0.01443576 0.03522169 0.04885685 -0.9981846 -0.03824889 -0.001849651 -0.9992666 0.01204246 0.06561404 -0.9977725 -0.01242011 -0.07828706 -0.9968535 -0.02684032 -0.02944201 -0.9992061 0.007874488 0.04205507 -0.9990844 0.5673886 0.8222261 -0.04488366 0.6957912 0.7176606 0.02894616 0.974168 0.2240978 -0.02787268 0.9886743 0.1490985 0.01711165 0.9699509 -0.2422044 0.02307111 0.9274548 -0.3731247 -0.02460998 0.7617071 -0.6475539 0.02182334 0.6278243 -0.7780759 -0.02084451 0.4881764 -0.8719791 0.03655701 -0.02573746 -0.9995352 -0.0163412 -0.06219142 -0.9972848 -0.03943574 -0.5635662 -0.8250209 0.04164034 -0.7192353 -0.6936664 -0.03908401 -0.9180701 -0.3951547 0.03162217 -0.9744734 -0.2208704 -0.04022163 -0.9690154 0.2415089 0.0517944 -0.8842083 0.4640284 -0.0534178 -0.646435 0.7618156 0.04193919 -0.4607636 0.8874296 -0.01287221 -0.2803702 0.9593781 0.03140383 -0.004584252 0.9993284 -0.03635805 0.2743905 0.9610126 0.03412955 -0.02590364 -0.9923968 0.1203225 0.1968359 -0.4741147 0.8581789 0.3448464 -0.1877188 0.9196971 0.5182797 0.1383277 0.84395 0.5876398 0.6035453 0.5388995 0.2947977 0.3995131 0.8680344 0.2707701 0.9481034 0.1666841 -0.06122815 0.4297682 0.900861 -0.4465174 0.4493057 0.7737872 -0.7766414 0.1958085 0.5987381 -0.6502326 0.1415116 0.7464396 -0.6091743 -0.278427 0.7425532 -0.562668 -0.248328 0.7885037 -0.5356332 -0.7824637 0.3175653 -0.1455492 -0.3793944 0.9137151 -0.537349 0.1776298 -0.8244416 -0.9243181 -0.2052705 -0.3217142 -0.4263319 -0.3191977 -0.846377 0.211395 -0.3789629 -0.9009436 0.7580306 -0.6031228 -0.2482586 0.539647 -0.01092815 -0.8418206 -0.2724017 0.9447435 0.1823654 -0.9543702 0.236458 0.1823875 -0.6820008 -0.7099117 0.175785 0.2739763 -0.9447641 0.1798824 0.9539275 -0.2359512 0.1853359 0.681953 0.7082589 0.1825091 -0.3841995 -0.3841194 0.8395494 0.100754 -0.5249307 0.8451606 -0.5236781 0.1258128 0.8425749 -0.1293604 0.5230636 0.8424195 0.3856487 0.3803941 0.8405805 0.5205575 -0.1363918 0.8428626 -0.2517101 0.9677633 0.008745431 -0.3002704 0.953278 0.0331462 -0.2584815 0.9660073 0.004147112 -0.9639021 0.2661668 0.006932973 -0.9760745 0.2157184 0.02728283 -0.9665036 0.256653 3.35703e-4 -0.7115262 -0.7026593 6.45495e-4 -0.6749262 -0.7373462 0.02820068 -0.7085236 -0.705684 -0.002114892 0.2383792 -0.9702212 0.04296749 0.3125517 -0.9489842 -0.04171729 0.2515404 -0.9678366 -0.004454076 0.9636305 -0.2672384 6.89232e-5 0.9557461 -0.2936375 0.01807379 0.9729702 -0.2206791 0.06804269 0.7130689 0.7010927 0.001303732 0.6755633 0.7364822 0.0347594 0.7126055 0.7015644 8.6197e-4 0.02458107 0.07862496 0.9966012 0.5049892 0.8631258 2.78482e-5 0.5018882 0.8649325 -3.0717e-5 0.4928331 0.8701038 -0.005931377 0.4999981 0.8660261 0.001006662 -0.006719648 0.3978445 -0.9174283 -0.493722 0.8696198 -1.80228e-5 -0.4849401 0.8745474 -2.41949e-5 -0.5346325 0.8446958 -0.02563965 -0.4999807 0.8659958 0.008407652 -0.4392443 0.4684538 -0.7665609 -0.3290689 0.2046268 -0.9218685 -0.9999839 -0.005681157 -1.68102e-6 -0.9999896 0.00296247 -0.003497481 -0.9999698 -0.007726848 8.65308e-4 -0.999987 0 -0.005115926 -0.4269367 -0.1671527 -0.8886986 -0.6015211 -0.1237108 -0.7892199 -0.4012284 -0.4516457 -0.796889 -0.3557697 -0.2839871 -0.8903815 -0.5050006 -0.863119 2.78043e-5 -0.5072417 -0.8618032 0.001126825 -0.4999997 -0.8660241 0.001642525 -0.4908096 -0.8711615 -0.01355648 0.006711423 -0.3978546 -0.9174239 0.4849238 -0.8745565 -3.62931e-5 0.5072532 -0.861796 0.001382112 0.4999828 -0.8659945 0.008411645 0.4794581 -0.7045849 -0.5231444 0.3596121 -0.3082381 -0.8807204 0.4353366 -0.1849747 -0.8810598 0.9999821 -0.006005287 4.63597e-5 0.9987639 0.0495361 -0.004130661 0.9999666 -0.008134722 9.52757e-4 0.9997127 0 -0.02397251 0.9864528 -0.1320826 0.09728908 0.3459109 0.2043387 -0.9157463 -0.004237353 -2.50972e-4 -0.9999911 0.004386067 2.63787e-4 -0.9999904 -0.009443461 0.02060884 -0.9997431 0.006166577 -0.007704973 -0.9999514 0.01161873 0.01981753 -0.9997362 -8.21332e-4 6.78203e-4 -0.9999995 -0.001522302 3.82145e-4 -0.9999989 -0.00197792 -0.008974432 -0.9999579 -0.001045644 3.90056e-4 -0.9999995 -9.60747e-4 5.54696e-4 -0.9999995 -0.003144323 -0.004418373 -0.9999854 -0.01037895 0.01861327 -0.999773 0.001082658 6.25153e-4 -0.9999992 0.001135706 4.2362e-4 -0.9999993 2.39567e-4 -0.009971618 -0.9999504 0.01153916 -0.01969832 -0.9997394 0.002749562 0.003612935 -0.9999898 -0.007046937 0.005875587 -0.999958 9.59977e-4 7.92537e-4 -0.9999993 0.004927515 0.004294753 -0.9999787 -0.00821501 -0.01094949 -0.9999064 0.007582366 -0.008515954 -0.9999351 -0.004928112 -0.00429356 -0.9999787 0.01709419 0.01448619 -0.999749 -0.001303672 0.001504063 -0.999998 -0.003255426 -0.002893209 -0.9999906 -0.8710827 -0.07301062 -0.4856795 -0.4066462 -0.4486077 -0.795858 -0.4146667 -0.8464201 -0.3341025 0.03928029 -0.5416349 -0.8396956 0.5661358 -0.7593511 -0.3207433 0.50648 -0.4227942 -0.7514807 0.7034127 -0.01924324 -0.7105212 0.8710972 0.07301163 -0.4856534 0.4066597 0.4486017 -0.7958545 0.4146772 0.84643 -0.3340648 -0.03928411 0.5416428 -0.8396903 -0.5661422 0.7593597 -0.3207116 -0.5064879 0.4227941 -0.7514754 -0.7034209 0.01923745 -0.7105132 -0.9996067 0.02482515 0.01304894 -0.765419 0.6432804 0.01800155 -0.7048071 0.7090283 -0.02293694 -0.1729457 0.9849236 -0.003928124 -0.07632619 0.9964277 0.03614205 0.4801423 0.876179 -0.04211556 0.6729786 0.7375896 0.05533033 0.9913883 0.115931 -0.06090408 0.9996064 -0.02483475 0.01304548 0.7654139 -0.6432861 0.01801526 0.7047954 -0.7090397 -0.02294129 0.1729549 -0.984922 -0.003928065 0.07632976 -0.9964274 0.03614348 -0.4801445 -0.8761777 -0.04211962 -0.6729621 -0.737605 0.0553261 -0.9913892 -0.1159258 -0.06089907 0.6088438 -0.6014266 0.5172961 0.5887674 -0.5944103 0.5477495 0.1083681 -0.605153 0.7886991 -0.1805622 -0.8784021 0.442501 -0.2848511 -0.5211104 0.8045519 -0.871621 -0.3242312 0.3676292 -0.5629034 -0.06565052 0.8239113 -0.6088353 0.6014125 0.5173225 -0.5887988 0.5944288 0.5476956 -0.1083632 0.6051455 0.7887056 0.1805631 0.8784038 0.4424974 0.2848546 0.5211108 0.8045504 0.8716238 0.3242446 0.3676104 0.5628933 0.06564581 0.8239186 8.80673e-4 0.002109169 0.9999974 0.004262745 0 0.999991 -6.64857e-5 -0.001234471 0.9999992 -9.71854e-4 -0.001683294 0.9999982 6.56438e-5 0.001234471 0.9999992 9.72215e-4 0.00168389 0.9999982 7.62474e-4 -0.003361463 0.9999941 8.40907e-4 -0.001456499 0.9999987 -8.80205e-4 -0.00210905 0.9999974 -0.004262149 0 0.9999909 -7.62381e-4 0.003360986 0.9999941 -8.40789e-4 0.00145626 0.9999986 0.007609665 -0.01014983 -0.9999195 0.003633558 -0.008297979 -0.999959 -0.003342151 -0.01123982 -0.9999313 -0.003676295 -0.01024395 -0.9999408 -0.01348346 -0.007449269 -0.9998814 -0.009725153 3.58891e-4 -0.9999527 -0.01211124 0.003894448 -0.9999192 -0.006319522 0.008583247 -0.9999432 -0.005705416 0.008392632 -0.9999486 0.001523137 0.01400899 -0.9999008 0.00513947 0.009432792 -0.9999424 0.01082205 0.01004832 -0.9998911 0.01067316 -2.08183e-4 -0.9999431 0.01326322 -0.002253711 -0.9999095 -0.03284657 -0.00768131 0.9994309 -0.02457499 0.006368875 0.9996778 -0.03222692 0.003222048 0.9994754 0.02557098 -0.01230746 0.9995973 0.02029925 -0.01352196 0.9997025 0.01888597 -0.02807182 0.9994275 0.004054009 -0.03708297 0.999304 -0.008242428 -0.02800416 0.9995738 -0.01146006 -0.02916419 0.999509 -0.02121275 -0.01834595 0.9996067 -0.02189016 -0.02233934 0.9995108 -0.02110576 0.01915228 0.9995938 -0.02630233 0.01935082 0.9994668 -0.01291137 0.03981137 0.9991238 0.01018273 0.02845114 0.9995434 0.009586453 0.02819436 0.9995566 0.01478654 0.01878857 0.9997141 0.02177959 0.01883643 0.9995853 0.03091847 0.00603491 0.9995038 0.0257216 -8.96216e-5 0.9996692 0.399028 0.9168835 0.01006448 0.4944958 0.8691793 0.001151323 -0.1062851 0.9943346 0.001520693 -0.1084396 0.9941016 0.001697719 -0.6466112 0.7628192 9.77418e-4 -0.7111653 0.7029805 0.007896125 -0.974187 0.2257012 -0.004342317 -0.9996309 -0.02513933 0.01030313 -0.9249932 -0.3799347 -0.006113827 -0.7566031 -0.653811 0.009116709 -0.2264285 -0.974002 0.007102489 -0.4627565 -0.8864747 -0.004383265 0.0155248 -0.9998766 -0.00242871 0.4356696 -0.9000952 0.004574298 0.4065702 -0.9136174 0.001963734 0.8538742 -0.5204792 6.76406e-4 0.8929974 -0.4500073 0.007004976 0.9977253 0.06722474 -0.005027174 0.941675 0.3363559 0.01063257 0.8342244 0.5514242 -0.001121342 0.003244876 -0.002117335 0.9999925 -0.006142318 0.003859102 0.9999737 0.005116999 0.001764833 0.9999853 -0.001859068 -0.001637041 0.999997 0.9813295 0.1915543 -0.01730811 0.980476 0.1961302 -0.01413732 0.9009945 -0.4336485 0.01257133 0.885214 -0.4651239 -0.007493257 0.5582019 -0.829677 0.006841361 0.5338221 -0.8455731 -0.006341636 0.1086827 -0.9940531 0.006837368 0.07970416 -0.9967984 -0.006344974 -0.3657209 -0.9306995 0.006837248 -0.3926554 -0.9196639 -0.006347775 -0.7563494 -0.6541322 0.006833016 -0.7750715 -0.6318417 -0.006343841 -0.9737038 -0.2277153 0.006837308 -0.979922 -0.1992802 -0.006345331 -0.9679971 0.2508682 0.006833255 -0.9602871 0.2789416 -0.006346464 -0.740527 0.6719919 0.006837129 -0.7206675 0.6932519 -0.006347358 -0.3084823 0.9511975 0.007881045 -0.3159305 0.9487023 0.01232653 0.1610985 0.9865455 -0.02784705 0.3216719 0.9460544 0.03883868 0.6353779 0.7712768 -0.03777611 0.7560507 0.6538721 0.02895945 -0.4356634 -0.3551654 -0.8270761 -0.3621097 -0.8481195 -0.3867426 -0.01441103 -0.5613728 -0.8274376 0.05761075 -0.7204801 -0.6910785 0.3863849 -0.5824453 -0.7151674 0.3484278 -0.5519195 -0.7576166 0.7462817 -0.393214 -0.5370721 0.5050433 -0.1596077 -0.848208 0.9097121 0.1819695 -0.3732439 0.4334887 0.2140613 -0.8753657 0.6100962 0.7412793 -0.2797995 0.1223037 0.5232582 -0.8433521 0.1051781 0.6441252 -0.7576546 -0.2607766 0.7830781 -0.5646098 -0.2754697 0.4209104 -0.8642634 -0.6037041 0.5807417 -0.5461507 -0.7541634 0.2190669 -0.6190696 -0.5015225 0.05468076 -0.8634149 -0.8305588 -0.1688939 -0.5307041 -0.4547942 -0.383586 -0.8037562 0.800935 0.293749 0.521742 0.5359087 0.01452654 0.844151 0.8276132 -0.4216701 0.3704735 0.2739101 -0.4870518 0.8293092 0.2718089 -0.6192222 0.7366708 -0.1812519 -0.7889174 0.5871604 -0.271851 -0.452984 0.8490598 -0.6292211 -0.5442588 0.5548543 -0.7594975 -0.02617871 0.6499834 -0.5351983 0.06211924 0.8424393 -0.6112915 0.6118057 0.5020126 -0.2057789 0.4851073 0.8498976 -0.08866935 0.8120731 0.5767798 0.3852441 0.6717821 0.6326894 0.3674843 0.4417656 0.8184123 0.9831556 0.02464675 -0.1811015 0.5120037 -0.8418903 -0.1705083 -0.4732275 -0.8418986 -0.2593508 -0.9830134 -0.02397251 -0.1819617 -0.5124224 0.8394875 -0.1807879 0.4707197 0.8639612 -0.178869 -0.2654229 -0.4540041 -0.8505475 0.1866863 -0.4576976 -0.8692877 0.3383023 -0.3603299 -0.8693181 0.5245893 0.05635416 -0.8494882 0.2450274 0.4747112 -0.8453466 -0.3149387 0.4376085 -0.842207 -0.5405803 -0.002578437 -0.8412885 0.9990801 0.002547621 -0.04280692 0.9979171 0.0644921 -0.001521229 0.9985722 0.05317127 0.005151271 0.4980477 -0.8671496 -1.00978e-4 0.5370926 -0.8429719 -0.0304982 0.5032113 -0.8620453 -0.06046891 0.5809478 -0.8139409 -5.057e-5 -0.4569517 -0.8893721 -0.01457589 -0.523123 -0.851544 -0.0348584 -0.4744163 -0.8802994 -0.001538157 -0.9986617 -0.05167979 -0.00203216 -0.9996631 8.66229e-4 -0.02594393 -0.9990074 -0.04446107 0.002770483 -0.5444 0.8388198 0.003209471 -0.499913 0.865451 -0.03288644 -0.5451778 0.8383165 0.002640366 0.4544321 0.8907796 0.001850306 0.4971958 0.8665423 -0.04359883 0.4454777 0.8952816 -0.004528462 0.102118 -0.1021522 -0.9895135 0.6714691 0.7410048 0.006418645 -0.1229014 -0.9057788 0.4055367 -0.3131959 -0.6100782 0.7278138 -0.7005491 -0.6454315 0.3043835 -0.5973096 -0.248801 0.7624431 -0.9406263 0.02061307 0.3388175 0.4112524 0.6219356 0.666384 0.5885565 0.5303816 0.6101611 0.004217088 0.8676252 0.497201 -0.07619571 0.7205771 0.6891756 -0.5398744 0.611377 0.5785792 -0.5896583 0.6384104 0.4947072 -0.5778823 0.1998627 0.7912692 0.007028043 -0.7576053 0.6526752 0.3228252 -0.6695256 0.6689689 0.5428953 -0.7642397 0.3481413 0.6048539 -0.3667943 0.7068336 0.7530691 -0.3456065 0.5598601 0.8108302 0.0709421 0.5809662 0.7781478 0.04712706 0.6263105 -0.7058104 -0.707161 -0.04189372 -0.6431426 -0.761142 0.08384776 -0.3001502 -0.9484006 -0.1022071 -0.1279593 -0.9864972 0.102225 0.2593405 -0.9622539 -0.08252233 0.3387167 -0.9399793 0.04135113 0.7643466 -0.6431318 -0.0464304 0.7963792 -0.6030128 0.04643338 0.9969731 -0.05795955 -0.05182147 0.9978799 -0.003090441 0.06501084 0.7526045 0.6546289 -0.07104635 0.7132381 0.6973106 0.07106024 0.1087633 0.9922994 -0.05926614 0.06067031 0.9977344 0.02907472 -0.3919476 0.919641 -0.02524954 -0.4634838 0.8807986 0.09683382 -0.8328783 0.5277386 -0.1667504 -0.9166011 0.3633713 0.1667451 -0.9781086 -0.1747013 -0.1130622 -0.9653258 -0.2581697 0.03866267 -0.9415152 -0.3368541 -0.008859694 -0.9997944 -0.01746851 0.01030731 -0.9996863 0.01851201 -0.0168789 -0.9120109 0.4098187 0.01687765 -0.8967595 0.4423984 -0.0103048 -0.689996 0.7237399 0.01030355 -0.6866894 0.7269187 0.006850898 -0.4133403 0.9102496 -0.02440267 -0.3160336 0.9481031 0.03497445 -0.06407362 0.9973322 -0.03497439 0.04032409 0.9988886 0.02440601 0.3856236 0.9226104 -0.009205281 0.3668466 0.9302359 0.009202241 0.6675481 0.7441665 -0.02440696 0.741302 0.6702601 0.03496903 0.8875927 0.4592999 -0.03496831 0.9309535 0.3643211 0.02440816 0.999805 0.01747173 -0.0092054 0.9997977 0.006735563 -0.01895457 0.9120119 -0.4098163 0.01687765 0.8967573 -0.4424028 -0.01030606 0.7077737 -0.7063838 0.008860766 0.6866816 -0.7269044 -0.008857965 0.4400621 -0.8979237 0.008860886 0.4134486 -0.9104843 -0.008864581 0.1246595 -0.9921602 0.008853375 0.09540998 -0.9953987 -0.008854329 -0.2042459 -0.9788796 0.008853733 -0.2329645 -0.9724449 -0.008858323 -0.511017 -0.8595249 0.008860766 -0.5360883 -0.8441154 -0.008860826 -0.7624203 -0.6470217 0.008857309 -0.7811249 -0.6243121 -0.008856534 -0.9311944 -0.3644154 0.008860826 -0.8478152 -0.5300316 0.01661962 -0.8224443 -0.5681948 -0.0272091 -0.3788602 -0.9248254 0.03410172 -0.3255761 -0.9445467 -0.04279994 0.3989589 -0.9157736 0.04680395 0.4195469 -0.9076487 0.01242893 0.9047949 -0.4222627 -0.05514043 0.9250581 -0.3796906 0.01012706 0.988276 0.1391122 0.06291788 0.9556732 0.2840842 -0.07736313 0.7450336 0.6648045 0.05440557 0.686333 0.7267785 -0.02720868 0.2436385 0.9694843 0.0272153 0.1216843 0.9884249 -0.0906049 -0.2409278 0.9653689 0.1000831 -0.5651 0.8205222 -0.08605462 -0.7588276 0.6429956 0.1036218 -0.8999805 0.4265934 -0.08973991 -0.9975248 -0.02933418 0.06390541 -0.9933977 -0.1135123 -0.01661628 -0.8483063 -0.5293834 0.01139008 -0.8198077 -0.5725259 -0.01139003 -0.3870133 -0.9219786 0.01327723 -0.327868 -0.9444733 -0.02174544 0.3515053 -0.9359334 0.02174472 0.4100596 -0.9119623 -0.01327049 0.8339415 -0.5517354 0.0113902 0.8613514 -0.5078818 -0.0113942 0.9994326 0.03096085 0.01327276 0.9953258 0.0940957 -0.02174109 0.7053332 0.7085427 0.0217384 0.6592003 0.7518503 -0.01327687 0.1554506 0.987778 0.0113945 0.104173 0.9944941 -0.01138269 -0.4032539 0.9150173 0.01139396 -0.4500113 0.8929502 -0.01139414 -0.8339451 0.5517299 0.01139026 -0.8613486 0.5078866 -0.01139396 -0.9998468 0.01329272 0.01138973 -0.9991966 -0.03842604 -0.0113902 0.01586627 0.04359525 0.9989233 -0.02750992 0.06600111 0.9974403 -0.05295246 0.01391297 0.9985001 -0.04378002 0.01904904 0.9988596 -0.03030592 -0.02612733 0.9991992 -0.01362508 -0.005203604 0.9998937 -0.006750643 -0.01231414 0.9999015 -0.006798744 -0.01113563 0.9999149 0.006045937 -0.0127809 0.9999001 0.006386101 -0.01051443 0.9999244 0.01484429 -0.005456745 0.999875 0.009968519 2.21164e-4 0.9999503 0.01167708 0.005619287 0.9999161 0.02980506 -0.003745496 0.9995487 0.0192117 0.04352575 0.9988676 0.01865333 -0.01543289 -0.999707 0.02097272 -0.02261984 -0.9995241 0.04011505 0.002524316 -0.9991919 0.01454275 0.0172103 -0.9997462 0.01386159 0.01354479 -0.9998122 0.004066646 0.01583927 -0.9998663 0.01199507 0.02254307 -0.9996739 -0.009103596 0.03546214 -0.9993296 -0.02334427 0.02485865 -0.9994184 -0.02289527 0.01849079 -0.9995669 -0.03416848 0.01110202 -0.9993544 -0.02926629 -0.005582749 -0.9995561 -0.03111022 -0.004677772 -0.9995051 -0.02478212 -0.02050173 -0.9994826 0.004755139 -0.02223861 -0.9997414 -2.05431e-4 -5.18695e-4 -0.9999999 8.85743e-5 -5.46092e-4 -1 -0.005530416 -0.01783704 -0.9998256 -0.4665051 -0.8845067 -0.004569828 -0.8340148 -0.5517417 6.93687e-4 -0.4790696 -0.8777697 -0.003598332 -0.9205633 -0.3905401 -0.006456255 -0.9866254 -0.1629904 0.002135455 -0.9544032 0.298488 -0.004438281 -0.9664686 0.2567819 -0.001261174 -0.611735 0.7910621 -0.001070916 -0.6066957 0.7949328 -0.001531124 -0.02760297 0.9996187 -8.14482e-4 0.003371417 0.9999896 -0.003067255 0.616541 0.7873207 -0.001838445 0.5959023 0.8030486 -0.003670215 0.9570111 0.2900404 -0.002548277 0.9263957 0.376445 -0.008961677 0.9990973 -0.04240089 0.002590835 0.9191657 -0.3937835 -0.008303284 0.848066 -0.5298889 0.001362025 0.4867718 -0.8735247 0.002790808 0.2486093 -0.9685649 -0.008691728 0.08733278 -0.9961793 5.45933e-5 0.001128017 0.005189836 -0.9999859 0.00234425 -0.001705229 -0.9999958 0.001203954 0.00494486 -0.9999871 -8.38293e-4 -0.005367517 -0.9999853 -0.3677491 -0.9288294 -0.04512941 -0.7165086 -0.6962368 0.04324209 -0.7705137 -0.6374232 -6.86006e-4 -0.9819695 -0.1873304 -0.02536565 -0.9984154 -0.01107639 0.05517297 -0.9500939 0.3087055 -0.04497522 -0.7363622 0.6753849 0.04032373 -0.6845511 0.7289646 -6.83775e-4 -0.2486156 0.9682701 -0.02536451 -0.07144314 0.9958593 0.056216 0.2484465 0.9676095 -0.04479163 0.599704 0.7996143 0.03118258 0.7149516 0.69827 -0.03554344 0.9393606 0.3395392 0.04811483 0.9954358 0.06262087 -0.07201534 0.9345394 -0.3491237 0.06891119 0.7685071 -0.6357759 -0.07201445 0.4802204 -0.8754307 0.05486059 0.1679044 -0.984804 -0.04437762 -0.08758676 -0.9953281 0.0406264 -0.0670979 0.9531692 0.2949008 -0.166589 0.4221191 0.8911024 -0.7324658 0.671 0.1151217 -0.4550678 0.1319367 0.8806282 -0.9470679 -0.008437752 0.3209226 -0.4575436 -0.2406901 0.8559919 -0.6663166 -0.6485551 0.3679653 -0.2194361 -0.4456393 0.8679018 -0.08403682 -0.9575226 0.2758409 0.2115521 -0.4847517 0.8486822 0.336755 -0.6152021 0.7128272 0.6452541 -0.2699224 0.714695 0.7474237 -0.2792207 0.6028214 0.5412341 0.1290969 0.830903 0.7617469 0.2785296 0.584947 0.4993042 0.6641386 0.5564308 0.2174602 0.4323574 0.8750876 0.2358281 -0.9030759 -0.3589417 0.4855198 -0.3120071 -0.816653 0.7150451 -0.3121012 -0.6255425 0.645538 0.1782802 -0.7426285 0.66723 0.1988319 -0.7178232 0.4812707 0.6451394 -0.5934423 0.1596501 0.4852685 -0.8596665 0.001090705 0.8288793 -0.5594265 -0.4719561 0.6184637 -0.6282994 -0.4140581 0.3753768 -0.8292456 -0.7913764 0.2103316 -0.574007 -0.5523809 -0.0888459 -0.8288438 -0.7648744 -0.3274433 -0.5547507 -0.363543 -0.6839603 -0.6324831 -0.1011208 -0.4652426 -0.8793885 0.5107138 -0.8409385 0.1788681 0.98363 0.02182388 0.1788743 -0.4729202 -0.8627583 0.1788708 0.2763246 0.4573787 0.8452511 0.5338369 0.02241086 0.8452905 0.2763648 -0.4526765 0.8477657 -0.255145 -0.4655382 0.8474522 -0.5360429 0.006730318 0.844164 -0.2873417 0.4490936 0.8460198 0.4990423 -0.8662022 0.02550303 0.5210326 -0.8534936 0.00858885 0.5404618 -0.8410633 0.0226674 0.999922 -0.002896308 0.01214981 0.9999151 0.01293611 0.001556932 0.9986129 0.04751425 0.0226866 0.4896683 0.871517 0.02613782 0.4880542 0.8723579 0.0281952 -0.3791996 0.9229888 -0.06556928 -0.6142338 0.7868041 -0.06046599 -0.5094975 0.8602215 0.02076882 -0.9997704 -0.01397007 0.01625376 -0.9997705 -0.01401013 0.01621025 -0.5006321 -0.865284 0.02551841 -0.4788056 -0.8778774 0.008759915 -0.4582232 -0.888534 0.02321451 0.07659423 0.982732 -0.1684377 -0.2789286 -0.3369247 -0.8992668 0.0932151 -0.2639789 -0.9600137 -0.3255875 -0.5813038 -0.7457069 -0.01656764 -0.595269 -0.8033558 0.2405519 -0.9262053 -0.2903078 -0.594877 -0.7771545 -0.2053104 -0.5592069 -0.4636422 -0.687258 -0.8949376 -0.1013936 -0.4345182 -0.8203652 -0.1384075 -0.5548371 -0.6392883 0.1987839 -0.7428293 -0.7254355 0.6348451 -0.2659231 -0.4380568 0.5655909 -0.6987226 0.03017318 0.8759411 -0.4814738 0.2475421 0.3814735 -0.8906183 0.890417 0.3564081 -0.2830739 0.8923498 0.356106 -0.2773092 0.6305606 0.05389887 -0.7742662 0.5366208 -0.2498918 -0.8059729 0.7894088 -0.5282814 -0.3126543 0.3611448 -0.4392195 -0.8225939 -0.008204758 -0.004166364 0.9999577 -0.008796095 -0.005773007 0.9999447 -0.003277659 -0.00892961 0.9999548 -0.003431379 -0.009026825 0.9999534 0.003813207 -0.01255935 0.9999139 0.008568286 -0.006584525 0.9999417 0.009316205 -0.006597697 0.9999349 0.01183509 1.56732e-4 0.99993 0.008947074 0.002604186 0.9999567 0.009961962 0.007707417 0.9999207 0.001928508 0.01211285 0.9999248 0.002390921 0.01261752 0.9999176 -0.008297681 0.01166599 0.9998975 -0.007776618 0.006072342 0.9999514 -0.01297175 0.001740992 0.9999144 0.02673041 -0.01268559 -0.9995622 0.009025275 -0.01089125 -0.9999001 0.006277859 -0.02811324 -0.9995851 0.03859835 -0.007821559 -0.9992242 -0.03592932 -1.4946e-4 -0.9993544 -0.02765023 -0.007376134 -0.9995905 -0.02724975 -0.01611834 -0.9994988 -0.01877909 -0.01899272 -0.9996433 -0.01508873 -0.02657735 -0.9995329 -0.01009541 -0.02503633 -0.9996356 0.004586279 -0.03650552 -0.999323 0.01813924 0.01705819 -0.9996899 0.01547753 0.008205056 -0.9998466 0.03094452 0.00331366 -0.9995157 0.01611179 0.0283789 -0.9994674 0.01849877 0.02922946 -0.9994016 -0.007137238 0.04352307 -0.999027 -0.02424389 0.008401215 -0.9996709 -0.0133357 0.01085644 -0.9998522 -0.01861155 0.02678304 -0.999468 0.1679874 0.9857634 -0.00713253 0.3584849 0.9335194 0.005491375 0.7136661 0.7004481 -0.007292747 0.8184833 0.5745289 0.001323819 0.9942528 0.1069066 -0.005691289 0.9956095 0.09335982 -0.006770312 0.9062702 -0.4226728 0.004708468 0.7574809 -0.6527551 -0.01155632 0.457533 -0.8891776 0.005182683 0.1712052 -0.9851932 -0.009117245 -0.4418501 -0.8970519 -0.008146882 -0.1786605 -0.9839047 0.003475129 -0.6477066 -0.7618863 0.002381086 -0.9073101 -0.4204375 -0.004571557 -0.8933655 -0.4493265 -0.00196439 -0.9917705 0.1280277 -7.02501e-4 -0.9760244 0.2175184 -0.007887244 -0.7532151 0.6577677 0.002948522 -0.5155333 0.8568041 -0.01059556 -0.3176471 0.9482049 0.002814829 0.005957603 -0.002504348 -0.9999791 -0.002129375 0.006305992 -0.999978 -3.94757e-4 -0.002450048 -0.999997 -0.002463936 -2.19903e-4 -0.999997 -0.6335632 0.7718977 0.05264645 -0.7744429 0.6304548 -0.05258101 -0.9786714 0.2006515 0.04405975 -0.9992367 -0.004158675 -0.03884571 -0.948345 -0.3159549 0.02853715 -0.8603433 -0.5088877 -0.02903068 -0.6928846 -0.7204836 0.0285387 -0.4933426 -0.8689616 -0.03897202 -0.2786212 -0.9596802 0.0372036 0.1246153 -0.9918115 -0.02794796 0.1994129 -0.9798951 0.006349742 0.6380191 -0.7699803 -0.007884383 0.6653649 -0.7464136 0.01251059 0.9799821 -0.1985878 -0.01407051 0.9873625 -0.1578467 0.01413565 0.8834484 0.4683601 -0.01256966 0.8664523 0.4992036 0.007497966 0.4937011 0.869596 -0.007884383 0.5005007 0.8656485 -0.01232159 -0.003024756 0.9995053 0.03130865 -0.1616109 0.9854526 -0.05258435 0.183898 -0.9036539 0.3867702 -0.1145467 -0.5250089 0.8433533 -0.1819713 -0.626794 0.7576383 -0.5721185 -0.5949066 0.5645942 -0.4677695 -0.3368266 0.8171533 -0.7787404 -0.2594497 0.5711824 -0.5781223 -0.03329485 0.8152706 -0.8831309 0.180327 0.4330844 -0.4200333 0.3009139 0.8561676 -0.5985135 0.729194 0.3317496 -0.1394277 0.5209399 0.8421293 -0.001771152 0.8672043 0.4979495 0.1738791 0.5523213 0.8152958 0.4242243 0.7337328 0.5307258 0.5070279 0.3370816 0.7932835 0.6358383 0.3677586 0.6785745 0.6820756 -0.09493076 0.7250938 0.7336902 -0.1172897 0.6692847 0.4275889 -0.5428729 0.7228118 0.3598535 -0.4059587 0.8400613 -0.4220486 0.7163732 -0.5555938 -0.3635579 0.3548662 -0.8613337 -0.9074903 0.1980273 -0.3704681 -0.5497432 -0.1834293 -0.8149455 -0.6549937 -0.3329702 -0.6783171 -0.2725536 -0.6504004 -0.7090091 -0.2706286 -0.5429788 -0.7949429 0.1521233 -0.8772787 -0.4552371 0.3513435 -0.4292184 -0.8320633 0.5697868 -0.5003618 -0.6519059 0.6765099 0.1165915 -0.7271457 0.5728863 0.06260991 -0.8172401 0.6354603 0.623595 -0.4553235 0.1422225 0.5420895 -0.8281979 0.1095221 0.6610989 -0.7422623 -0.7450982 0.6419087 0.1810578 -0.9294929 -0.3270379 0.1705554 -0.1671954 -0.9512221 0.2592728 0.7453815 -0.641308 0.1820179 0.928307 0.3249151 0.1807665 0.1831156 0.9666987 0.17878 -0.08224666 -0.5194292 0.8505463 -0.4344071 -0.2358755 0.8692831 -0.4900282 -0.06449681 0.8693174 -0.3701967 0.3759335 0.8494871 0.1111515 0.5225355 0.8453415 0.5209043 0.1390763 0.8422093 0.4166359 -0.3444569 0.8412871 -0.7714151 0.6348907 0.042809 -0.7312676 0.682089 0.001519978 -0.7389459 0.6737451 -0.005145251 -0.9347065 -0.3554207 1.13604e-4 -0.9495996 -0.3119788 0.03049468 -0.9354657 -0.3482086 0.06045526 -0.9651408 -0.2617314 5.89979e-5 -0.2098526 -0.9776245 0.01456815 -0.1347033 -0.9902725 0.03486466 -0.1906021 -0.9816663 0.001547753 0.7399764 -0.6726298 0.002032101 0.7740147 -0.6326364 0.02593016 0.7448017 -0.6672802 -0.002770185 0.9526211 0.3041427 -0.00321567 0.9350699 0.352934 0.03289115 0.9529061 0.3032543 -0.00263673 0.2127071 0.9771143 -0.001850247 0.1642866 0.9854496 0.04358083 0.222491 0.9749242 0.004533231 -0.1947123 -0.818843 -0.5399844 0.2445195 -0.5484886 -0.7996065 0.6040972 -0.3317726 -0.7245644 -0.2212401 0.6556966 -0.7218828 -0.1847767 -0.8054915 -0.563064 0.4058826 -0.7030348 -0.5839533 -0.3085444 0.7599061 -0.572139 0.2495202 0.7149162 -0.6531727 0.3008728 0.7669619 -0.5667849 0.3998841 0.3689889 -0.8390114 0.7315825 0.4533448 -0.5091814 0.7076453 0.05852168 -0.7041402 0.8595865 0.1391308 -0.4916847 0.6121478 -0.3424485 -0.7127441 -0.3932258 -0.5600385 -0.7291985 -0.6400861 -0.5679032 -0.5174708 -0.636322 -0.296195 -0.7122941 -0.8880149 -0.1238162 -0.4428308 -0.6160036 0.1382819 -0.7755113 -0.7735776 0.3924059 -0.4975896 -0.4255144 0.3758133 -0.8232265 0.03537195 0.002170324 -0.999372 0.03326523 -0.003437221 -0.9994407 -0.005733132 -0.007956743 -0.999952 0.03535109 0.002210915 -0.9993726 0.03708505 0.02513653 -0.998996 -0.01510047 0.03510129 -0.9992697 -0.03886067 0.01375693 -0.99915 -0.02076148 0.002447247 -0.9997816 -0.003205657 -0.01882946 -0.9998176 0.005337715 0.007154583 -0.9999602 -0.01950436 0.01087576 -0.9997507 -0.004290223 0.009085297 -0.9999495 0.001970112 0.01406621 -0.9998992 0.03102898 2.31966e-4 -0.9995185 0.03101491 1.10077e-4 -0.9995189 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.5656991 0.8245446 0.01052546 0.4955195 0.8685968 -2.31999e-4 0.04622405 0.9988216 0.01479673 -0.06394457 0.9979495 0.002803921 -0.3403077 0.9402465 0.01128202 -0.5729315 0.8195601 -0.008424639 -0.7985613 0.6017711 0.01309251 -0.9179896 0.396591 -0.003277719 -0.9953003 0.09491151 0.01921284 -0.9894256 -0.1450403 5.80934e-4 -0.9305049 -0.3659844 0.0146985 -0.7655239 -0.6433544 -0.008272588 -0.537069 -0.8434219 0.01401937 -0.3131962 -0.949687 -0.001656651 -0.06508743 -0.9977186 0.01792424 0.232625 -0.9725631 -0.002577543 0.5198399 -0.8540319 0.0198974 0.1088714 -0.9921074 0.0622105 0.8479715 -0.5300142 -0.005408048 0.9578322 -0.2867783 0.01777106 0.9979069 -0.06466829 1.11814e-4 0.9559031 0.293353 0.01390844 0.9165966 0.3998132 -3.13295e-4 0.02638244 -0.01617193 0.9995211 0.01885086 -0.03232705 0.9992997 0.01517176 0.009299159 0.9998418 0.02413666 -0.01088094 0.9996495 0.01751863 -0.02079647 0.9996303 -0.01110768 0.02756732 0.9995583 -0.06544452 0.06343609 0.9958378 0.8176888 0.5756235 -0.006532728 0.7423275 0.6675178 0.05805277 0.3858826 0.9212241 -0.04940485 0.09697532 0.9945166 0.03915107 -0.1292527 0.9912356 -0.02731257 -0.4005693 0.9162124 0.009949266 -0.4510927 0.8924302 -0.009159982 -0.7871293 0.6167204 -0.00913757 -0.8333094 0.5520021 0.0298227 -0.9973283 0.07008397 -0.02060818 -0.9978911 -0.05796939 0.0292043 -0.9311431 -0.3605123 -0.05480629 -0.6967819 -0.7155596 0.04969441 -0.5967994 -0.8023381 -0.009172081 -0.2246106 -0.9744055 -0.009174227 -0.1627353 -0.9864889 0.01889675 0.339012 -0.9407711 -0.004549622 0.3409262 -0.940072 -0.005841076 0.8321745 -0.5544824 -0.005903184 0.8507828 -0.5254189 0.01017659 0.9845648 -0.1727416 -0.02815192 0.9997923 -0.008823275 0.01836836 0.974917 0.2175651 -0.04692959 -0.356382 0.09133291 -0.9298658 -0.7734144 0.6076349 -0.1805821 -0.3313603 0.5039799 -0.7976245 -0.01181924 0.5129753 -0.858322 0.3837171 0.9155775 -0.1203287 0.2643161 0.2740552 -0.9246788 0.2264217 -0.2252287 -0.9476315 0.326168 -0.8958547 0.3017598 -0.08430355 -0.4258403 -0.9008624 -0.1183679 -0.5027802 -0.8562718 -0.5789898 -0.779488 -0.2391014 -0.3723673 -0.2143549 -0.902992 -0.3171545 -0.2953255 0.9012191 -0.2824032 0.3353016 0.8987889 0.9764677 -0.1150993 -0.1823815 0.3885537 -0.9031978 -0.1823734 -0.5895258 -0.7883919 -0.1757775 -0.9767495 0.1166538 -0.1798676 -0.3879829 0.9028397 -0.1853372 0.5879017 0.7880769 -0.1825007 -0.316504 -0.4415683 -0.8395492 -0.5343281 0.01402384 -0.8451609 0.2093237 -0.496235 -0.8425762 0.5371391 -0.04255414 -0.8424196 0.3125969 0.4423873 -0.8405812 -0.2192525 0.4914324 -0.8428658 0.9958195 -0.09092432 -0.008743822 0.989426 -0.1412008 -0.0331428 0.9951879 -0.09789752 -0.004143536 0.4194135 -0.9077689 -0.006929636 0.3716253 -0.9279819 -0.02728223 0.4104551 -0.9118808 -3.36302e-4 -0.5775553 -0.8163514 -6.4654e-4 -0.6177328 -0.7858826 -0.0281952 -0.5810315 -0.8138785 0.002116084 -0.9960751 0.07738268 -0.04296934 -0.9871875 0.1540154 0.0417152 -0.9958634 0.09075379 0.004453599 -0.4204249 0.9073273 -7.10119e-5 -0.4451937 0.895252 -0.01806968 -0.3760067 0.9241154 -0.06804144 0.5757518 0.8176236 -0.001303732 0.6167762 0.7863708 -0.03476119 0.5763036 0.8172354 -8.64387e-4 0.7052695 -0.3009678 0.6418827 0.2186229 -0.2218635 0.9502529 0.3455151 -0.6636261 0.6634905 0.08425265 -0.4378699 0.8950818 0.1254227 -0.522337 0.843465 -0.09389591 -0.7656479 0.6363701 -0.150404 -0.3128674 0.9378128 -0.2085204 -0.6336817 0.7449609 -0.4529219 -0.5118815 0.7299584 -0.3568868 -0.3006345 0.8844494 -0.6654515 -0.3815865 0.6415343 -0.5504548 -0.08378249 0.8306505 -0.5399944 -0.07969111 0.8378876 -0.7571387 0.1681534 0.6312413 -0.4321321 0.1860821 0.8824031 -0.6351218 0.4196873 0.6484466 -0.3413748 0.4452252 0.827791 -0.2820646 0.3991985 0.872399 -0.2807085 0.6903687 0.6667788 -0.03275674 0.5578385 0.8293029 -0.0344631 0.5635823 0.8253408 0.2316535 0.7312649 0.6415515 0.4354087 0.1519914 0.8873094 0.5773343 0.2429694 0.7795199 0.6476063 0.5083126 0.5676482 0.2027443 0.2764949 0.9393857 0.3000658 0.5341035 0.7903758 0.6210638 -0.02097028 0.7834796 0.5586692 -0.03427177 0.8286823 0.4454221 -0.2866624 -0.8481886 0.2466464 -0.4640966 -0.8507525 0.5242327 0.01981544 -0.8513446 -0.4331446 -0.3086705 -0.8468225 -0.1125992 -0.5255432 -0.8432828 -0.4269894 0.322243 -0.8448904 -0.05985885 0.5430829 -0.8375428 -0.5268701 -0.008267879 -0.8499057 0.4144018 0.3533899 -0.8386816 0.5176055 -0.1371467 -0.8445563 0.2812535 -0.4570631 -0.8437949 -0.08482891 -0.5219668 -0.8487372 -0.3312067 -0.4100255 -0.8498126 -0.5185873 -0.1193081 -0.8466598 -0.4462383 0.3073559 -0.8404784 -0.07781749 0.5347229 -0.8414369 0.470224 0.2444357 -0.8480217 0.2845605 0.4426497 -0.850345 0.4433537 -0.3061916 -0.8424276 -0.4997693 -0.165611 -0.8501786 -0.2992789 -0.4424671 -0.8453727 0.08949798 -0.5309224 -0.8426811 -0.5109484 0.1483367 -0.8467161 -0.2811358 0.4571971 -0.8437615 0.5208848 0.1164941 -0.8456407 0.3353124 0.4077863 -0.8492797 0.08852618 0.5205826 -0.8492096 0.4269939 -0.3222452 -0.8448871 0.0895673 -0.5291445 -0.8437914 0.5268687 0.008253216 -0.8499067 -0.4628547 -0.2534714 -0.8494222 -0.2741858 -0.4521781 -0.8487386 -0.5221835 0.1130554 -0.8453065 0.4381241 0.2962078 -0.8487098 -0.2954697 0.4524728 -0.8414072 0.1288643 0.5245192 -0.8415901 -0.5119522 -0.1988484 -0.8356819 -0.4079383 -0.1025882 -0.9072278 -0.9192618 -0.1885282 -0.3455648 -0.8943328 -0.1956948 -0.4023336 -0.7913438 -0.1560911 -0.5911097 -0.3580356 0.01208287 -0.9336298 -0.8313227 -0.007888436 -0.5557342 -0.9365634 -0.06146234 -0.3450672 -0.7266842 -0.06621843 -0.6837729 -0.481909 -0.04097926 -0.8752626 -0.1294172 -0.01495981 -0.9914774 0.77077 -0.636864 0.01782792 0.999553 0.02799302 -0.01049935 0.8467196 -0.5320297 -0.003251135 0.4609889 -0.8873518 -0.009808421 0.1079128 -0.9940509 0.01475805 -0.207714 -0.9779965 -0.01943796 -0.5810339 -0.8137052 0.01683598 -0.8122759 -0.583089 -0.01466852 -0.9764966 -0.2150201 0.01486134 -0.9998487 -0.01407819 -0.01022619 -0.7970137 0.6039415 0.004902899 -0.8035237 0.5952668 0.002680361 -0.109702 0.9939573 -0.003793954 -0.1353654 0.9907494 -0.009580373 0.5810439 0.8137151 0.01599997 0.7591823 0.6505468 -0.02076512 0.9746152 0.2234338 0.01424151 0.9700511 -0.2428126 0.00655806 -0.2885764 -0.9573163 0.01641136 -0.8895758 -0.4564214 0.01828342 0.9649994 -0.2622395 0.002591967 0.5240751 -0.8516656 -0.003368616 0.4966577 -0.8679431 0.002455949 -0.1544117 -0.9880024 -0.002916216 -0.6355992 -0.7719421 -0.01091402 -0.9742558 -0.2250775 -0.01287907 0.2589675 0.9656907 0.01942402 0.5354512 0.8445011 -0.01049149 0.8532841 0.5213935 0.007432162 -0.9569303 0.2897824 0.01762336 -0.8239805 0.566203 -0.02169317 -0.4965744 0.86781 0.01788032 -0.1441866 0.9893237 -0.02118968 0.8863346 0.4630399 -0.002249121 0.9089576 -0.4159196 0.02841097 0.1567751 -0.987623 0.004747331 -0.5895345 -0.8077337 -0.003952443 -0.9655841 -0.2600375 0.005290091 0.815573 -0.5785949 -0.008284747 0.1700804 -0.9854283 0.0019176 -0.5618944 -0.8272057 0.002374351 -0.9487752 -0.3159409 -0.00264734 -0.4846282 0.8747069 0.004837453 0.1605678 0.987019 -0.003424048 0.2988424 0.9541737 0.01568043 0.88569 0.4639386 0.01772069 0.9735319 0.2281424 -0.01366591 -0.9598777 0.2803716 -0.005147635 -0.9452185 0.3264319 0.002070069 -0.5231416 0.8522391 -0.003380894 0.6379101 0.7700306 -0.01112163 0.9998492 0.01404476 -0.0102272 0.7970072 -0.60395 0.004902899 0.8035317 -0.595256 0.002683222 0.1668979 -0.9859684 -0.003371834 0.1353864 -0.9907899 0.002452731 -0.5132815 -0.8582155 -0.002912104 -0.5811121 -0.8137794 0.008482158 -0.8794323 -0.4758999 -0.0108723 -0.9592897 -0.2821953 0.01136672 -0.9334961 0.358398 0.01165407 0.668828 0.7432785 0.01436626 -0.9756876 0.218958 -0.009547531 -0.5510694 0.8343636 -0.01264113 -0.4724792 0.8813385 0.00241363 0.2375521 0.9713688 -0.003425478 0.1748391 0.98447 -0.01582008 0.8264296 0.5629431 -0.01045948 0.9821643 0.1876782 0.01142078 0.9347766 0.1952995 -0.2967337 0.7273786 0.1916473 -0.6589324 0.6172586 0.2342774 -0.7510699 0.4444963 0.04888457 -0.894446 0.6064106 0.01474452 -0.7950151 0.9496231 0.09806019 -0.2976583 0.9031519 0.07083696 -0.4234368 0.7779619 0.08093416 -0.623077 0.4002875 0.08156216 -0.9127528 0.1789582 0.03172492 -0.9833451 0.1491221 -0.9888163 0.002235174 0.1468158 -0.9891169 -0.009648799 0.1501712 -0.988635 0.007050275 0.1480597 -0.9889785 -3.09453e-4 0.6692804 -0.7428649 -0.01468461 0.8758887 -0.4824979 -0.003830313 0.6369802 -0.7708802 0 0.8542082 -0.5194149 0.02316784 0.9887612 0.1494712 0.003135263 0.9892189 0.1464436 4.60331e-4 0.9892069 0.1465255 1.5421e-5 0.9892518 0.1462202 -8.33908e-4 -0.9888026 -0.1491029 0.006165981 -0.9894429 -0.144114 -0.01529973 -0.9889032 -0.1484359 0.006104052 -0.9891351 -0.1470055 0.001119792 -0.7536639 -0.6570791 -0.0154255 -0.68276 -0.7300736 0.02883523 -0.4891414 -0.8716727 -0.03045785 -0.4037218 -0.9148326 0.009489715 0.1470274 -0.9891121 0.006352424 0.1465547 -0.9892022 8.66145e-4 0.1443387 -0.9894778 -0.01000362 0.1449715 -0.9893474 -0.0132361 -0.1441922 0.9894933 -0.01057171 -0.1465207 0.9892077 -1.57927e-6 -0.1466383 0.9891899 -8.01499e-4 -0.1465029 0.9892082 0.001991748 -0.7354086 0.6775828 -0.007462978 -0.919264 0.3936144 0.004619717 -0.7238551 0.6899397 0.004153132 -0.9148712 0.4037461 -1.48734e-6 -0.988765 -0.1494455 0.003156542 -0.9894105 -0.1451426 -6.91347e-4 -0.9893181 -0.1457693 9.70485e-4 -0.9894137 -0.1451198 -8.31741e-4 0.005676388 -0.01234012 -0.9999079 -0.004046678 -0.005667626 -0.9999758 9.83186e-4 -0.007201373 -0.9999737 0.00486952 -0.009147167 -0.9999463 0.008751332 -0.006483197 -0.9999407 0.01548558 -0.00361526 -0.9998736 -0.00624895 -0.004758059 -0.9999693 -0.01743578 -0.003997802 -0.9998401 -0.001767456 -0.006593823 -0.9999767 -0.001041948 -0.008028805 -0.9999672 -2.90918e-6 2.05628e-6 -1 7.29067e-7 9.15272e-7 -1 6.53154e-7 1.48705e-6 -1 3.92377e-7 -2.61101e-7 -1 4.88129e-7 -8.06623e-7 -1 -0.001192927 0.002636969 -0.9999958 -0.001273572 0.002225816 -0.9999967 -0.002003312 5.01528e-4 -0.9999979 -0.004850625 -0.002791166 -0.9999845 -0.004722177 -0.00288546 -0.9999847 0 -3.00931e-6 -1 0.0156657 0.004218757 -0.9998684 0.006939053 0.00486207 -0.9999641 0.004129052 0.005657613 -0.9999755 -0.001146554 0.007228314 -0.9999733 -0.004872322 0.0091632 -0.9999462 -0.01114702 0.005100607 -0.999925 -0.01433855 0.00383985 -0.9998899 0.005889177 -0.0109862 -0.9999223 0.008356213 -0.003207981 -0.99996 0.01365381 0.005076706 -0.9998939 0.0147016 0.004324436 -0.9998826 0.007986426 0.01118427 -0.9999057 -0.004478931 0.03278076 -0.9994525 0.003092527 0.01684361 -0.9998534 0.9888137 0.1491178 0.003388881 0.9890536 0.1475173 -0.003407955 0.98877 0.1493377 0.005674779 0.989025 0.1477486 1.23156e-4 0.7585477 0.6516176 0 0.4933793 0.8698068 -0.003647029 0.76568 0.6432051 -0.004617989 0.5073726 0.8616945 0.007462322 -0.1464465 0.9892187 1.28097e-5 -0.1466154 0.9891935 -3.90824e-4 -0.1475774 0.9890406 -0.004461884 6.5237e-5 9.84437e-6 -1 -1.80298e-7 0 -1 -2.1796e-5 -2.03542e-5 -1 -7.33346e-7 0 -1 3.04295e-7 0 -1 -1.2076e-5 -4.50351e-5 -1 0.2586897 -0.8864851 -0.3836976 0.1659832 -0.7741247 -0.6108852 0.1966719 -0.5678004 -0.7993265 0.04888528 -0.4445033 -0.8944424 0.01474416 -0.6064115 -0.7950143 0.0529952 -0.9059773 -0.4199962 0.08622133 -0.7900495 -0.6069495 0.08147823 -0.4004083 -0.9127073 0.03152304 -0.1759459 -0.9838951 1.76596e-5 -3.99004e-5 -1 -5.60483e-5 1.70332e-5 -1 -3.16513e-7 0 -1 -2.76797e-7 0 -1 2.86503e-5 2.27717e-5 -1 -6.60693e-5 -9.79539e-6 -1 2.11394e-7 0 -1 9.12398e-6 4.19782e-5 -1 -0.2586875 0.8864778 -0.3837158 -0.1659855 0.7741231 -0.6108864 -0.1966723 0.5677945 -0.7993308 -0.04888188 0.4444827 -0.8944528 -0.01474452 0.6064129 -0.7950132 -0.05299401 0.9059768 -0.4199973 -0.08622145 0.7900486 -0.6069507 -0.08147776 0.4004093 -0.9127069 -0.0315209 0.1759346 -0.9838971 -1.60076e-5 3.0159e-5 -1 5.36458e-5 7.96429e-6 -1 -2.92762e-5 1.46784e-5 -1 0.9974986 0.07044357 -0.005855143 0.9922595 0.1234643 -0.0133391 0.996401 0.08475953 -0.001013159 0.5291544 -0.848373 -0.01608675 0.6315655 -0.77527 0.009034872 0.7401394 -0.6723657 -0.01086366 0.7503184 -0.661062 -0.004426956 0.875498 -0.483056 0.01265597 0.915951 -0.4009417 -0.01672309 0.9888002 -0.1483732 -0.01611489 0.9998044 -0.01728624 0.009613215 0.3576118 -0.9338703 -4.58576e-4 -0.03967618 -0.9991177 0.01377278 -0.1588193 -0.9871633 -0.01688808 -0.2600017 -0.9655703 0.008562743 -0.3828069 -0.9238218 -0.003498017 -0.5305774 -0.8475916 -0.008734643 -0.5988165 -0.8008488 0.007748365 -0.7044801 -0.7097046 -0.005224347 -0.9777165 -0.2096188 -0.01142138 -0.9775159 -0.2105656 -0.0111742 0.9643956 -0.2639746 0.01608031 0.4255348 -0.9047889 0.01665693 -0.4332994 -0.9012053 0.008986115 -0.7216162 -0.6922874 0.002892136 -0.8429542 -0.5379806 -0.002288818 -0.86053 -0.5093303 0.008420467 -0.9179248 -0.3966658 -0.008396565 -0.9586881 -0.2841848 0.01250213 0.4720114 -0.8815903 0.001939237 0.2064396 -0.9784564 -0.002402245 0.196758 -0.980452 -5.27934e-4 0.09771198 -0.9951247 -0.01339131 0.1168223 -0.9930188 -0.0163235 -0.999264 -0.01505243 -0.03528445 -0.998928 -0.04625546 -0.00184077 -0.5138047 0.8578613 -0.00888288 -0.8111152 0.5847439 -0.01291531 -0.8785691 0.4775038 0.01031094 -0.928964 0.3699288 -0.01336222 -0.3576076 0.9338719 -4.60704e-4 0.03968167 0.9992125 1.73978e-4 0.2827048 0.9592052 0.001905441 0.5107364 0.8597303 -0.00350368 0.6911565 0.722701 0.002476394 0.801328 0.5981615 -0.008736491 0.8547605 0.5189204 0.0103116 0.9116714 0.4107419 -0.01209855 0.9966658 0.07127577 -0.03971362 0.9578332 0.2873171 -0.002133548 -0.9998873 0.005362153 0.01402962 -0.991572 0.1289539 -0.01249045 -0.9628372 0.2695984 0.01616805 -0.7342936 0.6786317 0.01649552 -0.6632102 0.7483834 -0.00863564 -0.5601106 0.8284106 0.003496825 -0.4028427 0.9152046 0.01087808 0.286096 0.9581947 0.003480136 0.5097153 0.8603381 -0.002965688 0.7127416 0.7013071 0.01295584 0.9522027 0.3052064 0.01262325 -0.4723078 0.8814316 0.001928091 -0.2064321 0.9784581 -0.002400755 -0.1967593 0.9804517 -5.29703e-4 -0.09771263 0.9951246 -0.01339244 -0.0305792 0.9995275 -0.003136575 0.07735008 0.9968535 0.01732248 7.33917e-7 0 1 -1.37045e-6 0 1 8.62329e-6 -3.8445e-6 1 0 -7.49244e-6 1 1.45863e-6 -7.63761e-6 1 -4.96079e-5 2.43955e-5 1 2.66101e-5 2.92568e-5 1 6.2041e-7 0 1 -5.35121e-7 0 1 5.76032e-5 1.6814e-4 1 1.25142e-4 1.22753e-5 1 2.00455e-5 -2.84473e-4 1 7.03069e-7 5.29238e-7 1 1.0399e-6 -1.53989e-6 1 6.92319e-7 0 1 1.45263e-6 0 1 -1.13542e-6 0 1 -8.97057e-7 0 1 -8.27401e-6 4.26671e-6 1 0 7.40169e-6 1 3.91992e-5 -4.83399e-6 1 1.00424e-5 -2.17059e-5 1 -1.82556e-5 -1.53371e-5 1 -2.35134e-7 0 1 -7.62702e-7 0 1 6.26811e-7 0 1 -3.43966e-7 0 1 1.19816e-5 2.80756e-5 1 2.89627e-5 2.65687e-6 1 2.86062e-5 1.08918e-5 1 7.50529e-6 -2.95564e-5 1 0.9987875 0.04814004 0.01030713 0.9825458 -0.1857842 -0.009391427 0.9741122 -0.2230567 0.03675901 0.8739216 -0.4852175 0.0287227 0.7994424 -0.6000246 -0.0293681 0.7261572 -0.6869708 0.02769458 0.5691688 -0.8216508 0.03061097 0.05438637 -0.9977893 0.03819531 -0.8998019 -0.4341743 0.04300552 0.9944471 0.09752058 -0.03955751 0.9032141 -0.4280968 -0.03061848 0.6298714 -0.7756813 -0.03975701 0.3775795 -0.9252369 -0.03701752 0.3421618 -0.939592 0.009611606 0.09395235 -0.995506 -0.01186734 -0.2093348 -0.9768553 -0.04396361 -0.2247408 -0.9742192 -0.0197134 -0.4603516 -0.8866808 0.04328751 -0.5676526 -0.8211575 -0.05891478 -0.622065 -0.7829192 0.008533239 -0.8032622 -0.5954735 -0.01346331 -0.7891876 -0.6124244 -0.04603809 -0.9379253 -0.3451089 -0.03458189 -0.9791473 -0.1997475 0.0370351 -0.9729413 0.2298897 0.02315193 -0.9369387 0.3482582 -0.02936244 -0.8913655 0.4524388 0.02768856 -0.7873306 0.6160963 0.02314817 -0.7050738 0.708526 -0.0293591 -0.6200644 0.7840623 0.02768856 -0.4453787 0.8948189 0.03061044 -0.1867815 0.9815965 0.03976094 0.2551251 0.9663623 0.032485 0.6363084 0.7708271 0.0306161 0.8286287 0.5579862 0.04501003 0.9322409 0.3570215 -0.05884361 0.9677745 0.2494804 0.03423821 -0.9947903 -0.09100067 -0.04594689 -0.9988167 0.03692847 0.03164619 -0.985583 0.16769 -0.0225045 -0.8323875 0.5532412 -0.03248405 -0.5120488 0.8580357 -0.03976058 -0.2610641 0.9648361 -0.03061121 -0.05689424 0.9979963 -0.02768898 0.05682295 0.9979524 0.02936255 0.1796892 0.9834511 -0.02314758 0.3661532 0.9301425 -0.02769392 0.4694005 0.8824968 0.02936834 0.5855512 0.8101266 -0.02871805 0.7903116 0.6115142 -0.03818702 1.5474e-6 0 1 -3.52329e-6 0 1 3.58964e-7 0 1 -2.27433e-6 0 1 6.67544e-7 0 1 6.43546e-7 0 1 3.32058e-7 0 1 -8.05775e-7 0 1 2.22202e-7 0 1 3.12274e-6 0 1 -3.33777e-7 0 1 -3.76276e-7 0 1 5.44726e-7 0 1 2.89201e-6 0 1 -6.1022e-7 0 1 3.89341e-6 0 1 -3.33222e-7 0 1 -4.74094e-7 0 1 0 0 1 -3.52056e-6 0 1 6.30307e-7 0 1 9.70521e-7 0 1 -3.73566e-7 0 1 -3.5899e-7 0 1 0 0 1 0.9818656 -0.1894263 0.007602751 0.7365853 -0.6763157 0.006269335 0.526589 -0.8500971 -0.006253421 0.3221108 -0.9466836 0.005912423 -0.08843278 -0.9960572 0.007057726 -0.9112714 -0.4115821 0.01359385 0.9968137 -0.07954055 -0.006003916 0.8183835 -0.5746343 -0.00664246 0.09453338 -0.9954968 -0.007057249 -0.3163046 -0.9486393 -0.005913197 -0.5523149 -0.8335952 0.008209049 -0.7466152 -0.6651514 -0.01180368 -1.05048e-6 0 1 1.34241e-6 0 1 -0.9962546 0.08628267 0.005661725 -0.8739724 0.4859244 0.007057368 0.03848373 0.9991662 0.01363843 0.9228611 0.3850222 0.009241878 0.913647 0.4064664 0.00585556 -0.9885876 -0.1504074 -0.00850141 -0.9437668 0.3305559 -0.006079673 -0.7379733 0.674804 -0.005912005 -0.5232163 0.8521518 0.009064018 -0.28693 0.9578568 -0.01347386 0.2810642 0.9596566 -0.007882177 0.5523144 0.8335955 0.00820893 0.7140411 0.7000567 -0.008119404 0.8259356 0.5636873 0.009334444 0.9968133 0.07762354 -0.01838362 0.9994156 -0.02669423 0.0213533 0.825536 -0.5640073 -0.0196501 0.7348875 -0.6771888 0.03682237 0.3946364 -0.918057 -0.03786027 0.09734177 -0.9945308 0.03785723 -0.3308407 -0.9428633 -0.03941231 -0.4569002 -0.8893375 0.01792037 -0.922571 -0.3852517 -0.02107149 -0.9498358 -0.3120386 0.02106928 -0.9036164 0.4278244 -0.02106541 -0.9102059 0.4130856 -0.02975833 -0.541401 0.8398246 0.03974682 -0.3424541 0.9386935 -0.03974676 0.2204014 0.9749553 0.02975791 0.2046791 0.9786024 0.0210675 0.7874301 0.6161436 -0.01792025 -7.61008e-4 2.12052e-4 -0.9999997 -0.8641005 0.5033193 2.47083e-5 -0.914669 0.404202 0.001219153 -0.8653917 0.4996317 -0.03828179 -0.8277259 0.5603355 0.02990335 -0.4069613 0.004593014 -0.9134339 -0.8627334 -0.5056591 -3.20634e-5 -0.9100146 -0.4145719 0.001909017 -0.8660229 -0.4999969 -0.002756536 -0.8334976 -0.5495845 -0.056912 -0.1091166 -0.3085849 -0.9449175 -0.32943 -0.3788135 -0.8648562 -0.1128476 -0.4162862 -0.9022036 -0.001978695 -0.9999905 -0.00389862 0.001915276 -0.9999922 -0.003473997 0 -0.9999971 -0.002402365 0.1671671 -0.4269401 -0.8886942 0.1291395 -0.5820756 -0.8028146 0.4516447 -0.4012122 -0.7968977 0.2839806 -0.3557802 -0.8903795 0.8631215 -0.5049964 2.99887e-5 0.8618071 -0.507235 0.001130521 0.8660244 -0.4999992 0.001638174 0.8711609 -0.4908105 -0.01355677 0.3978563 0.006715476 -0.9174233 0.8745554 0.4849258 -3.93172e-5 0.8599239 0.5104196 -0.001707196 0.8659944 0.499983 0.008409678 0.6977185 0.474799 -0.5364279 0.2911971 0.3388907 -0.8946269 0.1260398 0.5566695 -0.8211171 0.161832 0.4121829 -0.8966135 -3.15463e-4 0.9999963 -0.002719521 0 0.9999998 6.02607e-4 -0.004509389 0.9999725 -0.005885541 -0.1153206 0.4214453 -0.8994916 -0.1352471 0.3246359 -0.9361195 -0.3323476 0.3861163 -0.8604994 7.63293e-4 -0.01034522 -0.9999463 -7.16198e-4 0.009781479 -0.999952 -1.65538e-4 0.01013606 -0.9999486 -0.001598536 -0.008561074 -0.9999621 -6.78849e-4 -8.21665e-4 -0.9999995 -3.82473e-4 -0.001522541 -0.9999988 0.02425086 -0.003499209 -0.9996998 -3.90047e-4 -0.001045703 -0.9999995 -5.54681e-4 -9.60943e-4 -0.9999994 -0.004435777 0.001190483 -0.9999895 -0.001400053 -0.01302194 -0.9999142 0.003351807 -0.005022048 -0.9999818 -6.2507e-4 0.001082658 -0.9999992 -4.2356e-4 0.001135349 -0.9999994 0.02410984 -9.79777e-4 -0.9997089 0.01969563 0.01153695 -0.9997395 -0.003611445 0.002749621 -0.9999898 -0.005873978 -0.007044792 -0.999958 -7.91829e-4 9.59847e-4 -0.9999992 -0.008044183 -0.002465009 -0.9999646 0.008535444 6.27466e-4 -0.9999635 0.006516516 0.006092429 -0.9999603 0.004293143 -0.004928171 -0.9999787 -0.01693195 0.01146382 -0.9997909 -0.001503527 -0.00130397 -0.9999981 0.002893269 -0.003256142 -0.9999905 0.07300937 -0.8710961 -0.4856555 0.4485998 -0.4066542 -0.7958585 0.846435 -0.4146859 -0.3340414 0.5416208 0.03928142 -0.8397046 0.7593576 0.5661348 -0.3207295 0.4227985 0.5064831 -0.7514761 0.01924908 0.7034278 -0.7105061 -0.07301092 0.8710918 -0.4856631 -0.4485901 0.4066401 -0.795871 -0.8464447 0.4146737 -0.3340317 -0.5416249 -0.03927993 -0.8397022 -0.7593488 -0.5661386 -0.3207437 -0.4228234 -0.5065044 -0.7514477 -0.01923477 -0.7034409 -0.7104935 -0.02483189 -0.9996066 0.01304596 -0.6432992 -0.7654032 0.01800608 -0.7090273 -0.7048081 -0.02293485 -0.9849216 -0.172957 -0.003934025 -0.9964268 -0.07633185 0.03615695 -0.8761811 0.4801385 -0.04211658 -0.7375973 0.6729707 0.05532336 -0.1159424 0.9913864 -0.06091463 0.02484691 0.9996062 0.01304543 0.6432861 0.7654142 0.01800185 0.7090319 0.7048034 -0.02293354 0.9849188 0.1729722 -0.003934085 0.9964274 0.07632404 0.03615528 0.876174 -0.4801508 -0.04212492 0.737598 -0.6729702 0.05532169 0.601418 0.6088493 0.5172997 0.5944254 0.5887861 0.5477129 0.605144 0.1083735 0.7887054 0.8783887 -0.1805539 0.442531 0.521095 -0.2848489 0.8045627 0.3242458 -0.8716436 0.3675626 0.06563919 -0.5629161 0.8239035 -0.6014074 -0.6088312 0.5173333 -0.5944385 -0.5888051 0.5476784 -0.6051339 -0.1083695 0.7887136 -0.8784046 0.1805613 0.4424963 -0.5211222 0.2848457 0.8045462 -0.3242249 0.8715889 0.3677105 -0.06565499 0.5628798 0.8239271 -0.002109587 8.80364e-4 0.9999974 0 0.004263043 0.9999909 0.001234233 -6.65791e-5 0.9999992 0.001682937 -9.71669e-4 0.9999982 -0.001234471 6.60254e-5 0.9999993 -0.001683592 9.72049e-4 0.9999981 0.00336188 7.6236e-4 0.9999941 0.00145626 8.40794e-4 0.9999986 0.002109229 -8.79899e-4 0.9999974 0 -0.004262089 0.999991 -0.003361046 -7.62436e-4 0.9999942 -0.00145632 -8.40839e-4 0.9999986 -0.004330694 0.008672356 0.9999531 -0.008241415 0.009329378 0.9999225 -0.008224427 0.003290295 0.9999608 -0.01462095 -0.001092612 0.9998926 -0.007907509 -0.01010459 0.9999177 -0.008100986 -0.01156377 0.9999004 0.00187397 -0.01221394 0.9999237 0.002878069 -0.009731769 0.9999485 0.01015752 -0.008072137 0.9999158 0.0100907 -0.001910924 0.9999473 0.01119309 -0.001156568 0.9999368 0.01074379 0.007917165 0.999911 0.006448686 0.008213877 0.9999455 0.002096891 0.01621025 0.9998664 -0.03438651 -0.01320433 -0.9993214 -0.03781914 -0.0123437 -0.9992083 -0.02540612 -0.03179508 -0.9991714 -0.005696892 -0.02948504 -0.999549 0.01163202 0.02785742 -0.9995443 0.01420962 0.02913564 -0.9994745 -0.008359789 0.03331947 -0.9994099 -0.007530033 0.03515213 -0.9993537 -0.02830916 0.02885729 -0.9991827 -0.02989953 0.008426308 -0.9995174 -0.04336613 0.02396506 -0.9987719 0.001279711 -0.02324438 -0.999729 0.007918059 -0.02629536 -0.9996229 0.01728552 -0.01761966 -0.9996954 0.01881462 -0.03609454 -0.9991713 0.03123313 -0.01006239 -0.9994615 0.02411973 0.001420915 -0.9997081 0.02683603 0.004652321 -0.9996291 0.02364408 0.01815962 -0.9995556 0.01849573 0.0190674 -0.9996472 0.9674341 -0.2529453 -0.009500026 0.9857839 -0.1680029 -0.002275109 0.6934584 -0.7204924 -0.002486646 0.7004703 -0.7136796 -0.001696407 0.1660298 -0.9861203 -9.52843e-4 0.09335899 -0.9956095 -0.006769478 -0.4118937 -0.9112211 0.004454076 -0.6527379 -0.7575023 -0.01111489 -0.8775499 -0.4794433 0.006350874 -0.9851931 -0.1712059 -0.009117066 -0.8970655 0.4418407 -0.00710237 -0.9790556 0.2035462 0.004383146 -0.7638245 0.6454195 0.002429187 -0.4204547 0.907302 -0.004571676 -0.4493294 0.8933641 -0.001964151 0.1382545 0.9903966 -6.77104e-4 0.217516 0.9760317 -0.007004618 0.6840873 0.7293828 0.005027353 0.8568077 0.5155264 -0.01063281 0.9514673 0.3077493 5.21266e-4 0.002202153 0.004773378 -0.9999862 0.005007028 -0.002056479 -0.9999853 -0.001758754 0.001741647 -0.999997 -0.001593887 0.001747548 -0.9999972 0.7925292 0.6087194 -0.03685653 0.5978056 0.7998368 0.05375719 0.3849385 0.9219157 -0.04351764 -0.03939688 0.9982522 0.04405355 -0.2431675 0.9692061 -0.03884798 -0.5701352 0.820682 0.03777629 -0.7000021 0.7135533 -0.02896362 -0.962363 0.271216 0.0173071 -0.961135 0.2757169 0.0141344 -0.9334575 -0.3584679 -0.01257133 -0.9203061 -0.3911274 0.007498502 -0.6242257 -0.7812141 -0.006837308 -0.601229 -0.7990517 0.006343901 -0.1896685 -0.9818245 -0.006841361 -0.1610167 -0.9869313 0.006346344 0.2883259 -0.9575081 -0.006833076 0.3160745 -0.9487133 0.006341934 0.7002826 -0.7138331 -0.006837189 0.7207636 -0.6931519 0.006344139 0.9518038 -0.3066316 -0.006837248 0.960327 -0.2788044 0.006345391 0.98528 0.1708117 -0.006836414 0.9698742 0.2421911 0.02622061 -0.5707915 0.03618675 0.8202973 -0.9067896 0.2601225 0.3317664 -0.4106817 0.3495327 0.8421208 -0.4940805 0.7126787 0.4979695 -0.1418927 0.5342966 0.8333029 -0.03652805 0.9080678 0.4172273 0.3317452 0.4671069 0.8196075 0.3794146 0.5076357 0.7735312 0.848443 0.2110016 0.4854098 0.5042527 0.013493 0.8634508 0.8139482 -0.2363065 0.5307048 0.4219321 -0.4195342 0.8037191 0.4052063 -0.3896847 0.827015 0.2914233 -0.8747316 0.3871914 -0.06879758 -0.509364 0.8577967 -0.09050118 -0.5547273 0.8270956 -0.5544365 -0.73687 0.3868112 -0.4793733 -0.2925268 0.8274233 -0.7319669 -0.3122708 0.605567 0.699401 0.4113531 -0.5844885 0.252111 0.5211314 -0.8153908 0.1806994 0.8373258 -0.5159781 -0.2855197 0.5432958 -0.7894987 -0.2719014 0.5323023 -0.8017008 -0.8016709 0.3966236 -0.4472289 -0.5533382 -0.031933 -0.8323444 -0.6745016 -0.1166912 -0.7289931 -0.5407369 -0.6180352 -0.5706455 -0.2250801 -0.4552754 -0.861431 0.090631 -0.9239181 -0.3717007 0.3637613 -0.398879 -0.841768 0.4093431 -0.4172278 -0.8113934 0.880024 -0.1480715 -0.4512568 0.5514433 0.1838763 -0.8136951 0.6419318 0.7451054 0.1809462 -0.3270446 0.9294905 0.170556 -0.951188 0.1671948 0.2593982 -0.6413072 -0.7453929 0.1819739 0.3249143 -0.9282861 0.1808747 0.9666772 -0.1831133 0.1788986 -0.5194292 0.08224576 0.8505463 -0.2358823 0.4344028 0.8692834 -0.06448882 0.4900208 0.869322 0.3759351 0.3701987 0.8494856 0.5225277 -0.1111458 0.8453471 0.1390733 -0.5209104 0.8422061 -0.3444492 -0.4166332 0.8412917 0.6349013 0.7714062 0.04281324 0.6820874 0.7312691 0.001507997 0.6737476 0.7389437 -0.005145192 -0.3554314 0.9347024 1.17809e-4 -0.3119872 0.9495967 0.03049814 -0.3482193 0.9354608 0.06046843 -0.2617382 0.965139 5.89976e-5 -0.9776235 0.2098569 0.01457381 -0.9902734 0.1347002 0.03484982 -0.9816667 0.1905995 0.001545369 -0.6726292 -0.7399769 0.002040565 -0.6326361 -0.7740145 0.0259478 -0.6672775 -0.7448041 -0.002775073 0.3041376 -0.9526228 -0.003217637 0.3529403 -0.9350674 0.03289628 0.3032585 -0.9529048 -0.002640366 0.9771137 -0.2127103 -0.001842021 0.9854515 -0.1642721 0.04359006 0.9749252 -0.2224869 0.004514157 -0.03092074 -0.1046674 0.9940266 0.7431707 -0.02720123 0.6685488 0.8252896 -0.1566206 -0.5425561 -0.8409454 0.4423584 -0.311657 -0.6647081 0.1429857 -0.7332928 -0.897691 -0.2943295 -0.3279041 -0.5615957 -0.3320653 -0.7578541 0.8035843 0.1352596 -0.579618 0.4629975 -0.3947854 -0.7935855 0.5067449 -0.668995 -0.543742 0.1015833 -0.8078671 -0.5805442 0.1253904 -0.7523747 -0.6466912 -0.3689225 -0.7738922 -0.5147691 -0.3971469 -0.7963377 -0.4562026 -0.5686784 0.474186 -0.6721253 -0.3201835 0.6883202 -0.6509209 -0.2850235 0.8577515 -0.4278131 0.09876686 0.6958041 -0.7114083 0.2391566 0.8171617 -0.524453 0.5641159 0.5734664 -0.594062 0.5210121 0.5634281 -0.641167 -0.002170264 0.03537172 -0.999372 0.003437101 0.03326523 -0.9994407 0.007956802 -0.005733191 -0.9999519 -0.002210855 0.03535109 -0.9993726 -0.02513647 0.03708529 -0.998996 -0.03510147 -0.01510059 -0.9992697 -0.01375681 -0.03886085 -0.9991499 -0.002447068 -0.0207616 -0.9997816 0.01882946 -0.003205895 -0.9998176 -0.007154464 0.005337238 -0.9999603 -0.0108757 -0.01950448 -0.9997506 -0.009085178 -0.004290163 -0.9999495 -0.01406604 0.001970112 -0.9998992 -2.31652e-4 0.03102922 -0.9995185 -1.10028e-4 0.03101485 -0.9995189 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.8245443 0.5656995 0.01052504 -0.868598 0.4955174 -2.3183e-4 -0.9988216 0.0462234 0.01479673 -0.9979496 -0.06394481 0.00280404 -0.940248 -0.3403035 0.01128196 -0.8195582 -0.5729341 -0.008424639 -0.6017695 -0.7985627 0.01309299 -0.3965936 -0.9179884 -0.003277897 -0.09491288 -0.9953002 0.01921266 0.1450433 -0.9894253 5.80644e-4 0.3659834 -0.9305053 0.01469832 0.6433535 -0.7655246 -0.008272171 0.8434237 -0.5370662 0.0140196 0.9496869 -0.3131965 -0.001657068 0.9977184 -0.06509166 0.01792418 0.9725617 0.2326312 -0.002577662 0.8540334 0.5198376 0.01989758 0.9921072 0.1088722 0.06221067 0.5300151 0.847971 -0.005407929 0.2867773 0.9578325 0.01777094 0.06466752 0.9979069 1.11726e-4 -0.2933521 0.9559034 0.01390862 -0.3998132 0.9165967 -3.13674e-4 0.01617217 0.02638298 0.9995211 0.03232848 0.01885074 0.9992996 -0.009300231 0.015172 0.9998417 0.01088112 0.02413672 0.9996495 0.02079498 0.01751905 0.9996303 -0.02756714 -0.01110804 0.9995583 -0.06343603 -0.06544506 0.9958378 -0.5756227 0.8176893 -0.006532728 -0.6675174 0.7423276 0.05805325 -0.9212244 0.3858819 -0.04940474 -0.9945166 0.09697455 0.03915143 -0.9912356 -0.1292518 -0.02731329 -0.9162117 -0.4005709 0.009948611 -0.89243 -0.451093 -0.009160339 -0.61672 -0.7871296 -0.009138047 -0.5520022 -0.8333092 0.02982354 -0.0700857 -0.9973281 -0.02060961 0.05796772 -0.9978913 0.02920359 0.3605114 -0.9311433 -0.05480641 0.7155607 -0.6967808 0.04969459 0.8023373 -0.5968005 -0.009173154 0.9744057 -0.2246093 -0.009174168 0.9864884 -0.1627374 0.01889801 0.9407714 0.3390115 -0.004549622 0.9400714 0.340928 -0.005840897 0.5544826 0.8321745 -0.005903661 0.5254194 0.8507825 0.01017737 0.1727426 0.9845646 -0.0281524 0.008822798 0.9997924 0.01836794 -0.2175659 0.9749168 -0.04692947 -0.09133428 -0.3563853 -0.9298644 -0.6076341 -0.7734153 -0.180582 -0.5039833 -0.3313633 -0.797621 -0.5129738 -0.01181948 -0.8583229 -0.9155778 0.3837178 -0.1203246 -0.2740545 0.2643151 -0.9246793 0.2252273 0.226423 -0.9476315 0.8958547 0.3261674 0.3017601 0.4258407 -0.08430403 -0.9008621 0.5027773 -0.1183683 -0.8562734 0.7794907 -0.5789935 -0.2390834 0.2143533 -0.3723635 -0.902994 0.2953257 -0.3171557 0.9012186 -0.3353021 -0.2824027 0.8987888 0.1150994 0.9764671 -0.1823848 0.9031972 0.3885548 -0.1823736 0.7883933 -0.5895257 -0.1757718 -0.1166538 -0.9767465 -0.179884 -0.9028379 -0.3879855 -0.1853399 -0.7880781 0.5879001 -0.1825007 0.4415681 -0.3165037 -0.8395493 -0.01402425 -0.5343297 -0.8451599 0.4962345 0.2093234 -0.8425765 0.0425536 0.537139 -0.8424197 -0.442386 0.3125969 -0.8405818 -0.4914339 -0.2192529 -0.8428648 0.0909264 0.9958193 -0.008741319 0.1411983 0.9894264 -0.03314363 0.09789884 0.9951878 -0.004142343 0.9077692 0.4194129 -0.006929397 0.9279807 0.371628 -0.02728325 0.9118813 0.4104541 -3.357e-4 0.8163518 -0.5775547 -6.47592e-4 0.7858848 -0.61773 -0.02819514 0.8138779 -0.5810323 0.002116739 -0.07738077 -0.9960752 -0.04297173 -0.1540189 -0.9871869 0.04171735 -0.09074848 -0.995864 0.004454076 -0.9073259 -0.420428 -6.89233e-5 -0.8952526 -0.4451923 -0.018072 -0.9241157 -0.3760062 -0.06804108 -0.817622 0.5757541 -0.001304805 -0.7863709 0.6167761 -0.03475999 -0.8172361 0.5763024 -8.64385e-4 0.3009679 0.7052689 0.6418833 0.2218683 0.2186243 0.9502516 0.6636321 0.3455153 0.6634845 0.437875 0.08425259 0.8950794 0.5223349 0.1254228 0.8434663 0.7656605 -0.09389835 0.6363546 0.312866 -0.1504042 0.9378132 0.6336877 -0.2085208 0.7449557 0.5118842 -0.4529247 0.7299547 0.3006336 -0.3568878 0.8844493 0.3815905 -0.665459 0.641524 0.08378547 -0.550442 0.8306585 0.07968884 -0.5399898 0.8378906 -0.1681548 -0.7571361 0.631244 -0.1860793 -0.4321292 0.8824052 -0.4196839 -0.6351165 0.6484539 -0.4452269 -0.3413738 0.8277904 -0.3991995 -0.2820639 0.8723988 -0.6903787 -0.2807123 0.6667668 -0.5578483 -0.03275752 0.8292963 -0.5635828 -0.03446316 0.8253404 -0.7312837 0.2316576 0.6415286 -0.151988 0.4354039 0.8873124 -0.2429695 0.5773389 0.7795163 -0.508318 0.6476093 0.5676399 -0.2764895 0.2027401 0.9393882 -0.5341112 0.3000707 0.7903689 0.02096688 0.6210586 0.7834837 0.03427195 0.5586661 0.8286843 -0.03537195 -0.002170324 -0.999372 -0.03326523 0.003437221 -0.9994407 0.005733132 0.007956743 -0.999952 -0.03535109 -0.002210915 -0.9993726 -0.03708505 -0.02513653 -0.998996 0.01510047 -0.03510129 -0.9992697 0.03886067 -0.01375693 -0.99915 0.02076148 -0.002447247 -0.9997816 0.003205657 0.01882946 -0.9998176 -0.005337715 -0.007154583 -0.9999602 0.01950436 -0.01087576 -0.9997507 0.004290223 -0.009085297 -0.9999495 -0.001970112 -0.01406621 -0.9998992 -0.03102898 -2.31966e-4 -0.9995185 -0.03101491 -1.10077e-4 -0.9995189 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.5656991 -0.8245446 0.01052546 -0.4955195 -0.8685968 -2.31999e-4 -0.04622405 -0.9988216 0.01479673 0.06394457 -0.9979495 0.002803921 0.3403077 -0.9402465 0.01128202 0.5729315 -0.8195601 -0.008424639 0.7985613 -0.6017711 0.01309251 0.9179896 -0.396591 -0.003277719 0.9953003 -0.09491151 0.01921284 0.9894256 0.1450403 5.80934e-4 0.9305049 0.3659844 0.0146985 0.7655239 0.6433544 -0.008272588 0.537069 0.8434219 0.01401937 0.3131962 0.949687 -0.001656651 0.06508743 0.9977186 0.01792424 -0.232625 0.9725631 -0.002577543 -0.5198399 0.8540319 0.0198974 -0.1088714 0.9921074 0.0622105 -0.8479715 0.5300142 -0.005408048 -0.9578322 0.2867783 0.01777106 -0.9979069 0.06466829 1.11814e-4 -0.9559031 -0.293353 0.01390844 -0.9165966 -0.3998132 -3.13295e-4 -0.02638244 0.01617193 0.9995211 -0.01885086 0.03232705 0.9992997 -0.01517176 -0.009299159 0.9998418 -0.02413666 0.01088094 0.9996495 -0.01751863 0.02079647 0.9996303 0.01110768 -0.02756732 0.9995583 0.06544452 -0.06343609 0.9958378 -0.8176888 -0.5756235 -0.006532728 -0.7423275 -0.6675178 0.05805277 -0.3858826 -0.9212241 -0.04940485 -0.09697532 -0.9945166 0.03915107 0.1292527 -0.9912356 -0.02731257 0.4005693 -0.9162124 0.009949266 0.4510927 -0.8924302 -0.009159982 0.7871293 -0.6167204 -0.00913757 0.8333094 -0.5520021 0.0298227 0.9973283 -0.07008397 -0.02060818 0.9978911 0.05796939 0.0292043 0.9311431 0.3605123 -0.05480629 0.6967819 0.7155596 0.04969441 0.5967994 0.8023381 -0.009172081 0.2246106 0.9744055 -0.009174227 0.1627353 0.9864889 0.01889675 -0.339012 0.9407711 -0.004549622 -0.3409262 0.940072 -0.005841076 -0.8321745 0.5544824 -0.005903184 -0.8507828 0.5254189 0.01017659 -0.9845648 0.1727416 -0.02815192 -0.9997923 0.008823275 0.01836836 -0.974917 -0.2175651 -0.04692959 0.356382 -0.09133291 -0.9298658 0.7734144 -0.6076349 -0.1805821 0.3313603 -0.5039799 -0.7976245 0.01181924 -0.5129753 -0.858322 -0.3837171 -0.9155775 -0.1203287 -0.2643161 -0.2740552 -0.9246788 -0.2264217 0.2252287 -0.9476315 -0.326168 0.8958547 0.3017598 0.08430355 0.4258403 -0.9008624 0.1183679 0.5027802 -0.8562718 0.5789898 0.779488 -0.2391014 0.3723673 0.2143549 -0.902992 0.3171545 0.2953255 0.9012191 0.2824032 -0.3353016 0.8987889 -0.9764677 0.1150993 -0.1823815 -0.3885537 0.9031978 -0.1823734 0.5895258 0.7883919 -0.1757775 0.9767495 -0.1166538 -0.1798676 0.3879829 -0.9028397 -0.1853372 -0.5879017 -0.7880769 -0.1825007 0.316504 0.4415683 -0.8395492 0.5343281 -0.01402384 -0.8451609 -0.2093237 0.496235 -0.8425762 -0.5371391 0.04255414 -0.8424196 -0.3125969 -0.4423873 -0.8405812 0.2192525 -0.4914324 -0.8428658 -0.9958195 0.09092432 -0.008743822 -0.989426 0.1412008 -0.0331428 -0.9951879 0.09789752 -0.004143536 -0.4194135 0.9077689 -0.006929636 -0.3716253 0.9279819 -0.02728223 -0.4104551 0.9118808 -3.36302e-4 0.5775553 0.8163514 -6.4654e-4 0.6177328 0.7858826 -0.0281952 0.5810315 0.8138785 0.002116084 0.9960751 -0.07738268 -0.04296934 0.9871875 -0.1540154 0.0417152 0.9958634 -0.09075379 0.004453599 0.4204249 -0.9073273 -7.10119e-5 0.4451937 -0.895252 -0.01806968 0.3760067 -0.9241154 -0.06804144 -0.5757518 -0.8176236 -0.001303732 -0.6167762 -0.7863708 -0.03476119 -0.5763036 -0.8172354 -8.64387e-4 -0.7052695 0.3009678 0.6418827 -0.2186229 0.2218635 0.9502529 -0.3455151 0.6636261 0.6634905 -0.08425265 0.4378699 0.8950818 -0.1254227 0.522337 0.843465 0.09389591 0.7656479 0.6363701 0.150404 0.3128674 0.9378128 0.2085204 0.6336817 0.7449609 0.4529219 0.5118815 0.7299584 0.3568868 0.3006345 0.8844494 0.6654515 0.3815865 0.6415343 0.5504548 0.08378249 0.8306505 0.5399944 0.07969111 0.8378876 0.7571387 -0.1681534 0.6312413 0.4321321 -0.1860821 0.8824031 0.6351218 -0.4196873 0.6484466 0.3413748 -0.4452252 0.827791 0.2820646 -0.3991985 0.872399 0.2807085 -0.6903687 0.6667788 0.03275674 -0.5578385 0.8293029 0.0344631 -0.5635823 0.8253408 -0.2316535 -0.7312649 0.6415515 -0.4354087 -0.1519914 0.8873094 -0.5773343 -0.2429694 0.7795199 -0.6476063 -0.5083126 0.5676482 -0.2027443 -0.2764949 0.9393857 -0.3000658 -0.5341035 0.7903758 -0.6210638 0.02097028 0.7834796 -0.5586692 0.03427177 0.8286823 0.504984 0.8631287 2.43661e-5 0.5018867 0.8649334 -4.30031e-5 0.4928328 0.8701038 -0.005928158 0.4999982 0.8660259 0.001010656 -0.006718993 0.3978527 -0.9174248 -0.493719 0.8696216 -1.0943e-5 -0.4849431 0.8745458 -3.02442e-5 -0.5346297 0.8446977 -0.02563071 -0.4999799 0.8659962 0.008407652 -0.4389081 0.4677531 -0.767181 -0.3290622 0.2046277 -0.9218708 -0.9999839 -0.005692422 0 -0.9999896 0.002967715 -0.003495693 -0.9999698 -0.007717728 8.68819e-4 -0.999987 0 -0.005115926 -0.4269278 -0.1671437 -0.8887045 -0.6015178 -0.1237232 -0.7892205 -0.4012194 -0.4516476 -0.7968924 -0.3557704 -0.283987 -0.8903813 -0.5049948 -0.8631225 3.00652e-5 -0.5072417 -0.8618031 0.00113058 -0.4999996 -0.8660242 0.001638174 -0.4908076 -0.8711627 -0.01355206 0.006714522 -0.3978517 -0.9174253 0.4849207 -0.8745582 -3.02439e-5 0.5072595 -0.8617923 0.001375079 0.499981 -0.8659956 0.008409678 0.479501 -0.7046732 -0.5229862 0.359619 -0.3082065 -0.8807287 0.4353355 -0.1849751 -0.8810604 0.9999819 -0.00601226 4.4598e-5 0.9987639 0.04953515 -0.004130542 0.9999666 -0.008134543 9.49107e-4 0.9997127 0 -0.02397412 0.9864527 -0.1320766 0.09729743 0.3459168 0.2043412 -0.9157436 -0.004237115 -2.50972e-4 -0.9999911 0.004386305 2.63787e-4 -0.9999904 -0.009443879 0.02060961 -0.999743 0.0061661 -0.00770545 -0.9999514 0.01161855 0.01981675 -0.9997361 -8.22176e-4 6.78212e-4 -0.9999995 -0.001522243 3.82134e-4 -0.9999988 -0.00197798 -0.008974134 -0.9999579 -9.60276e-4 5.54675e-4 -0.9999995 -0.003144383 -0.004418849 -0.9999853 -0.01037883 0.01861333 -0.9997729 0.001082956 6.2519e-4 -0.9999992 0.001135706 4.23635e-4 -0.9999993 2.39179e-4 -0.009972393 -0.9999504 0.01153916 -0.0196982 -0.9997395 0.002749562 0.003612935 -0.9999898 -0.007047057 0.005875766 -0.999958 9.59528e-4 7.92526e-4 -0.9999992 0.004927337 0.004294574 -0.9999787 -0.008215427 -0.01095032 -0.9999064 0.007582485 -0.008516252 -0.9999351 -0.004928231 -0.004294395 -0.9999787 0.01709502 0.01448518 -0.999749 -0.001303732 0.001504182 -0.999998 -0.003256201 -0.002894103 -0.9999906 -0.8710765 -0.0730139 -0.4856902 -0.4066383 -0.4485956 -0.7958691 -0.414668 -0.8464327 -0.3340692 0.03928202 -0.5416375 -0.8396939 0.5661397 -0.7593613 -0.3207122 0.5064948 -0.4228045 -0.7514649 0.7034133 -0.01924842 -0.7105205 0.8710921 0.0730158 -0.4856617 0.4066541 0.4485899 -0.7958642 0.4146778 0.8464233 -0.3340805 -0.03928017 0.5416193 -0.8397058 -0.5661523 0.7593648 -0.3206818 -0.5064863 0.4227986 -0.7514739 -0.7034192 0.01923751 -0.7105149 -0.9996066 0.02482926 0.01304697 -0.7654176 0.6432821 0.01800149 -0.7048119 0.7090233 -0.02293878 -0.1729459 0.9849236 -0.003933966 -0.07632559 0.9964271 0.03615802 0.4801498 0.8761748 -0.04212027 0.6729764 0.7375922 0.05532222 0.9913883 0.1159309 -0.06090402 0.9996063 -0.02484464 0.01304739 0.7654075 -0.6432939 0.01801532 0.7048037 -0.7090317 -0.022933 0.1729504 -0.9849227 -0.003927946 0.07632964 -0.9964274 0.03614354 -0.4801559 -0.8761712 -0.04212421 -0.6729655 -0.7376019 0.05532646 -0.9913892 -0.1159266 -0.06089782 0.8332512 -0.3402736 0.4357826 0.4071963 -0.4127117 0.8147763 0.2436035 -0.798259 0.5508537 0.1242351 -0.6967505 0.7064732 -0.3509747 -0.6575576 0.6666594 -0.350296 -0.6403343 0.6835676 -0.6956785 -0.0811972 0.7137495 -0.7465389 -0.1102688 0.6561406 -0.5229217 0.5681567 0.635414 -0.5887957 0.5944208 0.5477076 -0.108356 0.6051377 0.7887126 0.1805621 0.878395 0.4425152 0.2848578 0.5211233 0.8045413 0.7978646 0.3776798 0.4698619 0.5456959 0.06363314 0.8355639 0.001494407 -7.42133e-4 0.9999987 5.50805e-4 0 1 0.001552522 7.51731e-4 0.9999985 -3.21295e-4 -5.56502e-4 0.9999998 -2.54995e-4 -0.002931296 0.9999957 6.56172e-5 0.001234412 0.9999992 9.72209e-4 0.00168389 0.9999982 9.4011e-4 -0.001628279 0.9999983 -0.001015245 -6.1966e-4 0.9999993 -0.001529455 0 0.9999989 -0.002218604 -4.12685e-4 0.9999976 -8.48828e-4 0.001260757 0.9999989 -8.40764e-4 0.001456201 0.9999987 7.64027e-6 0 1 -2.62585e-6 0 1 -3.60259e-7 0 1 6.19352e-6 0 1 -3.57295e-6 0 1 2.16878e-7 0 1 -2.79032e-7 0 1 1.2125e-5 0 1 -6.73894e-6 0 1 -3.39049e-6 0 1 2.6188e-6 0 1 3.97215e-6 0 1 -2.26765e-6 0 1 -2.03811e-5 0 1 8.8033e-6 0 1 -5.65173e-6 0 1 3.18303e-6 0 1 6.73895e-6 0 1 -2.26765e-6 0 1 2.20185e-6 0 1 -4.53868e-7 0 1 4.71634e-7 0 1 7.78335e-7 0 1 -1.36038e-6 0 1 1.69049e-6 0 1 5.45926e-6 0 1 1.90931e-6 0 1 2.31547e-6 0 1 -2.94001e-5 0 1 -5.44958e-6 0 1 -4.58088e-6 0 1 5.52189e-6 0 1 -2.24101e-6 0 1 -7.14563e-7 0 1 6.76944e-6 0 1 2.24101e-6 0 1 -4.67705e-7 0 1 -4.72408e-7 0 1 3.14344e-6 0 1 8.91803e-7 0 1 3.69148e-6 0 1 -1.68838e-5 0 1 1.58217e-5 0 1 1.9613e-6 0 1 5.39741e-6 0 1 -1.88915e-6 0 1 7.15277e-6 0 1 -1.40907e-6 0 -1 -6.7198e-7 0 -1 -1.54129e-6 0 -1 1.29853e-7 0 -1 -8.81721e-6 0 -1 -2.72962e-6 0 -1 -4.83512e-6 0 -1 2.60849e-5 0 -1 -2.12809e-7 0 -1 0 0 -1 2.62585e-6 0 -1 9.07736e-7 0 -1 -3.82463e-7 0 -1 9.93035e-7 0 -1 4.15127e-7 0 -1 1.04682e-6 0 -1 -3.13221e-6 0 -1 2.0907e-6 0 -1 -2.59218e-7 0 -1 3.69149e-6 0 -1 4.13267e-6 0 -1 -4.76091e-7 0 -1 -6.50398e-7 0 -1 -9.93038e-7 0 -1 -1.04682e-6 0 -1 3.13221e-6 0 -1 0 0 -1 5.93622e-7 0 -1 -5.01354e-6 0 -1 -8.1957e-7 0 -1 3.1688e-7 0 -1 1.22113e-6 0 -1 -5.61942e-6 0 -1 6.10364e-6 0 -1 1.33785e-6 0 -1 -7.43632e-6 0 -1 -3.24006e-6 0 -1 -3.12094e-6 0 -1 5.1044e-6 0 -1 -2.48765e-6 0 -1 4.35087e-7 0 -1 4.69308e-6 0 -1 -5.43283e-7 0 -1 4.40861e-6 0 -1 -1.25952e-7 0 -1 -5.11046e-6 0 -1 -1.78534e-5 0 -1 4.00073e-6 0 -1 -1.40488e-6 0 -1 -7.15105e-6 0 -1 2.13081e-7 0 -1 -1.74657e-6 0 -1 2.27906e-6 0 -1 1.99544e-6 0 -1 1.27143e-6 0 -1 3.30544e-6 0 -1 -4.10766e-6 0 -1 1.52467e-5 0 -1 -7.55661e-7 0 -1 1.93003e-6 0 -1 0 0 -1 4.49427e-6 0 -1 -3.43711e-6 0 -1 4.03954e-6 0 -1 -2.11836e-6 0 -1 -2.72405e-6 0 -1 2.71964e-6 0 -1 1.41416e-7 0 -1 3.2853e-7 0 -1 -4.49799e-6 0 -1 5.48683e-7 0 -1 -1.46719e-6 0 -1 4.35189e-6 0 -1 1.04924e-6 0 -1 -1.76171e-6 0 -1 6.22733e-7 0 -1 -5.48997e-6 0 -1 1.05121e-5 0 -1 0.3511235 -0.9363293 0 0.3511235 -0.9363293 1.10556e-6 1 0 0 0.3511235 0.9363293 0 0 1 0 -0.9999884 0.00481975 0 -0.9971996 0 0.0747869 -0.9999865 -0.005193829 0 0 -1 0 0 -1 -2.54711e-6 -0.9450997 -0.3267824 0 -0.9642677 -0.2583755 0.05856472 -0.7054907 -0.7054892 -0.06758654 -0.3056479 -0.9469197 0.09961217 -0.1351223 -0.9897896 -0.04537135 0.6119144 -0.7896216 0.04537141 0.6550902 -0.7555508 0 0.9818716 -0.1895474 0 0.9897895 -0.135123 -0.04537165 0.74079 0.6696113 0.05339318 0.7534173 0.6532347 0.07514673 0.1346333 0.9862077 -0.09627175 -0.2074832 0.9669224 0.1483637 -0.6523013 0.7523336 -0.09218078 -0.9231868 0.3772401 0.07359409 -0.9659264 0.2588171 0 -0.9776904 -0.1887438 -0.09218126 -0.7381584 -0.6672328 0.09961253 -0.7058917 -0.7058947 0.05856418 -0.2582273 -0.9637171 -0.06758761 0.2087603 -0.9728806 0.09961169 0.2583763 -0.9642676 0.05856579 0.7054871 -0.7054929 -0.06758457 0.9469202 -0.3056461 0.09961307 0.9897896 -0.1351225 -0.04537141 0.7407906 0.6696107 0.0533936 0.7534179 0.6532338 0.07514727 0.2582274 0.9637172 -0.06758618 -0.208761 0.9728803 0.09961313 -0.2583742 0.9642681 0.05856567 -0.7867639 0.6097005 -0.09627032 -0.9411204 0.3037769 0.1483649 -0.7407919 -0.6696093 0.05339276 -0.7534132 -0.6532393 0.07514721 -0.2582274 -0.9637172 -0.06758618 0.1348938 -0.9881232 0.0735951 0.2588177 -0.9659262 0 0.7555544 -0.6550861 0 0.7896226 -0.6119132 -0.04537194 0.9897896 0.135122 0.04537129 0.9818717 0.189547 0 0.6550893 0.7555516 0 0.7058946 0.7058917 0.05856436 0.2582273 0.9637171 -0.06758761 -0.2087597 0.9728806 0.09961283 -0.2583755 0.9642679 0.05856418 -0.7054885 0.7054913 -0.06758761 -0.9469203 0.3056461 0.09961181 -0.9897894 0.1351243 -0.04537117 -0.9637169 -0.2582281 -0.06758671 -0.7381581 -0.6672333 0.09961158 -0.7058938 -0.7058923 0.05856722 -0.2582266 -0.9637174 -0.06758594 0.1348947 -0.9881232 0.07359325 0.2588188 -0.965926 0 0.755552 -0.6550887 0 0.8072845 -0.5858533 -0.07118737 0.9760281 0.2094357 0.05920976 0.9779921 0.1951944 0.07369446 0.70549 0.70549 -0.067586 0.3056467 0.9469198 0.09961462 0.2583752 0.964268 0.05856126 -0.2582287 0.9637167 -0.06758755 -0.6108816 0.788294 0.07359516 -0.7071068 0.7071068 0 -0.9818713 0.1895489 0 -0.9642681 0.2583742 0.0585646 -0.9881231 -0.134895 0.07359433 -0.9659257 -0.2588198 0 -0.6550888 -0.7555521 0 -0.7058925 -0.7058939 0.05856418 -0.2582269 -0.9637172 -0.06758749 0.2583763 -0.9642676 0.05856436 0.7054877 -0.705492 -0.06758755 0.9469198 -0.3056474 0.09961229 0.9806447 -0.1957269 0.005201458 0.9230856 0.3840397 -0.02065622 0.7381591 0.6672321 0.09961241 0.7058931 0.7058931 0.05856573 0.2582266 0.9637174 -0.06758743 -0.1348947 0.9881232 0.07359325 -0.2588184 0.965926 0 -0.7555533 0.6550872 0 -0.7058924 0.7058938 0.05856567 -0.9637174 0.2582266 -0.0675863 -0.7407892 -0.6696121 0.05339372 -0.6696107 -0.7407906 -0.0533936 0.2095059 -0.9763486 0.05339354 0.3067401 -0.9502946 -0.0533939 0.9247444 -0.3778747 0.04536998 0.97288 -0.2087625 -0.09961348 0.9410763 0.3253892 0.0921812 0.7523319 0.6523029 -0.09218323 0.3056479 0.9469196 0.09961289 0.1351239 0.9897893 -0.04537385 -0.6119114 0.7896239 0.04537361 -0.6550852 0.755555 0 -0.9818719 0.1895462 0 -0.9897909 0.1351131 -0.04537087 0.2095059 -0.9763484 0.05339646 0.3067375 -0.9502954 -0.05339491 0.9502981 -0.3067296 0.05339211 0.9763484 -0.2095068 -0.05339229 0.7896195 0.6119172 0.04537063 0.7555508 0.6550902 0 0.1895487 0.9818714 0 0.135123 0.9897895 -0.04537206 -0.6119102 0.7896248 0.04537236 -0.6550881 0.7555526 0 -0.9818733 0.1895383 -2.56621e-6 -0.98979 0.1351202 -0.04537105 -0.7407864 -0.6696154 0.05339348 -0.6696108 -0.7407907 -0.05339217 0.2095044 -0.9763489 0.05339372 0.3067392 -0.9502949 -0.05339372 0.9502945 -0.3067401 0.05339378 0.9763495 -0.2095012 -0.05339306 0.7896252 0.6119098 0.04537206 0.6672292 0.7381618 -0.09961128 0.1887424 0.9776907 0.09218132 -0.3037748 0.9411212 -0.1483646 -0.6097016 0.7867626 0.09627377 -0.9790959 0.1890095 -0.07514584 -0.9763473 0.2095123 -0.05339223 0.2095058 -0.9763485 0.05339372 0.3067366 -0.9502958 -0.05339235 0.9502942 -0.3067409 0.05339461 0.7896265 0.6119081 0.04537194 0.6672308 0.7381603 -0.09961253 -0.303776 0.9411206 -0.1483646 -0.6097029 0.7867619 0.09627169 -0.9790955 0.1890102 -0.07514816 -0.9763472 0.2095123 -0.0533933 -1 0 0 0 1 2.54313e-7 -0.7071069 0.7071067 0 0.7071064 0.7071073 0 0.7071064 -0.7071073 0 -0.7071069 -0.7071067 0 -0.7071068 -0.7071068 -2.24783e-7 -0.7071058 0.7071078 0 0.7071068 0.7071068 8.99133e-7 0.7071068 0.7071068 0 0.7071068 -0.7071068 -1.79827e-6 0.7071055 -0.7071081 -1.79827e-6 -0.7071086 -0.707105 0 -0.7071068 -0.7071068 0 -0.6998906 0.7139059 0.02217191 -0.7548877 0.6548541 -0.03620696 -0.9903011 -0.1351934 0.03204309 -0.981872 -0.1895455 0 -0.6727694 -0.7398523 0 -0.6459296 -0.763141 -0.01977419 0.7051973 -0.6998527 0.1135914 0.957077 -0.2587414 -0.1306003 0.9570769 0.2587414 0.1306021 0.7052006 0.699849 -0.1135931 0.009805917 -0.9954084 -0.09521585 0.001019537 -0.9999774 0.006648957 0.009805917 0.995408 0.09522038 0.001019537 0.9999774 -0.006648957 -0.6459324 0.7631385 0.01977425 -0.6727694 0.7398523 0 -0.981872 0.1895455 0 -0.9903011 0.1351934 -0.03204309 -0.7548877 -0.6548541 0.03620696 -0.6998884 -0.7139081 -0.02217203 0.7095971 -0.7042168 0.02346968 0.7681981 -0.6392725 -0.03467643 0.9645119 0.2607523 0.04153448 0.9299838 0.3636341 -0.05385541 0.003489732 -0.9997526 -0.02196902 0.009839713 0.9988402 0.04713374 0.005261421 0.9999631 -0.006815314 -0.7071077 0.7071059 0 -0.7071068 -0.7071068 -8.99133e-7 -0.7071077 -0.7071059 0 0.7071068 -0.7071068 0 0.6458443 -0.7630321 0.02582973 0.7672475 -0.638486 -0.06055682 0.9797812 -0.1891477 0.06520795 0.9797812 0.1891477 -0.0652076 0.7537592 0.6538733 0.06555092 0.6459341 0.7631371 -0.01977276 -0.7095983 0.7042156 0.02346968 -0.7681978 0.639273 -0.03467506 -0.96451 -0.2607589 0.04153615 -0.9764229 -0.1884936 0.1052073 -0.6428999 -0.7595558 -0.0987662 -0.003489732 0.9997527 -0.02196669 -0.001019537 0.9999774 0.006648957 -0.009787499 -0.9935399 0.1130605 0.003487765 -0.9991821 -0.04028731 0.6459341 -0.7631371 0.01977276 0.75376 -0.6538723 -0.06555086 0.9797812 -0.1891477 0.0652076 0.9797812 0.1891477 -0.06520795 0.7537605 0.653872 0.0655502 0.6459295 0.7631409 -0.01977562 -0.7051997 0.6998504 0.113591 -0.9570747 0.2587488 -0.1306036 -0.9570751 -0.2587485 0.1306007 -0.7052009 -0.6998492 -0.1135908 -0.009805798 0.9954082 -0.09521812 -0.001019537 0.9999774 0.006646633 -0.009805917 -0.995408 0.09522038 -0.001019537 -0.9999774 -0.006648957 -0.7052022 0.6998482 0.1135889 -0.957075 0.2587479 -0.1306023 -0.9570751 -0.2587479 0.1306014 -0.7052006 -0.699849 -0.1135931 0.9299822 -0.3636384 0.05385553 0.9645121 -0.2607514 -0.04153519 0.7681981 0.6392725 0.03467524 0.7096006 0.7042132 -0.02346754 0.03855317 -0.9982471 -0.04490494 -0.01751649 -0.9954901 0.09323436 0.009473264 0.9997209 0.02164024 -0.03844225 0.9953948 -0.08781462 0.00897634 0.004939079 -0.9999476 -0.0217784 -0.01428705 -0.9996607 7.15973e-4 -0.02840095 -0.9995964 0.02794665 -0.01811927 -0.9994452 0.03054457 0.0114606 -0.9994677 -0.008791327 0.004701733 -0.9999503 0.02248412 0.01397413 -0.9996495 0.02972418 0.006479501 -0.9995372 -9.52796e-4 0.02930986 -0.99957 0.0389198 0.03678876 -0.9985649 0.02746051 0.05279672 -0.9982277 -0.02182936 0.0120902 -0.9996886 -0.01892089 0.03321337 -0.9992693 -0.004201352 0.03200381 -0.9994789 0.009250044 0.00491333 -0.9999452 0.005678176 0.027287 -0.9996115 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.2615009 -0.9650718 0.01592904 0.1642143 -0.9864223 -0.002203762 0.1543675 -0.9880133 -6.02821e-4 0.6710385 -0.7414182 0.00256592 0.6723685 -0.7402127 0.002389073 0.8656007 -0.5005153 0.01482933 0.9590252 -0.2833069 -0.002825856 0.9987457 0.04634135 0.01896452 0.9649266 0.2625188 7.31094e-4 0.8739469 0.4858126 0.01425307 0.6829459 0.7304214 -0.008342981 0.4069677 0.9133125 0.01541805 0.1971632 0.9803695 -0.001579403 -0.04096859 0.9990685 0.01355421 -0.3474537 0.9376614 -0.008192539 -0.6212088 0.7834945 0.01536691 -0.7883504 0.6151407 -0.01028507 -0.2958254 0.9547999 -0.02906417 -0.9905492 0.1349264 0.0246427 -0.9969723 -0.07772243 -0.002342879 -0.9115158 -0.4109194 0.01686304 -0.8203816 -0.5718153 0.001167178 -0.5796363 -0.8147864 0.01204049 -0.4671584 -0.8841723 0.001535832 -0.03038793 0.01738053 0.9993872 -0.00824052 -0.02212816 0.9997213 -0.002675294 -0.0455414 0.9989589 0.01605558 0.04259747 0.9989634 0.146802 -0.05616074 0.9875704 0.007415592 -0.02489972 0.9996625 0.01380962 -0.02951997 0.9994688 -0.2772218 -0.9594697 -0.05065453 -0.03181493 -0.9992466 0.0222271 0.07950413 -0.9967988 -0.008441925 0.4903856 -0.8713972 0.01373952 0.4917356 -0.8706488 0.0129106 0.830164 -0.5565288 -0.03321897 0.925598 -0.3767185 0.03676205 0.9873045 -0.1576285 -0.0195747 0.9875581 0.1572296 -0.002825736 0.9867588 0.1621063 -0.005357265 0.8235933 0.5654009 -0.04489952 0.6747992 0.7372167 0.03402477 0.402157 0.9146562 -0.04091542 0.2297706 0.9731749 0.01166999 -0.03590387 0.9986642 -0.03715932 -0.3677579 0.9294942 0.0281921 -0.3969774 0.9177311 0.01336443 -0.7708237 0.6361724 -0.03340297 -0.8832249 0.4686819 0.01584547 -0.9179931 0.3964697 -0.01002961 -0.9983072 -0.05651694 0.01373815 -0.9956494 -0.09299165 -0.005906403 -0.7590472 -0.6510091 -0.005876183 -0.6975619 -0.7150226 0.04636973 0.3904362 -0.1717632 -0.9044651 0.6696642 -0.4463811 -0.5935435 0.3938184 -0.7018748 -0.5935309 0.1234173 -0.3790752 -0.9170989 -0.230356 -0.6068704 -0.7606868 -0.7251263 -0.6246564 -0.289821 -0.3426081 -0.1844256 -0.9211987 -0.9917674 -0.09220999 -0.08885347 -0.5054349 0.1317318 -0.85275 -0.2088553 0.2915681 -0.9334707 -0.4651263 0.1470252 0.8729498 -0.5725243 0.7214145 0.3895858 -0.1444426 0.4402242 0.8861935 0.2767152 0.3391422 0.8991169 0.2044761 -0.4388813 0.8749702 -0.8350776 -0.5190122 -0.1824061 -0.8670185 0.4636943 -0.1823911 -0.03086686 0.983946 -0.1757771 0.8362741 0.5179722 -0.1798626 0.8663507 -0.4637674 -0.1853548 0.03194028 -0.9826809 -0.1825323 -0.02798253 0.5425617 -0.8395498 0.4264249 0.3222829 -0.8451601 -0.4731106 0.2573561 -0.8425759 -0.4464176 -0.3017305 -0.8424193 0.03154593 -0.5407651 -0.840582 0.477876 -0.2474098 -0.8428659 -0.835129 -0.5499848 -0.008746385 -0.8614884 -0.5066946 -0.03314477 -0.8389872 -0.5441353 -0.004143536 -0.8940004 0.4480125 -0.006929218 -0.8692446 0.493629 -0.02728217 -0.8895579 0.4568224 -3.3329e-4 -0.05765938 0.9983362 -6.46536e-4 -0.007252573 0.9995762 -0.02819621 -0.05340033 0.998571 0.002117335 0.8268846 0.5607278 -0.0429697 0.8677325 0.4952776 0.04171717 0.8350579 0.5501441 0.004455149 0.8945153 -0.4470375 -6.57912e-5 0.9063405 -0.4221618 -0.01806843 0.87026 -0.4878714 -0.06803768 0.05986016 -0.998206 -0.001307904 0.008305251 -0.9993613 -0.03475666 0.0591889 -0.9982464 -8.61969e-4 -0.689817 -0.2197057 0.6898419 -0.4411965 -0.01900327 0.8972094 -0.2428194 0.03760075 0.9693426 -0.5905306 0.3342529 0.7345397 -0.3653115 0.2844129 0.8863729 -0.5061013 0.5583183 0.6573752 -0.2194408 0.5138833 0.8293189 -0.1644334 0.442249 0.8816903 -0.09911453 0.7279606 0.6784171 0.1061394 0.5462302 0.8308833 0.1065491 0.5323913 0.839766 0.4128615 0.6563192 0.6314986 0.3196138 0.3426361 0.8834295 0.6073415 0.4559103 0.6506013 0.5335183 0.1715736 0.8282034 0.4623149 0.1263558 0.8776668 0.73887 0.03183555 0.6730956 0.5351984 -0.1564112 0.8301194 0.5382377 -0.1565804 0.8281201 0.6157115 -0.4718715 0.63106 0.3213019 -0.3563375 0.8773761 0.4059842 -0.6662418 0.6255387 -0.2455662 -0.3903539 0.8873112 -0.2997673 -0.5499959 0.7795154 -0.1684024 -0.8666455 0.4696447 0.09637498 -0.5366756 0.8382669 0.0835334 -0.5063261 0.8582867 -0.4961167 -0.373587 0.7837737 -0.4466927 -0.3137235 0.8378803 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -1.27108e-7 0 1 -3.71662e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 1.40488e-4 -0.999998 0.002022683 6.42282e-4 -0.9999928 -0.003748059 0.9471275 -0.3208577 0 0.9472864 -0.3203478 -0.005066692 -0.9459555 0.324185 -0.008501708 -0.9462245 0.323511 7.16303e-7 -0.002529323 0.9999141 -0.01286518 -0.001293241 0.9999982 0.001374721 -0.9471274 0.3208577 0 -0.9468566 0.3215739 0.007265925 0.9455122 -0.3240329 -0.03177475 0.9468817 -0.3215824 7.30356e-7 -0.004424512 -0.9999902 0 -0.005900621 -0.999971 0.004826128 0.003200769 -0.9999949 0 0.004280149 -0.999979 -0.00487858 -0.004424512 0.9999902 0 -0.005900621 0.999971 -0.004826128 -0.9472086 -0.320618 -8.03155e-7 -0.9472953 -0.320351 0.002666056 0.9459556 0.3241848 0.008502364 0.9462243 0.3235112 0 -0.5545782 -0.8321317 0 -0.5545787 -0.8321313 0 -0.8185655 -0.5744133 0 -0.8185667 -0.5744114 0 -0.971141 -0.2385063 0 -0.9711403 -0.2385088 0 -0.9915324 0.1298602 0 -0.876967 0.480551 0 -0.8769657 0.480553 0 -0.6321781 0.7748231 0 -0.6428716 0.7656406 0.02259814 -0.4216139 0.9060843 -0.03539985 -0.2472693 0.9684236 0.03183823 -0.2736505 0.9618293 -2.82691e-6 0.04364222 0.9990473 0 0.04364246 0.9990473 0 0.4029266 0.9152323 0 0.7073687 0.7068448 0 0.707368 0.7068455 0 0.9155302 0.4022496 0 0.9155303 0.4022489 -1.24184e-6 0.9990794 0.04290211 -6.89323e-7 0.9990792 0.04290342 0 0.9466437 -0.3222821 0 0.9466433 -0.3222833 0 -0.9659259 -0.2588186 0 -0.9659257 -0.2588196 0 -0.7071089 -0.7071047 0 -0.7071068 -0.7071068 -2.10555e-6 -0.2588176 -0.9659263 0 -0.2588226 -0.965925 0 0.2588186 -0.9659259 0 0.2588226 -0.965925 0 0.9659259 -0.2588186 0 0.9659259 0.2588186 0 0.2588186 0.9659259 0 -0.2588186 0.9659259 0 -0.9659259 0.2588186 0 -0.9659263 0.2588176 0 -0.9503219 -0.3067452 -0.05287563 -0.7408125 -0.6696277 0.0528751 -0.2095038 -0.9763773 -0.05287438 0.2095004 -0.976378 0.05287349 0.7408145 -0.6696254 -0.05287492 0.9251567 -0.3780497 0.03411453 0.9447652 0.326668 -0.02658778 0.9514819 0.3071258 -0.01886808 0.307116 0.951485 0.01887035 0.2097619 0.9775704 -0.01887047 -0.612464 0.7903361 0.01602905 -0.7413851 0.6701499 -0.03531599 -0.9813491 0.1894404 0.03265661 -0.7417133 -0.6704517 0.01886796 -0.6704446 -0.7417199 -0.01886558 0.2097717 -0.9775683 0.01887053 0.3071272 -0.9514815 -0.01886814 0.9255789 -0.3782154 0.01602685 0.9450999 -0.3267818 0 0.9450999 0.3267818 0 0.9255809 0.3782104 -0.01602905 0.3782233 0.9255757 0.01602888 0.3267894 0.9450973 0 -0.3267894 0.9450973 0 -0.3782233 0.9255757 -0.01602602 -0.9514842 0.3071188 0.01886934 -0.9775695 0.2097663 -0.01886814 -0.2163641 0.9753987 0.04223746 -0.6149117 0.7871344 -0.04799157 -0.8768074 0.4792616 0.03895056 -0.9954974 -0.08287006 -0.04601705 -0.9344009 -0.3549562 0.03002244 0.2165613 -0.9762322 0.008487045 0.2876185 -0.9576631 -0.01253145 0.8773953 -0.4795746 0.01363188 0.9147185 -0.4038621 -0.01363062 0.934748 0.3550903 0.01253426 0.9062045 0.4227546 -0.008488357 -0.4534634 -0.8912351 -0.008423328 -0.4523511 -0.8917907 -0.009372413 0.4523528 0.8918046 0.007851183 0.4017435 0.9152455 -0.03046095 -0.3251727 0.9455819 0.01173949 -0.2920126 0.956131 0.02328532 -0.8284081 0.5590853 -0.03411626 -0.9479521 0.3165804 0.03411531 -0.9362087 -0.3506726 -0.02328151 -0.9480338 -0.3179532 -0.01173669 0.2545574 -0.9670091 0.009690046 0.2920919 -0.9563903 0 0.7968662 -0.6041558 0 0.8287823 -0.5593417 -0.01602756 0.9721221 0.233833 0.01734548 0.9480354 0.3179485 -0.01173675 -0.4288795 -0.9032987 -0.01067453 -0.4552819 -0.8902834 0.01067703 0.4552798 0.8902844 0.01067954 0.4288796 0.9032986 -0.01067703 0.9466431 0.3222838 1.37865e-6 0.9466435 0.3222826 0 0.9990792 -0.04290342 0 0.9990794 -0.04290211 6.53803e-7 0.9155303 -0.4022489 1.37865e-6 0.9155302 -0.4022496 0 0.707368 -0.7068455 0 0.7073694 -0.7068442 3.661e-6 0.4029266 -0.9152323 0 0.4029254 -0.9152329 0 0.0436424 -0.9990473 0 0.04364246 -0.9990473 0 -0.3215838 -0.9468812 0 -0.3215833 -0.9468814 0 -0.6430358 -0.7658361 0 -0.8769657 -0.480553 0 -0.876967 -0.480551 0 -0.9915324 -0.1298602 0 -0.9711403 0.2385088 0 -0.971141 0.2385063 0 -0.8185667 0.5744114 0 -0.8185655 0.5744133 0 -0.5545787 0.8321313 0 -0.5545775 0.8321321 0 -0.9659263 -0.2588176 0 -0.2588186 -0.9659259 0 0.9659252 -0.2588215 0 0.9659257 0.2588196 0 0.965925 0.2588226 0 0.2588226 0.965925 0 -0.2588226 0.965925 0 -0.9659257 0.2588196 0 -0.9251586 -0.3780447 -0.03411608 -0.7408124 -0.6696276 0.05287736 0.2095048 -0.9763771 0.05287462 0.7408121 -0.6696278 -0.05287706 0.95032 -0.3067508 0.05287694 0.9503206 0.3067494 -0.05287551 0.7408099 0.6696305 0.05287575 0.3265978 0.944599 -0.03265976 -0.2096664 0.9771351 0.03531324 -0.3782104 0.9255809 -0.01602905 -0.9514837 0.3071202 0.01886856 -0.9447644 0.32667 0.02658796 -0.9775695 -0.2097663 0.01886814 -0.9514842 -0.3071188 -0.0188682 -0.3782233 -0.9255757 0.01602602 -0.3267952 -0.9450952 0 0.3267894 -0.9450973 0 0.3782233 -0.9255757 -0.01602888 0.9514847 -0.3071174 0.01886814 0.9775705 -0.2097619 -0.01886874 0.7417135 0.6704514 0.01886808 0.6704445 0.7417198 -0.0188679 -0.1352488 0.9906821 0.01602917 -0.1895565 0.9818698 0 -0.7555481 0.6550932 0 -0.7903311 0.6124704 -0.01602905 -0.9344001 0.3549581 -0.03002333 -0.9954974 0.08287006 0.04601734 -0.8768088 -0.4792594 -0.03894937 -0.6149072 -0.7871378 0.0479924 -0.2163713 -0.975397 -0.04224222 0.9062045 -0.4227546 0.008489131 0.9347488 -0.3550883 -0.0125364 0.9147185 0.4038621 0.01363062 0.8773953 0.4795746 -0.01363188 0.287624 0.9576614 0.01253443 0.2165613 0.9762322 -0.008487045 0.4523528 -0.8918046 -0.007848501 0.4017443 -0.9152451 0.03046339 -0.4534654 0.8912342 0.00841844 -0.4523511 0.8917907 0.009372413 -0.9220266 0.3870053 0.009694278 -0.9718202 0.2337655 -0.03032082 -0.9639739 -0.2639847 0.03265631 -0.7964467 -0.6038264 -0.03265601 -0.4064347 -0.9131767 0.03032225 -0.2545574 -0.9670092 -0.009693503 0.9480354 -0.3179485 0.01173675 0.9721221 -0.233833 -0.01734548 0.8287823 0.5593417 0.01602756 0.7968662 0.6041558 0 0.2920919 0.9563903 0 0.2545574 0.9670091 -0.009690046 0.4552798 -0.8902844 -0.01067954 0.4288796 -0.9032986 0.01067447 -0.4288795 0.9032987 0.01067453 -0.4552798 0.8902844 -0.01067703 -0.9466431 -0.3222838 1.37865e-6 -0.9466434 -0.322283 6.89325e-7 -0.9990792 0.04290342 -1.72331e-7 -0.9990794 0.04290205 8.26133e-7 -0.9155303 0.4022489 1.37865e-6 -0.9155302 0.4022496 0 -0.707368 0.7068455 0 -0.7073687 0.7068448 0 -0.4029266 0.9152323 0 -0.04364246 0.9990473 0 0.3215833 0.9468814 0 0.6430358 0.7658361 0 0.8769657 0.480553 0 0.876967 0.480551 0 0.9915324 0.1298602 0 0.9711403 -0.2385088 0 0.971141 -0.2385063 0 0.8185667 -0.5744114 0 0.8185655 -0.5744133 0 0.5545787 -0.8321313 0 0.5545775 -0.8321321 0 0.9659257 -0.2588196 0 0.9659263 0.2588176 0 0.2588186 0.9659259 -2.10555e-6 -0.9503206 -0.3067494 -0.05287551 -0.7408099 -0.6696305 0.05287575 -0.3265978 -0.944599 -0.03265976 0.2096664 -0.9771351 0.03531324 0.3782104 -0.9255809 -0.01602905 0.9514837 -0.3071202 0.01886856 0.9447644 -0.32667 0.02658957 0.9251586 0.3780447 -0.03411608 0.7408124 0.6696276 0.05287736 0.2095038 0.9763773 -0.05287438 -0.2095048 0.9763771 0.05287462 -0.7408121 0.6696278 -0.05287706 -0.95032 0.3067508 0.05287694 -0.7417135 -0.6704514 0.01886808 -0.6704445 -0.7417198 -0.0188679 0.1352488 -0.9906821 0.01602917 0.1895565 -0.9818698 0 0.7555481 -0.6550932 0 0.7903311 -0.6124704 -0.01602905 0.9775695 0.2097663 0.01886814 0.9514842 0.3071188 -0.0188682 0.3782233 0.9255757 0.01602602 0.3267952 0.9450952 0 -0.3782233 0.9255757 -0.01602888 -0.9514847 0.3071174 0.01886814 -0.9775705 0.2097619 -0.01886874 0.9344001 -0.3549581 -0.03002333 0.9954974 -0.08287006 0.04601734 0.8768088 0.4792594 -0.03894937 0.6149072 0.7871378 0.0479924 0.2163713 0.975397 -0.04224222 -0.9062045 0.4227546 0.008489131 -0.9347488 0.3550883 -0.0125364 -0.9147185 -0.4038621 0.01363062 -0.8773953 -0.4795746 -0.01363188 -0.287624 -0.9576614 0.01253443 -0.2165613 -0.9762322 -0.008487045 -0.4523528 0.8918046 -0.007848501 -0.4017443 0.9152451 0.03046339 0.4534654 -0.8912342 0.00841844 0.4523511 -0.8917907 0.009372413 0.9220266 -0.3870053 0.009694278 0.9718202 -0.2337655 -0.03032082 0.9639739 0.2639847 0.03265631 0.7964467 0.6038264 -0.03265601 0.4064347 0.9131767 0.03032225 0.2545574 0.9670092 -0.009693503 -0.9480354 0.3179485 0.01173675 -0.9721221 0.233833 -0.01734548 -0.8287823 -0.5593417 0.01602756 -0.7968662 -0.6041558 0 -0.2920919 -0.9563903 0 -0.2545574 -0.9670091 -0.009690046 -0.4552798 0.8902844 -0.01067954 -0.4288796 0.9032986 0.01067447 0.4288795 -0.9032987 0.01067453 0.4552798 -0.8902844 -0.01067703 0.947079 0.3210011 8.03804e-7 0.9468656 0.3215769 -0.005824983 0.9476831 0.3191476 0.006456255 -0.9459556 -0.3241848 0.008501708 -0.9462245 -0.3235111 0 0.5545775 0.8321321 0 0.5545787 0.8321313 0 0.818566 0.5744127 0 0.8185667 0.5744114 -5.49158e-7 0.971141 0.2385066 -6.89325e-7 0.9711405 0.2385082 -2.06797e-6 0.9915324 -0.1298602 0 0.9915323 -0.1298606 0 0.876967 -0.480551 0 0.8769657 -0.480553 0 0.6430364 -0.7658356 0 0.6430358 -0.7658361 -2.85333e-6 0.3215837 -0.9468812 2.75729e-6 0.3215833 -0.9468814 0 -0.04364246 -0.9990473 0 -0.4029266 -0.9152323 0 -0.7073687 -0.7068448 0 -0.707368 -0.7068455 0 -0.9155302 -0.4022496 0 -0.9155306 -0.4022485 0 -0.9990793 -0.04290348 0 -0.9990794 -0.04290068 -9.07129e-7 -0.9466435 0.3222826 0 -0.9466434 0.322283 0 -0.9659259 -0.2588186 -1.05278e-6 -0.9659263 -0.2588176 -1.05277e-6 -0.7071048 -0.7071089 -2.10554e-6 0.2588186 -0.9659259 2.10555e-6 0.9659263 -0.2588176 0 -0.965925 0.2588226 0 -0.9659271 0.2588147 -1.05278e-6 -0.9447652 -0.326668 -0.02658778 -0.9514819 -0.3071258 -0.01886808 -0.307116 -0.951485 0.01887035 -0.2097619 -0.9775704 -0.01887047 0.612464 -0.7903361 0.01602905 0.7413851 -0.6701499 -0.03531599 0.9813491 -0.1894404 0.03265661 0.9503219 0.3067452 -0.05287563 0.7408125 0.6696277 0.0528751 -0.2095004 0.976378 0.05287349 -0.7408145 0.6696254 -0.05287492 -0.9251567 0.3780497 0.03411453 -0.9450999 -0.3267818 0 -0.9255809 -0.3782104 -0.01602905 -0.3782233 -0.9255757 0.01602888 -0.3267894 -0.9450973 0 0.3782233 -0.9255757 -0.01602602 0.9514842 -0.3071188 0.01886934 0.9775695 -0.2097663 -0.01886814 0.7417133 0.6704517 0.01886796 0.6704446 0.7417199 -0.01886558 -0.2097717 0.9775683 0.01887053 -0.3071272 0.9514815 -0.01886814 -0.9255789 0.3782154 0.01602685 -0.9450999 0.3267818 0 0.2163641 -0.9753987 0.04223746 0.6149117 -0.7871344 -0.04799157 0.8768074 -0.4792616 0.03895056 0.9954974 0.08287006 -0.04601705 0.9344009 0.3549562 0.03002244 -0.2165613 0.9762322 0.008487045 -0.2876185 0.9576631 -0.01253145 -0.8773953 0.4795746 0.01363188 -0.9147185 0.4038621 -0.01363062 -0.934748 -0.3550903 0.01253426 -0.9062045 -0.4227546 -0.008488357 0.4534634 0.8912351 -0.008423328 0.4523511 0.8917907 -0.009372413 -0.4523528 -0.8918046 0.007851183 -0.4017435 -0.9152455 -0.03046095 0.3251727 -0.9455819 0.01173949 0.2920126 -0.956131 0.02328532 0.8284081 -0.5590853 -0.03411626 0.9479521 -0.3165804 0.03411531 0.9362087 0.3506726 -0.02328151 0.9480338 0.3179532 -0.01173669 -0.2545574 0.9670091 0.009690046 -0.2920919 0.9563903 0 -0.7968662 0.6041558 0 -0.8287823 0.5593417 -0.01602756 -0.9721221 -0.233833 0.01734548 -0.9480354 -0.3179485 -0.01173675 0.4288795 0.9032987 -0.01067453 0.4552819 0.8902834 0.01067703 -0.4552798 -0.8902844 0.01067954 -0.4288796 -0.9032986 -0.01067703 0.9537499 0.3001527 0.01641607 0.943212 0.3321918 0 0.6532171 0.7571708 0 0.6532189 0.7571691 0 0.2350517 0.9719829 0 0.235053 0.9719825 0 -0.5963159 0.8027374 -0.004496872 -0.5658296 0.8244269 0.01254194 0.9540483 -0.2991753 -0.01691377 0.9432119 -0.3321921 0 0.6205662 -0.7841541 0 0.5952107 -0.8034284 0.01507061 -0.5821767 -0.8130508 0.004347801 -0.5549649 -0.8317799 -0.01249867 0.8603506 -0.5094632 0.01563048 0.5848523 -0.8109756 -0.01632887 0.5293051 -0.8483555 0.01136535 -0.9952195 0.08993995 -0.03806561 -0.9535039 -0.3000777 0.02799898 -0.9270148 -0.3750249 0 -0.6205662 -0.7841541 0 -0.5952107 -0.8034284 -0.01507061 0.580939 0.8139356 0.004333674 0.5536879 0.8326275 -0.01269447 -0.9532383 0.3018185 -0.01556915 -0.943212 0.3321918 0 -0.6205662 0.7841541 0 -0.5952107 0.8034284 0.01507061 -0.9907615 -0.1352548 0.009893298 -0.6546145 -0.7550041 -0.03806567 -0.6930427 -0.7206192 -0.01999813 0.1352441 -0.9906827 0.01602786 0.1895476 -0.9818716 0 0.7555515 -0.6550892 0 0.7903342 -0.6124663 -0.01602786 0.9906827 0.1352441 0.0160278 0.9818716 0.1895476 0 0.6550892 0.7555516 0 0.6124663 0.7903342 -0.01602798 -0.1352441 0.9906827 0.01602786 -0.3254604 0.9446684 -0.04095202 -0.7549283 0.6545489 0.04060912 -0.9947941 0.08962649 -0.04849416 0.7071066 0.707107 0 0.7071073 0.7071063 0 0.7071075 -0.7071061 0 -0.7071066 0.707107 0 -0.9902332 -0.1351827 0.03411692 -0.6548575 -0.7552846 -0.02658879 -0.7552851 -0.654857 0.02658808 -0.1351827 -0.9902332 -0.03411626 0.1351827 -0.9902332 0.0341165 0.7552855 -0.6548566 -0.02658802 0.7417171 -0.6704475 -0.01886808 0.9906829 0.1352428 0.01602798 0.9510595 0.3069837 -0.03531116 0.6547387 0.7551496 0.03265595 0.2095108 0.9763757 -0.05287522 -0.135182 0.9902334 0.03411602 -0.7552847 0.6548573 -0.02658808 -0.6548565 0.7552855 0.02658843 -0.9902332 0.1351827 -0.03411686 -0.9902332 -0.1351827 0.03411686 -0.6548566 -0.7552855 -0.02658802 -0.6704481 -0.7417165 -0.01886808 0.1352434 -0.9906828 0.01602751 0.3069842 -0.9510594 -0.03531175 0.7551492 -0.6547391 0.03265619 0.9763757 -0.2095108 -0.05287539 0.9902334 0.1351814 0.0341168 0.6548575 0.7552846 -0.02658802 0.7552851 0.654857 0.02658808 0.1351827 0.9902332 -0.03411704 -0.1351827 0.9902332 0.03411704 -0.7552851 0.654857 -0.02658808 -0.6548575 0.7552846 0.02658879 -0.9902332 0.1351828 -0.03411698 -0.9906829 -0.1352428 0.01602798 -0.9818716 -0.1895477 0 -0.6550881 -0.7555526 0 -0.7069559 -0.7069547 0.02070134 -0.135182 -0.9902334 -0.03411632 0.135182 -0.9902334 0.03411602 0.7552847 -0.6548573 -0.02658808 0.6548565 -0.7552855 0.02658843 0.9902332 -0.1351827 -0.03411686 0.9902332 0.1351827 0.03411692 0.6548575 0.7552846 -0.02658879 0.1351827 0.9902332 -0.03411626 -0.1351827 0.9902332 0.0341165 -0.7552855 0.6548566 -0.02658802 -0.7417171 0.6704475 -0.01886808 -0.9902334 -0.1351814 0.0341168 -0.6548575 -0.7552846 -0.02658802 -0.1351827 -0.9902332 -0.03411704 0.1351827 -0.9902332 0.03411704 0.7552851 -0.654857 -0.02658808 0.6548575 -0.7552846 0.02658879 0.9902332 -0.1351828 -0.03411698 0.9902332 0.1351827 0.03411686 0.6548566 0.7552855 -0.02658802 0.6704481 0.7417165 -0.01886808 -0.1352434 0.9906828 0.01602751 -0.3069842 0.9510594 -0.03531175 -0.7551492 0.6547391 0.03265619 -0.9763757 0.2095108 -0.05287539 -0.9447661 -0.3266654 -0.02658915 -0.9514864 -0.3071118 -0.0188682 -0.3071227 -0.951483 0.01886749 -0.3266686 -0.9447649 0.02658796 0.3780461 -0.925158 -0.03411698 0.6696254 -0.7408145 0.05287504 0.9763762 -0.2095084 -0.05287563 0.9902345 0.1351729 0.03411602 0.6548552 0.7552867 -0.026587 0.7552828 0.6548596 0.02658748 0.1351831 0.9902332 -0.0341171 -0.2095114 0.9763755 0.05287599 -0.7408102 0.6696302 -0.05287551 -0.9251598 0.3780418 0.03411692 -0.9251597 -0.3780417 -0.0341174 -0.7408096 -0.6696308 0.05287611 -0.2095114 -0.9763755 -0.05287623 0.1351845 -0.990233 0.03411763 0.7552828 -0.6548596 -0.02658748 0.6548551 -0.7552866 0.02658742 0.9902345 -0.1351729 -0.03411602 0.9763761 0.2095086 0.05287569 0.6696254 0.7408145 -0.05287492 0.3780461 0.925158 0.03411716 -0.3266686 0.9447649 -0.02658796 -0.3071227 0.951483 -0.01886749 -0.9514865 0.3071115 0.0188682 -0.9447661 0.3266654 0.02658933 -0.9775707 -0.209761 0.01886838 -0.9815269 -0.1894683 0.02658838 -0.6121841 -0.7899791 -0.03411674 -0.3067487 -0.9503208 0.05287551 0.3067479 -0.950321 -0.05287557 0.6121869 -0.7899768 0.0341168 0.9815245 -0.1894806 -0.026587 0.9775707 -0.2097609 -0.01886832 0.7552803 0.6548624 0.0265873 0.1351845 0.990233 -0.03411781 -0.1351845 0.990233 0.03411763 -0.7552843 0.6548579 -0.0265882 -0.7417164 0.6704483 -0.01886755 -0.990684 -0.1352348 0.01602798 -0.9818728 -0.1895415 0 -0.65509 -0.7555509 0 -0.6124657 -0.7903347 -0.01602816 0.1352459 -0.9906824 0.01602828 0.189549 -0.9818713 0 0.7555513 -0.6550895 0 0.7903295 -0.6124726 -0.01602751 0.9775707 0.2097613 0.01886838 0.9514849 0.3071167 -0.0188688 0.3071229 0.9514829 0.01886856 0.2097713 0.9775684 -0.01886868 -0.6704453 0.7417191 0.01886874 -0.7417132 0.6704517 -0.01886814 -0.7417172 -0.6704474 0.01886802 -0.670452 -0.741713 -0.01886743 0.1352415 -0.990683 0.01602661 0.1895454 -0.981872 0 0.7555551 -0.6550852 0 0.7903454 -0.6124518 -0.01602721 0.9775686 0.2097707 0.01886808 0.9514819 0.3071258 -0.01886779 0.3782137 0.9255796 0.01602768 0.2096695 0.9771346 -0.03531128 -0.326601 0.944598 0.03265601 -0.6547452 0.755144 -0.03265708 -0.9510579 0.3069889 0.03530991 -0.9906814 0.1352538 -0.01602751 -0.7417213 -0.6704429 0.01886874 -0.6704471 -0.7417175 -0.01886904 0.1352415 -0.990683 0.01602739 0.1895462 -0.9818718 0 0.7555544 -0.6550859 0 0.790345 -0.6124525 -0.01602721 0.9775686 0.2097707 0.01886785 0.9514819 0.3071258 -0.01886749 0.3782156 0.9255788 0.0160284 0.20967 0.9771344 -0.03531128 -0.3266047 0.9445968 0.03265637 -0.6547448 0.7551444 -0.03265631 -0.9510578 0.3069893 0.03530991 -0.9906814 0.1352536 -0.01602739 -0.7071076 0.7071059 0 -0.7071068 0.7071068 6.7435e-7 0.707107 0.7071066 3.37175e-7 0.7071071 0.7071066 6.74349e-7 -0.7071063 -0.7071073 0 -0.7071076 -0.7071059 0 0.707107 -0.7071066 0 0.7071063 0.7071073 3.37175e-7 0.7071065 0.7071071 6.7435e-7 -0.7071071 0.7071066 0 -0.707107 0.7071066 -3.37175e-7 0.7071063 -0.7071073 -6.7435e-7 0.7071068 -0.7071068 6.7435e-7 -0.9763759 -0.2095096 0.0528751 -0.7551508 -0.6547372 -0.03265607 -0.3069842 -0.9510594 0.03531086 -0.1352444 -0.9906827 -0.01602828 0.6704447 -0.7417197 0.01886814 0.7417171 -0.6704475 -0.01886826 0.990684 0.1352345 0.01602804 0.9510613 0.3069781 -0.03531169 0.6547406 0.7551479 0.03265631 0.2095114 0.9763755 -0.05287623 -0.7552867 0.6548551 -0.02658808 -0.6548584 0.7552838 0.02658838 -0.9902336 0.1351799 -0.03411626 -0.9902336 -0.1351799 0.03411626 -0.6548584 -0.7552838 -0.02658879 -0.7552867 -0.6548551 0.02658808 -0.1351845 -0.990233 -0.03411781 0.2095114 -0.9763755 0.05287599 0.7408099 -0.6696305 -0.05287551 0.9503236 -0.30674 0.05287611 0.9813492 0.1894401 -0.03265583 0.7413842 0.6701512 0.0353108 0.6124647 0.7903354 -0.01602816 -0.1352444 0.9906827 0.01602828 -0.3069842 0.9510594 -0.03531116 -0.7551508 0.6547372 0.03265625 -0.9763759 0.2095096 -0.0528751 0.8193708 0.573264 0 0.8193715 0.5732629 0 0.8193708 0.5732641 0 0.8193712 -0.5732633 0 0.8193709 -0.573264 5.78039e-7 -0.9659271 -0.2588148 0 -0.7071058 -0.7071079 0 -0.7071114 -0.7071023 0 -0.2588198 -0.9659257 0 -0.258817 -0.9659264 0 0.2588198 -0.9659257 0 0.7071058 -0.7071079 0 0.9659243 -0.2588252 0 0.9659271 -0.2588148 0 0.9659271 0.2588148 0 0.9659243 0.2588252 0 0.7071058 0.7071079 0 0.2588198 0.9659257 0 -0.258817 0.9659264 0 -0.2588198 0.9659257 0 -0.7286791 0.6848553 0 -0.7631129 0.6459111 -0.02139234 -0.9993869 0.01247471 0.03271591 -0.999992 0.004037201 0 3.5086e-6 0 1 -4.59108e-6 0 1 1.20718e-6 0 1 -6.02296e-6 0 1 7.87593e-6 0 1 -9.93726e-7 0 1 4.58599e-6 0 1 -0.978743 0.2050852 -0.001465141 -0.6669806 0.7450737 0.001465201 -0.6179345 0.7862284 -0.001465201 -0.0320084 0.9994866 0.00146526 -0.0452696 0.9989727 0.002072274 0.416402 0.9091763 -0.002829611 0.5791683 0.8152031 0.002829611 0.8877693 0.4602842 -0.002072274 0.881585 0.4720231 -0.001465201 0.9898602 -0.1420379 0.00146526 0.9787438 -0.2050819 -0.00146526 0.6669771 -0.7450768 0.001465141 0.6179355 -0.7862275 -0.001465082 0.08033877 -0.9967669 0.001247465 0.04527103 -0.9989748 0 -0.3842109 -0.9232454 0 -0.4164081 -0.9091771 -0.001247286 -0.8495764 -0.5274638 0.00146526 -0.8815844 -0.4720243 -0.001465141 -0.9898608 0.1420336 0.001465201 0.9809067 -0.1944743 -0.001442849 0.9589254 -0.283655 0.001442909 0.3971729 -0.9177428 -0.001442849 0.3112907 -0.9503136 0.00144279 -0.4698228 -0.88276 -0.001226246 -0.5135425 -0.8580643 0 -0.913846 -0.406061 0 -0.9303677 -0.3666265 0.001056551 -0.9303677 0.3666266 -0.001056611 -0.913846 0.406061 0 -0.5135408 0.8580653 0 -0.4698213 0.8827608 0.001226246 0.2449169 0.9695433 -0.001226186 0.2932742 0.9560284 0 0.7899054 0.6132289 0 0.8196884 0.5728084 0.001226305 -2.37518e-6 0 1 -7.47424e-7 0 1 3.34878e-6 0 1 -2.81392e-7 0 1 -4.51734e-6 0 1 4.08603e-6 0 1 -7.89561e-7 0 1 4.76837e-7 0 1 2.74266e-6 0 1 6.14813e-6 0 1 5.63014e-6 0 1 2.17989e-5 0 1 -3.89336e-6 0 1 -2.34716e-6 0 1 -4.79174e-6 0 1 1.19597e-6 0 1 2.6154e-6 0 1 5.05059e-6 0 1 4.03047e-6 0 1 -6.20307e-6 0 1 8.34492e-6 0 1 -3.34262e-6 0 1 -5.363e-6 0 1 -8.34509e-7 0 1 1.59964e-6 0 1 -3.21778e-6 0 1 2.81507e-6 0 1 2.38802e-6 0 1 -4.0439e-6 0 1 1.14356e-6 0 1 2.24783e-7 0 1 -4.76837e-7 0 1 2.99207e-6 0 1 2.25867e-6 0 1 -4.99429e-7 0 1 1.6643e-5 0 1 -4.95247e-6 0 1 -1.42462e-6 0 1 2.12306e-6 0 1 1.04173e-6 0 1 6.42539e-7 0 1 0.3326564 0.9430342 -0.005131483 0.3217681 0.9468186 0 -0.02794426 0.9996095 0 -0.02794575 0.9996095 0 -0.8521729 -0.5232605 0 -0.8521729 -0.5232604 -2.354e-7 0.7101098 0.7040898 0.00132215 -0.9659257 0.2588196 0 0.9659256 0.2588202 0 0.9659261 0.2588183 0 0.9659261 -0.2588183 0 0.9659256 -0.2588202 0 0.7071073 -0.7071063 0 0.7071063 -0.7071073 0 0.2588193 -0.9659258 0 -0.2588193 -0.9659258 0 -0.2588183 -0.9659261 0 -0.7071083 -0.7071053 0 -0.9659261 -0.2588183 0 -0.9659261 0.2588183 0 -0.965926 0.2588188 0 -0.7071065 0.7071071 0 -0.7071076 0.707106 0 -0.2588187 0.9659259 0 -0.2588193 0.9659259 0 0.2588193 0.9659259 0 0.2588192 0.9659259 1.38851e-7 0.5047702 0.8632538 6.24942e-6 0.7101113 -0.7040895 0 0.7071063 0.7071073 0 0.2588193 0.9659258 0 -0.2588193 0.9659258 0 -0.2588183 0.9659261 0 -0.7071083 0.7071053 0 -0.7071063 0.7071073 0 -0.9812993 -0.1924884 0 -0.9658875 -0.2588084 0.008930265 -0.7490527 -0.6624261 -0.01056897 -0.7071076 -0.707106 0 -0.2588187 -0.9659259 0 -0.2588193 -0.9659259 0 0.2588188 -0.9659259 0 0.2588193 -0.9659259 0 0.5049095 -0.8631724 6.77375e-6 0.7071058 -0.7071067 0.00130093 -0.8521733 0.5232598 0 -0.8521728 0.5232607 0 0.7071065 -0.7071071 0 0.7071074 -0.7071063 0 0.7071074 0.7071063 0 0.7071065 0.7071071 0 -0.7071073 0.7071064 0 -0.7071064 0.7071073 0 0.8096331 -0.586889 -0.007453858 0.8156824 -0.5785001 0 0.9941734 -0.1077931 0 0.9941734 -0.1077933 0 0.9415504 0.3368723 0 0.9415507 0.3368716 0 0.7001504 0.7139954 0 -0.7071062 0.7071074 0 -0.707107 0.7071066 0 -0.707107 0.7071067 0 -0.02794575 -0.9996095 0 -0.02794575 -0.9996095 0 0.3221482 -0.9466893 0 0.3383746 -0.9409801 0.007694065 0.7055267 -0.7086722 0.003980278 0.7061172 -0.7080951 0 1.54747e-6 0 -1 4.54369e-6 0 -1 -6.68152e-6 0 -1 4.54368e-6 0 -1 -3.32542e-6 0 -1 -6.86346e-7 0 -1 2.44985e-7 0 -1 -1.12338e-6 0 -1 1.23434e-6 0 -1 0 0 -1 -7.62648e-7 0 -1 6.35621e-7 0 -1 -5.83692e-6 0 -1 2.01523e-6 0 -1 -2.70412e-6 0 -1 4.13594e-6 0 -1 1.08985e-5 0 -1 -8.26854e-7 0 -1 7.99067e-7 0 -1 -2.65191e-7 0 -1 0.7001504 -0.7139954 0 0.9415504 -0.3368723 0 0.9415507 -0.3368716 0 0.9941734 0.1077931 0 0.9941734 0.1077933 0 0.8156819 0.5785008 0 0.8096335 0.5868886 0.007453978 -0.7071073 -0.7071064 0 -0.7071067 -0.7071069 0 0.7059969 0.7082149 0 0.7044663 0.7096645 -0.01017743 -0.7071062 -0.7071074 4.13724e-7 -0.7071065 -0.7071071 0 -0.707107 -0.7071066 0 0.9999991 -2.30554e-4 0.001411318 0.9999991 2.30554e-4 -0.001411318 -0.965926 -0.2588186 0 0.9659257 -0.2588199 0 -0.965926 -0.2588188 0 -0.7071065 -0.7071071 0 0.2588193 -0.9659259 0 0.7071065 -0.7071071 0 0.965926 -0.2588188 0 -0.7071073 0.7071063 0 -0.9659256 0.2588202 0 0.9659258 0.2588192 6.14119e-7 -0.965926 0.2588186 0 0.9659259 0.2588187 0 0.7071052 0.7071084 5.45885e-7 0.7071065 0.7071071 0 -0.258817 0.9659265 0 -0.2588193 0.9659259 8.45594e-7 -0.7071079 0.7071057 0 -0.9659256 -0.2588202 0 -0.7071073 -0.7071063 0 0.9659262 0.2588179 0 -0.5073572 0.8617359 0 -0.5073571 0.861736 0 0.5073544 -0.8617376 0 0.5073575 -0.8617358 -1.17496e-5 -0.9982405 -0.03761774 -0.04583507 0.5073567 0.8617362 0 0.5073546 0.8617374 -1.38613e-5 -0.5073571 -0.861736 0 -0.5073572 -0.8617359 0 0.9805588 0.1957083 0.01424449 0.9253435 0.3781195 -0.02766191 0.7068788 0.7068788 0.02539467 0.258756 0.9656923 -0.02199566 0.2096571 0.9770551 -0.03751415 -0.2587351 0.9656144 0.02539491 -0.7069347 0.7069368 -0.02199351 -0.6550882 0.7555524 0 -0.9904308 0.1352104 -0.02766239 -0.9656141 -0.2587364 0.02539467 -0.7069352 -0.7069363 -0.02199453 -0.6700959 -0.741326 -0.03751516 -0.2587357 -0.9656143 0.02539497 0.258756 -0.9656924 -0.02199345 0.3069589 -0.9509832 -0.03751468 0.7068799 -0.7068777 0.02539467 0.9232366 -0.3841004 -0.0100643 0.9448095 -0.3266826 -0.02477103 0.8090488 0.5871323 0.02675354 0.7555516 0.6550891 0 0.1352089 0.990431 -0.02766191 -0.2587351 0.9656144 0.02539438 -0.7069368 0.7069347 -0.02199459 -0.7413253 0.6700966 -0.03751462 -0.9656141 0.2587364 0.02539467 -0.9656921 -0.258757 -0.02199441 -0.9818716 -0.1895476 0 -0.7071057 -0.7071079 0 -0.6123097 -0.790134 -0.02766257 0.2587555 -0.9656925 -0.02199345 0.3069587 -0.9509833 -0.0375142 0.7068788 -0.7068788 0.02539455 0.9802816 -0.1956546 -0.0277 0.9775015 -0.2097537 -0.02223718 0.7903225 0.6124545 0.01702946 0.6700959 0.741326 -0.03751516 0.2587346 0.9656146 0.02539455 -0.2587555 0.9656925 -0.02199453 -0.1895471 0.9818717 0 -0.7555516 0.6550891 0 -0.7903225 0.6124545 -0.01702946 -0.9906664 -0.1352412 0.01702934 -0.9509826 -0.3069607 -0.03751444 -0.7068809 -0.7068766 0.02539503 -0.2587555 -0.9656925 -0.02199453 -0.2096564 -0.9770553 -0.0375151 0.2587357 -0.9656143 0.02539551 0.7069336 -0.7069379 -0.02199345 0.655089 -0.7555518 0 0.9818717 -0.1895471 0 0.9906665 -0.135241 -0.01702928 0.9906665 0.135241 0.01702928 0.9818717 0.1895468 0 0.7071046 0.707109 0 0.6123111 0.7901329 -0.02766263 0.2587346 0.9656146 0.02539509 -0.2587555 0.9656925 -0.02199232 -0.3069597 0.9509829 -0.03751581 -0.7068766 0.7068809 0.02539461 -0.9814798 0.1894715 -0.02824836 -0.9775469 0.2097623 -0.02004712 -0.7903225 -0.6124545 0.01702946 -0.7555516 -0.6550891 0 -0.2588181 -0.9659262 0 -0.1352089 -0.990431 -0.02766191 0.2587357 -0.9656143 0.02539467 0.755251 -0.6548267 -0.02824932 0.7416986 -0.6704337 -0.02004712 -5.65143e-6 0 1 9.27218e-6 0 1 -5.27448e-6 0 1 5.89456e-6 0 1 -2.63726e-6 0 1 5.27448e-6 0 1 -5.89456e-6 0 1 2.63726e-6 0 1 2.9473e-6 0 1 -9.63303e-6 0 1 5.65143e-6 0 1 -9.27218e-6 0 1 2.31805e-6 0 1 6.926e-6 0 1 -6.92595e-6 0 1 2.40826e-6 0 1 2.31803e-6 0 1 0.990796 0.1352584 0.005343258 0.9818714 0.1895481 0 0.655087 0.7555535 0 0.6125355 0.7904251 -0.005343794 -0.1352578 0.990796 0.0053429 -0.3071539 0.951587 -0.01177692 -0.7555066 0.6550505 0.0108903 -0.9775914 0.2097705 -0.01764702 -0.9775915 -0.2097705 0.01764708 -0.7555077 -0.6550493 -0.01089024 -0.3071568 -0.9515861 0.01177692 -0.1352615 -0.9907956 -0.005342543 0.6705502 -0.7418376 0.006290256 0.7418307 -0.6705578 -0.006290256 0.9907961 0.1352581 0.005343198 0.9818715 0.1895478 0 0.6550865 0.755554 0 0.6125319 0.7904279 -0.0053429 -0.1352615 0.9907956 0.005342543 -0.3071568 0.9515861 -0.01177692 -0.7555075 0.6550496 0.01089036 -0.9775914 0.2097705 -0.01764708 -0.9775915 -0.2097705 0.01764702 -0.7555066 -0.6550505 -0.0108903 -0.3071539 -0.951587 0.01177692 -0.1352587 -0.990796 -0.005342483 0.67055 -0.7418377 0.006289899 0.7418308 -0.6705576 -0.006289899 0.7418357 0.6705522 0.006290555 0.7555271 0.6550574 0.00886482 0.1352491 0.9907464 -0.01137793 -0.2097668 0.9775922 0.01764655 -0.7417348 0.6704612 -0.01764744 -0.9256359 0.3782444 0.01137822 -0.9450631 -0.3267681 -0.008865535 -0.9516329 -0.3071733 -0.006290078 -0.3782587 -0.9256846 0.00534296 -0.3267827 -0.9450995 0 0.3267827 -0.9450995 0 0.3782632 -0.9256828 -0.00534296 0.951632 -0.307176 0.006290435 0.9777234 -0.2098031 -0.006290495 0.9515041 0.3071298 -0.01764661 0.741732 0.6704643 0.01764672 0.3267684 0.9450418 -0.01089024 -0.2097903 0.9776755 0.01177585 -0.3782632 0.9256828 -0.00534296 -0.951632 0.307176 0.006290435 -0.9450627 0.326769 0.008865356 -0.9256359 -0.3782444 -0.01137834 -0.7417348 -0.6704612 0.01764744 -0.2097668 -0.9775922 -0.0176469 0.2097698 -0.9775916 0.0176469 0.7417348 -0.6704612 -0.01764678 0.951503 -0.3071331 0.01764696 0 1 -4.01687e-6 0.9712214 -0.03853142 0.2350415 0.9987207 0.05056834 0 0 -1 -2.85353e-6 0 -1 4.01688e-6 0 -1 -1.27889e-7 -0.9988546 -0.04751443 0.005665063 -0.9996216 -0.0275098 0 -0.9987422 -0.002197504 0.05009239 -0.9961198 0 0.08800774 -0.9986692 0.05126345 -0.005654275 -0.9995459 0.03013455 0 -0.9991649 0.002163708 -0.04080206 -0.9975204 0 -0.07037919 -8.45196e-7 1 0 0 1 2.55778e-7 0 2.68567e-7 -1 7.61657e-6 0 -1 1 -1.95381e-7 0 0 -1 -6.05753e-7 -0.9994254 -0.03344738 0.005504608 -0.9998161 -0.01918274 0 -0.9985139 -0.003500938 0.05438548 -0.9910959 0 0.1331506 -0.9991531 0.03985452 -0.01023167 -0.99984 0.01789432 0 -0.9995917 0.002501904 -0.02846789 -0.9981448 0 -0.06088608 1 0 -3.17891e-7 1 0 -3.17892e-7 0 1 4.00144e-7 0 1 -1.86734e-7 -0.9965326 -0.01867872 0.08107942 -0.9798765 0.06851959 0.1874759 -1 -4.56563e-6 0 -0.9996756 0.02512121 -0.004208981 -0.999003 -0.04325944 -0.01103115 -0.9992051 -0.03917682 -0.007385373 -1 4.05835e-6 0 -1 -7.60083e-6 0 -1 8.5509e-6 0 -0.9984255 0.04957211 -0.02625179 -0.9963025 -0.01225996 0.08503586 -0.9985014 0.007861077 0.05415874 0 -1 -5.72466e-7 0 -1 -9.86149e-7 0 -1 7.46936e-7 0 1 7.60941e-7 1.53775e-7 1 -6.20429e-7 1 0 -3.17892e-7 1 0 -3.17892e-7 1.53775e-7 -1 -8.20135e-7 0 -1 7.60941e-7 -1 -7.39169e-6 0 -1 6.80495e-6 0 -3.07551e-7 1 1.20834e-6 0 1 7.72647e-7 0 1 -1.70747e-7 1 1.31565e-7 0 1 0 -1.90735e-7 0 1 7.72649e-7 0 1 -1.70747e-7 1 0 -1.90735e-7 0 1 -4.71697e-7 1 0 0 1 0 0 0 1 7.72646e-7 0 1 3.00951e-7 1 0 0 0 1 7.72648e-7 0 1 7.72648e-7 0.258949 0.006994187 0.9658657 -1 -3.72058e-6 1.35994e-5 -1 0 0 -1 0 0 0 1 1.5453e-6 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0.02455419 0.4267615 0.9040309 0.06764733 0.8778722 0.4740931 0.311721 0.147903 0.9385919 0.08158326 0.06806099 0.99434 0.2917757 0.4345259 0.8520882 0.3689565 0.07192933 0.9266593 0.08468985 -0.01565289 0.9962844 0.7427451 -0.4678152 -0.4790395 0.02947723 -0.1271892 0.9914404 0.2133162 0.9129877 0.3477782 0.2244228 0.9202585 0.3205603 0.3301183 0.8150743 0.4761047 0.500124 0.8037741 0.3222162 0.4958305 0.8026603 0.3314945 0.5696759 0.6735005 0.4710272 0.7099429 0.6109928 0.3502413 0.7203134 0.6107603 0.328817 0.7575097 0.4549319 0.4682052 0.8632373 0.3642672 0.3494721 0.8762957 0.3593016 0.3209491 0.8545116 0.2075824 0.4761508 0.9474024 0.06532394 0.3133077 0.9409405 0.07066309 0.3311161 0.8797775 -0.06308472 0.4711814 0.9133842 -0.218924 0.3432224 0.9166384 -0.2235413 0.331366 0.8130322 -0.3478518 0.4668809 0.8020487 -0.4845832 0.3491377 0.7935492 -0.4591838 0.399287 0.6926822 -0.5936828 0.4095512 0.6926338 -0.6276211 0.3554579 0.5661401 -0.6799885 0.4659411 0.4944087 -0.7965188 0.3480201 0.4917451 -0.8089472 0.3221668 0.3331362 -0.8150225 0.4740872 0.2104445 -0.929947 0.3015156 0.2171165 -0.9188386 0.3295393 0.06826084 -0.8763533 0.4768078 0.04225778 0.7736667 0.6321822 0.1576683 0.6465134 0.7464323 0.1886513 0.690654 0.6981461 0.3730887 0.6039575 0.7043012 0.3791556 0.609497 0.6962431 0.5414636 0.4591042 0.7043015 0.5489405 0.462499 0.6962465 0.6568304 0.2693164 0.7043029 0.6649963 0.2702272 0.6962451 0.7079085 0.05316329 0.7043005 0.6430894 0.06562691 0.7629739 0.7769129 -0.08575952 0.6237401 0.6018627 -0.146777 0.7849955 0.7523788 -0.3175861 0.5771182 0.5608494 -0.3263005 0.7609047 0.5737612 -0.518482 0.6340147 0.5426778 -0.4698349 0.6962442 0.3687511 -0.6066147 0.704302 0.3709315 -0.6145351 0.6962445 0.1632466 -0.6908751 0.7043026 0.1654202 -0.6249025 0.7629765 0.03683286 -0.7807618 0.6237422 -0.0195024 0.296869 0.9547191 0.1158321 0.4277871 0.8964269 0.1147736 0.4257385 0.8975376 0.2049313 0.3294231 0.9216743 0.2414755 0.362725 0.9000668 0.3273195 0.2757803 0.9037739 0.3362724 0.2805425 0.8990088 0.3965214 0.1611329 0.9037738 0.3054187 0.144491 0.9411917 0.4653535 0.08693927 0.8808449 0.3814113 0.03786259 0.9236298 0.4741956 -0.05128407 0.8789246 0.4959195 -0.0580632 0.8664252 0.3198075 -0.1349942 0.9378166 0.468463 -0.2859109 0.835941 0.2733667 -0.2366743 0.9323391 0.2639812 -0.213608 0.9405773 0.2140112 -0.3545632 0.910211 0.2156686 -0.3593549 0.9079379 0.1057577 -0.4031703 0.9089935 0.09858065 -0.5195575 0.8487297 0.01845061 -0.3622336 0.9319048 -0.9590667 -0.2529747 0.1272594 -0.1213588 -0.2030484 0.971619 -0.09102118 -0.09297263 0.9914995 -0.2751925 -0.1403329 0.9510919 -0.2296565 0.1065268 0.9674244 -0.4220055 0.1968796 0.8849576 -0.2856907 -0.4747726 0.8324494 -0.2522727 -0.4447181 0.8594094 -0.5195433 -0.3835303 0.7635309 -0.4128143 -0.2111959 0.8859913 -0.1381307 0.014988 0.9903006 -0.6268652 0.1282758 0.7684955 -0.8085223 0.1654483 0.5647289 -0.3101141 -0.8303501 0.4629775 -0.3695307 -0.651419 0.6626466 -0.5770701 -0.6758512 0.4584925 -0.6527966 -0.481902 0.5844888 -0.6171936 -0.484379 0.6200396 -0.7951334 -0.3540149 0.4923784 -0.8024547 0.3618494 0.4744805 -0.6707281 0.462319 0.5799871 -0.6747437 0.4824418 0.5585436 -0.5350767 0.3825803 0.75321 -0.09519416 0.1073726 0.989651 -0.5774822 0.6684057 0.4687731 -4.1783e-4 -0.141479 0.9899412 -0.01607567 -0.1783794 0.9838305 -0.04956293 -0.5498834 0.8337697 -0.05456966 -0.5600815 0.8266384 -0.07867014 -0.8074359 0.5846865 -0.05315613 -0.7828238 0.6199688 -0.1396453 -0.9802052 0.1403464 -0.3369257 -0.8968381 0.2866402 -0.4446247 -0.8886918 0.1119642 -0.6127021 -0.7509645 0.2462692 -0.8227452 -0.5522401 0.1346159 -0.8818864 -0.3926403 0.2609791 -0.8256138 -0.1444072 0.5454435 -0.769316 -0.1696411 0.6159341 -0.6248435 -0.137783 0.7684962 -0.1991719 -0.002953708 0.9799601 -0.4837344 -0.007173597 0.8751854 -0.8869196 0.003524243 0.4619107 -0.8080642 0.1647482 0.5655884 -0.4301903 0.7387622 0.5188128 -0.4467294 0.7053957 0.550318 -0.2497194 0.3989862 0.8822983 -0.2543984 0.4198799 0.8711959 -0.1381787 0.2280483 0.963795 -0.2477785 0.795899 0.5524044 -0.2363379 0.8176548 0.5249618 -0.178284 0.610547 0.7716522 -0.1029494 0.87788 0.4676839 -6.05073e-4 -7.83124e-5 0.9999998 5.75037e-5 1.98816e-4 1 6.97911e-4 1.87344e-4 0.9999998 -1.08361e-4 -8.90519e-5 1 0.001731336 5.64286e-4 0.9999983 1.79202e-4 -2.2808e-5 1 -0.08385401 0.9963638 0.01509135 -0.1423147 0.989821 -0.001020848 -0.4154146 0.9096308 -0.001660048 -0.3189752 0.9476463 0.01487988 -0.6548595 0.7557484 0.001868486 -0.4843724 0.8747546 0.01371085 -0.8412507 0.5406395 -0.00251311 -0.7976944 0.6028239 0.01694411 -0.6793585 0.7337101 0.01190268 -0.9594923 0.2817327 -0.001094281 -0.9193611 0.3931259 0.01507377 -0.9999738 -0.004538953 0.005652964 -0.9999912 0 0.004196107 -0.9753983 0.2200645 0.01303499 -0.9748038 -0.2225557 0.01505208 -0.9594478 -0.2817198 -0.009698271 -0.8412234 -0.5406219 -0.008434593 -0.8069927 -0.5903301 0.01653242 -0.699971 -0.714048 0.01326692 -0.6548387 -0.7557241 -0.008219838 -0.4522933 -0.8918601 0.004043817 -0.4153854 -0.909569 -0.01179826 -0.1423124 -0.9898074 -0.005347311 -0.09706407 -0.9951751 0.01432532 -1.87275e-6 0 1 -7.49281e-7 0 1 1.88042e-6 0 1 7.45843e-7 0 1 -1.89856e-6 0 1 -9.24675e-7 0 1 3.85548e-6 0 1 9.13896e-7 0 1 -2.88065e-6 0 1 7.49281e-7 0 1 1.87274e-6 0 1 1.87529e-6 0 1 1.88815e-6 0 1 -1.47147e-6 0 1 9.7338e-7 0 1 1.45183e-6 0 1 -4.9861e-7 0 1 -1.88816e-6 0 1 1.47147e-6 0 1 -7.13885e-7 0 1 1.49169e-6 0 1 -1.89856e-6 0 1 -1.47948e-6 0 1 -3.85549e-6 0 1 4.3867e-6 0 1 -1.44033e-6 0 1 -0.2210727 0.9752532 0.002856969 -0.120513 0.9925145 0.01979112 -0.08056908 0.996723 0.00721389 -0.383271 0.9233618 0.02250015 -0.3545936 0.9349849 0.008170604 -0.640838 0.76767 0.003069639 -0.5679461 0.8228132 0.02039051 -0.5233441 0.8521073 0.004935085 -0.7607456 0.6487699 0.01907533 -0.7484672 0.6630847 0.01075088 -0.920033 0.3918257 0.003446877 -0.8852675 0.4646229 0.02066338 -0.8543815 0.5196319 0.003890633 -0.9724153 0.2327127 0.01591759 -0.9708589 0.2392945 0.01307922 -0.9975481 -0.06987237 0.00399214 -0.9997878 0 0.02060419 -0.9973425 0.07279574 0.002985715 -0.9721281 -0.2340888 0.013022 -0.9708304 -0.2392879 0.01515346 -0.8564147 -0.5162672 0.004701972 -0.8852751 -0.4646287 0.0202099 -0.9207985 -0.3900323 0.002222239 -0.7599793 -0.6498644 0.01038664 -0.7484025 -0.6630277 0.01697242 -0.5274959 -0.8495393 0.00556755 -0.5679571 -0.8228278 0.0194782 -0.6416422 -0.7670025 0.001603662 -0.3822655 -0.9240178 0.008011043 -0.3545439 -0.9348558 0.01853388 -0.08614063 -0.9962538 0.00762701 -0.1205163 -0.9925407 0.01840996 -0.2213377 -0.9751966 0.001134276 0.001249313 0.025518 0.9996736 0.006303369 -0.004193961 0.9999714 -0.007051467 0.004736065 0.9999639 0.02919989 2.11402e-4 0.9995736 0.9998651 0.006962835 0.01488053 0.999998 -0.002031803 0 0.9999973 6.36868e-4 0.002287626 -8.84366e-4 -0.9999997 0 3.02607e-4 -0.9999989 0.00141561 0 -0.9999997 8.50358e-4 4.90976e-4 -1 0 -1 -1.22481e-5 0 -1 0 -2.35273e-5 -1 1.40748e-5 0 -0.2089942 0.9739906 0.08754235 -0.3641229 0.9311028 -0.02149957 -0.9509634 0.3069568 0.03802865 -0.9361768 0.3437873 0.07337182 -0.928829 -0.3637272 -0.07056444 -0.7355301 -0.6648545 0.1302466 -0.2364507 -0.964367 -0.1186898 -0.2089948 0.9739905 0.08754259 -0.364121 0.9311037 -0.02149242 -0.9509634 0.3069568 0.03803008 -0.9361778 0.3437849 0.07337033 -0.9288316 -0.3637203 -0.07056611 -0.7872859 -0.6100937 0.08925718 -0.1890711 -0.9794232 -0.07058513 -0.2378943 -0.9709327 -0.02638334 -0.2096415 0.9770137 0.03866308 -0.2810983 0.9592922 -0.02724665 -0.9509633 0.3069578 0.03802555 -0.9702247 0.2410656 -0.02348035 -0.7412325 -0.6700152 0.04067254 -0.6885411 -0.724691 -0.02709382 -0.6121778 0.7899588 0.03469067 -0.7213233 0.6890823 -0.06970185 -0.9786022 0.1889183 0.08153289 -0.9824042 -0.1720113 -0.07276105 -0.7390482 -0.6680301 0.08685415 -0.6251021 -0.7802453 -0.02155995 5.46944e-7 0 -1 -1.55168e-7 0 -1 2.40031e-6 0 -1 -1.18235e-6 0 -1 2.5257e-6 0 -1 -5.77718e-7 0 -1 6.79498e-7 0 -1 4.01632e-6 0 -1 8.7007e-6 0 -1 -1.93046e-5 0 -1 5.29123e-6 0 -1 -7.17314e-6 0 -1 2.1996e-6 0 -1 1.56027e-6 0 -1 -2.09938e-6 0 -1 4.98167e-6 0 -1 -1.78142e-6 0 -1 1.80262e-7 0 -1 -6.03559e-6 0 -1 -1.94529e-7 0 -1 1.50669e-7 0 -1 1.7902e-7 0 -1 -6.08925e-6 0 -1 7.32326e-6 0 -1 0.9200927 -0.04659408 -0.3889198 0.9668152 0.01377928 0.2551047 0 -1 1.75388e-6 0.00369817 0.001779556 0.9999916 0.001788258 8.95907e-4 0.999998 -0.001951336 0.00543493 0.9999834 0.002008855 -0.006533205 0.9999766 -0.0237286 -0.001690924 0.9997171 0.03852337 -2.42995e-4 0.9992578 0.002628982 -0.004602551 0.9999861 0.001866102 -0.02074825 0.999783 0.004713892 -0.002081811 0.9999868 -1.07348e-5 1 7.553e-5 0 0.9999998 7.22457e-4 0 0.9999998 7.25877e-4 0 0.9999998 7.22456e-4 0 0.9999998 7.29755e-4 0 0.9999998 7.18761e-4 0 0.9999998 7.29754e-4 0 0.9999998 7.18761e-4 0 0.9999998 7.26106e-4 0 0.9999998 7.22319e-4 0 0.9999998 7.26105e-4 0 0.9999998 7.22319e-4 0 0.9999998 7.24098e-4 0 0.9999998 7.23825e-4 0 0.9999998 7.23208e-4 0 1 1.86722e-5 1.89166e-4 1 0 0 0.9999998 7.24281e-4 0 0.9999998 7.22319e-4 0 0.9999998 7.22457e-4 0 0.9999998 7.25876e-4 0 0.9999998 7.22318e-4 0 0.9999998 7.25878e-4 1.02523e-5 1 6.53296e-5 0 0.9999998 7.18761e-4 0 0.9999998 7.15159e-4 -0.01395988 -0.0334714 -0.9993422 0.01991862 0.01390945 -0.999705 -0.001137495 0.00157839 0.9999982 2.98773e-4 -4.14069e-4 0.9999999 0.006928801 0.9375491 -0.3477841 -0.9865645 -0.005468487 -0.1632804 0.9882513 -0.152741 -0.005443096 0.9924253 -0.1228494 0 -0.9999791 0.006473898 0 -0.9999047 0.009674012 0.009851932 -0.01292806 -0.3782718 -0.9256043 -0.006350278 0.2847357 -0.9585851 -0.5245511 0.003395736 -0.8513722 0 -0.1221954 -0.9925061 -0.1802875 9.35641e-4 0.9836135 2.98418e-4 -0.03689408 0.9993191 0 -0.03069823 0.9995287 -0.02229553 0.9997144 -0.00860691 0.008397102 0.9936574 0.1121359 0.9759182 0.2180716 0.005335986 -3.31706e-4 -8.35914e-5 -1 5.26395e-5 1.85868e-4 -1 -0.001689612 7.58701e-4 0.9999983 6.0198e-4 -8.42001e-4 0.9999995 0.9702662 -0.2419776 -0.005502998 0.9806565 -0.1957367 0 -3.32631e-4 -0.008526802 -0.9999637 0 -0.003221571 -0.9999948 -0.009462416 -8.35834e-5 -0.9999552 -0.01548391 0 -0.9998802 5.336e-5 0.003723263 -0.9999931 0 0.003090202 -0.9999953 -0.001690983 0.02781575 0.9996117 0 -0.01948899 0.9998101 6.0153e-4 -0.0294305 0.9995667 -0.08986103 7.55648e-4 0.995954 -0.03510427 0 0.9993837 0 0.008421063 0.9999645 0.9842402 0.176749 0.005572557 0.9898335 0.1422306 0 5.38883e-5 1.48451e-6 1 0 -1 -5.04912e-7 0 -1 2.30996e-6 -7.90336e-6 1 3.49045e-6 0 -1.42459e-6 1 -0.9998218 0 0.01888233 -0.9929317 0.1186879 0 -0.9910936 -0.002772986 -0.133138 -0.996652 0 -0.0817613 -0.9914735 -0.1297821 0.01170283 0.9580639 -0.066998 0.2786125 0.9851164 0 0.1718889 0.9993114 -0.03542768 0.01103448 0.9988823 -0.04726725 0 -0.9997304 -0.002796947 -0.02305096 -0.99983 0 -0.01844257 0.9768675 0.01830923 0.2130603 0.9974058 0.06703722 0.02622503 0.9990679 0.04316663 0 0.9829716 0 0.183758 1.55853e-5 0 1 -2.13218e-5 0 1 -1.24682e-5 0 1 1.70575e-5 0 1 2.39378e-6 0 1 -9.25529e-7 9.71413e-7 1 -0.008042693 4.50636e-4 0.9999676 0.001938819 -0.004258334 0.9999891 0.00156933 0 0.9999988 0.001131474 8.3471e-4 0.9999991 0.0043388 4.60368e-4 0.9999905 0.006451547 4.85593e-7 0.9999792 0.005437493 0.001920163 0.9999834 0 0.006854176 0.9999765 -2.99723e-4 0.009300529 0.9999568 0.00141859 -3.46219e-4 0.999999 0 -0.004964709 0.9999877 0.004971623 -0.01067066 0.9999308 -0.02778297 0.005702018 0.9995977 1.20768e-6 0 1 3.569e-6 0 1 -0.01735359 -0.004053413 0.9998412 0.006253719 0.009199261 0.9999381 4.93065e-7 0.003161489 0.9999951 -0.00374782 0.0181837 0.9998278 0.002117216 -0.001255333 0.999997 0.001572251 0 0.9999988 0.0011487 -0.00109899 0.9999988 0 -0.005373358 0.9999856 4.27315e-4 -0.005825757 0.999983 0 -3.32596e-7 1 -0.006024599 2.49836e-5 0.9999819 -0.01601064 0.003595232 0.9998654 0 1.38353e-6 1 0.00975722 -0.02709835 0.9995852 0 -0.008163809 0.9999668 5.91139e-4 0.0106979 0.9999427 -0.008487701 0.002079129 0.9999619 -0.01342111 -0.004501342 0.9998999 0 0.04490238 0.9989914 -0.003368496 0.01789921 0.9998342 5.12088e-5 1.09068e-4 1 0 0.003207623 0.9999949 0 0.003208398 0.9999949 0 0.003206849 0.9999949 0 0.003207087 0.9999949 0 0.003206849 0.9999949 0 0.003206849 0.9999949 0 0.003207087 0.9999949 0 0.00320816 0.9999949 0 0.003207087 0.9999949 0 0.003207504 0.9999949 0 0.003207683 0.9999949 0 0.003206849 0.9999949 0 0.003208279 0.9999949 0 0.003207802 0.9999949 0 0.003207087 0.9999949 0 0.003207385 0.9999949 0 0.003207504 0.9999949 0 0.003207683 0.9999949 0 0.003207683 0.9999949 -8.04673e-7 0 1 7.17899e-7 0 1 9.2124e-7 0 1 -2.78855e-6 0 1 3.44267e-5 0 1 0 0 1 0 -6.2543e-7 1 0 -3.80846e-7 1 0 -6.17113e-7 1 1.33424e-5 -6.25434e-7 1 3.34098e-5 6.06876e-7 1 2.76527e-5 0 1 -1.738e-5 0 1 3.68703e-5 0 1 -3.68703e-5 0 1 -8.60678e-6 0 1 0 -2.03167e-7 1 8.60678e-6 0 1 -1.18301e-6 0 1 0 6.83191e-7 1 4.08817e-5 0 1 -1.4007e-5 0 1 -8.60678e-6 0 1 -6.24076e-6 0 1 0 6.2536e-7 1 0 1.64543e-7 1 0 3.14184e-7 1 0 6.25364e-7 1 -0.005895614 4.08422e-4 0.9999826 -0.004826366 0.01525151 0.9998722 0 0.005669653 0.999984 0.004473805 0.01373761 0.9998956 0.007757186 3.97521e-4 0.9999699 0.006427705 0.001199424 0.9999787 0.002957344 -0.002830147 0.9999917 0.003436148 -0.0016855 0.9999927 0.001525044 -0.001325666 0.999998 -0.02221447 0.001164257 0.9997526 -0.005833029 -9.2725e-5 0.9999831 -0.01469415 -0.00503391 0.9998794 0 -7.6294e-7 1 0 -7.6294e-7 1 0 -3.4509e-7 1 0.005894839 -0.009026408 0.999942 3.39463e-4 0.001199245 0.9999992 0 0.003207504 0.9999949 6.69083e-5 5.81371e-4 0.9999999 0 -2.67396e-6 1 0 1 2.85353e-6 0 -1 -1.00422e-6 0 1 7.13382e-7 0 -1 1.00422e-6 0 1 -1.00422e-6 -1.55853e-5 0 1 1.39815e-5 0 1 -1.24682e-5 0 1 -1.70575e-5 0 1 2.13218e-5 0 1 1.02199e-5 0 1 -1.39815e-5 0 1 1.24682e-5 0 1 -1.02199e-5 0 1 1.70575e-5 0 1 1.39815e-5 0 1 1.70575e-5 0 1 -2.49365e-5 0 1 3.41149e-5 0 1 -1.02199e-5 0 1 2.49365e-5 0 1 1.24682e-5 0 1 -1.70575e-5 0 1 4.88281e-6 0 1 -1.2207e-5 0 1 -1.55854e-5 0 1 1.24682e-5 0 1 -1.70574e-5 0 1 2.1322e-5 0 1 0.1351832 -0.9902549 0.03347676 0.2787723 -0.9577976 -0.07007026 0.7530362 -0.6529082 0.081532 0.964631 -0.2356106 -0.1182143 0.9693275 0.2079942 0.1309296 0.7660318 0.6387605 -0.07197475 0.3059955 0.9479996 0.08754152 0.1525126 0.9881011 -0.01990866 0.209649 -0.9770371 0.03802448 0.2794348 -0.959802 -0.02638888 0.9509414 -0.3069462 0.03866022 0.9698157 -0.2429254 -0.02108967 0.7411883 0.6699633 0.04229789 0.6879308 0.7253081 -0.02606868 0.6121894 -0.789973 0.03416061 0.720884 -0.6895256 -0.06986153 0.9786033 -0.1889129 0.08153289 0.9528173 0.2793772 -0.1186913 0.7355279 0.6648564 0.1302484 0.3451504 0.935758 -0.07230657 0.1347053 -0.9867872 0.09003055 0.7537136 -0.653481 -0.06984657 0.722406 -0.6909675 -0.02633583 0.990232 0.1351801 0.03416335 0.9572268 0.2805878 -0.07062166 0.6529443 0.753086 0.08077991 0.3451456 0.9357597 -0.07230764 0.2210719 -0.9752534 0.002856969 0.120513 -0.9925146 0.01979041 0.08056896 -0.996723 0.007214069 0.383271 -0.923362 0.02250111 0.3545935 -0.9349849 0.00816977 0.6408389 -0.7676693 0.0030694 0.5679465 -0.822813 0.02039045 0.5233447 -0.8521068 0.004935145 0.7607454 -0.6487702 0.01907563 0.7484669 -0.6630851 0.01075071 0.9200335 -0.3918247 0.003446877 0.8852671 -0.4646238 0.02066314 0.8543818 -0.5196313 0.003890812 0.9724154 -0.2327123 0.01591736 0.9708589 -0.2392951 0.01307886 0.9975479 0.06987297 0.00399214 0.9997878 0 0.02060449 0.9973423 -0.07279676 0.002985775 0.9721283 0.2340878 0.01302212 0.9708305 0.2392876 0.01515334 0.8564144 0.5162677 0.004701972 0.8852753 0.4646283 0.0202099 0.9207984 0.3900327 0.00222212 0.7599787 0.6498651 0.01038634 0.7484027 0.6630275 0.01697236 0.5274959 0.8495393 0.00556761 0.5679571 0.8228276 0.01947832 0.6416418 0.7670028 0.001603484 0.3822642 0.9240185 0.008010923 0.3545449 0.9348552 0.01853466 0.08614194 0.9962538 0.007627844 0.1205162 0.9925407 0.01841014 0.221338 0.9751965 0.001133263 0.08385378 -0.9963638 0.01509118 0.1423146 -0.989821 -0.001021146 0.4154142 -0.909631 -0.00165975 0.3189747 -0.9476465 0.01487976 0.6548593 -0.7557486 0.001868665 0.4843713 -0.8747552 0.01371031 0.8412511 -0.5406388 -0.002513229 0.7976939 -0.6028247 0.01694411 0.6793587 -0.7337098 0.01190268 0.9594926 -0.2817319 -0.00109452 0.9193602 -0.3931282 0.01507359 0.9999738 0.004539787 0.005653083 0.9999912 0 0.004196107 0.9753986 -0.2200635 0.01303499 0.9748038 0.2225556 0.01505219 0.9594478 0.2817195 -0.00969839 0.841224 0.540621 -0.008434355 0.806992 0.5903311 0.01653242 0.6999714 0.7140477 0.01326698 0.6548383 0.7557243 -0.008219838 0.4522947 0.8918594 0.004044175 0.4153861 0.9095687 -0.01179939 0.1423126 0.9898074 -0.005346775 0.09706443 0.995175 0.01432561 0.9590665 0.2529753 0.1272593 0.1555106 -0.1238124 0.9800444 0.1572401 0.193955 0.9683269 0.1121284 0.0930913 0.9893237 0.2125642 0.09844326 0.9721757 0.3186285 0.5616895 0.7635319 0.2912206 0.3608431 0.8859927 0.5147776 0.3800187 0.7684985 0.4389973 0.203306 0.8751845 0.3101156 0.8303484 0.4629793 0.3695279 0.6514168 0.6626503 0.5770711 0.67585 0.4584931 0.6527987 0.4819018 0.5844867 0.6171947 0.4843794 0.6200383 0.7951352 0.3540142 0.4923759 0.7561733 -0.3453869 0.5557966 0.7224277 -0.5104158 0.4664483 0.4438377 -0.4854682 0.7532124 0.547355 -0.5986964 0.584778 0.5468669 -0.6420659 0.537297 0.01235038 0.1651061 0.9861985 0.01435214 0.1713038 0.9851137 0.04098469 0.4892228 0.8711953 0.04958134 0.5088801 0.8594083 0.0786699 0.8074354 0.5846874 0.05315303 0.7828217 0.6199717 0.1396453 0.9802053 0.1403455 0.3369234 0.8968397 0.2866376 0.4446243 0.8886916 0.1119675 0.6127026 0.7509647 0.2462676 0.8227454 0.5522401 0.1346138 0.8818863 0.3926402 0.2609798 0.8419068 0.1538178 0.517236 0.7756906 0.1980632 0.5992287 0.5937001 0.1500943 0.7905644 0.1727995 0.004590749 0.9849463 0.1967544 -0.002776741 0.980449 0.5064072 -0.00904715 0.862247 0.5183651 -0.01454466 0.8550358 0.8594787 -0.02827805 0.510389 0.8367763 -0.005172252 0.5475205 0.1196507 -0.0831241 0.9893302 0.3597753 -0.2499468 0.8989374 0.5919198 -0.2581695 0.763531 0.7484454 -0.3264405 0.5772922 0.8648682 -0.1806674 0.4683613 0.4422234 -0.7642396 0.4694427 0.2477794 -0.7958956 0.5524091 0.2581838 -0.774549 0.577421 0.1779545 -0.5338571 0.8266372 0.1799793 -0.4662932 0.8661282 0.1162273 -0.3023204 0.9460939 0.1029503 -0.8778806 0.4676826 -0.03611773 -0.6478557 0.7609064 -0.03143334 -0.1389726 0.9897972 -0.08814328 -0.3247419 0.9416866 -0.04621577 -0.07349956 0.9962239 -0.2672046 -0.2114955 0.9401444 -0.7947924 0.268852 0.5440807 -0.07157343 0.05971419 0.9956462 -0.2736828 0.359435 0.8921346 -0.06272858 0.1050691 0.9924846 -0.02031135 0.08701235 0.9960002 -0.006349384 0.2356315 0.9718218 -0.07530659 -0.938406 0.3372285 -0.04867774 -0.9112724 0.408917 -0.2086883 -0.8877182 0.4103726 -0.2452068 -0.9036554 0.3511133 -0.3301174 -0.8150708 0.4761116 -0.5001198 -0.8037754 0.3222199 -0.4958331 -0.802661 0.3314888 -0.5696787 -0.6735006 0.4710236 -0.7099454 -0.6109924 0.350237 -0.7203148 -0.6107585 0.3288173 -0.757507 -0.4549353 0.4682062 -0.8632385 -0.3642648 0.3494717 -0.8762969 -0.3593024 0.3209447 -0.8545107 -0.2075812 0.476153 -0.9474022 -0.0653246 0.313308 -0.940941 -0.07066351 0.3311145 -0.8797789 0.06308364 0.4711788 -0.9133834 0.2189244 0.343224 -0.9166402 0.2235403 0.3313617 -0.8130307 0.347854 0.4668821 -0.8020446 0.4845857 0.3491435 -0.805549 0.497615 0.3216679 -0.6678501 0.5730032 0.4750195 -0.6096844 0.7315202 0.3052263 -0.6104511 0.7199528 0.330178 -0.4669435 0.7487614 0.4704469 -0.3580192 0.8711623 0.336004 -0.3576533 0.8722671 0.3335181 -0.195208 0.8636086 0.4648376 -0.07389819 0.9368954 0.3417107 -0.07067573 0.9411075 0.3306381 -0.2014863 -0.7466125 0.6340135 -0.172256 -0.6968291 0.696245 -0.3730913 -0.6039558 0.7043014 -0.3791577 -0.6094932 0.6962453 -0.5414521 -0.4591108 0.7043061 -0.5489499 -0.4624943 0.696242 -0.6568297 -0.2693167 0.7043035 -0.6649952 -0.2702274 0.696246 -0.7079086 -0.05316329 0.7043004 -0.6430854 -0.06562632 0.7629774 -0.7769135 0.08575856 0.6237396 -0.601855 0.1467776 0.7850012 -0.7227448 0.2792669 0.6321788 -0.5661497 0.3497327 0.7464326 -0.5985578 0.3928388 0.6981449 -0.4591096 0.5414612 0.7042999 -0.4624997 0.5489463 0.6962414 -0.2693167 0.6568312 0.7043021 -0.261142 0.5913349 0.7629731 -0.1585181 0.7653912 0.6237375 -0.04639303 0.6177625 0.7849952 -0.1192003 -0.4821872 0.8679209 -0.09730529 -0.4292982 0.8979058 -0.2260817 -0.3634315 0.9037725 -0.23312 -0.3707244 0.8990098 -0.3273233 -0.2757795 0.9037727 -0.3770753 -0.3021125 0.8755241 -0.3238054 -0.131582 0.9369292 -0.4636498 -0.1345483 0.8757429 -0.3464918 -0.03417485 0.9374304 -0.4374495 0.04712396 0.8980075 -0.289803 -0.001982152 0.9570842 -0.4659792 0.1509622 0.8718222 -0.3642003 0.142172 0.920405 -0.3110654 0.2027282 0.9285147 -0.4351736 0.3625543 0.8241229 -0.2329718 0.2765238 0.9323405 -0.2704293 0.4529711 0.8495205 -0.1538711 0.3510499 0.9236274 -0.09792739 0.4676458 0.8784747 -0.09732192 0.4279746 0.8985356 -0.5049892 -0.8631258 2.78482e-5 -0.5018882 -0.8649325 -3.0717e-5 -0.4928331 -0.8701038 -0.005931377 -0.4999981 -0.8660261 0.001006662 0.006719648 -0.3978445 -0.9174283 0.493722 -0.8696198 -1.80228e-5 0.4849401 -0.8745474 -2.41949e-5 0.5346325 -0.8446958 -0.02563965 0.4999807 -0.8659958 0.008407652 0.4392443 -0.4684538 -0.7665609 0.3290689 -0.2046268 -0.9218685 0.9999839 0.005681157 -1.68102e-6 0.9999896 -0.00296247 -0.003497481 0.9999698 0.007726848 8.65308e-4 0.999987 0 -0.005115926 0.4269367 0.1671527 -0.8886986 0.6015211 0.1237108 -0.7892199 0.4012284 0.4516457 -0.796889 0.3557697 0.2839871 -0.8903815 0.5050006 0.863119 2.78043e-5 0.5072417 0.8618032 0.001126825 0.4999997 0.8660241 0.001642525 0.4908096 0.8711615 -0.01355648 -0.006711423 0.3978546 -0.9174239 -0.4849238 0.8745565 -3.62931e-5 -0.5072532 0.861796 0.001382112 -0.4999828 0.8659945 0.008411645 -0.4794581 0.7045849 -0.5231444 -0.3596121 0.3082381 -0.8807204 -0.4353366 0.1849747 -0.8810598 -0.9999821 0.006005287 4.63597e-5 -0.9987639 -0.0495361 -0.004130661 -0.9999666 0.008134722 9.52757e-4 -0.9997127 0 -0.02397251 -0.9864528 0.1320826 0.09728908 -0.3459109 -0.2043387 -0.9157463 0.004237353 2.50972e-4 -0.9999911 -0.004386067 -2.63787e-4 -0.9999904 0.009443461 -0.02060884 -0.9997431 -0.006166577 0.007704973 -0.9999514 -0.01161873 -0.01981753 -0.9997362 8.21332e-4 -6.78203e-4 -0.9999995 0.001522302 -3.82145e-4 -0.9999989 0.00197792 0.008974432 -0.9999579 9.60747e-4 -5.54696e-4 -0.9999995 0.003144323 0.004418373 -0.9999854 0.01037895 -0.01861327 -0.999773 -0.001082658 -6.25153e-4 -0.9999992 -0.001135706 -4.2362e-4 -0.9999993 -2.39567e-4 0.009971618 -0.9999504 -0.01153916 0.01969832 -0.9997394 -0.002749562 -0.003612935 -0.9999898 0.007046937 -0.005875587 -0.999958 -9.59977e-4 -7.92537e-4 -0.9999993 -0.004927515 -0.004294753 -0.9999787 0.00821501 0.01094949 -0.9999064 -0.007582366 0.008515954 -0.9999351 0.004928112 0.00429356 -0.9999787 -0.01709419 -0.01448619 -0.999749 0.001303672 -0.001504063 -0.999998 0.003255426 0.002893209 -0.9999906 0.8710827 0.07301062 -0.4856795 0.4066462 0.4486077 -0.795858 0.4146667 0.8464201 -0.3341025 -0.03928029 0.5416349 -0.8396956 -0.5661358 0.7593511 -0.3207433 -0.50648 0.4227942 -0.7514807 -0.7034127 0.01924324 -0.7105212 -0.8710972 -0.07301163 -0.4856534 -0.4066597 -0.4486017 -0.7958545 -0.4146772 -0.84643 -0.3340648 0.03928411 -0.5416428 -0.8396903 0.5661422 -0.7593597 -0.3207116 0.5064879 -0.4227941 -0.7514754 0.7034209 -0.01923745 -0.7105132 0.9996067 -0.02482515 0.01304894 0.765419 -0.6432804 0.01800155 0.7048071 -0.7090283 -0.02293694 0.1729457 -0.9849236 -0.003928124 0.07632619 -0.9964277 0.03614205 -0.4801423 -0.876179 -0.04211556 -0.6729786 -0.7375896 0.05533033 -0.9913883 -0.115931 -0.06090408 -0.9996064 0.02483475 0.01304548 -0.7654139 0.6432861 0.01801526 -0.7047954 0.7090397 -0.02294129 -0.1729549 0.984922 -0.003928065 -0.07632976 0.9964274 0.03614348 0.4801445 0.8761777 -0.04211962 0.6729621 0.737605 0.0553261 0.9913892 0.1159258 -0.06089907 -0.6088438 0.6014266 0.5172961 -0.5887674 0.5944103 0.5477495 -0.1083681 0.605153 0.7886991 0.1805622 0.8784021 0.442501 0.2848511 0.5211104 0.8045519 0.871621 0.3242312 0.3676292 0.5629034 0.06565052 0.8239113 0.6088353 -0.6014125 0.5173225 0.5887988 -0.5944288 0.5476956 0.1083632 -0.6051455 0.7887056 -0.1805631 -0.8784038 0.4424974 -0.2848546 -0.5211108 0.8045504 -0.8716238 -0.3242446 0.3676104 -0.5628933 -0.06564581 0.8239186 -8.80673e-4 -0.002109169 0.9999974 -0.004262745 0 0.999991 6.64857e-5 0.001234471 0.9999992 9.71854e-4 0.001683294 0.9999982 -6.56438e-5 -0.001234471 0.9999992 -9.72215e-4 -0.00168389 0.9999982 -7.62474e-4 0.003361463 0.9999941 -8.40907e-4 0.001456499 0.9999987 8.80205e-4 0.00210905 0.9999974 0.004262149 0 0.9999909 7.62381e-4 -0.003360986 0.9999941 8.40789e-4 -0.00145626 0.9999986 0.02822709 0.002514958 0.9995984 0.008276402 -0.0304355 0.9995025 0.006216824 0.006222963 0.9999614 0.0061329 0.009211361 0.9999388 -0.01942551 0.004813253 0.9997998 -0.01194757 0.01926183 0.9997431 0.002614915 -0.009081482 0.9999554 -0.03902894 0.01504844 0.9991248 -0.0275678 0.02277171 0.9993606 -0.006191134 -0.006430506 0.9999603 -0.004487335 -0.01170349 0.9999215 -0.009073138 0.00260955 0.9999555 -0.01018697 -0.005240976 0.9999344 -0.01702338 -0.03436583 0.9992644 -0.008500695 0.0018875 0.9999622 0.02333647 -0.007773101 -0.9996975 0.01791697 -0.009406566 -0.9997953 0.01710349 -0.004220843 -0.9998449 0.0217483 0.004934489 -0.9997513 0.0134266 0.01294231 -0.9998261 0.02080297 0.013713 -0.9996896 0.009167134 0.0150128 -0.9998454 0.001347661 0.02160221 -0.9997658 -0.001462638 0.0183717 -0.9998302 -0.005259692 0.01621347 -0.9998548 -0.01293301 0.01601934 -0.9997881 -0.01453197 0.01027619 -0.9998417 -0.01729649 0.00696057 -0.9998262 -0.01869499 0.01114821 -0.9997631 -0.01946938 -0.004477798 -0.9998005 -0.03081291 5.89676e-4 -0.9995251 -0.009342491 -0.01664292 -0.9998179 -0.01019084 -0.01477289 -0.999839 -0.009361624 -0.01457154 -0.9998501 1.03917e-4 -0.02218699 -0.9997538 0.009587764 -0.01846778 -0.9997836 0.007412075 -0.02554178 -0.9996463 -0.546694 -0.8373314 0.001358449 -0.7512418 -0.6597014 -0.0207352 -0.868309 -0.4960007 -0.004788517 -0.9911579 -0.1318428 -0.01494759 -0.9962449 -0.08623409 -0.007729053 -0.9310659 0.3647893 0.006729006 -0.7812057 0.6242059 -0.009206354 -0.7441381 0.6677606 -0.01882797 -0.251362 0.967794 -0.01385664 -0.3903434 0.9206694 2.26282e-4 0.02136158 0.9997674 -0.00297594 0.2439674 0.9695793 -0.01990264 0.5115432 0.8592575 3.59593e-4 0.6974387 0.716473 -0.01567894 0.8780272 0.4785804 0.005411028 0.9761378 0.2166956 -0.01407772 0.9977903 -0.06610679 0.006660699 0.9182733 -0.3954583 -0.01967281 0.8077888 -0.5894607 0.003656685 0.3998925 -0.9164447 -0.01466798 0.4327378 -0.9014798 -0.008492469 -0.1430692 -0.9896215 -0.01343965 -0.1370003 -0.9904658 -0.01443576 -0.03522169 -0.04885685 -0.9981846 0.03824889 0.001849651 -0.9992666 -0.01204246 -0.06561404 -0.9977725 0.01242011 0.07828706 -0.9968535 0.02684032 0.02944201 -0.9992061 -0.007874488 -0.04205507 -0.9990844 -0.5673886 -0.8222261 -0.04488366 -0.6957912 -0.7176606 0.02894616 -0.974168 -0.2240978 -0.02787268 -0.9886743 -0.1490985 0.01711165 -0.9699509 0.2422044 0.02307111 -0.9274548 0.3731247 -0.02460998 -0.7617071 0.6475539 0.02182334 -0.6278243 0.7780759 -0.02084451 -0.4881764 0.8719791 0.03655701 0.02573746 0.9995352 -0.0163412 0.06219142 0.9972848 -0.03943574 0.5635662 0.8250209 0.04164034 0.7192353 0.6936664 -0.03908401 0.9180701 0.3951547 0.03162217 0.9744734 0.2208704 -0.04022163 0.9690154 -0.2415089 0.0517944 0.8842083 -0.4640284 -0.0534178 0.646435 -0.7618156 0.04193919 0.4607636 -0.8874296 -0.01287221 0.2803702 -0.9593781 0.03140383 0.004584252 -0.9993284 -0.03635805 -0.2743905 -0.9610126 0.03412955 0.02590364 0.9923968 0.1203225 -0.1968359 0.4741147 0.8581789 -0.3448464 0.1877188 0.9196971 -0.5182797 -0.1383277 0.84395 -0.5876398 -0.6035453 0.5388995 -0.2947977 -0.3995131 0.8680344 -0.2707701 -0.9481034 0.1666841 0.06122815 -0.4297682 0.900861 0.4465174 -0.4493057 0.7737872 0.7766414 -0.1958085 0.5987381 0.6502326 -0.1415116 0.7464396 0.6091743 0.278427 0.7425532 0.562668 0.248328 0.7885037 0.5356332 0.7824637 0.3175653 0.1455492 0.3793944 0.9137151 0.537349 -0.1776298 -0.8244416 0.9243181 0.2052705 -0.3217142 0.4263319 0.3191977 -0.846377 -0.211395 0.3789629 -0.9009436 -0.7580306 0.6031228 -0.2482586 -0.539647 0.01092815 -0.8418206 0.2724017 -0.9447435 0.1823654 0.9543702 -0.236458 0.1823875 0.6820008 0.7099117 0.175785 -0.2739763 0.9447641 0.1798824 -0.9539275 0.2359512 0.1853359 -0.681953 -0.7082589 0.1825091 0.3841995 0.3841194 0.8395494 -0.100754 0.5249307 0.8451606 0.5236781 -0.1258128 0.8425749 0.1293604 -0.5230636 0.8424195 -0.3856487 -0.3803941 0.8405805 -0.5205575 0.1363918 0.8428626 0.2517101 -0.9677633 0.008745431 0.3002704 -0.953278 0.0331462 0.2584815 -0.9660073 0.004147112 0.9639021 -0.2661668 0.006932973 0.9760745 -0.2157184 0.02728283 0.9665036 -0.256653 3.35703e-4 0.7115262 0.7026593 6.45495e-4 0.6749262 0.7373462 0.02820068 0.7085236 0.705684 -0.002114892 -0.2383792 0.9702212 0.04296749 -0.3125517 0.9489842 -0.04171729 -0.2515404 0.9678366 -0.004454076 -0.9636305 0.2672384 6.89232e-5 -0.9557461 0.2936375 0.01807379 -0.9729702 0.2206791 0.06804269 -0.7130689 -0.7010927 0.001303732 -0.6755633 -0.7364822 0.0347594 -0.7126055 -0.7015644 8.6197e-4 -0.02458107 -0.07862496 0.9966012 0 1 -2.94488e-6 -2.16873e-5 -1 -2.49258e-5 1.19728e-4 -1 1.805e-4 0.4029499 -0.00786817 -0.9151883 0.4502542 -0.01910239 -0.8926961 0.4502515 0.01910287 0.8926975 0.4029669 0.007867991 0.9151808 -0.9971365 -0.01340675 0.07442462 -0.9971369 0.01340699 -0.07441926 -0.4022889 -0.0582394 -0.9136584 0.5625776 0.04238069 -0.8256576 0.9963305 -0.04238057 -0.07436072 0.5901101 0.05823975 0.8052193 -0.4489771 -0.07753247 0.8901732 -0.9954009 0.07753628 -0.05626189 -0.5971449 0.0217449 -0.8018387 -0.9680296 -0.07423228 0.2396005 -0.9990214 -0.01468831 -0.04172033 -0.4140529 0.05297905 0.9087098 0.6925318 -0.05074799 0.7196002 0.7658751 -0.02379369 0.6425492 0.8962032 0.02800405 -0.4427592 0.272939 -0.07946163 -0.9587441 0.2763694 -0.08025717 -0.9576946 -0.8692244 -0.001852571 -0.4944143 -0.9889112 -0.08909511 0.1188141 -0.9564169 -0.04582136 0.2883875 -0.3317009 0.04606747 0.9422593 0.6102012 -0.04206144 0.7911293 0.8110679 0.02008986 0.5846071 0.5459408 -0.03066706 -0.8372625 -0.2364243 0.02279835 -0.9713825 0.7233861 -0.1023796 -0.6828112 0.01426166 0.9983309 0.05596607 0 1 2.38099e-6 -0.01037114 0.9997348 0.02056169 -0.009211957 0.9994398 0.03217554 0.05513906 0.9520012 0.301087 -0.03834044 0.9992607 0.002869606 0.01076459 0.9981328 0.06012672 0 1 1.22535e-5 0 1 -5.24572e-6 8.028e-7 0.7071122 0.7071014 0.05944466 0.9783673 0.1981506 0.9989002 0.03767192 -0.02791661 0.9999309 -0.01176005 1.72306e-4 0.9881891 -0.01162141 -0.1527985 0.9886261 0.08568793 0.1235972 -0.02911692 0.04438239 -0.9985902 0.1633411 0.1132618 -0.9800468 0 -0.5144952 -0.8574934 -6.54209e-6 -0.5144923 -0.8574951 0 -0.5144956 -0.8574931 0 -0.514496 -0.8574929 -0.2898536 0.8115995 0.5072389 1 0 1.19209e-6 1 -9.53674e-7 0 1 0 0 1 -9.62844e-7 -4.40156e-7 -1 5.96044e-7 0 -1 9.53674e-7 0 0 1 6.35783e-6 0 1 -5.44957e-6 0 1 7.06422e-6 0 1 7.26609e-6 0 1 -3.1789e-6 1 -1.39426e-7 0 -1.31726e-4 -0.9998602 0.01672857 0 -0.9999128 -0.01320791 0.003264069 -0.9999947 0 -3.30555e-5 -0.9999948 0.003251671 1.48573e-4 -0.9998934 0.01459944 0 -0.9950664 -0.09921127 -0.004478335 -0.9996368 0.02657741 -0.04184478 -0.996316 0.07485747 0.0405181 -0.9987103 0.03059619 -3.27693e-5 -0.9881067 -0.1537698 -0.001110315 -0.9999887 0.004637479 0.001311898 -0.999366 0.03557997 0.009425461 -0.9972351 0.07371193 0.01118052 -0.9996091 -0.02562487 -0.04610848 -0.9982545 0.03690659 0.009671151 -0.9999027 0.01006573 -0.004965901 -0.9999877 0 8.31553e-4 -0.9997496 0.02236497 0.02814972 -0.9852306 -0.1689035 0.2538082 -0.9653457 0.06073898 -3.99449e-4 -0.9999183 -0.01277911 0.07238703 -0.9973766 0 0.1453759 -0.9880744 -0.05074399 0.09191453 0.9957284 -0.008753776 0.1000037 0.9948803 -0.01457667 3.56038e-6 1 0 -3.81469e-6 -1 0 -3.81469e-6 -1 0 -1 5.67662e-7 -3.12214e-7 -0.04660958 0 -0.9989132 0.03893768 0 -0.9992417 0 -0.01704394 -0.9998548 -0.03123021 0 -0.9995123 0.0328722 0 -0.9994596 -0.009837985 -0.02214032 -0.9997066 0.00750631 0.01981043 -0.9997756 0.02883279 0 -0.9995843 -0.03059762 0.0173844 -0.9993807 -0.03060144 0 -0.9995318 -0.02883636 -0.001236379 -0.9995834 0 0.02677774 -0.9996415 0 0.02677792 -0.9996415 0.03496718 0.01986986 -0.999191 0.03498107 -0.002350568 -0.9993852 0 -0.01547116 0.9998803 0.03188228 0 0.9994916 -0.2179872 0.04333341 0.9749892 -0.1101884 0.005971074 0.9938929 -0.08303976 0 0.9965463 0.006479561 -0.0454027 0.9989478 0.006655633 0.03193753 0.9994677 0.03108227 0.03113758 0.9990318 0.2194796 -0.04331851 0.974655 -7.62934e-6 0 1 -3.42929e-6 0 1 3.87528e-5 0.01173067 0.9999313 -0.315948 -0.04212671 -0.9478409 0.2105803 0.09937781 -0.9725122 -0.2048044 -0.975286 0.08290022 -0.03109824 -0.9951542 -0.09327918 4.95291e-4 0.999918 -0.01279896 -0.07125121 0.9974584 0 -0.1145741 0.9929448 -0.03055077 -0.1314708 -0.990687 -0.03542202 -0.1042219 -0.9944232 -0.01613861 -0.9848692 0.09479594 -0.1450744 -0.9981147 0 0.06137627 -0.9999636 0 -0.008536279 -0.9998159 0.01173818 -0.01517772 -1 -9.43274e-6 2.5225e-6 -1 8.19146e-7 0 -1 -4.71638e-6 0 -1 -2.35587e-6 0 -1 -4.71178e-6 0 -0.04212605 -0.3159461 0.9478415 0.09629917 0.198569 0.9753445 0.04212629 0.3159468 0.9478413 -0.1000566 -0.2132357 0.9718639 -0.01338803 0.7686539 0.6395249 -0.103927 0.9505147 0.2927815 0.04965347 0.813111 -0.5799872 -0.03470683 -0.3236189 -0.9455509 -0.005824685 -0.2266362 -0.9739621 0.004566788 -0.988448 0.1514917 -0.08691465 -0.8364102 0.5411689 0.01659542 -0.2722643 0.9620795 -0.0972439 0.3351728 0.9371249 0.01188462 0.767793 0.6405878 -0.001925885 0.8138995 -0.5810027 -0.05876433 0.6459386 -0.7611243 0.05753862 -0.3238692 -0.9443507 -0.07568061 -0.9810017 -0.1786285 -1.886e-4 -0.988469 0.1514232 0.003255665 -0.2729724 0.9620164 0.0102787 0.767867 0.640527 -0.04550558 0.917577 0.3949453 0.02954131 0.8136423 -0.5806148 -0.03756248 0.4839663 -0.8742802 0.05753672 -0.3238372 -0.9443618 -0.04953998 -0.9174212 -0.3948219 0.02615445 -0.9880803 0.1517015 -0.05785727 -0.4834817 0.8734403 -0.01519435 -0.2738257 0.9616594 -0.0631203 0.1166892 0.9911607 0.01847362 0.7674952 0.6407885 -0.05484056 0.9983326 -0.01801574 0.04965662 0.8131399 -0.5799464 -0.03470587 -0.3236105 -0.9455537 0.02607131 -0.1168729 -0.9928047 -0.03118485 -0.9993511 0.01802808 -1.88596e-4 -0.988473 0.1513977 0.003253161 -0.2729724 0.9620165 -0.01338595 0.7686547 0.6395239 -0.1039271 0.9505146 0.2927818 0.0496537 0.8131002 -0.5800021 -0.03470528 -0.3236215 -0.94555 -0.005827605 -0.2266399 -0.9739613 0.004566788 -0.9884505 0.1514756 -0.08691567 -0.8364029 0.54118 0.01659554 -0.2722656 0.9620791 -0.11379 0.4474155 0.8870576 -0.01200652 0.7686334 0.6395768 0.03701847 0.8134888 -0.5804013 -0.06922423 0.4020016 -0.9130186 0.04140806 -0.323995 -0.9451522 -0.05225759 -0.9958642 -0.07432121 -1.86724e-4 -0.988474 0.1513903 0.003255546 -0.2729505 0.9620226 -0.09724271 0.3351733 0.9371247 0.01188272 0.7677932 0.6405877 -0.001923978 0.8139013 -0.5810001 -0.05876374 0.6459372 -0.7611255 0.05753719 -0.3238719 -0.9443498 -0.07568013 -0.9810016 -0.1786289 -1.88134e-4 -0.9884696 0.1514196 0.003253161 -0.272974 0.962016 -0.09670448 0.1081271 0.9894225 0.02126258 0.7673668 0.6408558 -0.04137694 0.9000605 -0.433796 0.002000689 0.8138691 -0.5810449 0.03351771 -0.3240514 -0.9454456 -0.1044085 -0.8318651 -0.5450685 0.03491914 -0.9877977 0.151778 -0.01530313 -0.2738404 0.9616535 -0.9745025 -0.2074071 -0.08559954 -0.9951531 -0.03109908 0.09329169 0.975281 0.2048281 -0.08290117 0.9951524 0.03110015 0.09329938 -0.03772914 -0.9988981 0.02791434 0.01175904 -0.9999309 -1.72095e-4 0.01174587 -0.99879 -0.04775577 0.09261357 -0.9871572 0.1301677 -0.0949403 0.9848532 0.1450884 0 0.9981225 -0.06124991 0 0.9999637 0.008528888 -0.01178658 0.9998152 0.01519083 1.90736e-6 1 0 1.90735e-6 1 0 0 -1 0 -2.38419e-7 -1 0 -0.5144948 0 0.8574936 -0.5144919 0 0.8574953 -5.33521e-6 2.00082e-7 -1 -0.022152 -0.001813709 -0.9997531 0 0.04381704 -0.9990397 -1.44414e-6 0 -1 0.04345238 -0.2057648 -0.9776363 0.0103507 -0.1099991 -0.9938778 6.49864e-7 0 -1 -4.0495e-5 6.13503e-4 -0.9999999 -0.04330503 0.2206931 -0.9743815 -0.004998624 0.1102223 -0.9938944 -0.01069241 0.001209378 -0.9999421 0.0160318 -0.001813948 -0.99987 0.001654863 0.001209437 -0.999998 0.00644958 -0.02837812 -0.9995765 0.00731188 -5.51122e-4 -0.9999732 -0.9905362 -0.1319802 0.03767359 -0.9948835 -0.09997469 0.01455897 -1 7.69817e-6 0 -0.9999182 -4.3521e-4 0.01278913 -0.9974588 0.0712459 0 -0.9929468 0.1145576 0.0305522 0.9999183 3.98708e-4 0.01278084 0.9973765 -0.07238954 0 0.9929826 -0.1145791 0.02928096 0.9906998 0.1313914 0.03536015 0.9944194 0.1042552 0.01615488 0 1 -2.7093e-7 0 1 5.57705e-7 -1 0 2.38418e-6 -0.9997663 -3.18446e-4 -0.02161949 -0.9968196 -3.17315e-4 -0.07969027 -0.9999466 2.99491e-4 -0.01033836 -0.9985556 0.04254484 -0.03281587 -0.9964445 -0.06623572 0.05206817 -0.9999975 0.002278268 -9.07459e-7 -0.9998418 0.01698076 -0.005302608 -0.9999142 -0.009259283 0.009278118 -0.9999085 -0.00104916 -0.01348829 -1 0 1.47251e-4 -0.9997707 -4.45969e-5 -0.02141541 -0.9999794 0 0.006411671 -0.9996837 -2.08768e-5 -0.02515065 -0.9986111 0.03740298 -0.0371074 -0.9987355 -0.0454837 -0.02141797 -0.9982238 0.04222369 -0.04203152 -0.9999378 -0.01066333 -0.003249645 -0.9999089 -0.002671599 -0.01322901 -0.9997473 -6.10512e-4 -0.02247685 -0.9951741 0 -0.09812533 -0.999942 8.70564e-4 -0.01073908 -0.9940316 0.1070181 0.02118015 -0.9986799 -0.05136275 -7.0279e-4 -0.9999604 0.008514881 0.002595841 -0.9998947 -0.01443934 0.001467168 -0.9999089 -0.002677321 -0.01323485 -0.999764 -3.51141e-4 -0.02172231 -0.9967471 1.76223e-4 -0.08059233 -0.999942 8.65237e-4 -0.01074504 -0.9978452 0.06387537 -0.01499968 -0.9979189 -0.05894577 0.02614104 -0.9999777 0.006647408 -6.75072e-4 -0.9999122 -0.01132339 0.006894052 -0.999909 -0.001454353 -0.01341485 -0.9999794 0 0.006411075 -0.9997472 -6.10582e-4 -0.02247953 -0.9976975 -2.47161e-4 -0.0678212 -0.9999334 0.001782894 -0.0114066 -0.9985032 0.04549068 -0.03036278 -0.9987637 -0.04682314 -0.01669406 -0.999897 0.01225942 -0.007469892 -0.9999322 -0.01141005 -0.002317965 -0.999909 -0.002665936 -0.01322889 -0.9997476 -6.10506e-4 -0.0224592 -0.9951741 0 -0.09812498 -0.999942 8.65219e-4 -0.01074481 -0.9957647 0.09156954 0.008221209 -0.9985765 -0.05307239 0.005338609 -0.999967 0.007963001 0.001617312 -0.9998694 -0.01584112 0.003219425 -0.9999088 -0.002671778 -0.0132417 -0.9999794 0 0.006411671 -0.9997472 -6.10563e-4 -0.02247852 -0.995176 0 -0.09810668 -0.9999419 8.65319e-4 -0.01074618 -0.9981175 0.05801576 -0.01989865 -0.9987472 -0.04592132 -0.01988065 -0.9999794 0.006300568 -0.001279652 -0.9999364 -0.01089936 -0.002954006 -0.999909 -0.002671658 -0.01322907 -0.9997744 -1.86703e-4 -0.02124232 -0.9972603 2.4126e-4 -0.07397353 -0.999942 8.70573e-4 -0.0107392 -0.9947147 0.1013558 0.01641929 -0.9986505 -0.05191904 0.001259267 -0.9999629 0.008319735 0.002255499 -0.9999828 -0.005439281 0.002204895 -0.9999084 -8.10912e-4 -0.01351398 1 2.3582e-6 0 1 9.43298e-6 0 1 9.43301e-6 0 1 4.71649e-6 0 0 1 1.1921e-6 0.7864806 -0.306422 -0.5362406 0.9772192 0.01776522 -0.2114877 0 -0.03756475 0.9992943 0 -0.02883291 0.9995843 4.59797e-4 -0.02953636 0.9995636 0.03059679 0 0.9995319 0 -0.03406947 0.9994195 -0.001945972 0.03149497 0.9995021 0.01788884 0.03149002 0.999344 0.1267845 -0.2824333 0.9508718 -0.3285844 0.1767219 0.927794 -0.03163105 0.02919262 0.9990732 3.05481e-6 0 1 -2.82571e-7 0 1 -0.03534966 -0.03262782 0.9988423 0 0.03996574 0.9992011 0.02837574 0.03122127 0.9991096 -0.009825527 -0.02883142 0.999536 2.13381e-6 0 1 -7.43126e-6 0 1 0.7931553 -0.3021595 -0.5287765 1 -4.7164e-6 0 -0.01375246 -0.8395094 0.5431711 0.03655189 -0.6799998 0.7323006 -0.03655189 0.9550504 0.2941817 0.01375204 0.9986217 0.05065423 -0.006445825 -0.2907196 -0.9567866 0.006448149 -0.2266349 -0.9739585 -0.06184673 0.1084139 0.9921801 0.06578779 0.8909246 0.449361 -0.0447632 0.8999351 -0.4337201 0.04476213 -0.07436454 -0.996226 -0.06578791 -0.834622 -0.5468803 0.06184852 -0.913457 0.4022077 0.7071031 0 -0.7071105 0.03578227 -0.05061089 0.9980773 -0.05173593 0.4497312 0.8916644 0.05066907 0.9555765 -0.2903555 -0.05824011 0.4022843 -0.9136605 0.0624178 -0.7313523 -0.6791377 -0.03841549 -0.9964905 -0.07437086 0.03578215 -0.05061072 0.9980773 -0.05173629 0.4497311 0.8916643 0.05066949 0.9555754 -0.2903588 -0.05823969 0.4022852 -0.9136601 0.06241953 -0.7313551 -0.6791344 -0.03841489 -0.9964905 -0.07437062 0.03578054 -0.05059945 0.9980779 -0.03125596 0.3366084 0.9411259 0.03462803 0.9562255 -0.2905747 -0.05142045 0.6461817 -0.7614495 0.05820983 -0.7315459 -0.6793027 -0.04187053 -0.9829626 -0.178973 -0.03243488 -0.4840478 0.8744402 0.07130348 0.2936258 0.9532574 -0.06407892 0.9818025 0.1787676 0.05902206 0.5422709 -0.8381282 -0.02521365 -0.1168701 -0.9928272 0.02313923 -0.9737211 -0.2265653 0.02061247 -0.9775301 -0.209786 0 -2.72475e-6 -1 -0.1371353 0.3526302 -0.9256597 5.86874e-6 0 -1 -7.78509e-6 -1.16776e-6 -1 -2.7094e-6 4.40277e-7 -1 -7.82502e-6 0 -1 4.47143e-6 0 -1 -1.05743e-6 0 -1 1.72767e-7 -1 -1.38214e-6 -5.59771e-7 -1 -1.24393e-6 0 -1 -1.22265e-6 -1.58943e-6 -1 0 3.83664e-7 -1 -5.48091e-7 3.53214e-7 -1 5.43406e-7 0 1 1.27317e-6 0 1 -2.98024e-6 -0.01375317 -0.839506 0.5431765 0.03655064 -0.6800012 0.7322995 -0.03655165 0.9550511 0.2941794 0.01375246 0.9986218 0.05065119 -0.006447672 -0.2907208 -0.9567862 0.006447076 -0.2266296 -0.9739597 1 0 1.41285e-6 1 5.10055e-6 0 0.9996019 -7.67763e-4 -0.02820706 0.9969832 0.05022329 -0.059179 0.9976993 0.03887313 -0.05554336 1 -5.6487e-6 0 1 1.8192e-6 0 0.9997391 -0.006162464 -0.02199923 0.9998357 -0.008163809 -0.01619046 1 -3.19464e-6 -5.43356e-6 1 0 -1.37418e-5 1 -1.05581e-5 -9.89817e-7 1 -1.8814e-5 1.2451e-5 1 2.99383e-6 8.0061e-7 1 1.73987e-5 1.63112e-6 1 0 -5.18637e-7 1 1.59076e-6 -2.38264e-6 1 0 -2.29719e-5 1 -2.33411e-6 2.15871e-6 1 -6.56362e-6 -1.25331e-6 1 -1.07147e-4 3.0135e-5 1 6.57151e-6 -1.84823e-6 1 4.47644e-6 -4.89659e-5 1 0 2.6138e-6 1 -4.08876e-6 1.98428e-6 1 0 2.09109e-6 1 5.12836e-6 4.51165e-7 1 -5.09752e-6 1.73232e-6 1 0 3.01308e-6 1 4.61276e-5 -1.24256e-6 1 0 1.92411e-6 1 0 2.78929e-6 1 1.7224e-6 1.6519e-6 0.9996075 0.02352362 -0.01522028 1 0 -2.76149e-7 1 0 2.14874e-6 0.9995581 0.01903831 -0.02283227 0.9992017 -2.12418e-4 -0.03994947 0.9998046 -0.004482984 -0.01925694 0.9994921 0.001212656 -0.03184634 1 1.53037e-6 0 1 -5.84369e-7 -6.19603e-6 1 0 1.90713e-5 0.9988687 -7.61023e-4 -0.04755032 0.9998104 -0.001258134 -0.01943278 0.9999066 -0.001599252 -0.01358062 0.9979693 0.002189874 -0.06365913 1 -9.42332e-6 0 -0.007870614 -0.5910797 0.8065748 0.007451832 -0.647022 0.7624349 -0.01259088 0.9837465 0.1791216 0.03538089 0.9977817 -0.05639129 -0.03225368 -0.3366019 -0.9410946 0.01340806 -0.5630196 -0.8263348 1 -1.39426e-7 0 -7.59903e-7 0 -1 0 -1 0 0 -1 0 -0.07528805 -0.08894515 -0.9931871 0.01825672 -0.04651445 -0.9987508 0.09073442 -0.3149211 -0.9447709 0.0182566 -0.04651415 -0.9987509 0.0907405 -0.3149209 -0.9447703 0.01963996 -0.05159407 -0.998475 -0.05551731 0.05677413 -0.9968424 -0.07596147 -0.07638674 -0.9941806 0.1778261 0.3111877 0.9335631 -0.07955747 -0.5545566 0.8283343 -0.05323272 -0.5589414 0.8274967 -0.07956266 -0.5545556 0.8283345 0.1778258 0.3111873 0.9335634 -0.07956272 -0.5545559 0.8283343 -0.05336052 -0.5602827 0.826581 -5.86877e-6 0 1 -3.17892e-6 0 -1 0.1066461 -0.9786584 0.1756539 0.1241805 -0.9587574 0.2556627 0.09470307 0.9944081 -0.04673093 0.1324759 0.9577198 -0.255388 -0.1174449 0.5276646 0.8412947 0.1318256 0.9578038 -0.2554096 -1 2.64909e-6 0 0.1269118 -0.9584236 0.2555733 0.09470039 0.9943791 -0.04735243 0.1318257 0.9578045 -0.2554069 0 1 2.10525e-6 0.1256412 -0.9585775 0.2556239 0.9881173 -0.1157855 -0.1010835 0.9996402 0 -0.02682566 0.9996415 0.02677696 0 1 3.04384e-6 -4.48967e-6 0.8912128 -0.01902961 -0.4531861 0.7143399 -0.4824497 0.506913 0.89388 -0.03491407 -0.4469448 0.9978752 0.037638 -0.05318325 0.0874623 -0.5754615 0.8131387 0.9977387 0.03246504 -0.05885237 0.8172875 -0.02932119 -0.5754836 0.895891 -0.04420715 -0.4420691 0.7250538 -0.4607132 0.5118988 0.9997697 0 -0.02146393 0.9996283 -0.0272662 0 0.8904986 -0.04442882 -0.4528115 0.9991723 0.03350853 -0.02306675 0.9179413 -0.3267747 0.2249493 0.9983454 0.03964215 -0.04165232 0.8921341 -0.03558313 -0.4503673 0.8660218 0 0.5000064 0.8660224 0 0.5000052 0.8660221 0 0.500006 0.8660221 0 0.5000058 0 1 9.90829e-7 -0.187754 0.9387827 -0.288852 0 1 1.09278e-6 0 1 -1.58617e-6 0 -0.1644012 -0.9863936 -0.1321662 0 -0.9912276 0 -1 0 0 -1 0 0 -1 0 -0.04937726 -0.9957616 0.07759273 -0.01947706 -0.9998103 0 -0.1876886 -0.9520329 -0.2416745 0.1442167 -0.9614194 -0.2342526 -0.03260064 -0.9994683 -7.29831e-4 -0.01636695 -0.9998215 -0.009449601 0 -0.9997318 -0.02316039 -0.1663247 -0.8436654 -0.5104554 -0.005612909 -0.9660448 -0.2583137 -0.2659506 -0.9633139 -0.03601169 -0.5032094 -0.8375985 -0.2126243 -0.1936234 0.9808887 0.01917147 -0.4592502 0.8779776 0.1350736 0.09244829 0.924502 -0.3697964 0.01592886 0.984658 -0.1737667 -0.1464955 -0.896407 0.4183224 0.09031659 -0.9289857 -0.3589268 -0.05558305 0.9147418 -0.4001975 -0.02747225 0.9549267 -0.2955677 0.7788947 0.01454287 -0.6269863 0 0.008570492 -0.9999634 0.01391768 0.003459513 -0.9998972 0.002893745 0.001174926 -0.9999951 0.02404224 -0.04542613 -0.9986785 0.02320092 -0.04315692 -0.9987989 0 0.001786053 -0.9999985 -0.04788362 -0.08293724 -0.9954038 0.00800693 0.0120486 -0.9998955 0.03452414 0.04160505 -0.9985376 -0.0393778 -0.05726635 -0.9975821 0.01761531 0.01301103 -0.9997602 -0.002863645 -0.00525242 -0.9999821 -0.04516792 -0.06366366 -0.9969487 0.01497596 0.01492011 -0.9997766 -0.07239848 -0.07574081 -0.9944958 0.01836526 0.01476061 -0.9997225 0.05271792 0.04328876 -0.9976708 -0.02235299 -0.01631593 -0.999617 8.28882e-6 0 1 -0.04117685 0.2744846 -0.9607095 -0.009224116 0.3162094 0.9486446 -0.04163056 0 0.9991331 0 -0.2169296 0.9761874 -1 -1.28104e-5 0 -1 -6.85025e-6 0 -1 -1.4901e-6 -2.38415e-6 -1 -1.1921e-6 1.90736e-6 -1 -1.21068e-6 9.68529e-7 -1 -7.22477e-7 -1.22821e-6 -1 -7.15254e-6 0 -1 -1.38998e-5 0 -1 3.28382e-6 0 -0.05705094 -0.9983713 0 -0.01514929 -0.9788672 -0.203935 1.36237e-6 0 1 2.72485e-6 0 1 -0.01514929 0.9788671 -0.2039362 -0.05705094 0.9983713 0 0.0291543 -0.999575 0 0 -0.9738411 -0.2272304 -0.04847157 -0.9971296 0.05816555 1.89218e-7 -1 0 -0.2952412 -0.9489862 -0.110715 1.58557e-7 -0.997559 0.06982856 1.27156e-6 0 -1 7.94728e-7 0 -1 -1.27156e-6 0 -1 1.27157e-6 0 -1 -0.01514983 0.9788671 -0.2039357 -0.05704939 -0.9983714 0 -0.01514875 -0.9788688 -0.2039276 2.72474e-6 0 1 -0.01514869 -0.9788685 -0.2039289 2.72483e-6 0 1 -0.05497962 0.9048131 -0.4222446 0 0.9850307 -0.172379 -0.2557616 0.9566212 0.1395061 0 1 1.98683e-7 -1.98683e-7 1 0 -0.01514923 -0.9788672 -0.2039353 1.36236e-6 0 1 1.58945e-6 0 1 -1.58946e-6 0 1 -0.01514869 0.9788685 -0.2039289 -0.05704939 0.9983714 0 -0.05705171 -0.9983713 0 -0.01514977 -0.978867 -0.2039361 -0.01514875 0.9788689 -0.2039277 -0.01514977 0.9788672 -0.2039353 -0.05705058 0.9983713 -3.10896e-6 -0.01514875 0.9788686 -0.2039287 -1 -6.69241e-6 0 -1 1.55068e-5 0 -1 5.19006e-6 0 -1 7.94736e-6 -3.17894e-6 -1 6.69243e-6 1.33849e-6 -1 0 9.08244e-6 -1 0 -1.81651e-6 -1 2.54317e-5 0 -1 0 3.97367e-6 -1 6.69245e-6 1.33849e-6 -1 -2.54314e-5 5.08627e-6 -1 0 3.97366e-6 -1 6.69239e-6 1.3385e-6 -1 3.78444e-6 -1.51377e-6 -1 -2.54314e-5 5.08626e-6 -1 0 -4.5412e-6 -1 0 5.42749e-6 -1 2.59502e-6 0 -1 3.1789e-6 5.40413e-6 -1 4.96704e-7 -1.83781e-6 -0.01514875 -0.9788686 -0.2039287 2.72484e-6 0 1 0 -1 0 0 -1 0 1 0 0 1 0 0 1.17236e-6 0 1 -2.36204e-6 0 -1 0 1 0 0 1 0 7.75794e-7 0 1 0 1 0 0 1 0 -2.71036e-6 0 -1 -5.01937e-7 -1 0 1 0 0 1 0 0 -1 0 0 -1.5878e-6 0 1 -1.53818e-7 -1 0 -1.53818e-7 -1 0 6.02507e-7 0 1 5.60985e-7 1 0 5.60985e-7 1 0 -7.61983e-7 0 -1 -1.40246e-7 -1 0 -1.40247e-7 -1 0 0 1 0 0 1 0 -8.10452e-7 0 1 -2.36204e-6 0 -1 -1.40246e-7 -1 0 0 1 0 1 -5.57702e-7 0 -1.24664e-6 0 1 -2.77327e-7 0 -1 -2.80491e-7 -1 0 -2.80493e-7 -1 0 -1 2.78851e-7 0 1 -1.24663e-6 0 1.24369e-5 0 1 -5.59309e-5 1.9378e-5 1 -0.006005167 -0.005324125 0.9999679 0.07673674 0.06051164 0.9952135 1.97722e-5 0 1 1.87125e-6 0 1 4.72194e-6 0 1 5.82259e-6 0 1 1.31081e-6 0 1 -5.41771e-5 0 1 2.68853e-6 0 1 7.41789e-7 0 1 -0.04318982 0.004621565 0.9990562 -0.07033425 -0.006264925 0.9975039 0.03961241 -1.96911e-4 0.9992152 0.7426093 0.06213986 -0.6668359 -0.3197515 2.37207e-4 0.9475014 -0.006012141 0.02430212 0.9996867 -0.382514 -0.08428049 0.9200978 0.129199 0.5241786 0.8417508 0 -0.008725166 0.999962 0.04402685 3.62296e-4 0.9990304 0.04396796 -0.04402047 0.9980627 0.1850924 0.03136849 0.9822204 0.1961298 0.6354916 0.7467821 -0.003089308 0.001516759 0.9999942 0.3435864 0.1444705 0.9279422 -0.3576435 -0.07245934 0.9310429 -7.32077e-5 -3.01465e-5 1 2.04248e-5 0 1 -4.30023e-7 0 1 -7.60035e-7 0 1 3.0116e-4 -4.18874e-4 1 -3.11745e-6 0 1 2.30804e-6 0 1 -4.57565e-6 0 1 1.75713e-6 0 1 -8.68178e-7 0 1 -1.5404e-6 0 1 1.5404e-6 0 1 7.4376e-6 0 1 -2.04455e-6 0 1 1.33192e-6 0 1 -1.4476e-6 0 1 6.66104e-7 0 1 -1.458e-6 0 1 -3.18621e-7 0 1 1.1536e-6 0 1 -1.13288e-6 0 1 2.67203e-6 0 1 -4.27224e-6 0 1 2.62016e-6 0 1 -3.26903e-6 0 1 1.45361e-6 0 1 -7.1278e-6 0 1 2.72658e-6 0 1 1.72255e-6 0 1 -5.06367e-6 0 1 2.62015e-6 0 1 -7.13978e-6 0 1 3.21567e-4 -7.96225e-4 0.9999997 -9.3095e-5 3.90016e-4 1 -1.32597e-5 3.45911e-4 1 2.34606e-4 -0.002246737 0.9999975 -4.51528e-5 2.46123e-4 1 1.59019e-5 -3.0715e-4 1 5.50923e-5 -1.1824e-4 1 -1.68721e-5 2.92214e-4 1 -1.31195e-4 -3.45023e-4 1 -1.56893e-4 -2.35073e-4 1 -6.34777e-5 4.6384e-4 1 4.45935e-6 4.98178e-6 1 -2.15488e-6 -3.81344e-6 1 1.41253e-6 0 1 2.87322e-6 0 1 -4.23479e-6 0 1 -6.50125e-6 0 1 4.003e-7 0 1 2.75076e-6 0 1 -2.75811e-6 2.75635e-6 1 0 0 1 0 3.53841e-6 1 -2.39822e-6 0 1 1.69639e-6 0 1 3.5307e-6 0 1 0 0 1 -1.51477e-6 0 1 -6.10468e-6 0 1 1.29982e-6 0 1 1.75045e-6 0 1 1.08259e-5 0 1 1.25609e-7 0 1 6.00126e-7 0 1 -1.49028e-6 -3.26347e-7 1 8.48873e-7 0 1 -2.50254e-6 -9.15811e-6 1 6.54027e-7 0 1 -5.60518e-7 0 1 8.47504e-7 0 1 -1.25811e-6 0 1 -2.39648e-6 0 1 1.09042e-6 0 1 3.78688e-7 0 1 1.50007e-6 -9.86419e-6 1 2.91939e-6 -7.54571e-6 1 1.59454e-6 0 1 -3.63314e-6 -4.95426e-5 1 1.61765e-6 0 1 5.94316e-5 -2.34776e-5 1 4.02444e-6 0 1 -1.21733e-6 0 1 3.23316e-6 0 1 -1.61463e-5 -4.01032e-5 1 -1.52747e-5 4.57529e-6 1 2.18666e-6 5.76694e-5 1 -2.10651e-6 -1.9043e-5 1 5.5842e-5 -1.13521e-5 1 1.98096e-6 -4.53665e-6 1 8.62119e-6 0 1 -9.08298e-7 -4.95432e-5 1 2.27843e-6 1.66993e-6 1 7.97769e-7 4.46137e-6 1 -5.63301e-7 4.25235e-6 1 -2.66154e-6 -4.65204e-6 1 -2.24565e-6 -5.49454e-6 1 -3.5598e-6 7.88843e-7 1 2.28067e-6 0 1 -1.41544e-5 -1.44547e-5 1 -1.52747e-5 4.57529e-6 1 2.18666e-6 5.76694e-5 1 -1.62548e-6 -2.14347e-5 1 -7.94197e-6 0 1 2.15009e-6 0 1 1.95642e-6 0 1 -5.22861e-6 0 1 -5.05105e-7 0 1 -3.81737e-6 0 1 2.7562e-6 0 1 1.14945e-6 0 1 5.60855e-7 0 1 -3.82524e-6 0 1 -1.49658e-6 0 1 -1.64787e-6 0 1 7.36567e-7 0 1 -5.33014e-7 0 1 -1.22108e-6 0 1 2.17523e-6 0 1 -3.32501e-6 0 1 -1.77044e-6 0 1 1.21712e-5 0 1 -2.10827e-5 0 1 2.73708e-7 0 1 8.98928e-7 0 1 -1.76737e-6 0 1 -4.90242e-6 0 1 3.78691e-7 0 1 -2.0754e-6 0 1 6.08235e-6 0 1 -2.59821e-6 0 1 2.57689e-6 0 1 -1.4368e-6 0 1 -4.39744e-7 0 1 2.32399e-7 0 1 -5.9965e-6 0 1 -3.70839e-7 0 1 -1.29981e-6 0 1 1.46662e-6 0 1 5.84273e-5 -1.13521e-5 1 6.58278e-5 2.99239e-5 1 0 7.10084e-6 1 7.97769e-7 4.46138e-6 1 7.7454e-7 4.25235e-6 1 -1.32621e-6 3.05069e-6 1 2.16526e-6 0 1 -1.30628e-5 0 1 -1.63912e-5 -1.44547e-5 1 -1.40516e-5 1.10393e-6 1 1.0952e-5 6.16079e-5 1 -1.77109e-4 6.23272e-5 1 4.45787e-6 0 1 2.91028e-6 -3.09408e-6 1 2.20019e-6 0 1 -9.96233e-6 0 1 -6.32711e-7 0 1 5.96111e-5 -5.85057e-6 1 -3.38579e-6 0 1 8.81688e-7 0 1 1.54039e-6 0 1 2.73182e-6 -3.62952e-5 1 5.61539e-6 0 1 -1.64425e-6 0 1 -1.32864e-6 0 1 -3.17046e-6 -9.20598e-6 1 0 -1.90958e-5 1 8.76175e-6 6.16091e-5 1 -1.42661e-5 2.58185e-6 1 -1.39993e-5 -4.29157e-7 1 2.86443e-6 0 1 -7.13666e-6 0 1 -4.02676e-6 0 1 -2.45357e-6 0 1 4.3494e-7 0 1 -1.65487e-6 0 1 4.09005e-7 0 1 1.18503e-6 0 1 9.42736e-7 1.7004e-6 1 1.85633e-6 2.49359e-6 1 4.45584e-6 0 1 1.87379e-6 0 1 8.89914e-7 0 1 4.31749e-6 0 1 2.83919e-6 0 1 -4.27426e-7 0 1 1.53786e-6 0 1 1.25313e-6 0 1 2.44305e-6 0 1 -1.93907e-6 0 1 -1.57846e-6 0 1 3.01869e-6 0 1 -1.95534e-6 0 1 -5.25301e-7 0 1 -2.9982e-6 0 1 5.87695e-7 0 1 1.49661e-6 0 1 -7.90134e-7 0 1 -2.42833e-6 0 1 -2.49468e-7 0 1 5.39942e-7 0 1 -1.02305e-6 0 1 -7.70198e-7 0 1 0 0 1 1.94536e-6 0 1 -6.21923e-7 0 1 2.2199e-5 0 1 -4.16271e-6 0 1 2.0155e-7 0 1 -4.9392e-5 0.001680016 0.9999987 1.64368e-4 5.41074e-4 1 2.08692e-6 0 1 3.16129e-6 0 1 -3.33745e-6 0 1 1.17559e-6 0 1 -5.0297e-7 0 1 -3.67744e-6 0 1 4.97914e-7 0 1 -1.04849e-6 0 1 9.08451e-6 0 1 -7.37876e-7 0 1 2.12298e-6 0 1 -1.06148e-6 0 1 1.58044e-6 0 1 1.93516e-6 0 1 -1.93517e-6 0 1 5.30561e-7 0 1 -1.0949e-6 0 1 -0.02477318 0.003477811 0.9996871 -0.02476894 -0.005192041 0.9996798 0.01760637 -0.005263805 0.9998312 0 -0.004362702 0.9999906 0.1801472 0.0251336 0.9833185 2.81231e-4 -5.56085e-4 0.9999998 5.89461e-7 0 1 8.79219e-7 0 1 -1.86744e-6 0 1 -3.92266e-7 0 1 2.55917e-6 0 1 -1.96134e-5 0 1 5.1732e-7 0 1 0 -1.85729e-6 1 6.68021e-7 1.48513e-6 1 -1.11877e-6 6.35113e-7 1 2.20804e-7 0 1 -5.50475e-7 0 1 1.57469e-6 0 1 1.20253e-6 0 1 3.14668e-7 0 1 -2.8051e-6 0 1 0 0 1 -6.78576e-7 0 1 -1.56202e-6 0 1 6.34914e-7 0 1 -7.34099e-7 0 1 1.10816e-6 0 1 -2.47973e-6 0 1 0.005270421 -0.004263401 0.9999771 0.6940205 -0.05980271 0.7174673 0.02285152 0.3187693 0.9475569 -0.2578735 0.6627718 0.7030184 -0.197719 -0.09242922 0.9758914 0.07686352 -0.01325231 0.9969536 -0.08777892 0.002227783 0.9961376 -0.4842492 0.0262534 0.8745362 -6.64756e-5 -4.25764e-5 1 5.1636e-4 -2.5359e-4 0.9999998 2.80563e-4 -5.38981e-5 1 1.93828e-4 -1.35913e-5 1 3.20841e-4 -1.77717e-4 1 -2.65995e-5 6.05379e-5 1 5.49537e-5 1.20291e-4 1 -2.52217e-4 0.001473546 0.9999989 3.16727e-4 -1.59586e-4 1 -1.07107e-6 0 1 9.29138e-7 0 1 -4.53577e-7 0 1 -1.56525e-7 0 1 0 0 1 5.91804e-7 0 1 -6.35579e-7 0 1 -1.48858e-6 0 1 1.41258e-5 0 1 8.85945e-7 0 1 1.42982e-6 0 1 -3.2665e-6 0 1 1.98684e-6 0 1 4.55712e-7 0 1 2.58726e-7 0 1 -1.62531e-6 0 1 3.65294e-6 0 1 1.26616e-6 0 1 7.91836e-7 0 1 -1.21564e-6 0 1 4.31212e-6 0 1 -1.64593e-6 0 1 5.22153e-6 0 1 -2.30131e-6 0 1 4.74455e-6 0 1 -3.56143e-5 0 1 0 0 1 1.32076e-6 0 1 -8.33458e-6 -4.58266e-6 -1 -4.84423e-7 0 -1 -3.47652e-6 0 -1 -2.32322e-7 0 -1 4.5668e-7 0 -1 4.50401e-6 0 -1 -3.67321e-6 0 -1 -2.8382e-7 0 -1 6.33534e-7 0 -1 1.67194e-6 0 -1 -3.01897e-6 0 -1 -4.24188e-6 0 -1 2.89739e-7 0 -1 -1.31081e-6 0 -1 -6.36982e-6 0 -1 -7.64656e-6 0 -1 -7.15308e-6 0 -1 2.46677e-6 0 -1 -8.46452e-7 0 -1 -6.28141e-7 0 -1 3.41785e-6 0 -1 -7.27354e-6 0 -1 2.58053e-6 0 -1 -1.02914e-6 0 -1 7.67852e-6 0 -1 -3.21015e-6 0 -1 -1.49911e-6 0 -1 1.98065e-6 0 -1 -1.36184e-5 0 -1 -1.8022e-6 0 -1 1.85447e-6 0 -1 -4.65224e-6 0 -1 2.1865e-5 0 -1 -2.47223e-6 0 -1 -9.06294e-6 0 -1 -3.15887e-7 0 -1 -2.41863e-6 0 -1 2.2043e-6 0 -1 -6.72413e-6 0 -1 4.13144e-6 0 -1 1.39057e-6 0 -1 -3.9889e-6 0 -1 -1.90864e-6 -2.19422e-6 -1 0 0 -1 0 -2.62138e-6 -1 9.99896e-7 0 -1 -1.51723e-6 0 -1 -8.14608e-6 0 -1 5.83203e-6 0 -1 -2.16634e-6 0 -1 -7.54717e-5 -2.41107e-4 -1 6.37404e-5 1.11641e-4 -1 5.91291e-5 7.93939e-5 -1 1.82322e-6 5.35695e-5 -1 -4.1333e-6 8.09167e-5 -1 -2.80672e-7 0 -1 2.1392e-6 0 -1 2.91392e-6 0 -1 1.36414e-6 0 -1 -6.57388e-6 0 -1 -1.35315e-6 0 -1 -1.43449e-6 0 -1 1.61765e-6 5.61131e-6 -1 4.17059e-5 1.62358e-4 -1 1.5456e-5 4.34397e-6 -1 1.75838e-6 0 -1 9.66349e-5 1.47586e-5 -1 -2.74723e-6 -2.20847e-5 -1 -9.28081e-6 -2.27111e-5 -1 -2.69002e-5 -3.65738e-5 -1 -2.68002e-6 0 -1 -3.32356e-5 -6.15601e-5 -1 -1.29982e-6 0 -1 6.72139e-6 -2.16791e-7 -1 4.21514e-6 6.52608e-7 -1 -4.4236e-7 0 -1 4.01918e-7 0 -1 -1.30556e-6 0 -1 9.45524e-6 -1.24894e-5 -1 3.09222e-6 2.07484e-5 -1 3.78314e-6 0 -1 -2.35899e-6 0 -1 8.14609e-6 0 -1 1.47078e-5 0 -1 -2.63961e-6 0 -1 -5.99966e-6 0 -1 7.99602e-6 0 -1 1.15757e-6 0 -1 -1.35542e-5 0 -1 1.47343e-6 0 -1 4.25625e-7 0 -1 -5.10374e-7 0 -1 1.26202e-6 0 -1 1.1546e-5 0 -1 -5.10037e-6 0 -1 2.28388e-6 0 -1 -2.32799e-5 0 -1 -1.27131e-7 0 -1 1.40266e-6 0 -1 -6.61999e-7 0 -1 -2.60497e-6 0 -1 -6.02532e-6 0 -1 -9.06643e-7 0 -1 1.58336e-6 0 -1 -2.45408e-6 0 -1 4.66587e-6 0 -1 1.30402e-6 0 -1 -4.74314e-6 0 -1 -1.18579e-6 0 -1 1.03515e-6 0 -1 -2.63354e-6 0 -1 -3.64813e-6 0 -1 1.57974e-6 0 -1 -1.97772e-6 0 -1 -4.05923e-6 0 -1 5.41258e-6 0 -1 -2.82562e-6 0 -1 1.23433e-7 0 -1 4.30067e-7 0 -1 -1.9902e-6 0 -1 6.66262e-7 0 -1 -4.62119e-6 0 -1 1.6775e-6 0 -1 1.70386e-6 0 -1 2.49377e-6 0 -1 1.82386e-6 0 -1 1.32627e-5 0 -1 -7.774e-7 0 -1 1.65799e-6 0 -1 -3.56346e-6 0 -1 2.35685e-7 0 -1 -2.17373e-7 0 -1 3.46976e-6 0 -1 -7.30009e-6 0 -1 8.52572e-7 0 -1 -1.0861e-6 0 -1 3.53136e-7 0 -1 4.54301e-6 0 -1 1.77848e-7 0 -1 4.2743e-7 0 -1 -3.08433e-6 0 -1 3.23902e-6 0 -1 9.44465e-7 0 -1 -3.82747e-7 0 -1 -1.20654e-6 0 -1 1.76695e-5 0 -1 -1.98233e-6 0 -1 -2.88156e-6 0 -1 7.96927e-7 0 -1 1.89814e-6 0 -1 -5.28137e-6 0 -1 4.69142e-6 0 -1 1.94947e-6 0 -1 2.61265e-5 0 -1 -2.88339e-6 0 -1 2.53958e-7 0 -1 -2.80494e-7 0 -1 -2.19563e-6 0 -1 5.40226e-6 0 -1 7.11058e-6 0 -1 -5.06086e-6 0 -1 6.80148e-6 0 -1 -1.33452e-6 0 -1 1.3351e-6 0 -1 4.06351e-6 0 -1 -9.33204e-6 -4.12467e-7 -1 -8.74839e-6 0 -1 -9.86793e-7 -7.9533e-6 -1 -3.03732e-6 0 -1 1.90078e-6 0 -1 -1.72693e-6 0 -1 1.98287e-5 0 -1 -4.48803e-6 3.19475e-7 -1 -4.72413e-6 6.5898e-5 -1 -2.4747e-6 0 -1 2.43679e-6 0 -1 1.43575e-6 0 -1 -5.48383e-6 0 -1 -6.24966e-7 0 -1 1.84362e-4 -1.26702e-7 -1 -7.40309e-5 1.26682e-4 -1 -1.56537e-5 6.00592e-5 -1 -6.85825e-6 -7.71349e-5 -1 -3.37255e-6 0 -1 -6.61709e-4 -5.53015e-5 -0.9999999 -1.50733e-4 -1.32921e-5 -1 -1.67419e-4 -3.21043e-4 -1 1.07978e-5 -3.7644e-5 -1 -0.1704457 4.11052e-5 -0.9853672 2.35459e-4 4.13006e-5 -1 -8.16476e-5 -2.46247e-5 -1 -5.59622e-5 -3.69491e-5 -1 8.28323e-5 -3.65407e-5 -1 -1.8053e-4 1.4863e-4 -1 -2.05008e-6 -1.80174e-5 -1 1.90491e-6 2.51123e-5 -1 -1.36725e-5 -4.36493e-5 -1 -6.07867e-6 1.36591e-6 -1 -1.32029e-4 -6.40629e-5 -1 -2.49272e-6 -2.60463e-5 -1 -6.33088e-6 4.57428e-6 -1 9.0584e-4 -9.92606e-5 -0.9999997 -6.35355e-5 2.86298e-5 -1 1.67118e-4 -1.44026e-4 -1 -1.36603e-4 1.48297e-4 -1 -1.41369e-7 0 -1 -1.1476e-6 0 -1 0 0 -1 -4.64381e-7 0 -1 -2.93338e-6 0 -1 3.66971e-7 0 -1 3.92772e-7 0 -1 -2.52567e-7 0 -1 2.71009e-7 0 -1 -2.13054e-7 0 -1 2.84733e-6 0 -1 2.39265e-6 0 -1 2.84597e-6 0 -1 -1.13475e-5 0 -1 -2.94635e-6 0 -1 -5.6298e-6 0 -1 -1.26529e-5 -4.00764e-5 -1 6.53017e-6 -2.27727e-5 -1 1.37494e-5 -9.80878e-6 -1 -4.88116e-6 0 -1 -1.37658e-6 0 -1 1.62204e-6 0 -1 2.85636e-6 -4.99153e-6 -1 1.20657e-6 -2.24408e-5 -1 2.73183e-6 -4.32893e-7 -1 2.51694e-5 4.95996e-5 -1 2.42436e-5 2.51105e-5 -1 1.52445e-6 0 -1 0 1.37736e-6 -1 6.64149e-7 2.98088e-6 -1 -1.09099e-6 0 -1 -2.14213e-6 0 -1 -1.45225e-6 5.63207e-7 -1 4.94018e-6 -4.95574e-7 -1 6.38366e-6 -5.05785e-7 -1 1.35233e-5 0 -1 -1.04607e-6 0 -1 2.46221e-5 0 -1 -2.44796e-6 0 -1 1.82899e-5 0 -1 -3.60722e-6 0 -1 1.09418e-6 0 -1 2.80697e-5 0 -1 0 0 -1 -1.63011e-6 0 -1 -0.323002 -0.9341634 -0.1516859 -0.7199177 -0.6507488 0.241339 -0.9140248 -0.3734958 -0.1583021 -0.93781 0.324265 0.1239551 -0.9479382 0.3059722 0.08828562 -0.3771995 0.9230845 -0.07507038 -0.3267829 0.9450994 0 0.3267879 0.9450978 0 0.3772032 0.9230827 0.07507437 0.9230839 0.3772002 -0.07507514 0.9451022 0.3267748 0 0.9450986 -0.3267853 0 0.9230849 -0.3771983 0.07507073 0.377201 -0.9230843 -0.0750668 0.2069802 -0.9645518 0.1637049 -0.2950832 -0.9496923 -0.1049315 -0.860924 -0.4765686 0.1780232 -0.9623398 0.184869 -0.1993124 -0.2852102 0.9386609 0.1938322 0.2852088 0.9386616 -0.1938308 0.9623397 0.1848691 0.1993131 0.8609241 -0.4765684 -0.1780231 0.2950836 -0.9496928 0.1049254 -0.07317793 -0.9803474 -0.1832048 -0.9623398 0.1848692 -0.1993124 -0.28521 0.938661 0.193832 0.09821271 0.9929246 -0.06674653 0.9923659 0.1168124 0.03955757 0.9816672 0.188581 -0.02769029 0.2960721 -0.9528707 0.06617295 -0.1881991 -0.9796575 -0.06965881 -0.981666 0.1885873 0.02769291 -0.9923657 0.1168141 -0.03955996 -0.09821945 0.9929234 0.06675326 0.1871265 0.9740701 -0.1271666 0.9740694 0.1871267 0.1271715 0.9740694 -0.1871268 -0.1271715 0.07362049 -0.9863193 0.1474933 -0.1881988 -0.9796571 -0.06966549 -0.9816658 0.1885877 0.02769285 -0.9720127 0.2261797 0.06351423 0.1883518 0.9804491 -0.05694901 0.2204203 0.9749045 -0.03124469 0.9929243 0.09821563 0.06674665 0.9740695 -0.1871263 -0.1271705 0.07362264 -0.9863183 0.147499 -0.7405043 -0.6693545 0.06014961 -0.93486 -0.3242094 -0.1446554 -0.9470634 0.3056997 0.09807521 -0.3258767 0.9396741 -0.1040052 -0.09831124 0.9938619 0.05072981 0.9432654 0.3271209 -0.05694198 0.9804492 0.1883531 0.05694305 0.3271209 -0.9432652 -0.05694544 0.2965809 -0.9544963 -0.03124886 -0.9720144 -0.2261735 -0.06351125 -0.9816661 -0.1885869 -0.02769201 -0.1881963 0.9796575 0.0696659 0.07362288 0.98632 -0.1474882 0.9740701 0.1871242 0.1271694 0.9929245 -0.09821486 -0.06674575 0.2204208 -0.9749042 0.03124886 0.188351 -0.9804494 0.05694526 -0.8747646 -0.4842293 -0.01757317 -0.9275496 -0.3317571 -0.1720146 -0.2872302 0.9453043 0.1545918 0.1744039 0.9578301 -0.2283524 0.9623393 0.1848707 0.1993139 0.7337228 -0.6226729 -0.2718996 0.2954379 -0.9508344 0.09290057 -0.2965779 -0.9544972 0.0312528 -0.4295027 -0.8911809 0.1460278 -0.9685193 0.1860603 -0.1653848 -0.7942681 0.5923309 0.1352115 0.288469 0.9493911 -0.1242666 0.4122384 0.9108289 -0.02121895 0.9425032 -0.3268566 0.0696609 0.8725861 -0.4830247 -0.07266831 -0.1881991 -0.9796572 -0.06966203 -0.9816657 0.1885886 0.02769201 -0.9720126 0.2261805 0.06351268 0.1883519 0.9804491 -0.05694901 0.2204207 0.9749042 -0.03124898 0.9929241 0.09821665 0.06674712 0.9740691 -0.187128 -0.1271713 0.07362276 -0.9863191 0.1474933 -0.9941244 0.07420581 -0.07880479 -0.9720137 0.2261763 0.06351083 0.1883487 0.9804499 -0.05694562 0.2204141 0.9749058 -0.03124892 0.992924 0.09821754 0.06674784 0.9929243 -0.09821534 -0.06674718 0.1168155 -0.9923654 0.03955924 0.07420539 -0.9941245 0.0788033 -0.1871235 -0.97407 -0.1271715 -0.9740707 -0.1871209 0.1271695 -0.9740704 0.1871236 -0.1271681 -0.1871241 0.9740699 0.1271711 0.1871235 0.9740701 -0.1271707 0.9740703 0.1871235 0.127169 0.9740707 -0.1871203 -0.12717 0.1871204 -0.9740712 0.1271669 -0.4078268 -0.9010812 0.1474117 -0.9865358 0.07363897 -0.1460294 -0.9432658 0.3271197 0.05694222 0.188351 0.9804497 -0.05694204 0.4295008 0.8911824 0.1460247 0.9842723 -0.09736043 -0.147408 0.7938271 -0.5919968 0.1392063 0.1157687 -0.9834728 -0.139208 -0.972014 -0.2261748 -0.06351315 -0.9941245 -0.0742039 0.07880479 0.07420539 0.9941241 -0.07880926 0.1168152 0.9923657 -0.0395559 0.992924 0.09821826 0.06674784 0.9929242 -0.09821629 -0.06674689 0.2204107 -0.9749062 0.03125733 0.1883525 -0.9804494 0.05694198 -0.9946113 -0.07424175 0.07236528 -0.9946113 0.07424181 -0.0723657 0.1885825 0.9816669 0.02768754 0.1168154 0.9923657 -0.03955584 0.9929242 0.09821623 0.06674736 0.9929246 -0.09821194 -0.06674724 0.1168154 -0.9923655 0.03955918 0.1885851 -0.9816664 -0.027691 -0.9517828 -0.3057858 0.02459031 -0.5964118 0.8018941 -0.03548002 -0.4835978 0.8723008 0.07228213 0.8980375 0.4328035 -0.07880187 0.954874 0.2901416 0.06351131 0.3271152 -0.9432676 -0.0569384 0.188346 -0.9804506 0.05694186 -0.9100497 -0.4113792 -0.05076223 -0.9941248 0.07420092 -0.07880407 -0.9720138 0.2261762 0.06351053 0.1883459 0.9804505 -0.05694532 0.2204129 0.9749062 -0.03124457 0.9929249 0.09820979 0.06674611 0.9929245 -0.09821408 -0.06674575 0.1168154 -0.9923656 0.03955566 0.07420337 -0.9941247 0.07880353 -0.9941245 0.0742039 -0.07880479 -0.9720141 0.2261748 0.06350934 0.1883483 0.98045 -0.0569455 0.3271181 0.9432659 0.05694878 0.9938613 -0.09831506 -0.05073374 0.9749091 -0.2204166 0.0311281 0.1168306 -0.9924945 -0.03613007 -0.0179854 -0.9972257 0.07223302 -0.8320952 0.5172516 0.2001712 -0.9461171 -0.220057 -0.2375657 -0.4794728 -0.8615402 0.1668962 0.2193131 -0.9699957 -0.1049298 0.7938252 -0.5919981 0.1392114 0.9842733 -0.09735077 -0.1474077 0.4968928 0.8580252 0.1299637 0.07333189 0.9818813 -0.1747326 -0.6633608 0.7365598 0.1320312 -0.009697556 0.9886792 -0.1497314 0.4129189 0.9067242 0.0857281 0.9889867 0.07606565 -0.1269626 0.9710082 -0.2247879 0.08132356 0.09843415 -0.9951263 0.005875766 0.002800345 -0.9974043 -0.07195085 -0.9915999 -0.1233078 0.03905004 -0.9436899 -0.3031907 -0.1323813 -0.9432653 -0.3271209 -0.05694454 -0.9804498 -0.1883498 0.05694484 -0.2261799 0.972013 -0.06351006 -0.188583 0.981667 -0.02768409 0.9796599 0.1881869 0.06965762 0.9971942 0.01799291 -0.07266485 0.2204228 -0.9749038 0.0312488 0.1883479 -0.9804502 0.05694246 -0.9503561 -0.2887192 0.1160363 -0.9498435 -0.2912203 0.1139659 0.01775586 -0.9847742 -0.1729298 0.5475251 -0.8035742 0.2334204 0.9295721 0.2969673 -0.2184179 0.8124626 0.5827197 0.01850384 -0.296227 0.9534897 0.0557397 -0.5233315 0.8430324 -0.1241798 0.9350509 0.3239151 0.14408 0.804786 -0.5726203 -0.156287 0.2305141 -0.9586812 0.1667139 -0.2950549 -0.9496076 -0.1057737 -0.97407 -0.1871242 0.1271703 -0.9386599 0.2852133 -0.1938323 -0.223048 0.9567192 0.1869173 0.5513343 0.8074793 -0.2097802 0.01802438 -0.9996831 0.01757746 -0.9885314 -0.1163632 -0.09625697 -0.9573024 0.2227546 0.1842621 -0.01788598 0.9918299 -0.1263068 0.2204155 0.9749095 0.03112298 0.9924947 0.1168293 -0.03612917 0.9949205 0.09840226 -0.02121877 0.07423532 -0.9946119 0.07236295 -0.2089887 -0.9739248 -0.08828496 -0.3059791 -0.9479359 0.08828538 -0.9230861 -0.377195 -0.07507467 -0.9645526 -0.2069709 0.1637114 -0.9341665 0.3229953 -0.1516813 -0.6507417 0.7199259 0.2413337 -0.2980983 0.9235238 -0.2413321 0.2980991 0.9235231 0.2413343 0.6507427 0.7199241 -0.2413363 0.9488447 0.2035986 0.2413322 0.9783163 -0.1335539 -0.158306 0.6500331 -0.7497276 0.1239577 0.6679483 -0.7389522 0.08828848 -0.187121 -0.9740707 -0.127169 -0.9101327 -0.4062371 0.08142554 -0.9744366 0.1871981 -0.1242185 -0.8756386 0.4808532 0.04513704 0.1883416 0.9804515 -0.0569421 0.2204138 0.9749058 -0.03124892 0.9929252 0.09820938 0.0667423 0.9740722 -0.187116 -0.1271651 0.1871153 -0.9740721 0.1271675 -0.09840923 -0.9949198 0.02121883 -0.1168302 -0.9924945 0.03612983 -0.9749107 -0.2204095 -0.03112882 -0.9938622 -0.09830659 0.05073261 -0.226177 0.9720135 -0.0635131 -0.1885797 0.9816675 -0.02768748 0.9946115 0.07424068 0.07236272 0.9946116 -0.07424038 -0.072362 -0.4741026 -0.8564823 -0.2041198 -0.9386258 -0.2851955 0.1940237 -0.9496133 0.2950384 -0.1057689 -0.1871062 0.9740747 0.1271609 0.1871045 0.9740753 -0.1271585 0.9496124 0.2950404 0.1057704 0.9386261 -0.2851952 -0.1940224 0.474105 -0.8564806 0.2041215 -0.1158308 -0.9839633 0.1356444 -0.4805438 -0.8681263 -0.1242357 -0.990192 -0.09793502 0.09964203 -0.9496143 0.2950348 -0.1057692 -0.1871027 0.9740755 0.1271597 0.1871026 0.9740754 -0.1271601 0.9863222 0.07361048 0.1474788 0.9453064 -0.287222 -0.1545948 -0.4804183 -0.8678966 -0.1263084 -0.6783396 -0.734089 0.03112697 -0.9545034 0.2965713 -0.03112757 -0.9098607 0.4118006 0.05073159 0.1883456 0.9804508 -0.05694228 0.2204177 0.9749048 -0.03125095 0.9759747 0.2094179 0.06014704 0.9386274 -0.2851936 -0.1940188 0.5764517 -0.8037256 0.1474069 0.06554013 0.9898425 0.1261602 -0.227144 0.9707582 -0.07767945 -0.9951061 0.09842437 -0.008749127 -0.9554298 -0.1927468 0.223613 -0.3021535 -0.9400469 -0.1581614 0.4777317 -0.8660538 0.1473882 0.7417096 -0.6701947 -0.02656978 0.9747331 0.2217089 0.02721625 0.907109 0.4123216 -0.08452421 0.1627321 0.9805497 0.1097304 -0.2266111 0.9684867 -0.1033487 -0.9464449 0.309346 0.09245121 -0.9938625 0.09830701 -0.05072695 -0.2358558 -0.9697493 0.06291586 -0.3034639 -0.9441335 0.1285359 0.7352484 -0.6643425 -0.1343839 0.9884244 -0.007559239 0.1515258 0.9071107 0.4123184 -0.08452069 -0.1881942 -0.9796582 -0.06966185 -0.9949196 0.09841078 0.02122163 -0.9664319 0.224873 0.1242638 -0.1158337 0.9840224 -0.1352123 0.2195661 0.9711639 0.09290575 0.9951277 0.09841459 -0.00594896 0.9863213 -0.07361543 -0.1474827 0.07361668 -0.9863213 0.1474826 -0.2965825 -0.9544997 -0.03113156 -0.4118005 -0.9098609 0.05072981 -0.9548753 0.2901368 -0.0635131 -0.8980358 0.4328072 0.07880198 0.5613278 0.8238331 -0.07880419 0.6818817 0.7286996 0.06351608 0.811561 -0.5820609 -0.05073404 0.7340826 -0.6783463 0.03112882 -0.9098669 -0.4117871 -0.05073219 -0.9767189 -0.1876235 0.1040079 -0.5923181 0.7942767 -0.1352182 -0.07233214 0.9691562 0.235594 0.8754797 0.4219304 -0.2356055 0.9840226 -0.1158367 0.1352092 0.3258671 -0.9396777 -0.1040027 0.09831041 -0.993862 0.0507304 -0.9720162 -0.2261655 -0.06351161 -0.9816688 -0.1885736 -0.02768355 -0.07423138 0.9946127 0.07235527 -0.01803052 0.999683 0.01757711 0.9711619 0.2195759 -0.09290349 0.9840225 -0.1158367 0.1352099 0.3258679 -0.9396773 -0.1040035 0.09831041 -0.9938619 0.05073142 -0.9720121 -0.2261828 -0.06351321 -0.9941245 -0.0742039 0.0788052 0.07420468 0.9941245 -0.07880479 0.2261734 0.9720144 0.06351089 0.9938622 -0.09830695 -0.05073213 0.974909 -0.2204166 0.03113126 0.2204184 -0.9749086 -0.03112733 0.09830898 -0.993862 0.05073225 -0.4231498 -0.8780125 0.2236926 -0.9432092 -0.2194694 -0.2493786 -0.7857165 0.5859535 0.1982628 0.07326936 0.981598 -0.1763434 0.4117988 0.9098618 0.05072885 0.9938622 -0.09830659 -0.05073231 0.9396752 -0.3258724 0.1040084 0.2190392 -0.9688211 -0.1157908 -0.1871287 -0.9740689 -0.1271719 -0.986319 -0.07362723 0.1474922 -0.9796563 0.1882037 -0.0696637 0.1885899 0.9816654 0.02769309 0.1168141 0.9923657 -0.03955936 0.9929234 0.09822225 0.06674963 0.9740688 -0.1871307 -0.1271704 0.1871275 -0.9740692 0.127171 -0.4231544 -0.8780101 0.2236934 -0.9432085 -0.2194737 -0.2493772 0.07326936 0.9815983 -0.1763419 0.4118005 0.9098609 0.05072981 0.9938622 -0.09830695 -0.05073201 0.9396756 -0.3258713 0.104009 0.2190397 -0.9688208 -0.1157929 -0.187128 -0.9740693 -0.1271704 -0.986319 -0.07362723 0.1474924 -0.9796563 0.1882037 -0.06966358 0.1885874 0.981666 0.02769136 0.1168137 0.9923658 -0.03955757 0.9929234 0.09822225 0.06674987 0.9740689 -0.18713 -0.1271704 0.1871259 -0.9740697 0.1271694 -0.222752 -0.9573036 0.1842595 -0.9700353 0.176629 -0.1668348 -0.9671721 0.2186641 -0.1294771 -0.09727972 0.9834555 0.1528137 0.6226736 0.7337214 -0.2719017 0.9691523 0.07234328 0.2356062 0.3244222 -0.9070459 -0.268362 -0.09727919 -0.9834553 -0.1528154 -0.9671723 -0.2186632 0.1294774 -0.9548743 -0.2901405 0.06351095 -0.2261748 0.972014 -0.06351262 -0.1885829 0.9816668 -0.02769017 0.9528695 0.2960762 0.06617164 0.9803469 -0.07317572 -0.1832084 0.4765694 -0.860924 0.1780216 -0.1883553 -0.9804487 -0.05694603 -0.3271262 -0.9432634 0.05694401 -0.9804499 0.1883491 -0.05694508 -0.943264 0.3271251 0.0569421 0.1883549 0.9804489 -0.05694293 0.2204147 0.9749054 -0.03125518 0.9438118 0.3263376 0.05218338 0.9744369 -0.187194 -0.1242224 0.8756293 -0.48087 0.045138 -0.1883515 -0.9804493 -0.05694741 -0.2204169 -0.974905 -0.03125292 -0.9929249 -0.09821015 0.06674534 -0.9740696 0.1871269 -0.1271689 -0.07362508 0.9863191 0.1474927 0.1881961 0.9796578 -0.06966292 0.9816667 -0.1885836 0.02769118 0.9720134 -0.2261777 0.06351083 -0.4231533 -0.8780109 0.2236922 -0.9003333 -0.4074894 -0.1528148 -0.6729516 0.7282666 0.1294755 -0.8010039 0.5973515 -0.03955024 0.4114151 0.9090013 0.06674122 0.7163299 0.6703007 -0.1938257 0.9258413 -0.3210817 0.1993104 0.4231553 -0.8780093 -0.2236948 -0.2190391 -0.968821 0.1157919 -0.939675 -0.3258723 -0.1040102 -0.9938623 -0.09830701 0.05073022 -0.4118049 0.909859 -0.05072855 -0.07327073 0.9815986 0.1763399 0.785718 0.585952 -0.1982618 0.9432077 -0.2194749 0.2493792 0.4231536 -0.8780112 -0.2236908 -0.1871296 -0.974069 -0.1271702 -0.9740688 -0.1871302 0.1271701 -0.9740687 0.1871307 -0.1271708 -0.2950612 0.9496054 0.1057759 0.1866758 0.9717134 -0.1446564 0.860926 0.4765655 0.178022 0.9623391 -0.1848703 -0.1993152 0.2852152 -0.93866 0.1938296 -0.2901371 -0.9548752 -0.0635125 -0.4328035 -0.8980374 0.07880365 -0.8238337 0.5613271 -0.07880365 -0.8009991 0.5973576 -0.03955191 0.4114134 0.909002 0.06674128 0.5815175 0.8107915 -0.0667423 0.9544976 -0.2965766 0.0312497 0.9432685 -0.3271116 0.05694299 -0.3229963 -0.9341653 -0.1516861 -0.7199231 -0.6507449 0.2413337 -0.9235235 -0.2980977 -0.2413343 -0.9235237 0.2980988 0.2413322 -0.7199217 0.6507455 -0.2413362 -0.3230029 0.9341638 0.1516809 0.2069771 0.9645514 -0.1637105 0.3771999 0.923084 0.07507449 0.9230859 0.3771956 -0.07507401 0.9450982 0.3267866 0 0.9450987 -0.3267852 0 0.9230841 -0.3772003 0.07507228 0.3771938 -0.9230865 -0.07507503 0.2069665 -0.9645538 0.1637094 -0.9946107 -0.07424575 0.07236838 -0.9946109 0.07424628 -0.07236659 0.09841489 0.9949193 0.02121919 0.1168306 0.9924945 0.03613007 0.974907 0.2204255 -0.03113079 0.993863 0.0982989 0.05073308 0.2261792 -0.9720132 -0.06351006 0.1885899 -0.9816654 -0.02769482 -0.8911823 -0.4295011 -0.1460241 -0.9865356 -0.07363748 0.1460309 -0.3231371 0.9317888 -0.1653848 0.1158333 0.9840222 0.1352152 0.907706 0.4108231 -0.08540713 0.9915081 0.09807002 0.08540505 0.5923287 -0.7942698 -0.1352118 0.1860574 -0.9685202 0.165382 -0.186058 -0.9685201 -0.1653826 -0.592334 -0.7942652 0.1352156 -0.9767198 0.187618 -0.1040092 -0.9098594 0.4118037 0.05073201 0.1883515 0.9804496 -0.05694222 0.3271136 0.9432682 0.05693781 0.9804486 -0.1883558 -0.05694544 0.8911817 -0.4295024 0.1460242 -0.0983082 -0.9938622 -0.05072981 -0.2204158 -0.9749094 0.03112262 -0.9749097 -0.2204135 -0.03112882 -0.9938622 -0.09830695 0.05073177 -0.2261764 0.9720138 -0.0635097 -0.07420587 0.9941245 0.07880377 0.9941247 -0.0742039 -0.07880258 0.9720154 -0.2261691 0.06351172 -0.1158308 -0.9839632 0.1356453 -0.6271126 -0.7389512 -0.2463352 -0.9842739 -0.09734559 0.1474071 -0.3320429 0.9283933 -0.1668334 -0.1885631 0.9816707 -0.02768659 0.9946122 0.07423216 0.07236218 0.9691591 -0.1764763 -0.1720082 -0.6271127 -0.7389513 -0.2463347 -0.9842738 -0.09734559 0.1474074 0.9946122 0.07423216 0.07236218 0.9691591 -0.1764763 -0.1720081 -0.4123255 -0.9110172 -0.005951046 -0.4830215 -0.8725879 -0.07266831 -0.9545037 0.2965574 0.03124648 -0.9749078 0.220406 -0.03124552 -0.09820091 0.9929262 0.06673955 0.1871054 0.9740749 -0.1271604 0.9386254 -0.2851971 -0.1940231 0.6678878 -0.7388936 0.08923149 -0.1158321 -0.9839632 0.1356443 -0.6271098 -0.7389541 -0.2463334 -0.9738458 -0.208956 0.08922874 -0.4842215 0.8747689 -0.01758116 -0.3317535 0.9275519 -0.1720094 0.9691607 0.1764671 0.1720088 0.9691603 -0.1764678 -0.1720097 -0.9946113 -0.07424414 0.072362 -0.9946124 0.07422894 -0.072362 0.1885654 0.9816703 0.02768713 0.1168047 0.9923671 -0.03955078 0.9929246 0.09821385 0.06674361 0.9929251 -0.09820955 -0.06674385 0.1168194 -0.9923653 0.03955245 0.1885804 -0.9816673 -0.02768802 0.06555354 0.9898429 0.1261503 -0.2271433 0.9707593 -0.07766878 -0.9951059 0.09842771 -0.008745849 -0.9974213 -0.001052677 0.07176071 -0.1280251 -0.9910166 -0.03867673 -0.3034539 -0.9441379 0.1285282 0.7352569 -0.6643338 -0.1343804 0.9884244 -0.007559239 0.1515262 0.9071115 0.4123169 -0.08452057 -0.9720161 -0.2261662 -0.06351196 -0.9941246 -0.0742104 0.07879811 -0.01798617 0.9972261 -0.0722264 0.2248623 0.9664348 0.1242612 0.9688215 0.2190374 -0.1157912 0.9688231 -0.2190304 0.1157912 0.3258679 -0.9396773 -0.1040039 0.09830939 -0.993862 0.05073142 0.06558853 0.9898425 0.1261356 -0.2271338 0.9707594 -0.07769536 -0.995106 0.09842813 -0.008724689 -0.9554306 -0.1927482 0.223608 -0.3021509 -0.9400489 -0.1581549 0.4777393 -0.86605 0.1473862 0.7417085 -0.670196 -0.02656966 0.9747331 0.2217089 0.02721601 0.9071115 0.4123162 -0.08452361 -0.1871184 -0.9740714 -0.1271685 -0.9740708 -0.187123 0.1271661 -0.9740707 0.1871233 -0.1271663 -0.18712 0.974071 0.1271684 0.1871213 0.9740709 -0.1271675 0.9740732 0.1871103 0.1271664 0.9740729 -0.1871112 -0.127167 0.1871204 -0.9740712 0.1271668 -0.1885859 -0.9816662 0.02769124 -0.226175 -0.9720144 0.06350672 -0.9804497 0.1883497 -0.05694395 -0.9749043 0.2204197 -0.03125464 -0.09821778 0.9929241 0.06674736 0.1871241 0.9740705 -0.1271665 0.9863195 0.07362431 0.1474902 0.9796575 -0.1881971 -0.06966447 0.01766681 -0.9787862 -0.2041214 -0.6702748 -0.7163012 0.1940215 -0.9807879 -0.1154642 -0.1572362 -0.724617 0.6695604 0.1631538 -0.01785314 0.9893922 -0.1441677 0.4107985 0.907716 0.0854181 0.9840204 0.1158454 -0.1352179 0.8754821 -0.4219266 0.2356036 -0.3916536 -0.910059 -0.1356471 -0.9622738 0.2238999 0.1545903 -0.8173731 0.5569088 -0.1474925 0.3249768 0.9371333 0.1271665 0.6490805 0.7500149 -0.1271698 0.9699083 -0.2192924 0.1057772 0.8085708 -0.5799013 -0.0996378 -0.01790702 -0.9920923 0.124226 -0.09793335 -0.9901927 -0.09963756 -0.8085687 -0.5799042 0.09963846 -0.9807885 -0.1154599 -0.1572361 -0.6412684 0.7409794 0.1993098 0.07254391 0.9719568 -0.2236903 0.8054668 0.5488018 0.2236958 0.9623423 -0.1848581 -0.1993108 0.3903963 -0.9071201 0.1572383 -0.8125966 -0.582796 -0.005957305 -0.9167083 -0.3278737 -0.2283523 -0.6412674 0.7409795 0.1993129 0.1723877 0.9467582 -0.2719035 0.8031448 0.547219 0.2356052 0.7344809 -0.6233108 -0.2683685 0.393478 -0.9142796 0.0962693 -0.1163692 -0.9885303 0.09626054 -0.9951255 -0.09843641 -0.005947768 -0.9578298 0.1744042 -0.2283533 -0.1848656 0.9623411 0.1993102 0.6226733 0.7337207 -0.2719043 0.9691531 0.0723375 0.2356054 0.3244205 -0.9070461 -0.2683631 -0.3914632 -0.9096021 -0.1392149 -0.803736 -0.5764371 0.1474074 -0.8175507 0.5570331 -0.1460309 -0.6533357 0.7549235 0.05694866 0.6533337 0.7549252 -0.05694884 0.8175517 0.5570318 0.1460305 0.8037344 -0.576439 -0.1474078 0.3914634 -0.909602 0.1392143 -0.6679514 -0.7389494 -0.08828884 -0.7389506 -0.6679496 0.0882917 -0.9880141 0.1348783 -0.07507431 -0.9818714 0.1895483 0 -0.6550871 0.7555534 0 -0.6108145 0.7882063 0.07507735 0.2089878 0.973925 -0.08828556 0.3059808 0.9479348 0.08829206 0.9479374 0.305974 -0.08828675 0.9739251 0.2089864 0.08828759 0.7882089 -0.6108117 -0.07507407 0.755553 -0.6550877 0 0.1895394 -0.9818732 0 0.1348739 -0.9880149 0.0750699 -1 0 8.0028e-6 -1 2.28102e-6 1.22265e-6 1 2.30075e-6 0 -1 0 1.05311e-5 -1 2.85835e-6 0 1 0 -1.08727e-5 -0.4020365 -0.9111437 -0.09046542 -0.4102586 -0.9098837 -0.06164139 0.04677003 0.06733787 -0.9966335 -0.1137432 0.0391013 -0.9927405 0.9998157 1.19192e-4 -0.01919829 0.04749739 0.04701495 -0.9977644 0 0.03935694 -0.9992253 1 3.11573e-6 0 1 -3.84909e-7 0 -0.00210148 0.1231827 -0.9923819 0.04310446 0.1630272 -0.9856796 -1 1.60759e-6 0 0.04065036 0.04529219 -0.9981464 0 0.03873527 -0.9992496 -0.354239 -0.1943737 -0.9147315 0.03678971 0.1666734 -0.9853256 0.04749822 0.04701495 -0.9977644 0 0.03935688 -0.9992253 -0.02005863 -0.2176195 -0.9758276 0.05346041 -0.151542 -0.9870041 -0.1858174 0.001849353 -0.9825826 -0.9993186 0.007838249 0.0360704 -0.9998993 0.01417469 7.55614e-4 0.168439 -0.7399012 -0.6512869 0.9883505 0.1420684 -0.05458825 0.8055422 -0.07364034 -0.5879446 0.8208667 -0.06148374 -0.5678008 0.561042 0.0508157 0.8262262 0.5294371 0.003255665 0.848343 -0.6822738 0.003564417 0.7310882 -0.7242652 -0.002795219 0.6895159 0.4102481 -0.9098877 0.06165379 0.4078294 -0.9103496 0.07027763 -0.9460783 -0.1109617 -0.3043413 -0.9938178 -0.08152276 -0.07536733 -0.01133948 -0.999916 0.00628823 0.01242023 -0.9998578 0.01140886 0.01048469 -0.9999451 0 0.04252392 -0.4149754 -0.9088384 -2.05374e-4 -0.01423722 -0.9998987 -0.9991275 0.02674973 -0.03207319 -0.9993 -0.03089523 -0.02109825 -0.9976654 -0.001504182 -0.06827634 -0.9968363 0.002101182 -0.07945472 0.9807028 0.1924702 -0.03431075 0.9931261 0.1133043 0.02937108 0.04197072 0.9984214 0.03732454 0.03968441 0.9988873 0.02548158 0.9987757 -0.01676392 0.04654163 0.9991498 0.01499187 -0.03840506 0.05276554 -0.99791 -0.03730225 0.05415219 -0.9975312 -0.04471123 0.9807004 0.1924812 -0.03432118 0.9931262 0.1133037 0.02937102 -0.8230462 -0.4901124 -0.2870276 -0.9931349 -0.1132316 0.02935612 -0.9807136 -0.1924123 -0.03432828 -0.9931349 -0.1132316 0.02935773 -0.04196727 -0.9984229 0.037292 -0.03968578 -0.9988864 0.02551412 -0.998775 0.01676362 0.04655736 -0.9991497 -0.01499968 -0.03840529 -0.05275827 0.9979104 -0.03730273 -0.05414998 0.9975314 -0.04471147 0.1403299 0.985857 -0.09161645 -0.1097589 0.9933171 -0.03569602 -0.06393939 0.9975628 0.02793413 -0.004910826 0.9999856 0.002177715 0.01163476 0.9998605 0.0119915 -0.6961961 0.01350194 -0.7177248 -0.6624795 -0.01573473 -0.7489148 -0.7078652 0.004978418 -0.70633 -0.6999324 0.01156729 -0.7141155 -0.7310556 -0.02924716 -0.6816909 -0.00123012 -0.152006 -0.9883789 -0.1233779 -0.06898164 -0.9899593 0.1141241 -0.1217895 -0.9859731 0.01255208 -0.07178151 -0.9973415 0.6977397 0.01351863 -0.716224 0.6676348 -0.0136947 -0.744363 0.7343732 0.004043936 -0.6787339 0.7245504 -0.007085859 -0.6891855 0.7105979 0.01858168 -0.7033529 0.6946669 -0.001199126 -0.7193306 -0.7468617 -0.02548557 0.6644909 -0.740463 -0.03503763 0.6711833 -0.7146564 0.006124854 0.699449 -0.7031054 -0.004885375 0.7110689 -0.7639791 0.06375306 0.6420838 0.04849648 0.9985073 0.02512985 0.04373282 0.9989088 0.01639598 -1.79071e-5 1 3.29133e-5 0.01646667 0.9994313 -0.02942639 -0.1133923 0.987853 -0.1062487 -0.06939733 -0.9919009 -0.1063797 0.1105282 -0.9932327 -0.03567206 0.0662626 -0.9974765 0.02549546 -0.02431315 -0.9996607 -0.009347319 0.04676479 -0.9977313 -0.04842889 0.007105231 0.8503126 -0.5262301 0.02887308 0.8379253 -0.5450207 -0.08245056 -0.3435213 0.9355186 0 -0.2818524 0.9594578 0.0636841 0.8302378 -0.5537596 -0.04019236 -0.3683485 0.9288186 0 -0.3391562 0.9407301 0.04452049 0.824017 -0.5648134 -0.06633853 -0.3317257 0.9410406 0 -0.2818542 0.9594573 0.05357992 0.8282754 -0.5577537 0.05044519 0.8221601 -0.567017 0.03739136 -0.3322352 0.9424551 0 -0.3597472 0.9330499 -0.001282036 0.8319315 -0.5548768 0.01663106 -0.3324185 0.9429854 0 -0.3446952 0.9387148 0.0394175 -0.5058601 -0.8617145 0.009850323 0.9988529 0.04686301 -0.008161604 0.9998915 -0.01226526 -0.9983418 0.05611109 -0.01285415 -0.9118202 0.1770043 -0.3704773 -0.8602427 -0.4648354 0.2095484 0.01435232 0.9988078 0.04666 -0.01434862 0.9988078 -0.04666 -0.1217408 0.1876753 0.9746575 -5.39975e-4 -0.05501079 0.9984857 0.1023523 0.2268934 0.9685265 6.23445e-4 0.04341256 0.9990571 0.9973741 0.05709081 -0.04456025 0.9936568 0.01273101 0.1117321 0.9952521 0.05755448 0.07849109 0.7267288 -0.6619077 -0.1836941 0.9268164 0.2573807 0.2734351 0.1109902 -0.04986345 0.9925699 0.4826704 0.1096462 0.8689115 -0.01086521 0.9967134 -0.08027654 0.006390035 0.9998371 -0.0168811 -0.005883634 0.9080626 -0.4187931 0.9873639 0.1214463 0.1017998 -0.02208012 -0.4118962 0.9109632 -0.002384185 -0.3733457 0.9276892 -0.9173058 0.1371493 0.3738183 -0.9960994 0.08822649 -0.001463115 -0.9916473 0.1067108 0.07244682 0.03864395 -0.01981222 -0.9990567 0.2036638 0.3166092 -0.9264339 -0.02354609 0.9312654 -0.3635802 -0.9997351 -0.02301728 0 -0.8007275 -0.003181278 -0.5990205 -0.7033081 0.08929908 -0.7052541 -0.9983705 0.005594491 0.05678886 -0.9977123 -0.003561317 0.06750982 0 0.0400325 0.9991984 -0.02514588 0 0.9996839 -0.1509075 0.2767946 0.9490057 0 0.03903341 0.9992379 -1 1.57683e-6 0 0.951154 0.1936629 -0.2404182 0.7070895 0.005823254 -0.7071001 0.7185611 -0.002290964 -0.6954602 0.9968085 0.01775336 0.07783108 0.9985176 -0.002221107 0.05438411 -0.1324903 -0.2775306 0.9515373 0.05939406 -0.01423257 0.9981333 0 0.1068864 0.9942712 -0.0783177 -0.01655751 0.996791 -0.05853402 0 0.9982855 -0.01979261 0.08046531 0.9965609 0 -0.006145656 0.9999811 0.00858128 0.06895041 0.9975833 -0.02951383 0.003471374 0.9995585 0.02851468 0.04218029 0.9987031 -2.0492e-4 0.003892183 0.9999925 0 0.003334641 0.9999945 4.18056e-4 0.002778828 0.9999961 -7.28262e-4 -0.004857301 0.999988 0.9973616 0.05731296 -0.04455578 0.9962745 0.06175071 -0.06019991 0.03916972 -0.08920031 -0.9952432 3.08545e-4 -0.03805726 -0.9992755 0.01484519 -0.08716392 -0.9960834 9.98274e-4 -0.06935381 -0.9975917 -0.9963499 0.05028986 0.06897628 -0.9984372 0.03201782 0.04580515 -0.9962137 0.02823299 0.08222651 -0.9870831 0.1139936 0.1125723 -0.1237761 -0.1123816 0.985926 -0.4846938 0.1119349 0.8674921 0 -1 2.67072e-5 0 -1 -1.23722e-4 0 -1 3.86615e-5 0 -1 1.23722e-4 0 -1 -1.23718e-4 0 -1 3.19829e-5 0 -1 -5.11728e-5 -0.05777096 -0.9298807 0.3632967 0.2054082 -0.9676935 0.1462083 0 -1 -5.22626e-6 -0.2069664 -0.6264259 0.7515022 0 -1 8.1069e-6 0.9779337 0.07366722 -0.1954967 0.9260877 0.05021297 -0.3739524 -0.03162282 0.8315142 -0.5546029 0.1304954 0.8177837 -0.5605364 0.130488 0.8161891 -0.5628573 0.1305166 0.8248185 -0.5501273 -0.1651667 0.1305671 -0.9775849 -0.05915832 0.06134825 -0.9963617 -0.26491 0.1307668 -0.9553653 0 -0.09246504 -0.995716 -0.01539731 0.6234026 -0.7817496 0.03260666 -0.09542667 -0.9949024 0 -0.06885439 -0.9976267 0.02958613 0.6402592 -0.7675891 0.1662382 -0.116441 -0.9791866 0 0.01307058 -0.9999147 -0.03019064 0.6231927 -0.7814854 0.003673732 -0.0954774 -0.9954248 0 -0.09246444 -0.995716 -0.1112692 0.7276095 -0.6769075 0.4621773 -0.09344923 -0.88185 0.3062471 -0.2746884 -0.9114599 0.08807343 0.9633022 0.2535587 -0.008686125 -0.1782529 -0.9839465 -0.1608122 0.1313424 -0.9782069 -0.1973664 0.6279516 -0.7528104 0.03615319 0.7543801 0.6554417 -0.01677447 -0.4147643 -0.9097743 -0.1929295 0.7184002 -0.6683409 0.008853495 0.1851106 -0.9826778 0.07151037 0.3642038 -0.9285699 -0.04160887 -0.3688141 -0.9285715 -0.1960374 0.6113831 -0.7666683 -0.03030538 -0.4190687 -0.9074487 0.05239999 0.8332577 0.5503962 -0.02379965 -0.4472562 -0.8940892 -0.06507295 -0.9978772 0.002539694 0.002188444 -0.952593 -0.3042399 0.01423382 -0.9524978 -0.3042128 -3.36128e-4 -0.9999978 -0.002101957 -0.06737756 -0.997717 -0.004602313 0.06365329 -0.9979289 0.009290635 0.7192657 -0.01831036 0.6944938 0.7156871 0.005681514 0.6983979 0.7254872 -0.009667336 0.6881678 0.7076523 0.06102389 0.7039207 0.6625836 0.1102174 0.7408341 -0.03923547 -0.9908468 0.1291632 0.01703804 -0.9994691 0.02777451 -0.05470395 -0.9936007 -0.09881895 -0.7806095 -0.02170932 -0.624642 -0.9735931 0.02195745 -0.2272324 -0.9999293 -0.01187276 -7.32533e-4 -0.9996223 0.02066069 -0.01812249 -0.9999658 0.008086621 -0.001793861 -0.9999786 0.006276309 0.001918673 -0.9996682 -4.83205e-4 0.02575677 -0.2377132 0.7278199 -0.6432501 0.9997196 0.0124467 -0.02015012 0.9992561 -0.02825808 -0.02624219 0.999524 0.006721317 -0.03011238 0.9988638 -1.16353e-4 -0.0476576 0.9959512 0.01194286 -0.08909881 0.2339372 -0.8527603 -0.4669834 0.09678059 -0.01051563 -0.9952502 0.3089324 0.03252661 -0.9505276 0.1931383 0.03964537 -0.9803704 -0.3194631 -0.09376317 -0.9429485 0.9740691 -0.0276789 -0.2245517 0.9814276 0.01501542 -0.1912448 0.9996704 -0.01963818 -0.01653766 0.9997853 0.01957046 -0.006819367 0.9996125 -2.3725e-4 0.02783805 0.9995521 -8.09039e-4 0.02991628 0.7230437 0.003014206 0.6907958 0.6834771 -0.002955675 0.7299661 -0.8309709 -0.07660645 -0.5510163 -0.8133919 -0.06090319 -0.5785191 -0.5616198 0.03092849 0.8268173 -0.5429832 0.002836585 0.8397388 0.5665487 -0.02589428 -0.8236213 0.5468858 -0.001966536 -0.8372049 0.07603234 -0.9940645 -0.07781404 0.08392512 -0.996102 -0.02715718 5.9511e-7 -1 -2.75179e-6 -1.02319e-4 -1 -3.27886e-5 0.006686091 -0.998989 -0.04445749 0.01512986 -0.99895 -0.043244 -0.01763719 -0.998333 -0.05495667 -0.02453464 -0.9982485 -0.05383467 1.29541e-4 -1 0 -3.90304e-6 -1 -3.40159e-5 0 -1 -9.21438e-6 -0.09847795 -0.9947043 -0.0294196 -0.09239423 -0.9951641 -0.03334289 -0.5671001 -0.01256334 -0.8235531 -0.5580423 -0.001389324 -0.8298114 -0.05046302 0.9976877 -0.04552942 -0.07070207 0.9953638 0.0652076 -0.01763236 0.9968045 -0.07790988 0.04799354 0.9985149 -0.0257824 -0.9462752 0.2706696 -0.1769216 -0.1777948 -0.7041124 0.6874698 0.9997459 0.02254605 0 0.9933909 -0.03677064 0.1087307 1 -4.03777e-6 3.87625e-6 1 -3.05278e-6 1.31873e-6 1 -1.58944e-6 0 1 -1.06497e-6 -1.22677e-6 0.03307837 -0.9985869 -0.04159373 -0.02376288 -0.9827742 -0.1832764 -0.01536047 -0.9982032 -0.05791866 -0.09737741 -0.9874058 -0.1246888 0.07114171 -0.9826027 -0.1715548 0 -0.9912283 0.1321612 -0.1025642 -0.9863287 0.1289822 0.004891157 -0.9908736 0.1347059 0 -0.9932847 0.1156962 -0.2055923 -0.9720832 0.1130765 0.08432525 -0.9905701 0.1079824 -0.9986603 -0.03914695 0.03384327 -0.9994263 9.47514e-5 0.03386992 -0.9998289 0.01849931 0 -1 -1.16945e-6 0 -0.989769 0.1388071 0.03301715 -0.2485362 -0.9648923 -0.08492743 -0.8904303 0.4366376 -0.1283804 -0.8388471 -0.3626959 0.4059399 -0.9893783 0.1453635 0 -0.9796229 0.1017287 -0.1731775 0.9785296 0.1173081 -0.1694658 0.9970905 0.07622647 0 0.942753 0.3293453 0.05242717 0.8407467 0.5272834 -0.1229526 0.65118 -0.6717372 -0.3531765 0.2077959 -0.9776368 -0.03236389 -0.9480272 -0.2557922 -0.1892485 0.08710622 -0.8817505 -0.4636042 -7.97467e-4 -0.8039083 -0.5947527 0.9861047 0.1192095 0.1157007 0.03722506 -0.6511111 0.7580692 0.001981377 -0.5876402 0.8091199 0.01950848 0.8889389 0.4576103 -0.01897168 0.8414813 0.5399529 -0.6158549 -0.7877453 0.01342612 -0.2610315 -0.8907841 -0.3719761 -0.8976078 0.4402003 -0.02288901 -0.9322332 0.3580885 0.05209767 -0.9939908 0.1094637 0 -0.9943381 0.1032607 -0.02508205 0.9785295 0.1173056 -0.1694684 0.9970908 0.07622385 0 0.9427408 0.3293801 0.05242645 0.8407396 0.5272962 -0.1229459 0.6464087 -0.6754745 -0.3548098 0.2084935 -0.9774895 -0.03232556 0.03070831 -0.6520949 0.7575153 0.002315521 -0.6018502 0.7986057 0.9861119 0.11918 0.1156694 3.45341e-4 0.009401023 0.9999558 0 -0.03151762 0.9995033 -0.08071851 0.121215 0.9893389 3.21132e-7 0 1 -7.02438e-4 5.01631e-4 0.9999997 -0.001614928 -0.04761487 0.9988645 2.03989e-4 0.009672403 0.9999532 -0.02261406 -0.001730561 0.9997429 -0.03451597 0.005755841 0.9993876 0.01165515 -0.03856736 0.9991881 -0.2222958 0.1585598 0.9619997 0.01002776 -0.001043498 0.9999493 1.38838e-4 0.006623864 0.9999781 7.9747e-4 0.00791049 0.9999685 0.1291081 0.09251677 0.9873054 0.003143966 -0.04004973 0.9991928 0.06536138 0.05599004 0.9962896 0.006805837 -0.00196284 0.9999749 1.46858e-5 -5.56225e-6 1 0.01054519 -0.0263254 0.9995978 -0.01205652 -0.02937716 0.9994958 0.08519184 0.2075768 0.9745021 0.08415728 0.05576467 0.9948909 0.02125298 0.01408171 0.999675 0 0.01814275 0.9998355 -0.03898948 0.007441937 0.999212 -0.01086509 -8.31946e-4 0.9999407 -0.003324091 -0.002075791 0.9999924 -0.01320016 -9.47142e-4 0.9999125 0.01693749 -5.39789e-4 0.9998565 0.003966331 -0.001942873 0.9999903 0 -1.58143e-6 1 -0.001490831 -0.03768748 0.9992886 4.48559e-4 -0.04112213 0.9991541 0.005592644 0.00400412 0.9999764 0.1291381 0.09252101 0.9873011 0.09224909 0.1036663 0.990325 -0.1591747 -0.05544304 0.9856925 0.0195018 0.8889343 0.4576193 -0.01897782 0.841484 0.5399489 -0.9898391 0.13837 0.03274595 0.01083171 -0.9227244 -0.3853082 -0.0316264 -0.8848571 -0.4647881 -0.02276688 -0.1063094 -0.9940725 0.02375888 0.0198906 -0.9995198 0.05413341 -0.02734732 -0.9981592 0 -0.007928192 -0.9999687 -0.01903486 0.022776 -0.9995595 2.07546e-4 0.00472182 -0.9999889 0 0.004164278 -0.9999914 -0.001251637 0.002498567 -0.9999962 0.1636261 0.04774135 -0.9853667 0.0218957 0.006320178 -0.9997404 0.03051501 0.003658294 -0.9995276 -3.87171e-4 0.1761463 -0.9843639 0.05916756 4.81468e-4 -0.998248 0.01673072 0.005838215 -0.9998431 -0.0245862 0.003612458 -0.9996912 -0.03416264 6.983e-4 -0.9994161 -0.05542665 -8.22693e-4 -0.9984624 -0.02796065 -0.01208895 -0.9995359 0.001198649 -0.06761044 -0.9977111 -3.37855e-4 -0.07765114 -0.9969806 -0.01574176 -0.05190497 -0.9985281 -0.1341964 0.05733716 -0.9892947 0.001499593 0.002998292 -0.9999944 -0.00413835 -0.004101991 -0.999983 -0.001317739 1.45019e-4 -0.9999992 -0.03279483 0.0341624 -0.9988781 0.009055852 -0.006001055 -0.9999411 2.89869e-6 0 -1 0.1045424 -0.05406159 -0.99305 -1.96043e-6 9.96015e-4 -0.9999995 -6.09127e-5 0.1830638 -0.983101 0.9996542 -0.0262947 0 0.03683406 0.002947986 0.9993171 -0.001582562 0.02154374 0.9997667 0.03935998 -0.005884528 0.9992079 0.03408282 0.04945611 0.9981946 -0.05870187 0.006474375 0.9982547 0.05824083 0.02752912 0.997923 0.005004882 0.5139117 0.8578286 0.9988629 0.01734489 0.04440724 0.9996439 0.00416094 -0.02635991 0.6737548 0.7378373 0.04062908 0.388168 -0.009683787 -0.9215377 0.07611685 0.02170014 -0.9968628 0 -0.01224398 -0.9999251 -0.006355941 -0.01156681 -0.9999129 0 -0.01224547 -0.9999251 -0.006376504 -0.01156753 -0.9999129 0 0.009947597 -0.9999506 0.0250864 0.007330954 -0.9996585 0 0.009947538 -0.9999506 0.02508652 0.007331013 -0.9996584 -0.05228608 0.02143919 -0.998402 1 3.30758e-7 0 -0.04445242 -0.2391032 -0.9699761 0.05345976 -0.1515437 -0.9870039 -0.9981131 -0.007847011 -0.06089878 -0.02221482 0.9325382 -0.3603876 0.001853406 0.9442402 -0.3292524 -0.02219969 0.9323285 -0.3609306 0.002258718 0.9442188 -0.3293111 0.1953129 0.9767213 -0.08870458 0.03650331 0.9982951 -0.04554474 -0.009212493 0.9999087 0.00988841 0.006412625 0.9997909 -0.01942104 -0.009612977 0.9996187 0.02588689 0.0168634 0.9976907 -0.06579542 0.001387953 0.9993181 0.03689932 -0.2103161 0.9776263 0.003751456 -0.07597965 0.9950847 0.06351113 -0.01268452 0.9846414 0.1741276 8.95614e-4 0.9992746 0.03807449 -0.001033723 0.9984484 0.05567699 0.342212 0.115683 -0.9324744 0.05390834 -0.1691998 -0.9841064 -1 3.21668e-6 0 0.1020427 0.05569773 -0.9932196 0.0104531 0.9977297 0.06653136 0.1139208 0.9293041 -0.3513059 -1.49145e-4 0.999999 0.001445889 0 0.9999992 0.00135678 0 0.9999991 0.001349806 0.009426712 0.9998982 -0.01072025 0 0.9999992 -0.001363694 0 0.9999991 -0.001360297 0 0.9999992 -0.00136882 0 0.9999991 -0.001360356 0 0.9999991 -0.001363694 -0.001508533 0.9999979 0.001435518 2.51788e-4 0.9999991 0.001328825 -1.24922e-4 0.9999995 -0.001093924 -6.1761e-4 0.9999999 1.80335e-4 -1.25345e-4 0.9999829 -0.005855441 -8.74777e-6 1 -2.79864e-5 0 1 2.72373e-6 3.74078e-4 0.9999999 4.5462e-4 0 1 2.94072e-6 -0.04420977 0.9929013 -0.1104199 -0.007840335 0.9988465 0.04737418 0 1 1.27589e-6 0.01775336 0.02767467 -0.9994594 0.1238173 -0.04550367 -0.9912612 -0.1048151 -0.07280921 -0.9918229 -0.0177806 -0.01715326 -0.9996948 -0.723405 0.07159292 -0.6867021 -0.9917081 -0.007894754 0.1282681 -0.04042339 0.09503746 0.9946526 -0.003070771 -0.004799604 0.9999838 -0.03782939 0.005432486 0.9992696 0 0 1 4.013e-6 2.31986e-6 1 0 0 1 1.98717e-6 -1.90208e-7 1 0.319106 -0.2738341 0.9072962 -0.2181803 7.74022e-6 0.9759085 -0.0422461 0.0377863 0.9983925 -0.01056605 -0.08582854 0.9962539 -1.68668e-6 0 1 -2.94047e-6 0 1 1.58288e-7 0 1 0.1596852 -0.1599923 0.9741166 0.08034563 0.06124329 0.9948838 0.02904027 0.08937519 0.9955747 0.001891136 -0.003061115 0.9999936 4.17793e-4 0.001519143 0.9999988 0.1689923 0.213225 0.9622768 -1.56177e-4 -6.24152e-5 1 1.68673e-6 0 1 1.83686e-6 1.75765e-7 1 0 2.4195e-6 1 -0.004387974 -0.02942907 0.9995573 -0.02092254 4.40148e-4 0.9997811 0 -2.17192e-6 1 3.16574e-7 0 1 -0.9847673 0.1585241 0.07143795 -0.9938828 0.07988792 -0.07625573 0.3981944 0.9146507 -0.0696789 0.4169999 0.9089046 0.001957416 -0.9799117 -0.1898601 -0.06104457 -0.9796646 0.1950798 -0.04691696 -0.9767797 0.002447128 0.2142324 -0.9710007 -3.33829e-4 0.2390763 0.007190465 -0.01453143 -0.9998686 0.02759706 0.007787764 -0.9995889 -0.005284965 -0.1319765 -0.9912388 0.01342022 -0.2095093 -0.9777145 0.006896018 0.02695548 -0.9996129 0.02285611 0 -0.9997388 -0.0660178 0.02372753 -0.9975363 0.05105161 -0.03519475 -0.9980757 0.02071917 0.1543461 -0.9877997 -0.007220745 0.06851637 -0.9976239 -0.02864712 0.08017373 -0.9963692 0.03296381 0.003758728 -0.9994495 -0.008738517 0.05762279 -0.9983003 0.03730946 0.02326309 -0.999033 -0.06851541 -0.01314103 -0.9975636 0.01799231 -5.2709e-4 -0.9998381 0.04601341 -0.06526798 -0.9968063 0.01775497 0.002023816 -0.9998404 -0.1175238 -0.3401575 -0.9329957 -0.1003654 -0.2779715 -0.9553318 0.008109509 -0.1382715 -0.9903612 -0.003327548 -0.05915534 -0.9982433 -0.02702587 0.01308929 -0.9995491 0.005846679 0.013094 -0.9998972 -0.03178036 -0.01142233 -0.9994297 2.48588e-6 0 -1 0.06036007 -0.01436203 -0.9980733 -0.02280652 0 -0.99974 -0.01980006 0.06532436 -0.9976677 -0.03484416 0.0205751 -0.999181 0.01188945 -0.001235187 -0.9999286 -0.1435779 -0.4173908 -0.8973129 -0.007293224 -8.31834e-4 -0.9999731 -0.006655156 -0.0114575 -0.9999122 0.04011654 -0.05097341 -0.997894 0.9815699 0.1809445 -0.06147927 0.9888903 0.06309026 0.1345942 1 6.62278e-6 0 -0.4474486 0.8920459 0.06359267 -0.4088224 0.8946315 0.1802739 0.637089 0.7366833 -0.2267499 0.9989306 -0.0210154 -0.04118323 0.9584203 0.2159258 0.1865654 0.9671149 -0.2340865 0.09946018 0.9794065 0 -0.2018986 -0.1042439 0.06498116 -0.9924267 -0.1522126 0.1013531 -0.9831373 -0.02546679 -0.5983313 -0.800844 0.02301031 -0.05136287 -0.998415 0.006524324 -0.1443415 -0.9895064 -0.08215939 -0.0589556 -0.994874 0.05185884 0.1130349 -0.9922368 0.002835988 0.874548 -0.4849307 0.006779491 0.1855674 -0.9826081 0.06643706 0.05749803 -0.9961326 -0.0264452 -0.05864173 -0.9979287 0.01295894 -0.3300788 -0.9438644 0.02753001 -0.06531167 -0.9974851 0.0885756 -0.1585822 -0.9833647 -0.0278424 0.06092625 -0.9977539 0.01854634 0.4665032 -0.8843251 1 -9.08232e-6 0 0.9749253 -0.1203343 0.1871906 0.9938342 -0.08933931 0.06566768 -5.65945e-6 1 0 -1.34088e-4 1 -8.05493e-5 -1.71246e-4 1 0 5.55881e-6 1 -4.71032e-5 2.79429e-7 1 0 2.83505e-7 1 0 -8.96499e-7 1 -5.52709e-6 8.14434e-5 1 -2.90504e-5 7.06948e-5 1 -5.29066e-5 2.5293e-5 1 1.00163e-5 7.12612e-7 1 0 -0.07152903 0.7214985 -0.6887115 0 -1 -3.72621e-6 0.9733239 0.1073501 0.2027724 0 1 -4.46164e-6 -1 -6.23314e-7 0 -1 0 5.29818e-7 0 -1 8.92325e-6 -1 0 1.05964e-6 -1 0 1.05964e-6 -1 0 1.05964e-6 -0.1140953 0.9698123 0.2155143 0 -1 -4.6749e-7 1 0 -1.05964e-6 -1 8.63054e-7 0 0 -1 3.26042e-6 1 0 2.6491e-7 0 1 -1.70707e-6 -1 0 9.53674e-7 0 1 -9.0381e-7 -1 0 1.05964e-6 -1 0 1.05964e-6 -0.1140947 -0.9698126 0.2155131 0 -1 1.24663e-6 0 1 -1.24663e-6 0 1 1.95625e-6 -0.9892035 1.23317e-6 0.1465486 -0.9969384 -0.07819181 0 0 -1 -1.67308e-7 0.9481348 -0.1487269 0.2809285 0 1 2.23081e-6 -1 0 1.05964e-6 0 1 -4.46163e-6 -0.9733239 0.1073495 0.2027727 -1 6.23314e-7 5.29818e-7 1.18101e-6 0 1 -1.18102e-6 0 1 0.7071057 0.7071079 2.23081e-6 0.7071079 0.7071057 0 0.7071056 -0.7071081 0 0.7071081 -0.7071056 0 -0.7071068 0.7071068 0 -0.7071068 0.7071068 4.82338e-7 0 1 0 4.03352e-7 1 0 5.8362e-7 1 5.84761e-6 0 1 4.92587e-7 0 1 -6.70039e-6 1 -2.74425e-7 0 1 0 0 -2.40704e-7 -1 0 -4.31283e-7 -1 0 0 -1 4.38236e-6 0 -1 6.78073e-6 -1 5.26762e-7 7.4932e-7 -1 2.35456e-7 1.66411e-6 -1 0 1.24616e-6 0.003583431 -0.01015961 0.9999421 0.004118561 -0.008068084 0.9999591 0.01081395 -0.004534304 0.9999313 0.01025652 -0.003645479 0.9999408 0.0151686 0.0077039 0.9998553 0.006365954 0.008313894 0.9999452 0.003207564 0.01412177 0.9998952 -0.00273931 0.009327411 0.9999528 -0.007180452 0.01091802 0.9999147 -0.01211255 0.001928985 0.9999248 -0.01261585 0.002389192 0.9999176 -0.01178359 -0.006966471 0.9999064 -0.005711138 -0.007357358 0.9999567 -0.00361514 -0.01165276 0.9999257 3.65687e-4 2.76779e-4 -1 0.01814234 0.003918528 -0.9998278 0.004264414 0.01761227 -0.9998359 -0.0141474 -0.03064358 -0.9994304 0.001497447 -0.02942854 -0.9995658 0.01370894 -0.01260524 -0.9998266 0.008087158 -0.01367115 -0.9998739 0.005457401 -0.02608919 -0.9996448 0.02871239 -0.01773506 -0.9994305 0.028723 -9.49264e-4 -0.9995869 -0.006424903 0.02393913 -0.9996928 -9.39992e-4 0.01328432 -0.9999113 -0.005922496 0.01732349 -0.9998325 -0.02059417 0.01298207 -0.9997037 -0.01051455 -0.007426202 -0.9999172 -4.30287e-4 -5.4175e-5 -1 -3.28002e-4 -2.52525e-4 -1 -0.02797579 -0.001680433 -0.9996073 -0.9791881 0.2028878 -0.00523287 -0.985782 0.1680137 -0.002275586 -0.7127664 0.7013971 -0.002498269 -0.700469 0.7136725 -0.003843069 -0.2024285 0.9792962 -0.001292288 -0.0933935 0.9955815 -0.009753704 0.4318662 0.9019318 0.003253757 0.6527508 0.7574912 -0.01111388 0.8456797 0.5336809 0.003288745 0.9852175 0.1712239 -0.005382418 0.9587333 0.2840427 -0.01225578 0.8970602 -0.4418513 -0.007103741 0.9573424 -0.2889558 3.69746e-4 0.7487506 -0.6628435 0.003330647 0.4493476 -0.8933163 -0.008529841 0.2828249 -0.9591712 8.99849e-4 -0.1966056 -0.9804683 -0.005328953 -0.217514 -0.9760321 -0.007004857 -0.6666644 -0.7453444 0.004499435 -0.856809 -0.515508 -0.01140505 -0.9666174 -0.2562019 0.003395199 0.001437604 0.002632081 -0.9999956 0.002319872 -0.005354106 -0.999983 0.002504825 -2.16654e-4 -0.9999969 -9.60928e-4 -0.002502799 -0.9999965 -0.7930441 -0.6091259 -0.006837308 -0.7749868 -0.6319457 0.006341993 -0.4191337 -0.9078988 -0.006841361 -0.3925341 -0.9197156 0.006349563 0.05080467 -0.9986853 -0.006837308 0.07985031 -0.9967868 0.006344616 0.5090945 -0.8606836 -0.00684154 0.5339252 -0.8455079 0.006345391 0.8507608 -0.5255088 -0.006837129 0.8657019 -0.5005198 0.006346046 0.9994233 -0.03303164 -0.007884144 0.9990882 -0.04087775 -0.01232254 0.9033648 0.427968 0.02784675 0.7974219 0.601017 -0.05382317 0.6008212 0.7985174 0.03720134 0.2351803 0.9715501 -0.02794086 0.1174842 0.9927287 0.02621638 -0.3232383 0.9453679 -0.04238867 -0.5355941 0.8421415 0.06274175 -0.844294 0.5322028 -0.06267231 -0.9473739 0.3171594 0.04350423 -0.9918114 -0.1246157 -0.02794635 -0.9798961 -0.1994076 0.006344437 0.7847602 -0.03210777 0.6189673 0.492828 -0.1075744 0.8634514 0.7337555 -0.4242371 0.5306844 0.3370746 -0.5070191 0.7932922 0.3484972 -0.5518646 0.7576247 0.06590312 -0.8226826 0.5646683 -0.08918339 -0.4950569 0.8642714 -0.3288733 -0.7705603 0.5459662 -0.6086733 -0.4963258 0.6190134 -0.4121555 -0.2093428 0.8867376 -0.8209472 -0.1670717 0.5460155 -0.7439401 0.2479231 0.6205542 -0.4567669 0.2243456 0.8608329 -0.4978759 0.7828351 0.3732144 -0.1791792 0.4984697 0.8481879 0.1056584 0.8862114 0.4510717 0.1936563 0.5429524 0.8171291 0.4934961 0.655882 0.5712097 0.4492473 0.3220792 0.8333318 0.7571214 0.3586848 0.5459969 -0.7765461 -0.4603357 -0.4301944 -0.1809172 -0.5712149 -0.8006139 -0.1529539 -0.7211629 -0.6756694 0.3688315 -0.6070603 -0.7038758 0.2710664 -0.5306272 -0.8030927 0.8042603 -0.3978877 -0.441419 0.5518051 0.03093045 -0.8333994 0.6745138 0.1166892 -0.728982 0.5407359 0.6180356 -0.5706458 0.2250745 0.4552708 -0.8614349 -0.09063786 0.923927 -0.3716769 -0.3543889 0.4329766 -0.8288184 -0.4657101 0.4746406 -0.7468805 -0.8007976 0.1340034 -0.583752 -0.5215939 -0.08920902 -0.8485174 -0.6419218 -0.7451041 0.1809871 0.3270446 -0.9294826 0.1705988 0.9511868 -0.1671929 0.259404 0.6412801 0.7453623 0.1821948 -0.324923 0.9283004 0.1807857 -0.966682 0.1831177 0.178869 0.519429 -0.08224213 0.8505467 0.2358828 -0.4343902 0.8692898 0.06448531 -0.4900278 0.8693184 -0.3759371 -0.3701997 0.8494843 -0.5225282 0.1111467 0.8453465 -0.1390742 0.5209071 0.8422079 0.3444552 0.4166364 0.8412876 -0.6348953 -0.7714122 0.04279518 -0.6820865 -0.73127 0.001527249 -0.6737466 -0.7389445 -0.005157351 0.3554332 -0.9347017 1.09395e-4 0.3119853 -0.9495976 0.03049027 0.348222 -0.9354599 0.06046873 0.2617397 -0.9651386 4.21414e-5 0.9776235 -0.2098574 0.01456946 0.9902735 -0.1347 0.03485029 0.9816666 -0.1906002 0.001540541 0.6726329 0.7399736 0.002032101 0.6326254 0.7740235 0.02593898 0.6672827 0.7447994 -0.002775132 -0.3041493 0.952619 -0.003225862 -0.3529294 0.9350719 0.03288727 -0.3032582 0.9529048 -0.002635478 -0.9771127 0.2127143 -0.001844108 -0.9854516 0.1642704 0.04359322 -0.9749249 0.2224882 0.004515349 -0.1905288 0.9740425 0.1222294 0.5769911 -0.1195744 -0.8079501 0.2355974 0.1185836 -0.9645889 0.5363739 0.5158047 -0.6680184 -0.6867712 0.1384249 -0.7135713 -0.1426392 -0.1550328 -0.9775576 0.5925674 0.5585516 -0.5804172 -0.8601989 0.1602494 -0.484126 0.7706115 -0.1081424 -0.6280632 0.9523296 0.2060236 -0.2249949 0.5724577 0.3926225 -0.7198193 -0.9501827 0.2172147 -0.2235413 -0.6196833 -0.1922662 -0.7609379 -0.3511648 0.3319359 -0.875501 -0.2025001 0.9792823 -2.5057e-4 0.1292608 0.4849153 -0.864956 0.5181259 -0.5318324 -0.6698506 0.5402239 -0.5954099 -0.5946808 0.1520928 -0.5263456 -0.8365574 -0.03714549 -0.8214439 -0.5690783 -0.07992106 -0.7269085 -0.682068 -0.5941033 -0.6394497 -0.4880013 -0.7554351 -0.6540778 -0.03873199 0.9808933 -0.1921477 0.03045845 0.9937925 0.1082119 -0.02582031 0.9245618 0.3801563 0.02582025 0.8038027 0.5945516 -0.02024096 0.5015102 0.8650562 0.01287037 0.5162739 0.8563944 0.007077753 0.006126642 0.9999562 -0.007078826 -0.04102098 0.9991189 0.008886456 -0.5688567 0.8223969 -0.008096933 -0.6025491 0.798072 0.003966152 -0.8651232 0.5015477 -0.003448367 -0.8835552 0.4682929 0.005647599 -0.9999563 0.006129562 -0.00707823 -0.9991188 -0.04102301 0.008886098 -0.7895621 -0.6135939 -0.009716749 -0.7579439 -0.6522474 0.009716868 -0.2382799 -0.9711559 -0.008886098 -0.1922335 -0.9813238 0.00707823 0.3362477 -0.941747 -0.007077991 0.3200588 -0.9473103 -0.01287072 0.693143 -0.7204415 0.02274018 0.8461238 -0.5317651 -0.03606355 -9.49974e-7 0 -1 1.53872e-6 0 -1 -1.11446e-6 0 -1 -1.56853e-6 0 -1 1.39964e-6 0 -1 1.48078e-6 0 -1 -0.9994741 -0.01259648 0.02988314 -0.8213909 -0.5697267 -0.02699011 -0.7092369 -0.7048857 0.01091986 -0.06344413 -0.9979834 -0.002004683 0.002270519 -0.999828 -0.01841199 0.584127 -0.8114364 0.01915287 0.7980439 -0.6021863 -0.02231168 0.942663 -0.3332353 0.01846355 0.9971137 0.07285159 -0.02137666 0.8592336 0.5110481 0.02339851 0.7744247 0.632611 -0.008359074 0.1080093 0.9941076 0.009168982 0.04226022 0.99908 -0.007303237 -0.6456835 0.7635704 0.007302641 -0.6264638 0.7793335 0.0135073 -0.9603281 0.2779133 -0.0231142 1.45461e-6 0 1 -7.96622e-7 0 1 -2.24084e-6 0 1 2.10753e-6 0 1 -1.90543e-6 0 1 7.88208e-7 0 1 1.47714e-6 0 1 -1.57616e-6 0 1 -3.18619e-6 0 1 0.9775292 -0.2107951 -0.001498639 0.9738716 -0.2270977 -8.46324e-4 0.9744033 -0.2248066 4.95147e-4 0.9677168 -0.251168 0.02095288 0.579259 -0.2580305 0.7732267 0.3957851 -0.2667295 0.8787546 0.2733967 -0.4753624 0.8362325 0.3133752 -0.9496216 0.003858804 0.2774717 -0.9607329 -0.001323103 0.292495 -0.9562012 -0.01122689 0.06048214 -0.6220424 0.7806442 0.2619037 -0.8580392 0.4417867 -0.09841859 -0.3699277 0.923833 -0.6791867 -0.7339554 0.003884017 -0.6047186 -0.7964388 -8.49147e-4 -0.7288393 -0.6841662 -0.0266444 -0.6814323 -0.7309621 0.03666627 -0.4539484 -0.2215897 0.8630346 -0.4479655 -0.1336963 0.883998 -0.628533 -0.002894043 0.7777777 -0.9737434 0.2276449 0.001274883 -0.973194 0.2299858 -3.33159e-4 -0.9743997 0.2248052 0.002840995 -0.9812219 0.1914277 -0.0236485 -0.3220925 0.2843459 0.9029972 -0.2946732 0.5715121 0.76586 -0.287987 0.3757689 0.8808299 -0.5314236 0.2477805 0.8100579 -0.2696222 0.9629662 -3.09917e-4 -0.3170629 0.9484041 9.66682e-4 -0.2924749 0.9561372 -0.0161252 -0.07513284 0.6356513 0.7683115 0.02843803 0.4717136 0.8812932 0.09770387 0.4234852 0.9006189 0.1786516 0.4369251 0.8815783 0.6707706 0.7416598 0.002763152 0.7648448 0.6401176 0.07253915 0.7561682 0.6543765 0.001102387 0.681349 0.7308734 0.0398454 0.6206759 0.783183 -0.0372281 0.3585439 0.1325692 0.9240518 0.648953 -0.02437692 0.760438 0.8710714 -0.1921241 0.452021 -6.8425e-4 -7.6295e-4 0.9999995 -0.005351305 -0.008560478 0.999949 -0.1977469 0.07702839 0.977222 -9.7451e-4 9.18786e-4 0.9999992 6.58019e-4 0.00233078 0.9999971 -0.005006074 -0.00666666 0.9999653 -0.001025199 -0.001270294 0.9999987 1.3329e-4 0.00301516 0.9999955 0.001295387 -0.001043081 0.9999987 6.05438e-4 -0.002131819 0.9999976 -0.002025127 -0.003810107 0.9999907 -4.86406e-4 -0.003103673 0.9999951 0.002147018 0.003913938 0.9999901 0.00148487 0.01105034 0.9999378 -1.57622e-4 -0.002507507 0.9999969 0.003104746 0.007612407 0.9999663 -6.51992e-5 -0.001063704 0.9999995 0.001137197 -5.25755e-4 0.9999993 0.04622226 -0.2186356 0.9747112 -0.001030743 -0.002735853 0.9999958 -0.004705309 1.74274e-4 0.9999889 -2.4642e-4 -0.001081347 0.9999995 -0.003680288 0.004458308 0.9999833 0.01179432 -0.007461488 0.9999027 -0.00352478 -0.005765616 0.9999772 -0.0090034 0.005161106 0.9999462 -6.96267e-4 -8.96368e-4 0.9999994 6.17379e-4 -8.03781e-4 0.9999995 7.98333e-4 -7.39774e-4 0.9999995 9.39457e-4 -6.21756e-4 0.9999995 -0.007233083 0.002472579 0.9999708 0.005110919 0.005136311 0.9999738 -0.6473888 -0.5873748 0.4856735 -0.6054224 0.008450448 0.7958596 -0.8184299 0.1734485 0.5478029 -0.4324689 0.4668431 0.7713808 -0.4537945 0.6993026 0.5523102 0.03405284 0.616883 0.7863178 0.361159 0.8688498 0.3386211 0.3821224 0.433907 0.815909 0.8544073 0.03502422 0.518422 0.8360233 0.02532166 0.5481095 0.5167091 -0.3334953 0.7885383 0.5333766 -0.6398352 0.5532814 0.1942949 -0.5860376 0.7866445 0.04320263 -0.8433862 0.5355682 -0.3503044 -0.4762097 0.8065428 -0.5912256 -0.8042038 -0.06089878 0.03792971 -0.9980992 0.04857385 0.3134576 -0.9486238 -0.04309719 0.6023109 -0.7977647 0.02816259 0.8379986 -0.5449451 -0.02816349 0.9682525 -0.2462312 0.04309916 0.9983043 0.03207939 -0.04857426 0.7608045 0.6461182 0.0608927 0.6634595 0.7480986 -0.01304584 0.05139482 0.998516 -0.01801061 -0.03803169 0.9990133 0.02293586 -0.602491 0.7981161 0.003933966 -0.6767956 0.7352828 -0.03615283 -0.9682918 0.2462464 0.04211807 -0.9984111 0.01071614 -0.05532205 -0.7608107 -0.6461102 0.06089937 -0.05901032 0.7699209 -0.6354051 -0.03330928 0.8359937 -0.5477272 -0.368735 0.4919009 -0.7887129 -0.765628 0.4668965 -0.4425172 -0.5754017 0.1469804 -0.8045557 -0.8203222 -0.3260691 -0.4698411 -0.418646 -0.3557626 -0.8355648 -0.3192857 -0.8415275 -0.4357618 0.02421867 -0.5792577 -0.8147847 0.4177656 -0.7224875 -0.5508936 0.4249446 -0.5659911 -0.7064533 0.7202759 -0.1916452 -0.6666895 0.7072634 -0.1804226 -0.6835395 0.5337469 0.4534938 -0.7137631 0.5897233 0.4708812 -0.6561231 -0.001612782 -6.23e-4 -0.9999985 -3.45556e-4 0.001480579 -0.9999989 -4.91629e-4 0.001607894 -0.9999986 -9.47567e-4 7.93699e-4 -0.9999992 -0.001893579 4.37085e-4 -0.9999982 5.50824e-4 -0.001798391 -0.9999983 0.001144409 3.20311e-4 -0.9999993 6.27865e-4 -1.44471e-4 -0.9999999 0.002314627 -0.001812636 -0.9999957 -4.74241e-4 -0.001599133 -0.9999986 -3.74364e-4 -4.02729e-4 -1 0.00104469 0.001118957 -0.9999989 0.00181216 0.001341462 -0.9999975 0.002170264 -0.03537172 -0.999372 -0.003437101 -0.03326523 -0.9994407 -0.007956802 0.005733191 -0.9999519 0.002210855 -0.03535109 -0.9993726 0.02513647 -0.03708529 -0.998996 0.03510147 0.01510059 -0.9992697 0.01375681 0.03886085 -0.9991499 0.002447068 0.0207616 -0.9997816 -0.01882946 0.003205895 -0.9998176 0.007154464 -0.005337238 -0.9999603 0.0108757 0.01950448 -0.9997506 0.009085178 0.004290163 -0.9999495 0.01406604 -0.001970112 -0.9998992 2.31652e-4 -0.03102922 -0.9995185 1.10028e-4 -0.03101485 -0.9995189 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.8245443 -0.5656995 0.01052504 0.868598 -0.4955174 -2.3183e-4 0.9988216 -0.0462234 0.01479673 0.9979496 0.06394481 0.00280404 0.940248 0.3403035 0.01128196 0.8195582 0.5729341 -0.008424639 0.6017695 0.7985627 0.01309299 0.3965936 0.9179884 -0.003277897 0.09491288 0.9953002 0.01921266 -0.1450433 0.9894253 5.80644e-4 -0.3659834 0.9305053 0.01469832 -0.6433535 0.7655246 -0.008272171 -0.8434237 0.5370662 0.0140196 -0.9496869 0.3131965 -0.001657068 -0.9977184 0.06509166 0.01792418 -0.9725617 -0.2326312 -0.002577662 -0.8540334 -0.5198376 0.01989758 -0.9921072 -0.1088722 0.06221067 -0.5300151 -0.847971 -0.005407929 -0.2867773 -0.9578325 0.01777094 -0.06466752 -0.9979069 1.11726e-4 0.2933521 -0.9559034 0.01390862 0.3998132 -0.9165967 -3.13674e-4 -0.01617217 -0.02638298 0.9995211 -0.03232848 -0.01885074 0.9992996 0.009300231 -0.015172 0.9998417 -0.01088112 -0.02413672 0.9996495 -0.02079498 -0.01751905 0.9996303 0.02756714 0.01110804 0.9995583 0.06343603 0.06544506 0.9958378 0.5756227 -0.8176893 -0.006532728 0.6675174 -0.7423276 0.05805325 0.9212244 -0.3858819 -0.04940474 0.9945166 -0.09697455 0.03915143 0.9912356 0.1292518 -0.02731329 0.9162117 0.4005709 0.009948611 0.89243 0.451093 -0.009160339 0.61672 0.7871296 -0.009138047 0.5520022 0.8333092 0.02982354 0.0700857 0.9973281 -0.02060961 -0.05796772 0.9978913 0.02920359 -0.3605114 0.9311433 -0.05480641 -0.7155607 0.6967808 0.04969459 -0.8023373 0.5968005 -0.009173154 -0.9744057 0.2246093 -0.009174168 -0.9864884 0.1627374 0.01889801 -0.9407714 -0.3390115 -0.004549622 -0.9400714 -0.340928 -0.005840897 -0.5544826 -0.8321745 -0.005903661 -0.5254194 -0.8507825 0.01017737 -0.1727426 -0.9845646 -0.0281524 -0.008822798 -0.9997924 0.01836794 0.2175659 -0.9749168 -0.04692947 0.09133428 0.3563853 -0.9298644 0.6076341 0.7734153 -0.180582 0.5039833 0.3313633 -0.797621 0.5129738 0.01181948 -0.8583229 0.9155778 -0.3837178 -0.1203246 0.2740545 -0.2643151 -0.9246793 -0.2252273 -0.226423 -0.9476315 -0.8958547 -0.3261674 0.3017601 -0.4258407 0.08430403 -0.9008621 -0.5027773 0.1183683 -0.8562734 -0.7794907 0.5789935 -0.2390834 -0.2143533 0.3723635 -0.902994 -0.2953257 0.3171557 0.9012186 0.3353021 0.2824027 0.8987888 -0.1150994 -0.9764671 -0.1823848 -0.9031972 -0.3885548 -0.1823736 -0.7883933 0.5895257 -0.1757718 0.1166538 0.9767465 -0.179884 0.9028379 0.3879855 -0.1853399 0.7880781 -0.5879001 -0.1825007 -0.4415681 0.3165037 -0.8395493 0.01402425 0.5343297 -0.8451599 -0.4962345 -0.2093234 -0.8425765 -0.0425536 -0.537139 -0.8424197 0.442386 -0.3125969 -0.8405818 0.4914339 0.2192529 -0.8428648 -0.0909264 -0.9958193 -0.008741319 -0.1411983 -0.9894264 -0.03314363 -0.09789884 -0.9951878 -0.004142343 -0.9077692 -0.4194129 -0.006929397 -0.9279807 -0.371628 -0.02728325 -0.9118813 -0.4104541 -3.357e-4 -0.8163518 0.5775547 -6.47592e-4 -0.7858848 0.61773 -0.02819514 -0.8138779 0.5810323 0.002116739 0.07738077 0.9960752 -0.04297173 0.1540189 0.9871869 0.04171735 0.09074848 0.995864 0.004454076 0.9073259 0.420428 -6.89233e-5 0.8952526 0.4451923 -0.018072 0.9241157 0.3760062 -0.06804108 0.817622 -0.5757541 -0.001304805 0.7863709 -0.6167761 -0.03475999 0.8172361 -0.5763024 -8.64385e-4 -0.3009679 -0.7052689 0.6418833 -0.2218683 -0.2186243 0.9502516 -0.6636321 -0.3455153 0.6634845 -0.437875 -0.08425259 0.8950794 -0.5223349 -0.1254228 0.8434663 -0.7656605 0.09389835 0.6363546 -0.312866 0.1504042 0.9378132 -0.6336877 0.2085208 0.7449557 -0.5118842 0.4529247 0.7299547 -0.3006336 0.3568878 0.8844493 -0.3815905 0.665459 0.641524 -0.08378547 0.550442 0.8306585 -0.07968884 0.5399898 0.8378906 0.1681548 0.7571361 0.631244 0.1860793 0.4321292 0.8824052 0.4196839 0.6351165 0.6484539 0.4452269 0.3413738 0.8277904 0.3991995 0.2820639 0.8723988 0.6903787 0.2807123 0.6667668 0.5578483 0.03275752 0.8292963 0.5635828 0.03446316 0.8253404 0.7312837 -0.2316576 0.6415286 0.151988 -0.4354039 0.8873124 0.2429695 -0.5773389 0.7795163 0.508318 -0.6476093 0.5676399 0.2764895 -0.2027401 0.9393882 0.5341112 -0.3000707 0.7903689 -0.02096688 -0.6210586 0.7834837 -0.03427195 -0.5586661 0.8286843 0.005430519 -0.009850859 0.9999368 0.01327502 -0.005452513 0.9998971 0.009462893 6.83257e-4 0.999955 0.01230591 0.005984127 0.9999065 0.00515896 0.009223639 0.9999442 0.005063176 0.009638786 0.9999408 -0.00245881 0.011559 0.9999303 -0.006369948 -0.0107727 0.9999217 -0.005690276 -0.01037311 0.99993 0.004976689 -0.01268094 0.9999073 -0.004670023 0.008374929 0.9999541 -0.01096504 0.008860051 0.9999007 -0.01151216 -7.05133e-4 0.9999336 -0.01314598 -0.001984655 0.9999117 0.03418475 0.01250243 -0.9993374 0.02312403 0.01598429 -0.9996049 0.01924061 0.02876585 -0.999401 0.03175562 -0.02287584 -0.9992339 0.03028035 -0.009385108 -0.9994975 0.03623384 -0.004822134 -0.9993318 0.008482694 0.0253756 -0.9996421 -0.001561999 0.03186815 -0.9994909 -0.01240521 0.02065503 -0.9997097 -0.006927788 0.06155776 -0.9980795 -0.03005677 0.01830095 -0.9993807 -0.02055084 -0.003654897 -0.9997822 -0.01923096 -9.41345e-4 -0.9998147 -0.01114785 -0.00669229 -0.9999155 -0.03703546 -0.00468105 -0.9993031 -0.01525771 -0.0232259 -0.9996139 -0.01748496 -0.02380239 -0.9995638 -0.004902005 -0.03683674 -0.9993093 0.01140505 -0.03117853 -0.9994488 0.01204258 -0.02884024 -0.9995115 -0.4673203 -0.88407 -0.005655288 -0.4425104 -0.8967584 -0.003015816 -0.8701089 -0.4928525 -0.002655625 -0.8948813 -0.4462414 -0.007483839 -0.9830963 -0.1830887 -6.22441e-4 -0.9760785 0.2173473 -0.005555987 -0.9529792 0.3027884 -0.01224523 -0.8067978 0.5908232 0.002309799 -0.5168475 0.8560564 -0.006018579 -0.5553567 0.8316106 -0.00167346 -0.004641056 0.9999881 -0.001476764 0.06098872 0.9981104 -0.007484138 0.5425457 0.8400102 0.005203723 0.7387095 0.6739218 -0.01173979 0.89265 0.4507376 0.00341624 0.9997903 0.01957678 -0.006018877 0.9978743 0.06514614 -0.001673221 0.868335 -0.495976 -0.001476764 0.8338947 -0.5518729 -0.007483959 0.4772475 -0.8787568 0.004618763 0.2142629 -0.9766932 -0.01272684 -0.05501782 -0.9984795 0.003436505 -0.002127707 0.00735557 -0.9999707 0.004115343 0.002622187 -0.9999881 3.79921e-4 -0.003147423 -0.999995 5.85808e-4 0.002213716 -0.9999974 0.3434989 -0.9391285 -0.00679332 0.374604 -0.9271231 0.01070564 0.8113433 -0.5844693 -0.01086181 0.8300176 -0.5577002 0.006431102 0.9912415 -0.1319305 -0.005895495 0.9944383 -0.105181 0.005440831 0.9391281 0.3435 -0.006795167 0.9271234 0.3746035 0.0107057 0.5559441 0.8311309 -0.01214939 0.557684 0.8299439 -0.01348364 0.1051518 0.9941647 0.02407556 -0.04888463 0.9982426 -0.03349602 -0.3743964 0.9266979 0.03253167 -0.514729 0.8569853 -0.02510869 -0.8540244 0.520022 0.01481688 -0.8299431 0.5576853 -0.01348364 -0.994165 0.1051505 0.02407622 -0.9982426 -0.04888421 -0.03349691 -0.9266983 -0.3743954 0.03253293 -0.8569856 -0.5147286 -0.02510809 -0.5489192 -0.8357895 0.01199376 -0.5576953 -0.8300209 0.006432354 -0.1319304 -0.9912415 -0.005895793 -0.1051819 -0.9944381 0.005442619 0.09416687 0.8902961 0.4455397 0.2704166 0.462998 0.8441017 0.3625198 0.5415772 0.7584679 0.789967 0.3183583 0.5240232 0.4828545 0.07025092 0.8728783 0.8156602 -0.08627218 0.5720626 0.643314 -0.4311016 0.6326915 0.4011938 -0.349011 0.8468973 0.3242252 -0.8043943 0.4978234 0.1033732 -0.5835936 0.8054394 -0.08463424 -0.8001667 0.5937764 -0.2157351 -0.5291722 0.8206309 -0.491724 -0.7330748 0.4699031 -0.5524534 -0.2375923 0.7989651 -0.6048014 -0.2431551 0.7583475 -0.8043701 0.08507591 0.5880058 -0.4949976 0.1778268 0.8505029 -0.7330762 0.4917186 0.4699066 -0.2128366 0.5505247 0.8072319 -0.2094985 0.5217796 0.8269562 0.1776809 -0.8404741 -0.5118915 0.6462462 -0.4198391 -0.6372606 0.4812768 -0.1885577 -0.8560484 0.8187051 0.05566591 -0.5715097 0.5344 0.3557031 -0.7667412 0.5962651 0.5335304 -0.5998444 0.1324628 0.5651125 -0.8143105 0.0439248 0.8158543 -0.5765869 -0.428525 0.6372219 -0.6405581 -0.3924474 0.3786055 -0.8382381 -0.8329575 0.2711148 -0.4823678 -0.5103709 -0.1226893 -0.8511576 -0.7285184 -0.3698914 -0.5765774 -0.3375906 -0.6897193 -0.6405622 -0.06678044 -0.4696581 -0.8803191 0.5107645 -0.8405568 0.1805104 0.9832666 0.02148127 0.1809015 0.4726026 0.8624295 0.1812793 -0.5112382 0.840038 0.1815816 -0.9832094 -0.02152836 0.1812065 -0.4726688 -0.862129 0.1825314 -0.2689417 -0.4711013 0.8400799 0.2636312 0.4718186 0.8413596 0.5394362 -0.00797367 0.8419888 0.2689394 -0.4711024 0.8400799 -0.5394328 -0.007991671 0.8419907 -0.2636306 0.4718202 0.8413589 0.4961025 -0.8682631 0.00130552 0.5397473 -0.8412489 0.03119844 0.4988056 -0.8667137 -7.41802e-4 0.9999843 -0.005190193 0.002133905 0.9984067 0.04588848 0.03283768 0.9999962 -0.002741336 5.38928e-4 0.5039485 0.863728 0.003194153 0.45885 0.8879141 0.03263771 0.5012279 0.8653147 0.001110196 -0.4968717 0.8678129 0.004407405 -0.5402914 0.8408793 0.03174078 -0.5012303 0.8653132 0.001118481 -0.999974 0.004695057 0.005485236 -0.9984898 -0.04660284 0.02909421 -0.9999961 -0.002763032 5.35366e-4 -0.5043129 -0.863514 0.00347799 -0.4584249 -0.8882495 0.02931982 -0.4988072 -0.8667128 -7.44243e-4 -0.667617 0.4878487 -0.5623978 -0.3538966 -0.7219259 -0.5946263 -0.3624549 0.5991182 -0.7139215 -0.7698621 0.5096159 -0.3841928 0.6868817 0.01408714 -0.7266327 0.7786496 0.400972 -0.4826245 0.7991638 0.3995544 -0.4491032 -0.4685764 -0.8204413 -0.3275857 -0.002616763 -0.6538682 -0.756604 -0.5057629 -0.3551676 -0.7861679 -0.698068 -0.2342505 -0.6766298 -0.9826655 -0.1852054 0.008227348 -0.4949607 0.08733797 -0.8645149 -0.2237719 0.8681008 -0.4430884 -0.002184629 0.7009553 -0.7132018 0.3101842 0.8516851 -0.4223959 0.37077 0.5840612 -0.7220818 0.8933067 -0.295618 -0.3385455 0.6254652 -0.3584535 -0.69304 0.4118798 -0.7961578 -0.4432697 0.4012339 -0.8878903 -0.2250829 0.004538357 -0.008525311 0.9999535 0.009397923 -0.007929027 0.9999244 0.01126313 -0.001362085 0.9999358 0.00950998 7.64916e-4 0.9999545 0.01129019 0.005786716 0.9999195 0.00503236 0.008988678 0.999947 -0.007267236 -0.01084482 0.9999148 -0.00546503 -0.009964942 0.9999355 0.002587914 -0.0130937 0.999911 -0.01163864 0.00601691 0.9999142 -0.0090698 -2.61608e-4 0.9999589 -0.0117498 -0.003741204 0.9999241 0.004676163 0.01089721 0.9999298 -0.005437672 0.01166039 0.9999173 -0.005766808 0.009400963 0.9999392 0.01050013 0.02506577 -0.9996307 0.02106028 0.03171479 -0.9992752 -0.01294136 0.02633774 -0.9995694 -0.003074169 0.01691859 -0.9998522 0.01739335 -0.02891206 -0.9994307 0.0202412 -0.01819014 -0.9996297 0.02541065 -0.01589268 -0.9995508 -0.01300895 -0.008136153 -0.9998823 0.003566622 -0.009904086 -0.9999447 -3.32886e-4 -5.77875e-4 -0.9999999 0.02147686 0.005963742 -0.9997516 0.01691812 9.17231e-4 -0.9998565 0.02511394 -0.005759298 -0.9996681 0.02626395 0.02069056 -0.9994409 -0.01079106 0.01315444 -0.9998553 -0.01153725 0.02432382 -0.9996376 -0.03071993 0.01101124 -0.9994674 -0.02917301 -5.60281e-4 -0.9995743 -0.01112997 -0.01483523 -0.9998281 -0.02036345 -0.008943617 -0.9997527 0.002417743 -0.03378397 -0.9994263 -0.4583331 -0.888664 -0.01440107 -0.3813416 -0.9244311 -0.002405881 -0.8231503 -0.5678215 -0.001578569 -0.8696283 -0.4935873 -0.0108776 -0.9953055 -0.09663295 0.005376517 -0.9359415 0.3517928 -0.01598489 -0.9688734 0.2475515 0.001637637 -0.6044352 0.7965716 -0.01147896 -0.5770907 0.8166484 -0.007203698 -0.1592438 0.9872311 0.004034101 0.1016458 0.9947098 -0.01485586 0.3409788 0.9400679 0.002446115 0.6799818 0.7332048 -0.00596553 0.6979795 0.7160648 -0.008714437 0.9458294 0.3246227 0.00518465 0.9977784 0.06481713 -0.01539695 0.9855013 -0.1696666 6.23416e-4 0.8173202 -0.5761437 -0.006799161 0.8378466 -0.5458993 -0.002669334 0.4473553 -0.8943555 -0.001280069 0.3663625 -0.9304098 -0.01077812 -0.08131301 -0.9966678 0.006440579 5.44759e-4 0.002870202 -0.9999958 1.71642e-4 0.002804219 -0.9999961 8.4364e-4 0.002683579 -0.9999961 -0.4832755 -0.8748379 -0.03322201 -0.6113595 -0.7908974 0.02685123 -0.8475008 -0.5300037 -0.02895408 -0.9032889 -0.4287444 0.01573294 -0.999889 -0.01485443 -0.001222729 -0.9998131 -0.01931416 8.88593e-4 -0.9412238 0.3375177 -0.01340979 -0.9135963 0.406311 0.01591831 -0.6586358 0.752461 -0.001220762 -0.6340871 0.773088 -0.01638638 -0.2469587 0.9689289 0.01371443 -0.1787078 0.9837158 -0.01915436 0.3213306 0.9468142 0.0170232 0.386021 0.9223533 -0.01588588 0.7202102 0.6936694 0.01095634 0.785291 0.6185687 -0.0262857 0.9440239 0.3285313 0.02976876 0.9976373 0.05408829 -0.04236108 0.9953756 -0.0946412 0.01644128 0.8422946 -0.5390044 -0.003780007 0.847855 -0.530223 0.002354681 0.5154495 -0.856688 -0.01994192 0.4140695 -0.9099119 0.02463018 0.0712853 -0.9970677 -0.02782791 -0.07752269 -0.9965074 0.03103947 -0.1511102 0.5975606 0.7874562 -0.1551828 0.6043452 0.7814636 -0.5278595 0.6030701 0.598056 -0.4615565 0.3631609 0.8093701 -0.7199516 0.3201848 0.6157528 -0.5898407 0.09444391 0.8019778 -0.8009681 -0.01189649 0.598589 -0.5689798 -0.2766172 0.7744321 -0.5646135 -0.2722073 0.7791758 -0.5235319 -0.6702658 0.525983 -0.1962377 -0.4532145 0.869533 -0.06721186 -0.8898557 0.4512643 0.2195341 -0.5212293 0.8246969 0.2652287 -0.5735808 0.7750218 0.7220977 -0.465796 0.5114773 0.5206067 -0.2079659 0.8280814 0.784678 -0.07374274 0.6155019 0.5666553 0.1152373 0.8158566 0.7403686 0.2607843 0.619553 0.5766389 0.5502924 0.6038757 0.270653 0.4098808 0.8710595 0.2744147 0.8081458 0.5211496 0.336456 -0.8570436 -0.3902225 0.5894473 -0.3807204 -0.7124632 0.4584313 -0.1828733 -0.8697116 0.8682634 0.05027306 -0.4935498 0.4115368 0.4375041 -0.7995173 0.4087999 0.4307505 -0.8045725 0.09306228 0.8856645 -0.4549043 -0.187642 0.4627608 -0.8663966 -0.4922588 0.6433078 -0.5863756 -0.7410184 0.1876551 -0.6447305 -0.4769315 -0.003765404 -0.8789324 -0.8007483 -0.4534261 -0.3914166 -0.2625128 -0.641161 -0.7211101 -0.08430868 -0.4457294 -0.8911888 0.511982 -0.8408727 0.1755217 0.9830944 0.02156502 0.1818253 0.4726139 0.8624209 0.1812906 -0.5120274 0.8402684 0.1782613 -0.9827216 -0.0218622 0.1837939 -0.4726717 -0.8621344 0.1824986 -0.2699984 -0.4547252 0.8487201 0.274221 0.4492006 0.8503069 0.5424685 -0.02183085 0.8397925 0.3113995 -0.431755 0.8465329 -0.542471 0.02183079 0.8397909 -0.3148034 0.4270866 0.8476414 0.5416734 -0.8403887 0.01835525 0.507704 -0.8615182 -0.004816293 0.4977723 -0.8673027 0.002965986 0.9999613 -0.004433333 0.007608354 0.9999874 0.004778444 0.001594603 0.9984681 0.04666328 0.02973419 0.4996282 0.8655504 0.03455722 0.4583941 0.888275 0.02902311 0.4757168 0.8794429 0.01654052 -0.5420637 0.8401001 0.01997244 -0.5067867 0.8620619 -0.004073202 -0.4975869 0.8674086 0.003107905 -0.9999612 0.004433333 0.007609844 -0.9999874 -0.004778504 0.001594603 -0.9984189 -0.0473932 0.03022509 -0.4997267 -0.8654116 0.03655141 -0.4583923 -0.8882761 0.02902287 -0.4745846 -0.8800386 0.01736843 -0.01991969 -0.3194534 -0.9473926 -0.7995374 0.06974387 -0.5965532 -0.5950692 -0.06650024 -0.8009185 0.7648365 -0.2578034 -0.5903918 0.611501 -0.09819781 -0.7851267 -0.1011449 -0.8730868 -0.4769584 -0.5529795 0.2236462 -0.8026184 0.5830618 -0.3345121 -0.7403652 -0.3178415 -0.6178302 -0.7192097 -0.06418251 -0.9857196 -0.1556843 -0.2351979 -0.1501834 -0.9602745 -0.5448464 -0.4260323 -0.7222458 -0.7864427 -0.5070769 -0.3526769 -0.711174 0.5845382 -0.3905725 -0.3257288 0.4497891 -0.8316193 -0.09778749 0.5801694 -0.8086045 6.21728e-4 0.8351173 -0.5500717 0.1634244 0.6602657 -0.7330359 0.4799907 0.7414153 -0.4689481 0.4976965 0.5343517 -0.6832032 0.6135702 0.2469252 -0.7500398 0.8246554 0.2389149 -0.5127021 0.5542718 -0.7051358 -0.4422289 0.2191802 -0.5826788 -0.782589 -0.001628398 0.1846154 0.9828095 0.001628398 0.6865958 0.7270376 -0.001628398 0.7270382 0.6865951 0.001628458 0.9828095 0.1846155 -0.001628458 0.9917567 0.1281251 0.002099454 0.8634387 -0.5044497 0.00456047 0.87765 -0.4792804 -0.01047635 0.3900648 -0.9207279 1.55226e-4 0.1600806 -0.9871039 -0.001584827 -0.004792451 -0.9999874 -0.002612888 -0.09871792 -0.9951121 0.008733212 -0.3594886 -0.9331087 -0.007408797 -0.7554543 -0.6551596 0.00426203 -0.8776515 -0.4792807 -0.001767039 -0.9842641 0.1766953 -0.00349456 -0.9805099 0.1964383 0.003110468 -0.5327217 0.8462848 -0.001898944 -0.4722011 0.8814889 0.001628398 0.128125 0.9917567 1 2.84558e-6 0 1 -1.9738e-6 0 1 2.35671e-6 0 1 -4.33854e-6 0 -1 4.98262e-6 0 0.3215824 -0.9468816 0 -0.9468816 -0.3215826 0 0.9468817 0.3215825 0 -3.96967e-7 0 1 0 0 1 3.96967e-7 0 1 0 0 1 0 0 1 -1.23209e-7 0 1 0 0 1 0 0 1 -3.28789e-7 0 1 2.68022e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1.23209e-7 0 1 0 0 1 -5.01545e-7 0 -1 0 0 -1 -1.2143e-6 0 -1 5.01545e-7 0 -1 -1.39516e-6 0 -1 0 0 -1 -3.00212e-7 0 -1 -0.9867299 -0.1347054 0.09065669 -0.6534471 -0.7536586 -0.07075095 -0.7536596 -0.6534462 0.07074892 -0.1347044 -0.9867303 -0.0906549 0.1347044 -0.9867302 0.09065538 0.7536599 -0.653446 -0.07074886 0.7409117 -0.6697193 -0.0502603 0.9899064 0.1351354 0.0427078 0.9474567 0.3058204 -0.0938065 0.6526157 0.7527009 0.08680027 0.2077435 0.9681403 -0.1398113 -0.1347036 0.9867304 0.09065419 -0.7536593 0.6534465 -0.07074892 -0.6534466 0.7536593 0.07074993 -0.9867299 0.1347054 -0.09065639 -0.9867299 -0.1347054 0.09065639 -0.6534469 -0.753659 -0.0707488 -0.6697197 -0.7409113 -0.05026024 0.1351372 -0.9899062 0.04270648 0.3058217 -0.9474561 -0.09380817 0.7526999 -0.6526166 0.08680081 0.9681401 -0.207744 -0.1398117 0.9867302 0.1347036 0.09065628 0.6534472 0.7536587 -0.07074874 0.7536596 0.6534462 0.07074892 0.1347044 0.9867301 -0.09065681 -0.1347044 0.9867301 0.09065681 -0.6534478 0.7536581 0.07075089 -0.9867299 0.1347054 -0.09065663 -0.9899064 -0.1351354 0.0427078 -0.9474567 -0.3058204 -0.0938065 -0.6526157 -0.7527009 0.08680027 -0.2077435 -0.9681403 -0.1398113 0.1347036 -0.9867304 0.09065419 0.7536593 -0.6534465 -0.07074892 0.6534466 -0.7536593 0.07074993 0.9867299 -0.1347054 -0.09065639 0.9867299 0.1347054 0.09065669 0.6534471 0.7536586 -0.07075095 0.1347044 0.9867303 -0.0906549 -0.1347044 0.9867302 0.09065538 -0.7536599 0.653446 -0.07074886 -0.7409117 0.6697193 -0.0502603 -0.9867302 -0.1347036 0.09065628 -0.6534472 -0.7536587 -0.07074874 -0.1347044 -0.9867301 -0.09065681 0.1347044 -0.9867301 0.09065681 0.6534478 -0.7536581 0.07075089 0.9867299 -0.1347054 -0.09065663 0.9867299 0.1347054 0.09065639 0.6534469 0.753659 -0.0707488 0.6697197 0.7409113 -0.05026024 -0.1351372 0.9899062 0.04270648 -0.3058217 0.9474561 -0.09380817 -0.7526999 0.6526166 0.08680081 -0.9681401 0.207744 -0.1398117 -0.496139 -0.8682432 0 -0.496139 0.8682432 0 0.496139 -0.8682432 0 0.496139 0.8682432 0 0.9845806 -0.1705179 0.03904855 0.9993045 -0.02376127 -0.02873951 0.8819231 0.4702942 0.03217256 0.8357927 0.5487672 -0.01747655 0.4475328 0.8942637 0.00262928 0.4071704 0.9129708 0.02639663 -0.006779551 0.9995814 -0.0281257 -0.2393283 0.9700778 0.04088038 -0.3835906 0.9233766 -0.01529717 -0.7402998 0.672275 0.001634478 -0.7665168 0.6419126 0.02001368 -0.9390513 0.3431323 -0.02104586 -0.9787931 0.2037677 0.02104669 -0.9959049 -0.08933532 -0.01387834 -0.9774273 -0.2100301 0.02287656 -0.8882118 -0.4583598 -0.03140538 -0.7244315 -0.6888257 0.02679836 -0.5664008 -0.8234992 -0.03224152 -0.3586212 -0.9327544 0.03688067 -0.02316641 -0.9990511 -0.03688114 0.2105541 -0.9770504 0.03224104 0.4079352 -0.9126175 -0.02679848 0.691816 -0.7207518 0.04367613 0.8376098 -0.5445201 -0.04367578 -0.9421131 0.335038 0.01314336 -0.9608342 0.2769263 -0.01046794 -0.9007411 -0.4342016 0.01159864 -0.8713994 -0.4902913 -0.01666444 -0.1207708 -0.9925182 0.01794928 -0.05435132 -0.9983995 -0.01563262 0.7034451 -0.710628 0.01314288 0.7455271 -0.6663932 -0.01046693 0.999194 -0.03875398 0.01046788 0.9998168 -0.01893895 0.002802968 0.7933991 0.6084964 -0.01580721 0.6538297 0.7548798 0.05160737 0.2406792 0.9694666 -0.046992 -0.3215909 0.9459385 0.04218524 -0.45383 0.8909914 -0.01314288 -0.5018947 -0.8649287 -3.53231e-5 -0.5004281 -0.8657769 0.00142467 -0.5000002 -0.8660249 0.001010179 -0.1927664 -0.5167977 -0.834123 0.002855896 -0.4477511 -0.8941538 0.08220523 -0.4812394 -0.8727262 0.4932792 -0.8698711 -1.17527e-5 0.4876745 -0.873017 -0.003886878 0.511807 -0.8590554 -0.008798003 0.4999985 -0.8660217 0.002841413 0.3582863 -0.2021293 -0.9114685 0.9999839 0.005690157 0 0.999973 -0.007283806 -9.85908e-4 0.9999753 0.00701797 5.67533e-4 0.9999884 0 -0.004829645 0.9998233 0.01407545 -0.01245915 0.6154531 0.1281991 -0.7776777 0.3899852 0.221546 -0.8937723 0.3770592 0.3081302 -0.8734313 0.5033212 0.8640994 2.95227e-5 0.400406 0.9163377 5.49809e-4 0.4996038 0.8653374 -0.03984171 0.5619376 0.8266074 0.03076374 0.004588544 0.4069522 -0.913438 -0.5056534 0.8627368 -3.74065e-5 -0.4056134 0.9140426 0.001982271 -0.4999973 0.8660227 -0.002756536 -0.5525012 0.8313342 -0.06021636 -0.3743212 0.300628 -0.8772153 -0.3871381 0.2198173 -0.8954354 -0.5909859 0.1402629 -0.7943941 -0.9999821 0.006005346 4.45886e-5 -0.9999902 0.002056777 -0.003938317 -0.9999741 0.007185518 5.44077e-4 -0.999996 0 -0.002831041 -0.9378922 -0.2725324 -0.2146731 -0.3459174 -0.2043417 -0.9157432 0.006496846 4.38877e-4 -0.9999789 -0.006642401 -4.51102e-4 -0.9999778 0.009603202 -0.0246728 -0.9996495 -0.006162941 0.007704734 -0.9999514 -0.01239639 -0.02375674 -0.999641 -0.006995201 -0.007606208 -0.9999467 0.003783404 -0.003412187 -0.9999871 0.003128886 0.01294624 -0.9999113 -0.001502096 -0.002737343 -0.9999951 0.003146231 0.00441873 -0.9999853 0.003771245 0.00243026 -0.9999899 7.30431e-4 -0.003101766 -0.999995 -7.05455e-4 0.01390665 -0.9999031 0.001191496 0.004436492 -0.9999895 -0.009186923 0.002220332 -0.9999554 0.001708269 -0.004425108 -0.9999888 5.1606e-4 0.00250858 -0.9999968 0.002984523 0.002677023 -0.999992 0.00886029 -0.00553739 -0.9999454 0.004074156 -0.007128596 -0.9999663 -0.002463459 0.008045077 -0.9999647 0.008748352 0.009124875 -0.9999202 0.0076496 0.01450198 -0.9998657 0.8710814 0.07301265 -0.4856814 0.4066469 0.4485958 -0.7958644 0.4146739 0.8464369 -0.334051 -0.03927654 0.5416346 -0.8396961 -0.5661397 0.7593569 -0.3207228 -0.5064827 0.4228001 -0.7514755 -0.7034186 0.01924502 -0.7105153 -0.8710815 -0.07301062 -0.4856815 -0.4066483 -0.4485972 -0.7958629 -0.4146729 -0.846437 -0.3340523 0.03928107 -0.541631 -0.839698 0.5661397 -0.7593569 -0.3207228 0.5064765 -0.4228019 -0.7514787 0.7034159 -0.01924502 -0.7105178 0.9996064 -0.02483564 0.01304918 0.7654128 -0.6432878 0.01800858 0.7047994 -0.7090358 -0.02293807 0.1729494 -0.9849229 -0.003934025 0.07632696 -0.9964273 0.03615158 -0.4801529 -0.8761732 -0.0421186 -0.6729672 -0.7376006 0.05532151 -0.991389 -0.1159259 -0.0609017 -0.9996063 0.02484005 0.01304924 -0.7654151 0.6432849 0.01800864 -0.7047994 0.7090358 -0.02293717 -0.1729511 0.9849227 -0.003929615 -0.07632929 0.9964272 0.03615057 0.4801478 0.8761759 -0.04211938 0.6729682 0.7375996 0.0553224 0.9913895 0.115923 -0.06090086 -0.6088486 0.6014143 0.5173048 -0.5887744 0.5944226 0.5477286 -0.1083658 0.6051434 0.7887068 0.1805608 0.8783984 0.4425092 0.2848491 0.5211086 0.8045539 0.8716288 0.3242395 0.3676032 0.5629036 0.06564742 0.8239114 0.6088486 -0.6014143 0.5173048 0.5887745 -0.5944193 0.547732 0.1083641 -0.6051399 0.7887098 -0.1805588 -0.8783968 0.4425129 -0.2848503 -0.5211086 0.8045533 -0.8716281 -0.3242393 0.3676049 -0.5628941 -0.06564784 0.8239179 -8.82613e-4 -0.002110779 0.9999974 -0.004264414 0 0.9999909 6.67959e-5 0.001234054 0.9999992 9.73439e-4 0.0016824 0.9999982 -6.83494e-5 -0.001234054 0.9999992 -9.71956e-4 -0.0016824 0.9999981 -7.60943e-4 0.003362774 0.9999942 -8.44162e-4 0.001456141 0.9999986 8.80031e-4 0.002110779 0.9999974 0.004264354 0 0.9999909 7.60945e-4 -0.003362774 0.9999941 8.40322e-4 -0.001456141 0.9999986 0.2832831 -0.4438257 -0.8501585 0.4753711 -0.2380685 -0.8469627 -0.2780709 -0.4444696 -0.8515417 -0.03763717 -0.5274878 -0.8487285 -0.5019732 -0.18133 -0.8456609 -0.3152456 0.4321925 -0.8448846 0.2851756 0.4414669 -0.8507537 0.0376451 0.5274752 -0.8487361 -0.5074298 0.1433632 -0.8496836 0.5129293 0.1590364 -0.8435705 0.3431939 -0.4034695 -0.8481925 -0.2904284 -0.4614033 -0.8383069 0.09639948 -0.5176261 -0.8501591 0.5232812 -0.1006957 -0.8461899 -0.5320921 -0.04754954 -0.8453503 -0.446003 0.2900794 -0.8467204 0.1045325 0.5160311 -0.8501677 -0.1626979 0.5031791 -0.8487287 0.4314514 0.3267367 -0.8408882 -0.2621709 -0.468261 -0.8437998 0.1343324 -0.5188974 -0.8442158 -0.5040168 -0.169854 -0.8468274 0.4454132 -0.2952508 -0.8452421 -0.3151576 0.4322834 -0.8448709 -0.5066437 0.1448289 -0.849904 0.5257456 0.01595407 -0.8504922 0.4134232 0.3394961 -0.8448809 0.07077676 0.5310446 -0.844383 0.3339448 -0.4085429 -0.849455 -0.2621749 -0.468256 -0.8438013 0.09639763 -0.5176241 -0.8501605 0.5066341 -0.1448251 -0.8499103 -0.504019 -0.16984 -0.846829 0.2524701 0.4742816 -0.8433955 -0.5042627 0.1743017 -0.8457766 -0.1797494 0.5121824 -0.8398569 0.5037614 0.1727311 -0.8463973 -0.5476161 -0.04190105 -0.83568 -0.420161 0.02007746 -0.9072275 -0.9344412 0.08604854 -0.3455651 -0.9126609 0.07196575 -0.4023323 -0.8026087 0.08001518 -0.5911151 -0.3391537 0.1153494 -0.9336323 -0.7979228 0.2334355 -0.5557223 -0.9141618 0.2126758 -0.3450759 -0.7146766 0.1472792 -0.6837736 -0.473088 0.1004791 -0.8752667 -0.1282058 0.02320003 -0.9914762 -0.2339991 -0.9721997 0.00849384 -0.5450528 -0.8383307 -0.01091581 -0.7982962 -0.6020945 0.01433598 0.8964014 -0.4431781 -0.007598161 0.8319234 -0.5548073 0.009619116 0.5324965 -0.8463496 -0.0118336 0.2936625 -0.9558396 0.01153504 -0.06514239 -0.9978455 -0.007804512 -0.9368038 -0.3494834 -0.01612764 -0.9999195 0.008055567 0.009805619 0.3520309 0.9357718 0.02013957 0.9698395 0.2433582 0.01371443 -0.9619691 0.2729602 -0.01040297 -0.8174976 0.5757653 0.01386064 -0.5876412 0.8089286 -0.01767623 -0.2936725 0.9558366 0.01153063 0.0651434 0.9978455 -0.007800519 0.5504476 0.8348383 -0.007253646 0.9545299 0.2981098 0.001822412 0.5530372 -0.8329657 0.01783031 -0.8184231 -0.5741955 0.02198457 -0.9981358 0.06085008 0.004735589 0.9813849 -0.1917249 -0.01119273 0.6561232 -0.7546468 -0.003251194 0.1766685 -0.9842163 -0.01032346 -0.184896 -0.9826433 0.01501977 -0.5485613 -0.8357049 -0.02603501 -0.9933794 -0.1138076 -0.01566118 -0.09344887 0.9952153 0.02852803 -0.8373839 0.5465912 -0.005146682 -0.8100019 0.5864238 0.002070069 -0.313431 0.9496065 -0.00291419 0.2049103 0.9787468 -0.008164882 0.7977135 0.6030246 0.003815531 0.7703959 0.6375352 -0.006252944 0.9975801 -0.06869727 0.01071029 0.8361257 -0.5482423 -0.01801222 0.5800122 -0.8143815 0.01920258 0.2452837 -0.9692845 -0.01798707 -0.1576527 -0.9873328 0.01787745 -0.4884403 -0.8723942 -0.01882731 -0.791979 -0.6103163 0.0168308 -0.9464244 -0.3225923 -0.01466625 -0.9968951 0.07732611 0.01486188 -0.5858399 0.8104103 0.005186319 0.1678423 0.9858033 -0.004588246 0.9928682 -0.1179595 0.01727455 -0.9609974 0.2763686 -0.0102263 -0.5868678 0.8096679 0.004928529 0.1313295 0.9913352 0.002662301 0.772549 0.6349466 -0.003284394 0.7920888 0.610402 0.002198874 0.9995198 0.03087729 -0.002620518 0.5617637 -0.8270903 0.01853281 0.9609941 -0.27638 -0.01022648 0.6358796 -0.7717804 0.003500819 0.1766654 -0.9842169 -0.01032108 -0.184902 -0.9826422 0.01501953 -0.4884459 -0.8723911 -0.01882517 -0.7919827 -0.6103117 0.01682972 -0.9464247 -0.3225914 -0.01466739 -0.9999195 0.008005678 0.009855628 -0.7894241 0.6135525 0.0190491 -0.06389367 0.9976497 0.02475202 -0.935747 0.352311 -0.01595818 -0.3428388 0.9391889 -0.0196467 0.463706 0.8856778 -0.02348858 0.7702564 0.6374173 0.02011656 0.9440423 0.3294743 -0.01518887 0.996896 -0.07731419 0.01486223 0.9528821 -0.08475679 -0.2912594 0.7517045 -0.02744603 -0.6589288 0.6586675 0.04527944 -0.7510707 0.4395754 -0.08207041 -0.8944485 0.5846431 -0.1616817 -0.7950168 0.9351907 -0.1821044 -0.3037374 0.8849033 -0.194017 -0.4234425 0.7680239 -0.1480616 -0.6230708 0.4067456 -0.03797906 -0.9127517 0.1804752 -0.02151632 -0.9833442 -0.1447238 -0.9893466 -0.01576292 -0.1436255 -0.9895791 -0.01025187 -0.1466903 -0.9891428 0.008851587 -0.1460203 -0.989281 0.001081585 0.4251886 -0.9049857 -0.01468938 0.7033893 -0.7106932 -0.01259958 0.3861553 -0.9224338 -3.62612e-6 0.662389 -0.7488258 0.02237755 0.9896366 -0.1435597 0.003178 0.9891961 -0.1465981 4.78656e-4 0.989569 -0.1440599 -6.3241e-6 0.9887177 -0.1491211 -0.01415163 -0.9887342 0.1488983 -0.0152983 -0.9893082 0.1458406 4.53866e-6 -0.9891118 0.1469888 0.007231414 -0.9892064 0.1465187 0.001742422 -0.851025 -0.5246481 -0.02237939 -0.8792499 -0.4761927 0.01265215 -0.6692826 -0.7428629 0.01468139 -0.6369653 -0.7708926 0 -0.1483619 -0.9889189 0.00532037 -0.1514561 -0.9884393 -0.006989777 -0.1499109 -0.9886414 0.01072818 -0.1447086 -0.9893863 -0.0132001 0.1488425 0.9888043 -0.01058375 0.1462739 0.9892435 0.001177787 0.1459409 0.9892928 -0.001130521 0.1460241 0.9892809 5.91128e-4 -0.4104096 0.9118254 -0.01177185 -0.4952925 0.868195 0.0303781 -0.6972258 0.7161327 -0.03209811 -0.7585436 0.6516007 0.00531882 -0.9896298 0.1436065 0.00318408 -0.9891915 0.1466143 -0.002135992 -0.9890757 0.1474085 -2.40163e-4 -0.9893605 0.1448034 -0.01407361 0.002029061 -0.01207065 -0.9999251 -0.002335429 -0.006208419 -0.999978 0.002020537 -0.01007968 -0.9999472 0.0029881 -0.00972259 -0.9999483 0.011339 -0.007985889 -0.9999039 0.01300263 -0.007834911 -0.9998849 -0.008768022 -0.002503275 -0.9999585 -0.009244859 -0.002319872 -0.9999547 -0.003413617 -0.007618367 -0.9999653 -1.71876e-5 2.93266e-5 -1 1.96239e-5 1.21816e-5 -1 1.5437e-5 2.27064e-5 -1 1.15962e-5 -8.12067e-6 -1 7.6091e-6 -1.59337e-5 -1 1.27126e-5 -7.96686e-7 -1 9.74366e-4 0.005178034 -0.9999862 -4.53731e-4 0.002375781 -0.9999971 -0.001128673 0.001700162 -0.999998 -0.004931926 -0.001368701 -0.999987 -0.006536006 4.50097e-4 -0.9999786 -0.004308402 -0.003565311 -0.9999845 -2.12156e-5 -3.29334e-5 -1 0.018269 -0.0014171 -0.9998322 0.007464289 0.002696454 -0.9999686 0.005517959 0.004251003 -0.9999758 0.001144826 0.007177174 -0.9999736 -0.002008736 0.01016604 -0.9999463 -0.006276845 0.008811712 -0.9999415 -0.01364266 0.007929801 -0.9998755 9.25202e-4 -0.01444751 -0.9998952 0.007066369 -0.005492329 -0.99996 0.01453906 9.00981e-4 -0.999894 0.01532334 -1.22837e-4 -0.9998826 0.01088607 0.008388817 -0.9999057 0.005732178 0.03046476 -0.9995194 0.007971525 0.01569682 -0.999845 0.9887342 -0.1488987 -0.01529836 0.9893082 -0.1458405 3.61929e-6 0.989112 -0.146988 0.007226765 0.9892067 -0.1465168 0.0017457 0.8616443 0.5074582 -0.007456839 0.6432051 0.7656801 0.004614889 0.8698117 0.49337 0.003709435 0.6516222 0.7585436 0 0.1480714 0.988974 -0.002311468 0.1476895 0.98903 -0.00273019 0.1483653 0.9889219 -0.004601538 5.47654e-5 1.55027e-5 -1 7.66576e-7 0 -1 -3.08715e-7 0 -1 -1.99518e-5 -3.68313e-5 -1 -0.009398043 -0.923412 -0.3836953 -0.06555122 -0.7889969 -0.6108904 0.02362775 -0.6004385 -0.7993218 -0.08207052 -0.4395753 -0.8944485 -0.1616761 -0.5846438 -0.7950174 -0.211912 -0.8824424 -0.4199865 -0.1465032 -0.7811091 -0.6069643 -0.03809839 -0.4068372 -0.912706 -0.02083796 -0.1775234 -0.983896 5.2161e-6 -4.32189e-5 -1 -4.89788e-5 3.27529e-5 -1 4.22561e-7 0 -1 -1.3915e-6 0 -1 -7.21649e-5 -1.28334e-5 -1 -2.11747e-7 0 -1 -5.59422e-7 0 -1 2.82404e-7 0 -1 2.31485e-5 5.28015e-5 -1 0.00939846 0.9234107 -0.3836983 0.06555157 0.7889932 -0.610895 -0.02362543 0.6004304 -0.7993279 0.08207148 0.4395823 -0.8944449 0.1616763 0.5846437 -0.7950173 0.2119136 0.8824243 -0.4200238 0.1465045 0.7811107 -0.6069617 0.03809708 0.4068318 -0.9127084 0.02083826 0.177537 -0.9838936 2.64502e-7 0 -1 -6.44664e-6 3.61095e-5 -1 7.19028e-5 -3.60593e-5 -1 0.9658043 -0.259234 -0.004444122 0.9773258 -0.2115833 -0.008176863 0.3942279 -0.919008 0.002966225 0.6005836 -0.7995551 -0.003330767 0.6120418 -0.7908206 0.002795875 0.7819015 -0.6233923 -0.003503322 -0.3276077 -0.9447135 0.01377147 -0.4381663 -0.8987353 -0.01688987 -0.528744 -0.8487381 0.008559167 -0.648445 -0.7612437 -0.005225419 -0.9964984 0.08282828 -0.01142489 -0.9965829 0.08183944 -0.01117426 0.9116201 -0.4108775 0.01133602 0.9175183 -0.397674 0.003954708 0.7826409 -0.6224663 -0.002967834 0.3931333 -0.9194748 0.003504216 0.157865 -0.9874563 -0.002962172 0.138213 -0.9903832 0.006208419 -0.6668627 -0.745175 0.002893388 -0.7995806 -0.6005544 -0.002288818 -0.8192912 -0.5733159 0.008420586 -0.8873014 -0.4611017 -0.009034037 -0.9424421 -0.3338493 0.01864796 -0.9626944 -0.2705195 -0.006213068 -0.9934754 -0.1135367 -0.01077789 -0.9997764 -0.01133167 0.01785886 -0.6024627 -0.7980836 -0.01007562 -0.08607071 -0.9962862 -0.002402305 -0.09591257 -0.9953896 -5.28806e-4 -0.1949551 -0.9807208 -0.01339274 -0.1760698 -0.9842428 -0.01630139 -0.9607223 0.2752597 -0.03528332 -0.9694433 0.2453088 -0.001841604 -0.4881499 0.8727015 -0.01009386 -0.5151188 0.8571148 0.002636373 -0.6944421 0.719541 -0.003329694 -0.7047402 0.70946 0.00279504 -0.8403228 0.5420788 -0.002894639 0.320385 0.9472566 0.007647633 0.413328 0.9105579 -0.006653726 0.7379759 0.6746948 -0.01336169 0.8052594 0.5928722 0.007748186 0.870981 0.4913043 -0.003496646 0.9444098 0.3285968 -0.01069188 0.9547169 -0.2949461 -0.0390197 0.9999704 -0.006061494 -0.00475955 -0.955398 0.2949879 0.01402908 -0.9196445 0.3926654 -0.008236885 -0.8533084 0.5213804 0.005224227 -0.2936429 0.9559042 0.004597246 -0.2800118 0.9599473 0.009728908 -0.1359317 0.9906691 -0.009869515 -0.03069514 0.999415 0.01509034 0.4645685 0.8855154 0.006212472 0.562856 0.8265056 -0.009034872 0.6624507 0.7489311 0.01616901 0.8967871 0.4423713 0.008985042 0.9719797 0.2347893 0.0113849 0.9919739 0.1259925 -0.01066118 0.999823 0.01673018 0.008607506 0.9882467 -0.1527623 0.005659341 0.1373678 0.9903318 -0.01931554 0.08456695 0.9963619 -0.0105682 0.1942903 0.9809288 -0.005476951 0.187415 0.98225 -0.007796406 0.0924592 0.9956036 -0.01499587 4.85004e-7 0 1 -1.40971e-6 0 1 5.33709e-7 0 1 -1.0112e-6 0 1 6.6167e-7 0 1 -7.11804e-5 8.02007e-5 1 8.77272e-5 1.00252e-5 1 0 -9.32732e-6 1 1.5915e-6 -9.95209e-6 1 -1.10264e-5 5.51937e-7 1 -8.82154e-7 0 1 6.16392e-7 0 1 5.01354e-7 0 1 9.29114e-5 -1.94835e-5 1 1.80569e-5 -1.05085e-4 1 2.06936e-5 1.40888e-6 1 -4.80851e-6 -3.06151e-5 1 9.68956e-5 5.35823e-5 1 -5.30091e-6 7.32499e-6 1 1.48668e-6 7.34529e-6 1 3.6251e-5 -1.61476e-5 1 2.23161e-6 -2.33415e-5 1 -2.31929e-5 -8.61763e-6 1 5.13071e-7 0 1 1.05501e-6 0 1 -4.06787e-7 0 1 -6.15207e-7 0 1 -6.97076e-7 0 1 2.02664e-5 2.31173e-5 1 2.79496e-5 -5.70017e-6 1 2.95823e-5 1.26502e-6 1 7.99654e-6 -2.47784e-5 1 0.975353 -0.2204304 -0.009850025 0.8756458 -0.4827886 0.01263707 0.7040627 -0.7100463 -0.01140677 0.4719603 -0.8810049 0.03292196 0.3379172 -0.9407176 -0.02936929 0.2288906 -0.9730585 0.02768266 -0.2371312 -0.9704305 0.04509413 -0.631122 -0.7753382 0.02314537 -0.7219471 -0.691325 -0.02936404 -0.7958319 -0.6048842 0.02768856 -0.9032118 -0.4281021 0.03061079 -0.9848967 -0.1686913 0.03900903 0.9784983 -0.2059652 0.0109356 0.884261 -0.4668255 -0.01250731 0.7149282 -0.6991049 0.01140224 0.5081681 -0.8611905 -0.0107752 0.09313124 -0.9947189 -0.04313838 0.04240411 -0.9990642 0.008533358 -0.1857579 -0.9825364 -0.01078045 -0.371851 -0.9278795 -0.0276885 -0.4748089 -0.8795993 0.02935475 -0.5799175 -0.8143462 -0.02315348 -0.8677185 -0.4954634 -0.03976118 -0.9696747 -0.2424739 -0.0306198 -0.998843 -0.04041355 -0.02606773 -0.9973254 0.06847834 0.02555119 -0.9662885 0.2558327 0.028921 -0.8644564 0.5015046 0.03476238 -0.686948 0.7258638 0.03498941 -0.4524239 0.8909162 0.03976106 -0.02371746 0.9991906 0.03249031 0.3968071 0.9173914 0.0306158 0.6209831 0.783734 0.01188135 0.811442 0.584322 -0.01139771 0.9986524 0.05070948 0.01104563 -0.9804406 0.1951895 -0.02524751 -0.8938481 0.4470422 -0.03447943 -0.7306225 0.6818841 -0.03499805 -0.5191109 0.8541585 -0.03061628 -0.3322249 0.9427937 -0.02768903 -0.2229814 0.9743805 0.02936238 -0.1009293 0.9946241 -0.02315562 0.09300285 0.9952808 -0.0276913 0.2054323 0.9782307 0.02936911 0.3371215 0.9410231 -0.02871751 0.589043 0.8071988 -0.03819113 0.8023371 0.5967624 0.01139771 0.9370138 0.3490725 -0.01239871 0.9427821 0.3332468 0.01041555 0.9976072 0.06800872 -0.01244658 -2.86844e-7 0 1 2.58384e-7 0 1 4.44145e-7 0 1 -3.3315e-7 0 1 -2.89783e-6 0 1 8.322e-7 0 1 -3.53897e-6 0 1 9.16545e-7 0 1 5.89148e-7 0 1 3.26248e-7 0 1 1.31526e-6 0 1 -5.60774e-7 0 1 8.84614e-7 0 1 -5.56128e-7 0 1 2.99813e-7 0 1 7.06644e-7 0 1 -1.31409e-7 0 1 -4.44188e-7 0 1 -2.47984e-6 0 1 7.17377e-7 0 1 4.02856e-7 0 1 0.8856238 -0.4643403 0.007662296 0.4880889 -0.872761 0.007594645 -0.04202878 -0.9990968 0.006270647 -0.3102719 -0.9506273 -0.006251633 -0.5159278 -0.8566117 0.005912363 -0.818378 -0.5746419 0.006641983 -0.9992307 -0.037799 0.01046037 0.9289121 -0.3702676 -0.004933893 0.5938608 -0.804532 -0.007594525 0.08844023 -0.9960594 -0.00664246 -0.7201256 -0.69379 -0.008636832 -0.9842633 -0.1765257 -0.008037447 9.12509e-6 0 1 -6.43736e-7 0 1 -6.83937e-6 0 1 -0.9113317 0.411503 -0.01182448 -0.7589524 0.6509078 0.017618 0.09453874 0.995499 0.00664252 0.5987806 0.8008667 0.008637368 0.9986466 0.05173391 0.005352258 -0.5552436 0.8316421 -0.008721232 -0.304427 0.9525152 0.006249725 -0.03590339 0.9993356 -0.006270587 0.4683161 0.8835361 -0.006641268 0.7857428 0.6185253 -0.005912184 0.904633 0.4261456 0.006252408 0.9860867 0.1661138 -0.006264746 0.9901651 -0.1359771 -0.03291356 0.9682597 -0.2485781 0.02611964 0.5795702 -0.8145768 -0.0237348 0.5072513 -0.8615595 0.02028775 -0.2110494 -0.9772484 -0.02106279 -0.2867082 -0.9577864 0.02106291 -0.8674542 -0.4970709 -0.02106767 -0.903618 -0.427821 0.02106541 -0.9666314 0.2555434 -0.01792407 -0.9549646 0.2967201 0 -0.6744288 0.7383399 0 -0.642103 0.7664089 0.01792037 0.003259479 0.9997729 -0.02106297 0.08130812 0.9964665 0.02106732 0.7482277 0.6630996 -0.02131313 0.8063704 0.5906376 0.0302335 -2.42502e-4 -8.23617e-6 -1 -3.11049e-4 3.37853e-5 -1 7.64928e-7 0 -1 0.9709751 0.2377828 0.02582025 0.8835949 0.4678147 -0.02024072 0.6028357 0.7977218 0.01513862 0.6139407 0.7892924 0.00971657 0.01289296 0.9998698 -0.009716391 -0.005686879 0.9999808 -0.002487301 -0.5011452 0.8653032 0.01020312 -0.6103436 0.7918661 -0.02070909 -0.8219937 0.5691158 0.02082335 -0.9454112 0.3244534 -0.03045809 -0.9986637 -0.03701788 0.03606367 -0.9606218 -0.2769272 -0.02273994 -0.751125 -0.6600347 0.01287037 -0.7830089 -0.6219981 -0.003931999 -0.4177985 -0.9084845 0.01002031 -0.3513514 -0.9361797 -0.01094657 0.1374224 -0.990512 0.00111097 0.1471579 -0.9891052 0.003965139 0.519616 -0.8543931 -0.003448665 0.5778493 -0.8160364 0.01322972 0.8608092 -0.5084979 -0.02091783 0.9413566 -0.3365746 0.02377742 0.9997488 -0.009967625 -0.02007281 9.21011e-7 0 -1 1.96606e-6 0 -1 -1.0169e-6 0 -1 -4.77764e-7 0 -1 5.18787e-7 0 -1 -8.14926e-7 0 -1 -0.8050064 -0.5932649 -0.001299619 -0.7971992 -0.6037024 -0.004094362 -0.322736 -0.9464803 0.004095733 -0.2672265 -0.9635975 -0.008359074 0.5207322 -0.8536612 0.01002472 0.5790476 -0.8152321 -0.0100252 0.9952523 -0.0968964 0.009169578 0.9997402 0.0134387 -0.01841253 0.7561165 0.65401 0.02363967 0.5932167 0.8046957 -0.02363967 -0.02377092 0.9995892 0.01601725 -0.1298026 0.9915183 -0.006540298 -0.7127946 0.7013424 0.006540596 -0.7236508 0.6901587 0.003234505 -0.9887667 0.1491249 -0.01010471 -0.9985724 0.05228853 0.0109201 1.34645e-6 0 1 -1.32597e-6 0 1 9.12769e-7 0 1 8.99251e-7 0 1 1.31585e-6 0 1 -1.85901e-6 0 1 -2.1137e-6 0 1 9.48374e-7 0 1 1.66796e-6 0 1 -1.10626e-6 0 1 1.44517e-6 0 1 -0.0275101 0.06600195 0.9974403 -0.05294978 0.01391327 0.9985002 -0.04378241 0.01904934 0.9988595 -0.03030675 -0.02612787 0.9991992 -0.01362508 -0.005203664 0.9998937 -0.006750643 -0.0123142 0.9999015 -0.006798684 -0.01113545 0.9999149 0.004252135 -0.01255106 0.9999122 0.005331993 -0.008778214 0.9999473 0.01268714 -0.006540238 0.9998981 0.01030629 2.28622e-4 0.999947 0.01292037 0.003490865 0.9999105 0.02630531 -0.009987831 0.9996041 0.02268618 0.04345303 0.9987979 0.03053122 -0.02311652 -0.9992666 0.02615106 -0.008384287 -0.9996229 0.03173708 6.27036e-4 -0.9994961 0.02717077 0.004431724 -0.9996211 0.02351361 0.0163837 -0.9995893 0.01616597 0.01642519 -0.9997344 0.006817042 0.02248775 -0.999724 -0.001564443 0.01555722 -0.9998778 -0.004152536 0.01617532 -0.9998607 -0.008336186 0.008877992 -0.9999259 -0.01681244 0.06629043 -0.9976588 -0.02485889 0.008077263 -0.9996584 -0.04309314 0.03444266 -0.9984773 -0.02971774 -0.00566858 -0.9995422 -0.01698082 -0.01186954 -0.9997854 -0.01703393 -0.01537507 -0.9997367 -0.002477884 -0.01455575 -0.9998911 -0.02236926 -0.03722769 -0.9990565 0.01100718 -0.02780169 -0.999553 0.008636832 -0.03508329 -0.9993471 -0.4664978 -0.8845106 -0.004569768 -0.8355181 -0.5494627 7.18241e-4 -0.479065 -0.8777722 -0.003598332 -0.9205576 -0.3905353 -0.007489562 -0.9960082 -0.08924394 0.001769721 -0.9664419 0.2567739 -0.007570028 -0.8743607 0.4852593 0.004104316 -0.606676 0.7949202 -0.006795346 -0.4597898 0.8880266 0.001510441 0.03882789 0.9992334 -0.005005717 0.003373324 0.9999913 -0.002470552 0.5979201 0.8015528 -0.002180337 0.5958998 0.8030553 -0.002360165 0.9570097 0.2900525 -0.001441955 0.9629444 0.2697004 9.71698e-5 0.9229787 -0.3848452 -0.002170205 0.930708 -0.3657492 -0.003214716 0.7715039 -0.6361562 -0.009329617 0.5443303 -0.8388654 0.003085076 0.1788249 -0.9838688 -0.004891514 0.08733302 -0.9961792 5.45934e-5 0.03326678 0.1206408 -0.9921388 0.04489099 -0.07610166 -0.996089 -1.40416e-4 -1.65685e-4 -1 0.003881633 -0.002614796 -0.9999892 -0.1680132 -0.9854488 -0.02573817 -0.7169617 -0.6966164 0.02629983 -0.7422554 -0.6701154 0.001533746 -0.9819724 -0.1873151 -0.02536422 -0.9984154 -0.01107847 0.05517303 -0.9500961 0.3086982 -0.04497528 -0.7363625 0.6753845 0.04032647 -0.6845471 0.7289684 -6.82769e-4 -0.2486175 0.9682695 -0.02536869 -0.07144272 0.9958593 0.0562157 0.289807 0.9553173 -0.05814421 0.5991644 0.7988077 0.05392986 0.8195653 0.571219 -0.04496341 0.9397473 0.3396288 0.03908085 0.998139 0.01957935 -0.05775052 0.9345391 -0.3491252 0.06890851 0.7961665 -0.6026679 -0.0539481 0.4806813 -0.8762374 0.03396731 0.3680631 -0.9296137 -0.01865905 -0.0876649 -0.9959775 0.01854211 -0.06709772 0.9531695 0.2948998 -0.1632165 0.467802 0.8686321 -0.6948298 0.6340836 0.3393371 -0.4573868 0.2406778 0.8560792 -0.9530228 -0.008650183 0.3027752 -0.4771347 -0.1335225 0.8686279 -0.6764338 -0.6582528 0.3303642 -0.2234908 -0.4027873 0.887589 -0.08403718 -0.9575223 0.2758421 0.2115494 -0.4847456 0.8486863 0.3367553 -0.6152116 0.7128188 0.645261 -0.2699219 0.714689 0.7474224 -0.2792262 0.6028204 0.7617526 0.2785365 0.5849363 0.4993063 0.6641384 0.5564292 0.2174615 0.4323586 0.8750867 0.1518577 -0.8367372 -0.5261276 0.3873568 -0.518333 -0.762421 0.5802419 -0.04441308 -0.8132324 0.8128311 0.2438617 -0.5289964 0.3892738 0.4581221 -0.7991183 0.406859 0.5440291 -0.7338243 9.67681e-4 0.8129979 -0.5822658 -0.1723011 0.4816335 -0.8592681 -0.502555 0.6585478 -0.560137 -0.7531006 0.2001683 -0.6267156 -0.4698948 -0.01731961 -0.8825525 -0.7670422 -0.3283469 -0.551212 -0.3640506 -0.6849411 -0.6311283 -0.1395605 -0.4992183 -0.8551631 0.5107163 -0.8409368 0.178869 0.2763261 0.4573781 0.845251 0.5338395 0.02241104 0.8452889 0.2763698 -0.4526789 0.8477627 -0.2551441 -0.4655383 0.8474525 -0.5360442 0.006724774 0.8441632 -0.2873387 0.4490945 0.8460205 0.4990361 -0.8662059 0.02550268 0.5210362 -0.8534912 0.008607804 0.5404638 -0.8410619 0.02266746 0.9999151 0.01293867 0.001556813 0.9986129 0.04751437 0.02268666 0.4896693 0.8715164 0.02613788 0.488056 0.8723568 0.02819639 -0.3791996 0.9229888 -0.06557124 -0.6142351 0.7868032 -0.06046593 -0.509499 0.8602207 0.02076888 -0.9997705 -0.0140146 0.01621025 -0.5006356 -0.8652819 0.02551859 -0.4788044 -0.877878 0.008759915 -0.458225 -0.8885331 0.02321463 -0.3024067 -0.5379933 -0.7868376 -0.3211583 -0.8809947 -0.347427 -0.007316172 -0.6545345 -0.7559969 0.3188351 -0.8459572 -0.427435 -0.3984407 -0.2742016 -0.8752477 -0.9401632 -0.1367198 -0.3120914 -0.8490563 -0.0812332 -0.5220197 -0.5574961 0.2527342 -0.7907741 -0.6798045 0.4880763 -0.5474007 -0.3096414 0.5957022 -0.7411215 -0.3110281 0.7227156 -0.6172063 0.01772749 0.5594019 -0.828707 0.2188958 0.8185089 -0.5311573 0.293338 0.4579735 -0.8391742 0.7218187 0.4408398 -0.5335149 0.6347925 0.1995812 -0.7464623 0.8597335 0.06405013 -0.5067109 0.7788417 -0.4176002 -0.4679914 0.6970888 -0.304143 -0.6492798 0.3915048 -0.5362787 -0.7477495 -0.01586627 -0.04359525 0.9989233 0.02750992 -0.06600111 0.9974403 0.05295246 -0.01391297 0.9985001 0.04378002 -0.01904904 0.9988596 0.03030592 0.02612733 0.9991992 0.01362508 0.005203604 0.9998937 0.006750643 0.01231414 0.9999015 0.006798744 0.01113563 0.9999149 -0.006045937 0.0127809 0.9999001 -0.006386101 0.01051443 0.9999244 -0.01484429 0.005456745 0.999875 -0.009968519 -2.21164e-4 0.9999503 -0.01167708 -0.005619287 0.9999161 -0.02980506 0.003745496 0.9995487 -0.0192117 -0.04352575 0.9988676 -0.01865333 0.01543289 -0.999707 -0.02097272 0.02261984 -0.9995241 -0.04011505 -0.002524316 -0.9991919 -0.01454275 -0.0172103 -0.9997462 -0.01386159 -0.01354479 -0.9998122 -0.004066646 -0.01583927 -0.9998663 -0.01199507 -0.02254307 -0.9996739 0.009103596 -0.03546214 -0.9993296 0.02334427 -0.02485865 -0.9994184 0.02289527 -0.01849079 -0.9995669 0.03416848 -0.01110202 -0.9993544 0.02926629 0.005582749 -0.9995561 0.03111022 0.004677772 -0.9995051 0.02478212 0.02050173 -0.9994826 -0.004755139 0.02223861 -0.9997414 2.05431e-4 5.18695e-4 -0.9999999 -8.85743e-5 5.46092e-4 -1 0.005530416 0.01783704 -0.9998256 0.4665051 0.8845067 -0.004569828 0.8340148 0.5517417 6.93687e-4 0.4790696 0.8777697 -0.003598332 0.9205633 0.3905401 -0.006456255 0.9866254 0.1629904 0.002135455 0.9544032 -0.298488 -0.004438281 0.9664686 -0.2567819 -0.001261174 0.611735 -0.7910621 -0.001070916 0.6066957 -0.7949328 -0.001531124 0.02760297 -0.9996187 -8.14482e-4 -0.003371417 -0.9999896 -0.003067255 -0.616541 -0.7873207 -0.001838445 -0.5959023 -0.8030486 -0.003670215 -0.9570111 -0.2900404 -0.002548277 -0.9263957 -0.376445 -0.008961677 -0.9990973 0.04240089 0.002590835 -0.9191657 0.3937835 -0.008303284 -0.848066 0.5298889 0.001362025 -0.4867718 0.8735247 0.002790808 -0.2486093 0.9685649 -0.008691728 -0.08733278 0.9961793 5.45933e-5 -0.001128017 -0.005189836 -0.9999859 -0.00234425 0.001705229 -0.9999958 -0.001203954 -0.00494486 -0.9999871 8.38293e-4 0.005367517 -0.9999853 0.3677491 0.9288294 -0.04512941 0.7165086 0.6962368 0.04324209 0.7705137 0.6374232 -6.86006e-4 0.9819695 0.1873304 -0.02536565 0.9984154 0.01107639 0.05517297 0.9500939 -0.3087055 -0.04497522 0.7363622 -0.6753849 0.04032373 0.6845511 -0.7289646 -6.83775e-4 0.2486156 -0.9682701 -0.02536451 0.07144314 -0.9958593 0.056216 -0.2484465 -0.9676095 -0.04479163 -0.599704 -0.7996143 0.03118258 -0.7149516 -0.69827 -0.03554344 -0.9393606 -0.3395392 0.04811483 -0.9954358 -0.06262087 -0.07201534 -0.9345394 0.3491237 0.06891119 -0.7685071 0.6357759 -0.07201445 -0.4802204 0.8754307 0.05486059 -0.1679044 0.984804 -0.04437762 0.08758676 0.9953281 0.0406264 0.0670979 -0.9531692 0.2949008 0.166589 -0.4221191 0.8911024 0.7324658 -0.671 0.1151217 0.4550678 -0.1319367 0.8806282 0.9470679 0.008437752 0.3209226 0.4575436 0.2406901 0.8559919 0.6663166 0.6485551 0.3679653 0.2194361 0.4456393 0.8679018 0.08403682 0.9575226 0.2758409 -0.2115521 0.4847517 0.8486822 -0.336755 0.6152021 0.7128272 -0.6452541 0.2699224 0.714695 -0.7474237 0.2792207 0.6028214 -0.5412341 -0.1290969 0.830903 -0.7617469 -0.2785296 0.584947 -0.4993042 -0.6641386 0.5564308 -0.2174602 -0.4323574 0.8750876 -0.2358281 0.9030759 -0.3589417 -0.4855198 0.3120071 -0.816653 -0.7150451 0.3121012 -0.6255425 -0.645538 -0.1782802 -0.7426285 -0.66723 -0.1988319 -0.7178232 -0.4812707 -0.6451394 -0.5934423 -0.1596501 -0.4852685 -0.8596665 -0.001090705 -0.8288793 -0.5594265 0.4719561 -0.6184637 -0.6282994 0.4140581 -0.3753768 -0.8292456 0.7913764 -0.2103316 -0.574007 0.5523809 0.0888459 -0.8288438 0.7648744 0.3274433 -0.5547507 0.363543 0.6839603 -0.6324831 0.1011208 0.4652426 -0.8793885 -0.5107138 0.8409385 0.1788681 -0.98363 -0.02182388 0.1788743 0.4729202 0.8627583 0.1788708 -0.2763246 -0.4573787 0.8452511 -0.5338369 -0.02241086 0.8452905 -0.2763648 0.4526765 0.8477657 0.255145 0.4655382 0.8474522 0.5360429 -0.006730318 0.844164 0.2873417 -0.4490936 0.8460198 -0.4990423 0.8662022 0.02550303 -0.5210326 0.8534936 0.00858885 -0.5404618 0.8410633 0.0226674 -0.999922 0.002896308 0.01214981 -0.9999151 -0.01293611 0.001556932 -0.9986129 -0.04751425 0.0226866 -0.4896683 -0.871517 0.02613782 -0.4880542 -0.8723579 0.0281952 0.3791996 -0.9229888 -0.06556928 0.6142338 -0.7868041 -0.06046599 0.5094975 -0.8602215 0.02076882 0.9997704 0.01397007 0.01625376 0.9997705 0.01401013 0.01621025 0.5006321 0.865284 0.02551841 0.4788056 0.8778774 0.008759915 0.4582232 0.888534 0.02321451 -0.07659423 -0.982732 -0.1684377 0.2789286 0.3369247 -0.8992668 -0.0932151 0.2639789 -0.9600137 0.3255875 0.5813038 -0.7457069 0.01656764 0.595269 -0.8033558 -0.2405519 0.9262053 -0.2903078 0.594877 0.7771545 -0.2053104 0.5592069 0.4636422 -0.687258 0.8949376 0.1013936 -0.4345182 0.8203652 0.1384075 -0.5548371 0.6392883 -0.1987839 -0.7428293 0.7254355 -0.6348451 -0.2659231 0.4380568 -0.5655909 -0.6987226 -0.03017318 -0.8759411 -0.4814738 -0.2475421 -0.3814735 -0.8906183 -0.890417 -0.3564081 -0.2830739 -0.8923498 -0.356106 -0.2773092 -0.6305606 -0.05389887 -0.7742662 -0.5366208 0.2498918 -0.8059729 -0.7894088 0.5282814 -0.3126543 -0.3611448 0.4392195 -0.8225939 -0.9814795 0.1898933 -0.02526843 -0.9834348 0.1810553 -0.008662223 -0.9199328 -0.3840353 0.07899874 -0.8854127 -0.459096 -0.07263088 -0.5482122 -0.8360295 0.02276462 -0.5367626 -0.842455 0.04642957 0.02270203 -0.9983984 -0.05182003 0.07746571 -0.9948735 0.06500667 0.6897429 -0.7211286 -0.06502485 0.7030866 -0.7105136 -0.02897697 0.9581988 -0.278367 0.06608384 0.9791266 -0.192211 -0.06607496 0.9506825 0.3088083 0.02898478 0.9631166 0.251926 -0.09455072 0.736745 0.6602352 0.1459324 0.5465037 0.8237859 -0.1507003 0.2218477 0.9634584 0.1501051 0.07342523 0.9945719 -0.07372593 -0.4482966 0.893844 0.00856316 -0.4581405 0.8884044 0.02906674 -0.7891024 0.6138758 -0.02177208 -0.8094146 0.586932 0.01894211 -0.7619474 0.6466243 -0.03624063 -0.5621373 0.8265782 0.02775239 -0.5110188 0.859524 -0.008857131 -0.232962 0.9724456 0.008857309 -0.1733488 0.9844694 -0.02775269 0.09535384 0.9947835 0.03624254 0.2918131 0.9552062 -0.04925644 0.4133376 0.9102509 0.02440249 0.7045282 0.7096163 -0.009208381 0.7120043 0.7019194 -0.01895409 0.9395105 0.3421042 0.01687765 0.9512954 0.3081086 -0.01030707 0.9998778 -0.01288646 0.008859872 0.9990655 -0.04230439 -0.008858323 0.9415152 -0.3368541 0.008860826 0.9311938 -0.364417 -0.008859276 0.7653629 -0.6435166 0.01030069 0.7624322 -0.6470319 0.006846845 0.5108849 -0.8593026 -0.02440619 0.4183295 -0.9076219 0.03497391 0.2041808 -0.9785751 -0.02647882 0.04488968 -0.9983383 0.03613364 -0.1245825 -0.9915472 -0.03624147 -0.3845251 -0.9226973 0.02775281 -0.4400621 -0.8979237 -0.008858621 -0.7045177 -0.7096116 0.01030641 -0.7077872 -0.7063926 0.00684297 -0.9118033 -0.40972 -0.02728724 -0.9392931 -0.3420293 0.02728849 -0.9992458 0.03772515 -0.009206235 -0.999805 0.01747155 0.009205341 -0.9309529 0.3643227 -0.02440828 -0.8751836 0.4812771 0.04925674 -0.9742258 0.2221747 0.03901898 -0.9846988 0.1732128 -0.01912266 -0.9427877 -0.3328452 0.01912111 -0.9244021 -0.379418 -0.03902244 -0.5123505 -0.8578892 0.03902769 -0.4690152 -0.882983 -0.01913207 -0.00904715 -0.9998211 0.01661282 0.03676259 -0.9989539 -0.02719676 0.5759848 -0.8167492 0.0340929 0.6212652 -0.7824311 -0.04279088 0.986631 -0.1561064 0.04679721 0.9942381 -0.09644031 -0.04679703 0.7977131 0.6015155 0.04281383 0.7624931 0.6460969 -0.03410679 0.2215604 0.9745503 0.0341016 0.165755 0.9852374 -0.04280853 -0.5441759 0.8376647 0.04680401 -0.5936014 0.8033967 -0.04681205 -0.9991965 0.03842544 0.01138967 -0.9998468 -0.01329272 -0.01138961 -0.861348 -0.5078876 0.01139414 -0.833944 -0.5517318 -0.01139014 -0.4100619 -0.9119611 0.01327693 -0.351504 -0.9359341 -0.02173882 0.3278661 -0.9444741 0.02173912 0.387011 -0.9219796 -0.01327717 0.8198077 -0.5725259 0.01139003 0.848305 -0.5293855 -0.01138603 0.9991968 -0.03841817 0.01139187 0.9998468 0.01329296 -0.01138949 0.8380182 0.5454807 0.01327705 0.8339619 0.5517463 0.009144544 0.4030956 0.9146603 -0.03017669 0.2346306 0.9710654 0.04450249 -0.2101355 0.9766589 -0.04450207 -0.3799839 0.9245008 0.03017628 -0.8198202 0.572548 -0.009148538 -0.8240385 0.5663784 -0.01327687 0.7058104 0.707161 -0.04189372 0.6431426 0.761142 0.08384776 0.3001502 0.9484006 -0.1022071 0.1279593 0.9864972 0.102225 -0.2593405 0.9622539 -0.08252233 -0.3387167 0.9399793 0.04135113 -0.7643466 0.6431318 -0.0464304 -0.7963792 0.6030128 0.04643338 -0.9969731 0.05795955 -0.05182147 -0.9978799 0.003090441 0.06501084 -0.7526045 -0.6546289 -0.07104635 -0.7132381 -0.6973106 0.07106024 -0.1087633 -0.9922994 -0.05926614 -0.06067031 -0.9977344 0.02907472 0.3919476 -0.919641 -0.02524954 0.4634838 -0.8807986 0.09683382 0.8328783 -0.5277386 -0.1667504 0.9166011 -0.3633713 0.1667451 0.9781086 0.1747013 -0.1130622 0.9653258 0.2581697 0.03866267 0.9415152 0.3368541 -0.008859694 0.9997944 0.01746851 0.01030731 0.9996863 -0.01851201 -0.0168789 0.9120109 -0.4098187 0.01687765 0.8967595 -0.4423984 -0.0103048 0.689996 -0.7237399 0.01030355 0.6866894 -0.7269187 0.006850898 0.4133403 -0.9102496 -0.02440267 0.3160336 -0.9481031 0.03497445 0.06407362 -0.9973322 -0.03497439 -0.04032409 -0.9988886 0.02440601 -0.3856236 -0.9226104 -0.009205281 -0.3668466 -0.9302359 0.009202241 -0.6675481 -0.7441665 -0.02440696 -0.741302 -0.6702601 0.03496903 -0.8875927 -0.4592999 -0.03496831 -0.9309535 -0.3643211 0.02440816 -0.999805 -0.01747173 -0.0092054 -0.9997977 -0.006735563 -0.01895457 -0.9120119 0.4098163 0.01687765 -0.8967573 0.4424028 -0.01030606 -0.7077737 0.7063838 0.008860766 -0.6866816 0.7269044 -0.008857965 -0.4400621 0.8979237 0.008860886 -0.4134486 0.9104843 -0.008864581 -0.1246595 0.9921602 0.008853375 -0.09540998 0.9953987 -0.008854329 0.2042459 0.9788796 0.008853733 0.2329645 0.9724449 -0.008858323 0.511017 0.8595249 0.008860766 0.5360883 0.8441154 -0.008860826 0.7624203 0.6470217 0.008857309 0.7811249 0.6243121 -0.008856534 0.9311944 0.3644154 0.008860826 0.8478152 0.5300316 0.01661962 0.8224443 0.5681948 -0.0272091 0.3788602 0.9248254 0.03410172 0.3255761 0.9445467 -0.04279994 -0.3989589 0.9157736 0.04680395 -0.4195469 0.9076487 0.01242893 -0.9047949 0.4222627 -0.05514043 -0.9250581 0.3796906 0.01012706 -0.988276 -0.1391122 0.06291788 -0.9556732 -0.2840842 -0.07736313 -0.7450336 -0.6648045 0.05440557 -0.686333 -0.7267785 -0.02720868 -0.2436385 -0.9694843 0.0272153 -0.1216843 -0.9884249 -0.0906049 0.2409278 -0.9653689 0.1000831 0.5651 -0.8205222 -0.08605462 0.7588276 -0.6429956 0.1036218 0.8999805 -0.4265934 -0.08973991 0.9975248 0.02933418 0.06390541 0.9933977 0.1135123 -0.01661628 0.8483063 0.5293834 0.01139008 0.8198077 0.5725259 -0.01139003 0.3870133 0.9219786 0.01327723 0.327868 0.9444733 -0.02174544 -0.3515053 0.9359334 0.02174472 -0.4100596 0.9119623 -0.01327049 -0.8339415 0.5517354 0.0113902 -0.8613514 0.5078818 -0.0113942 -0.9994326 -0.03096085 0.01327276 -0.9953258 -0.0940957 -0.02174109 -0.7053332 -0.7085427 0.0217384 -0.6592003 -0.7518503 -0.01327687 -0.1554506 -0.987778 0.0113945 -0.104173 -0.9944941 -0.01138269 0.4032539 -0.9150173 0.01139396 0.4500113 -0.8929502 -0.01139414 0.8339451 -0.5517299 0.01139026 0.8613486 -0.5078866 -0.01139396 0.9998468 -0.01329272 0.01138973 0.9991966 0.03842604 -0.0113902 0.9814795 -0.1898933 -0.02526843 0.9834348 -0.1810553 -0.008662223 0.9199328 0.3840353 0.07899874 0.8854127 0.459096 -0.07263088 0.5482122 0.8360295 0.02276462 0.5367626 0.842455 0.04642957 -0.02270203 0.9983984 -0.05182003 -0.07746571 0.9948735 0.06500667 -0.6897429 0.7211286 -0.06502485 -0.7030866 0.7105136 -0.02897697 -0.9581988 0.278367 0.06608384 -0.9791266 0.192211 -0.06607496 -0.9506825 -0.3088083 0.02898478 -0.9631166 -0.251926 -0.09455072 -0.736745 -0.6602352 0.1459324 -0.5465037 -0.8237859 -0.1507003 -0.2218477 -0.9634584 0.1501051 -0.07342523 -0.9945719 -0.07372593 0.4482966 -0.893844 0.00856316 0.4581405 -0.8884044 0.02906674 0.7891024 -0.6138758 -0.02177208 0.8094146 -0.586932 0.01894211 0.7619474 -0.6466243 -0.03624063 0.5621373 -0.8265782 0.02775239 0.5110188 -0.859524 -0.008857131 0.232962 -0.9724456 0.008857309 0.1733488 -0.9844694 -0.02775269 -0.09535384 -0.9947835 0.03624254 -0.2918131 -0.9552062 -0.04925644 -0.4133376 -0.9102509 0.02440249 -0.7045282 -0.7096163 -0.009208381 -0.7120043 -0.7019194 -0.01895409 -0.9395105 -0.3421042 0.01687765 -0.9512954 -0.3081086 -0.01030707 -0.9998778 0.01288646 0.008859872 -0.9990655 0.04230439 -0.008858323 -0.9415152 0.3368541 0.008860826 -0.9311938 0.364417 -0.008859276 -0.7653629 0.6435166 0.01030069 -0.7624322 0.6470319 0.006846845 -0.5108849 0.8593026 -0.02440619 -0.4183295 0.9076219 0.03497391 -0.2041808 0.9785751 -0.02647882 -0.04488968 0.9983383 0.03613364 0.1245825 0.9915472 -0.03624147 0.3845251 0.9226973 0.02775281 0.4400621 0.8979237 -0.008858621 0.7045177 0.7096116 0.01030641 0.7077872 0.7063926 0.00684297 0.9118033 0.40972 -0.02728724 0.9392931 0.3420293 0.02728849 0.9992458 -0.03772515 -0.009206235 0.999805 -0.01747155 0.009205341 0.9309529 -0.3643227 -0.02440828 0.8751836 -0.4812771 0.04925674 0.9742258 -0.2221747 0.03901898 0.9846988 -0.1732128 -0.01912266 0.9427877 0.3328452 0.01912111 0.9244021 0.379418 -0.03902244 0.5123505 0.8578892 0.03902769 0.4690152 0.882983 -0.01913207 0.00904715 0.9998211 0.01661282 -0.03676259 0.9989539 -0.02719676 -0.5759848 0.8167492 0.0340929 -0.6212652 0.7824311 -0.04279088 -0.986631 0.1561064 0.04679721 -0.9942381 0.09644031 -0.04679703 -0.7977131 -0.6015155 0.04281383 -0.7624931 -0.6460969 -0.03410679 -0.2215604 -0.9745503 0.0341016 -0.165755 -0.9852374 -0.04280853 0.5441759 -0.8376647 0.04680401 0.5936014 -0.8033967 -0.04681205 0.9991965 -0.03842544 0.01138967 0.9998468 0.01329272 -0.01138961 0.861348 0.5078876 0.01139414 0.833944 0.5517318 -0.01139014 0.4100619 0.9119611 0.01327693 0.351504 0.9359341 -0.02173882 -0.3278661 0.9444741 0.02173912 -0.387011 0.9219796 -0.01327717 -0.8198077 0.5725259 0.01139003 -0.848305 0.5293855 -0.01138603 -0.9991968 0.03841817 0.01139187 -0.9998468 -0.01329296 -0.01138949 -0.8380182 -0.5454807 0.01327705 -0.8339619 -0.5517463 0.009144544 -0.4030956 -0.9146603 -0.03017669 -0.2346306 -0.9710654 0.04450249 0.2101355 -0.9766589 -0.04450207 0.3799839 -0.9245008 0.03017628 0.8198202 -0.572548 -0.009148538 0.8240385 -0.5663784 -0.01327687 0.0275101 -0.06600195 0.9974403 0.05294978 -0.01391327 0.9985002 0.04378241 -0.01904934 0.9988595 0.03030675 0.02612787 0.9991992 0.01362508 0.005203664 0.9998937 0.006750643 0.0123142 0.9999015 0.006798684 0.01113545 0.9999149 -0.004252135 0.01255106 0.9999122 -0.005331993 0.008778214 0.9999473 -0.01268714 0.006540238 0.9998981 -0.01030629 -2.28622e-4 0.999947 -0.01292037 -0.003490865 0.9999105 -0.02630531 0.009987831 0.9996041 -0.02268618 -0.04345303 0.9987979 -0.03053122 0.02311652 -0.9992666 -0.02615106 0.008384287 -0.9996229 -0.03173708 -6.27036e-4 -0.9994961 -0.02717077 -0.004431724 -0.9996211 -0.02351361 -0.0163837 -0.9995893 -0.01616597 -0.01642519 -0.9997344 -0.006817042 -0.02248775 -0.999724 0.001564443 -0.01555722 -0.9998778 0.004152536 -0.01617532 -0.9998607 0.008336186 -0.008877992 -0.9999259 0.01681244 -0.06629043 -0.9976588 0.02485889 -0.008077263 -0.9996584 0.04309314 -0.03444266 -0.9984773 0.02971774 0.00566858 -0.9995422 0.01698082 0.01186954 -0.9997854 0.01703393 0.01537507 -0.9997367 0.002477884 0.01455575 -0.9998911 0.02236926 0.03722769 -0.9990565 -0.01100718 0.02780169 -0.999553 -0.008636832 0.03508329 -0.9993471 0.4664978 0.8845106 -0.004569768 0.8355181 0.5494627 7.18241e-4 0.479065 0.8777722 -0.003598332 0.9205576 0.3905353 -0.007489562 0.9960082 0.08924394 0.001769721 0.9664419 -0.2567739 -0.007570028 0.8743607 -0.4852593 0.004104316 0.606676 -0.7949202 -0.006795346 0.4597898 -0.8880266 0.001510441 -0.03882789 -0.9992334 -0.005005717 -0.003373324 -0.9999913 -0.002470552 -0.5979201 -0.8015528 -0.002180337 -0.5958998 -0.8030553 -0.002360165 -0.9570097 -0.2900525 -0.001441955 -0.9629444 -0.2697004 9.71698e-5 -0.9229787 0.3848452 -0.002170205 -0.930708 0.3657492 -0.003214716 -0.7715039 0.6361562 -0.009329617 -0.5443303 0.8388654 0.003085076 -0.1788249 0.9838688 -0.004891514 -0.08733302 0.9961792 5.45934e-5 -0.03326678 -0.1206408 -0.9921388 -0.04489099 0.07610166 -0.996089 1.40416e-4 1.65685e-4 -1 -0.003881633 0.002614796 -0.9999892 0.1680132 0.9854488 -0.02573817 0.7169617 0.6966164 0.02629983 0.7422554 0.6701154 0.001533746 0.9819724 0.1873151 -0.02536422 0.9984154 0.01107847 0.05517303 0.9500961 -0.3086982 -0.04497528 0.7363625 -0.6753845 0.04032647 0.6845471 -0.7289684 -6.82769e-4 0.2486175 -0.9682695 -0.02536869 0.07144272 -0.9958593 0.0562157 -0.289807 -0.9553173 -0.05814421 -0.5991644 -0.7988077 0.05392986 -0.8195653 -0.571219 -0.04496341 -0.9397473 -0.3396288 0.03908085 -0.998139 -0.01957935 -0.05775052 -0.9345391 0.3491252 0.06890851 -0.7961665 0.6026679 -0.0539481 -0.4806813 0.8762374 0.03396731 -0.3680631 0.9296137 -0.01865905 0.0876649 0.9959775 0.01854211 0.06709772 -0.9531695 0.2948998 0.1632165 -0.467802 0.8686321 0.6948298 -0.6340836 0.3393371 0.4573868 -0.2406778 0.8560792 0.9530228 0.008650183 0.3027752 0.4771347 0.1335225 0.8686279 0.6764338 0.6582528 0.3303642 0.2234908 0.4027873 0.887589 0.08403718 0.9575223 0.2758421 -0.2115494 0.4847456 0.8486863 -0.3367553 0.6152116 0.7128188 -0.645261 0.2699219 0.714689 -0.7474224 0.2792262 0.6028204 -0.7617526 -0.2785365 0.5849363 -0.4993063 -0.6641384 0.5564292 -0.2174615 -0.4323586 0.8750867 -0.1518577 0.8367372 -0.5261276 -0.3873568 0.518333 -0.762421 -0.5802419 0.04441308 -0.8132324 -0.8128311 -0.2438617 -0.5289964 -0.3892738 -0.4581221 -0.7991183 -0.406859 -0.5440291 -0.7338243 -9.67681e-4 -0.8129979 -0.5822658 0.1723011 -0.4816335 -0.8592681 0.502555 -0.6585478 -0.560137 0.7531006 -0.2001683 -0.6267156 0.4698948 0.01731961 -0.8825525 0.7670422 0.3283469 -0.551212 0.3640506 0.6849411 -0.6311283 0.1395605 0.4992183 -0.8551631 -0.5107163 0.8409368 0.178869 -0.2763261 -0.4573781 0.845251 -0.5338395 -0.02241104 0.8452889 -0.2763698 0.4526789 0.8477627 0.2551441 0.4655383 0.8474525 0.5360442 -0.006724774 0.8441632 0.2873387 -0.4490945 0.8460205 -0.4990361 0.8662059 0.02550268 -0.5210362 0.8534912 0.008607804 -0.5404638 0.8410619 0.02266746 -0.9999151 -0.01293867 0.001556813 -0.9986129 -0.04751437 0.02268666 -0.4896693 -0.8715164 0.02613788 -0.488056 -0.8723568 0.02819639 0.3791996 -0.9229888 -0.06557124 0.6142351 -0.7868032 -0.06046593 0.509499 -0.8602207 0.02076888 0.9997705 0.0140146 0.01621025 0.5006356 0.8652819 0.02551859 0.4788044 0.877878 0.008759915 0.458225 0.8885331 0.02321463 0.3024067 0.5379933 -0.7868376 0.3211583 0.8809947 -0.347427 0.007316172 0.6545345 -0.7559969 -0.3188351 0.8459572 -0.427435 0.3984407 0.2742016 -0.8752477 0.9401632 0.1367198 -0.3120914 0.8490563 0.0812332 -0.5220197 0.5574961 -0.2527342 -0.7907741 0.6798045 -0.4880763 -0.5474007 0.3096414 -0.5957022 -0.7411215 0.3110281 -0.7227156 -0.6172063 -0.01772749 -0.5594019 -0.828707 -0.2188958 -0.8185089 -0.5311573 -0.293338 -0.4579735 -0.8391742 -0.7218187 -0.4408398 -0.5335149 -0.6347925 -0.1995812 -0.7464623 -0.8597335 -0.06405013 -0.5067109 -0.7788417 0.4176002 -0.4679914 -0.6970888 0.304143 -0.6492798 -0.3915048 0.5362787 -0.7477495 0.5049892 0.8631258 2.53603e-5 0.5018933 0.8649296 -3.686e-5 0.4928305 0.8701052 -0.005934536 0.4999989 0.8660255 0.001008689 -0.00671631 0.3978548 -0.9174239 -0.4937196 0.8696213 -1.64147e-5 -0.4849187 0.8745592 -3.62925e-5 -0.5346438 0.8446882 -0.02564734 -0.4999824 0.8659948 0.008411705 -0.4390805 0.468169 -0.7668286 -0.3290719 0.2046304 -0.9218666 -0.999984 -0.005679547 0 -0.9999895 0.002967715 -0.003495752 -0.9999698 -0.007725119 8.6873e-4 -0.999987 0 -0.005115866 -0.4269277 -0.1671512 -0.8887032 -0.6015163 -0.1237216 -0.789222 -0.4012272 -0.451646 -0.7968895 -0.3557684 -0.2839872 -0.890382 -0.5049841 -0.8631287 2.43661e-5 -0.5072436 -0.8618021 0.001134335 -0.4999988 -0.8660246 0.001633822 -0.4908083 -0.8711624 -0.01353871 0.006718754 -0.3978466 -0.9174275 0.4849351 -0.8745502 -2.41956e-5 0.5072581 -0.8617932 0.001371145 0.4999807 -0.8659957 0.008413732 0.4795147 -0.7047241 -0.5229049 0.3596314 -0.3081875 -0.8807303 0.4353294 -0.1849803 -0.8810622 0.9999819 -0.00601232 4.45792e-5 0.9987633 0.04954671 -0.004130303 0.9999666 -0.008134603 9.49175e-4 0.9997126 0 -0.02397418 0.9864524 -0.1320821 0.09729343 0.345916 0.2043393 -0.9157443 -0.004238128 -2.51167e-4 -0.999991 0.004386723 2.63535e-4 -0.9999904 -0.009444653 0.02061164 -0.9997431 0.006166577 -0.007704257 -0.9999514 0.01161825 0.01981711 -0.9997361 -8.2216e-4 6.78303e-4 -0.9999995 -0.001522362 3.82156e-4 -0.9999989 -0.00197792 -0.008974611 -0.9999579 -0.001046061 3.90132e-4 -0.9999995 -9.61191e-4 5.54811e-4 -0.9999995 -0.003144085 -0.004417955 -0.9999854 -0.01037782 0.0186119 -0.999773 0.001083135 6.25246e-4 -0.9999992 0.001135706 4.23692e-4 -0.9999994 2.39179e-4 -0.009973466 -0.9999503 0.01154506 -0.0197038 -0.9997392 0.002751767 0.003616511 -0.9999897 -0.007056415 0.005881726 -0.9999579 9.60434e-4 7.9269e-4 -0.9999992 0.004926979 0.004294991 -0.9999787 -0.0082165 -0.0109499 -0.9999064 0.007582306 -0.008515894 -0.999935 -0.004924952 -0.004297792 -0.9999787 0.01709395 0.01448571 -0.999749 -0.003261148 -0.002904951 -0.9999905 -0.8710874 -0.07301056 -0.4856709 -0.4066545 -0.4485898 -0.7958641 -0.4146721 -0.8464213 -0.334093 0.03928077 -0.5415954 -0.8397212 0.5661487 -0.7593677 -0.3206812 0.5064833 -0.4227907 -0.7514804 0.7034139 -0.01924264 -0.71052 0.8710824 0.07301872 -0.4856787 0.4066433 0.4485983 -0.7958648 0.4146714 0.8464297 -0.3340729 -0.03928065 0.5416451 -0.839689 -0.5661327 0.7593603 -0.3207268 -0.5064761 0.4227948 -0.751483 -0.70342 0.01923835 -0.7105141 -0.9996066 0.02483195 0.01304334 -0.7654134 0.643287 0.01801526 -0.7048034 0.709032 -0.02293246 -0.1729562 0.9849217 -0.003928124 -0.07632869 0.9964275 0.03614306 0.4801529 0.8761731 -0.0421198 0.6729665 0.7376009 0.05532652 0.9913883 0.115933 -0.06090021 0.9996061 -0.02484738 0.01305115 0.7654215 -0.6432775 0.01800644 0.7048168 -0.7090185 -0.02293664 0.172942 -0.9849241 -0.003939747 0.0763266 -0.9964268 0.03616666 -0.4801402 -0.8761799 -0.04212427 -0.672976 -0.737592 0.05533009 -0.9913892 -0.1159238 -0.06090295 0.8332586 -0.3402817 0.435762 0.4071902 -0.4126908 0.8147898 0.2435996 -0.7982449 0.5508759 0.1242281 -0.6967533 0.7064716 -0.3509548 -0.6575164 0.6667106 -0.3503088 -0.6403852 0.6835135 -0.6956671 -0.08119016 0.7137615 -0.7465391 -0.1102601 0.6561419 -0.5229169 0.5681544 0.63542 -0.5887799 0.5944293 0.5477154 -0.1083644 0.6051413 0.7887087 0.1805624 0.878403 0.4424992 0.2848523 0.5211021 0.8045569 0.7978688 0.3776704 0.4698622 0.5456994 0.06363785 0.8355612 0.001493811 -7.41683e-4 0.9999987 5.508e-4 0 1 0.001553118 7.52199e-4 0.9999985 -3.21214e-4 -5.56359e-4 0.9999998 -2.54912e-4 -0.002931356 0.9999957 6.64355e-5 0.001234412 0.9999992 9.71868e-4 0.001683294 0.9999982 9.40455e-4 -0.001628875 0.9999983 -0.001016139 -6.19618e-4 0.9999994 -0.001529395 0 0.9999989 -0.002219378 -4.13166e-4 0.9999974 -8.4894e-4 0.001261055 0.9999989 -8.40887e-4 0.001456439 0.9999986 0.02815395 0.003259181 -0.9995983 0.00193417 0.03148341 -0.9995024 0.00818336 -0.005404889 -0.9999519 0.008735895 -0.007304728 -0.9999352 -0.02769291 -0.01327252 -0.9995284 -0.005374133 -0.02804797 -0.9995921 6.84637e-4 0.008912384 -0.9999601 -0.0567528 -0.01991277 -0.9981898 -0.02594023 -0.04161679 -0.9987969 0.02429348 -0.01663035 -0.9995666 0.02481657 -0.0204128 -0.9994837 0.03116381 -0.007802724 -0.999484 0.02349007 0.01085162 -0.9996652 0.02840089 -0.01208466 -0.9995236 0.02295696 0.03251761 -0.9992074 0.03001868 0.02250987 -0.9992959 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.8468531 0.5317228 0.01052635 -0.8880259 0.4597935 -2.31999e-4 -0.999875 0.005589842 0.01479727 -0.9945257 -0.1044553 0.002804219 -0.9256431 -0.3782295 0.0112822 -0.7955976 -0.6057669 -0.008424639 -0.5688161 -0.8223606 0.01309287 -0.3589578 -0.9333481 -0.003277957 -0.06756031 -0.9975477 0.01828676 0.185137 -0.9827123 0.001046597 0.4229067 -0.9059783 0.01879709 0.6739563 -0.7387663 -0.002709686 0.8650959 -0.5012637 0.01853996 0.9616293 -0.2743453 -0.001915693 0.999518 -0.02843242 0.01246821 0.9622789 0.2719445 -0.008102774 0.8421865 0.5389958 0.01433384 0.9904055 0.1350664 0.0292266 0.6958849 0.7177799 0.02315914 0.4950312 0.8688505 -0.006572484 0.173144 0.9848249 0.0118795 0.2002131 0.9796521 0.01402044 -0.3319535 0.9430661 0.0208131 -0.4567396 0.8896005 1.41264e-4 0.0162853 0.02626669 0.9995224 -0.01342052 0.01373374 0.9998157 -0.009685516 0.01414614 0.9998531 0.03138786 -0.002099692 0.9995052 0.1135795 -0.09032601 0.9894145 -0.02664577 -0.01222312 0.9995703 -0.06276941 -0.06974953 0.9955878 -0.6975618 0.7150228 0.04636955 -0.7474543 0.664298 0.004518091 -0.9852502 0.1697956 -0.02125048 -0.9979642 0.05649745 0.02958869 -0.9527825 -0.3027936 -0.02284145 -0.8830695 -0.4686027 0.02449148 -0.7412731 -0.6692739 -0.05086076 -0.4173375 -0.9087452 0.003391087 -0.3997133 -0.9165372 0.01373881 0.04459756 -0.9989589 -0.009605705 0.0979529 -0.9950955 0.01379328 0.5510576 -0.8343873 -0.0115565 0.6489614 -0.7600337 0.03461062 0.8282982 -0.5586023 -0.04342567 0.987092 -0.1600852 -0.004729449 0.987557 -0.1572282 -0.003253519 0.9876819 0.1551671 -0.02018934 0.9255964 0.3767225 0.03676116 0.8198504 0.5712242 -0.03934842 0.4944959 0.869162 -0.005587697 0.4904305 0.8714748 -0.003126859 0.1225526 0.992286 -0.0186944 -0.03180515 0.9989225 0.03379929 -0.3249847 0.9448313 -0.04097461 0.1476825 -0.3480777 -0.9257602 0.04334884 -0.9735672 -0.2242498 -0.2059832 -0.5772596 -0.7901534 -0.4093491 -0.05490279 -0.9107245 -0.9442676 0.1625903 -0.2862225 -0.3944987 0.3298721 -0.8576452 -0.4620056 0.4141678 -0.7842296 -0.3030291 0.8773521 -0.3720573 -0.02653574 0.4289119 -0.9029566 0.3661777 0.1715644 -0.9145927 0.1798651 0.4300237 0.8847193 0.4415694 0.1073029 0.8907876 -0.3235501 -0.2957986 0.8987873 0.07531976 0.9803338 -0.1824079 0.8866566 0.4249426 -0.1823844 0.8116939 -0.5569972 -0.1758043 -0.07686096 -0.9806805 -0.1798843 -0.886323 -0.4243552 -0.1853496 -0.8113237 0.5553785 -0.1825062 0.4540674 -0.2982963 -0.8395488 0.00770384 -0.5344551 -0.8451618 0.4873175 0.2293156 -0.842577 0.02068829 0.5384271 -0.8424182 -0.4547264 0.2943568 -0.840582 -0.4821169 -0.2390432 -0.8428651 0.05038082 0.9986919 -0.008743286 0.1008685 0.9943476 -0.03314143 0.05737179 0.9983443 -0.004144728 0.8899697 0.4559671 -0.006932139 0.9121111 0.4090344 -0.02728116 0.8944466 0.4471747 -3.31482e-4 0.8391472 -0.5439041 -6.46543e-4 0.8103365 -0.5852862 -0.02819585 0.8368203 -0.5474738 0.002116084 -0.03683483 -0.9983973 -0.04296743 -0.1137737 -0.9926305 0.041718 -0.05020028 -0.9987292 0.004456102 -0.8894916 -0.4569516 -6.9968e-5 -0.8764186 -0.4812108 -0.01807314 -0.9080668 -0.4132617 -0.06804054 -0.8403492 0.5420439 -0.001306891 -0.8107906 0.5843036 -0.0347585 -0.8399839 0.5426108 -8.63177e-4 0.2720593 0.7169163 0.6418838 0.2127866 0.2274531 0.9502563 0.6490638 0.3722288 0.663447 0.4402122 0.108748 0.8912841 0.5036748 0.1428369 0.8520032 0.7280598 -0.03443366 0.6846482 0.4233323 -0.1419958 0.8947777 0.5194661 -0.1476842 0.841632 0.6217923 -0.4628584 0.6317725 0.3148977 -0.3443811 0.884444 0.4059321 -0.6395402 0.6528457 0.129148 -0.544699 0.8286277 0.08880102 -0.4684009 0.8790421 -0.02155989 -0.7285485 0.6846548 -0.1771374 -0.5316932 0.8282057 -0.1715162 -0.4475283 0.8776679 -0.4112899 -0.6146562 0.6730814 -0.4426406 -0.3390941 0.8301112 -0.4445722 -0.3414293 0.8281193 -0.7407861 -0.2196003 0.634832 -0.3535079 0.01348888 0.9353343 -0.7001631 -0.07210612 0.7103326 -0.6437464 0.2092857 0.736064 -0.3966037 0.6246102 0.6727314 0.009263575 0.1899636 0.9817475 -0.6254049 0.4655409 0.6262112 -0.4040071 0.2040675 0.8917033 -0.03571707 0.5235891 0.851222 0.3215824 0.9468816 0 -0.9468816 0.3215826 0 -0.3215824 -0.9468816 0 0.9468817 -0.3215825 0 0 0 1 0 0 1 0.01263648 -0.003717541 0.9999133 0.01081126 -0.001967847 0.9999397 0.009577214 0.00630176 0.9999344 0.009091198 0.006260216 0.9999392 0.00106126 0.01486194 0.9998891 -0.002985715 0.01003789 0.9999452 -0.009538233 0.01089549 0.9998952 -0.009156703 0.00326842 0.9999527 -0.01167249 0.001550793 0.9999307 -0.01065206 -0.006020307 0.9999251 -0.007221937 -0.006795942 0.9999508 -0.005378484 -0.01257276 0.9999065 0.00290662 -0.01027208 0.9999431 0.005542337 -0.01225858 0.9999096 -7.09898e-4 0.04064971 -0.9991733 -0.01097226 0.02586936 -0.9996051 -0.02299773 0.02703559 -0.99937 0.03193271 -0.02122747 -0.9992646 0.02691435 -0.008922457 -0.999598 0.03361463 0.004678308 -0.9994239 0.02799254 0.007457256 -0.9995803 0.02260267 0.02642786 -0.9993953 0.01828563 0.02518296 -0.9995156 -0.02594155 0.009058058 -0.9996225 -0.03657782 0.02502739 -0.9990174 -0.03716868 -0.005518257 -0.9992939 -0.03391349 -0.007668137 -0.9993954 -0.03156822 -0.02489125 -0.9991917 -0.01579374 -0.02553355 -0.9995493 -0.01005333 -0.03752857 -0.9992451 0.009568691 -0.03037726 -0.9994927 0.009831845 -0.0294373 -0.9995183 -0.7510423 -0.6602311 -0.005537867 -0.715411 -0.6987029 -0.001151204 -0.9887958 -0.149267 -0.001521527 -0.9891181 -0.1471146 -0.001696944 -0.8953363 0.4453899 -9.54634e-4 -0.8602965 0.5097493 -0.006768941 -0.4950094 0.8688763 0.004453301 -0.2290483 0.9733517 -0.01111441 0.1280195 0.9917513 0.006349623 0.4406604 0.8976276 -0.009118616 0.8847913 0.4659333 -0.0071038 0.7402122 0.6723591 0.00438404 0.9711474 0.2384675 0.002429187 0.9811349 -0.1932705 -0.004572629 0.9868415 -0.1616786 -0.001963555 0.7199237 -0.6940529 -6.77854e-4 0.6616936 -0.7497416 -0.007005572 0.2110559 -0.9774636 0.00450015 -0.08665925 -0.9961727 -0.01140385 -0.360965 -0.9325733 0.003395557 -0.003642141 7.50433e-4 -0.9999932 -9.9181e-4 -0.001742899 -0.9999981 0.003068506 0.001067996 -0.9999948 -0.003735363 -0.001413941 -0.999992 -0.1849246 -0.9827324 0.00633496 0.3004593 -0.9537621 -0.007880926 0.3346751 -0.9422506 0.01250797 0.8326935 -0.5535556 -0.01407176 0.8313465 -0.5555327 -0.01569902 0.9992843 -0.02122944 0.03130894 0.9890841 0.1376518 -0.05258184 0.8134769 0.5799261 0.04405963 0.649021 0.7588639 -0.05382806 0.4144462 0.9093131 0.03720641 -0.01744335 0.9992741 -0.03386914 -0.0556367 0.9983751 -0.01232188 -0.5501882 0.8344536 0.03130877 -0.6475826 0.7612847 -0.03290164 -0.9440104 0.3296176 0.01402729 -0.9402385 0.340434 0.00749737 -0.9891344 -0.1468546 -0.006838262 -0.9754672 -0.2185784 0.02621972 -0.784557 -0.6186064 -0.04238474 -0.6510689 -0.7577709 0.04350519 -0.2586928 -0.9655556 -0.0279383 0.2706809 0.5938894 0.7576459 0.6864166 0.4904731 0.5369065 0.5151026 0.2674924 0.8143201 0.8140943 -0.07176387 0.5762817 0.6429557 -0.01500672 0.7657564 0.7019335 -0.4678389 0.5370441 0.3345596 -0.3490473 0.8753491 0.3208805 -0.9048529 0.2797805 -0.06338888 -0.5335888 0.8433652 -0.120692 -0.6413962 0.7576571 -0.549099 -0.6404815 0.5369114 -0.386799 -0.2900506 0.8753612 -0.9369324 -0.2094742 0.2797827 -0.4940134 0.1416384 0.85784 -0.6043086 0.2173172 0.7665406 -0.4804757 0.7302345 0.4856961 -0.1800349 0.4712795 0.8634138 -0.04715812 0.8462506 0.530694 0.2394494 0.5597706 0.7932976 -0.079764 -0.8284135 -0.5544086 0.08497822 -0.5004793 -0.8615679 0.6177131 -0.6936872 -0.3704439 0.5281593 -0.1088215 -0.8421435 0.5904411 -0.0929647 -0.8017088 0.7921451 0.41535 -0.4472032 0.2637211 0.463433 -0.8459794 0.2675461 0.5436799 -0.7955069 -0.2071645 0.8984807 -0.3870598 -0.3088806 0.4176035 -0.8545175 -0.7316193 0.4268609 -0.5315291 -0.5895826 0.08138823 -0.8035972 -0.8195537 -0.1218154 -0.5599042 -0.4606262 -0.4249482 -0.7792577 -0.4769899 -0.4701874 -0.7425661 0.2253993 -0.9573242 0.180902 0.9441832 -0.2818576 0.1705119 0.6944264 0.6711981 0.259355 -0.2259785 0.9569844 0.1819746 -0.941968 0.2828647 0.1807867 -0.7163931 -0.6743547 0.1789603 0.3718889 0.3718474 0.8505459 0.4900794 -0.06454962 0.8692845 0.4343158 -0.2359034 0.8693213 0.07847613 -0.5217446 0.8494846 -0.3970926 -0.3573673 0.8453437 -0.5031526 0.1937198 0.8422057 -0.1345492 0.5235769 0.8412869 0.2507988 -0.967092 0.04281443 0.1905868 -0.9816692 0.001532018 0.2017068 -0.9794325 -0.005149126 0.9650821 -0.2619475 1.09394e-4 0.9515873 -0.3058609 0.03051018 0.9614545 -0.2682338 0.06046384 0.9346222 -0.3556421 5.05702e-5 0.7444773 0.6674885 0.01458227 0.6911211 0.7218984 0.03484672 0.7312756 0.6820804 0.001538157 -0.2031835 0.9791386 0.002040624 -0.2542367 0.9667939 0.02594769 -0.2102422 0.9776454 -0.002770185 -0.949429 0.3139656 -0.003223836 -0.9639063 0.2642025 0.03289073 -0.9491333 0.3148638 -0.002631843 -0.7464922 -0.6653916 -0.001842021 -0.7122007 -0.7006214 0.04358947 -0.7531067 -0.6578829 0.004523694 -0.2760275 0.9208285 -0.2754698 0.4997864 0.4475708 -0.7415484 0.4868247 0.8444097 -0.2235493 0.05601513 0.6136986 -0.7875509 -0.5436353 -0.4786322 -0.6894721 -0.5478847 -0.7856487 -0.2873651 -0.2153359 -0.6298733 -0.7462508 -0.7817926 -0.1488326 -0.6055158 -0.850913 -0.1290754 -0.5092021 -0.7414331 0.3784558 -0.5541194 -0.7321601 0.365482 -0.5747734 -0.3304362 0.6280129 -0.704565 0.8280316 0.2277479 -0.5123423 0.8663653 0.2160903 -0.4502401 0.7146909 -0.1396082 -0.685366 0.8509454 -0.3753399 -0.3674399 0.4763781 -0.4616229 -0.7483103 0.2662115 -0.8126698 -0.518362 0.2119806 -0.976575 0.0369566 0.003965973 -0.008845269 -0.9999531 0.001998126 -0.01228582 -0.9999226 -0.002664506 -0.008448481 -0.9999608 -0.006272673 -0.009501278 -0.9999352 -0.0119872 -0.004340529 -0.9999188 -0.009725093 3.59275e-4 -0.9999527 -0.01120954 0.002558946 -0.999934 -0.007232308 0.008448123 -0.9999382 -0.005583286 0.008191168 -0.9999509 -0.03267723 -0.02332979 -0.9991937 0.06291568 -0.1035565 -0.9926317 0.004744589 0.008706986 -0.9999508 0.01079815 0.008389115 -0.9999066 0.01067316 -2.08803e-4 -0.9999431 0.01008206 2.58194e-4 -0.9999492 0.009803235 -0.008728146 -0.9999139 -0.02649176 -0.009868025 0.9996004 -0.03099447 -0.007248282 0.9994933 -0.03026753 0.00784409 0.9995111 0.01758366 2.22255e-4 0.9998455 0.02382576 -0.01403087 0.9996178 0.01163649 -0.02773505 0.9995476 0.01165717 -0.02774673 0.9995471 -0.006575405 -0.03836989 0.999242 -0.01792204 -0.02318578 0.9995706 -0.02457815 -0.02334713 0.9994253 -0.02828931 0.008869707 0.9995605 -0.02316039 0.02101624 0.9995108 -0.004231989 0.02202773 0.9997485 -0.006342351 0.01734459 0.9998295 0.002153694 0.01612621 0.9998677 -0.00137633 0.02269852 0.9997415 0.01757019 0.02481639 0.9995377 0.02395886 0.01221197 0.9996384 0.01768344 -0.001569628 0.9998424 0.01712697 -2.03878e-4 0.9998533 0.4945162 0.8691256 0.008623957 0.3144938 0.9492586 -0.001327574 -0.149701 0.9887121 0.006177306 -0.1084337 0.9940997 0.002840459 -0.6522242 0.7580237 0.001919806 -0.7111753 0.7029684 0.00807178 -0.9707328 0.2401064 -0.005200564 -0.9996305 -0.02515715 0.01030367 -0.9250035 -0.3799096 -0.006113231 -0.7565963 -0.6538189 0.00911647 -0.2264119 -0.9740058 0.007103621 -0.4627593 -0.8864731 -0.0043841 0.038531 -0.9992519 -0.003329873 0.4065369 -0.9135947 0.008529484 0.5971829 -0.8020992 -0.003119468 0.8929566 -0.4500346 0.009876906 0.9204726 -0.3907737 0.005107939 0.9928161 0.1196486 -6.81578e-4 0.9416604 0.3363567 0.0118336 0.7849177 0.6195863 -0.004151105 0.002727985 -0.004755675 0.999985 0.002167522 0.002818524 0.9999937 -7.67394e-4 -0.002704381 0.9999961 -0.001704454 -0.00325644 0.9999933 0.9703137 0.2386147 -0.03942757 0.9995076 -0.01190423 0.02903246 0.9599114 -0.2788473 -0.02853834 0.861034 -0.5070521 0.03896927 0.7201751 -0.6927943 -0.03720068 0.3867254 -0.9217714 0.0279482 0.315948 -0.9487553 -0.006348431 -0.1689043 -0.985601 0.007884263 -0.1999049 -0.9797651 -0.009932935 -0.3831812 -0.92286 -0.0387541 -0.7247433 -0.6884521 0.02794486 -0.7750689 -0.6318448 -0.006347537 -0.9737051 -0.22771 0.006834268 -0.9799207 -0.199287 -0.006344079 -0.9679982 0.250864 0.006838321 -0.9602871 0.278942 -0.006341755 -0.7405321 0.6719862 0.006837248 -0.7206631 0.6932564 -0.006346046 -0.3434236 0.9391558 0.006833076 -0.3159533 0.9487536 -0.006339907 0.1323675 0.9911772 0.006833136 0.1611552 0.9869087 -0.006346344 0.5778095 0.816143 0.006837308 0.6356317 0.7715471 -0.02622199 0.8903349 0.453812 0.03685969 -0.5058798 -0.4124045 -0.7576333 -0.4065249 -0.6345117 -0.6573678 0.03006649 -0.5374118 -0.8427839 0.2677916 -0.8041402 -0.5307035 0.4217128 -0.4582596 -0.7824044 0.5208945 -0.5010756 -0.6910805 0.6754316 -0.1797463 -0.7151807 0.6267491 -0.1820551 -0.7576552 0.8194406 0.2005627 -0.5369282 0.5387064 0.2160923 -0.8143093 0.4764526 0.6639485 -0.5763379 0.4078787 0.4972217 -0.7657712 0.13302 0.8146049 -0.564557 -0.0483061 0.5007311 -0.864254 -0.2646641 0.7947537 -0.5461864 -0.5659851 0.5444519 -0.6190583 -0.4453293 0.3245022 -0.8344939 -0.7882275 0.2289606 -0.5712044 -0.5789541 0.01076954 -0.815289 -0.8305611 -0.1689026 -0.530698 -0.4807912 -0.3735345 -0.7932917 0.8727957 0.3171488 0.3710047 0.4858841 -0.05713135 0.8721541 0.762368 -0.3906404 0.5159412 0.3064838 -0.5556933 0.7728343 0.2958328 -0.6725186 0.6783818 -0.2011909 -0.6759551 0.7089478 -0.1345885 -0.5915649 0.7949447 -0.6734497 -0.5824013 0.4552739 -0.5437477 -0.1095167 0.8320724 -0.757885 -0.02616643 0.6518633 -0.4495471 0.5187603 0.7271832 -0.4035783 0.4113578 0.8172572 -0.09661024 0.8850914 0.4552798 0.25124 0.4790999 0.8410362 0.2950587 0.5117813 0.8068584 0.9831612 0.02465826 -0.1810693 0.5120074 -0.8418958 -0.1704697 -0.4732304 -0.8418964 -0.2593519 -0.9830137 -0.02400642 -0.1819553 -0.5124084 0.8394773 -0.1808751 0.4707203 0.8639607 -0.1788701 -0.2654256 -0.4540098 -0.8505435 0.186683 -0.457709 -0.8692824 0.3382951 -0.3603199 -0.8693251 0.5245949 0.0563544 -0.8494849 0.245027 0.4747082 -0.8453484 -0.3149402 0.4376099 -0.8422056 -0.5405784 -0.002570569 -0.8412898 0.99908 0.002532184 -0.04281228 0.9979165 0.0645014 -0.001528143 0.9985731 0.05315566 0.005150258 0.4980425 -0.8671526 -1.00977e-4 0.5370854 -0.8429762 -0.030505 0.5032123 -0.8620457 -0.06045335 0.5809537 -0.8139367 -4.21427e-5 -0.4569582 -0.8893687 -0.01458173 -0.5231232 -0.8515443 -0.03485268 -0.4744155 -0.8802998 -0.001547753 -0.9986636 -0.05164486 -0.002033174 -0.9996631 8.50818e-4 -0.02594441 -0.9990073 -0.04446107 0.002770185 -0.5444011 0.838819 0.003225922 -0.4999142 0.8654504 -0.0328865 -0.5451823 0.8383134 0.002635478 0.4544256 0.8907828 0.001850247 0.4971823 0.8665505 -0.04358971 0.4454817 0.8952797 -0.004523754 0.8953846 -0.3878269 0.2188076 0.6931744 0.4036877 0.5971143 -0.3552606 -0.6892991 0.6313927 -0.4526626 -0.7527529 0.4779747 -0.7220385 -0.2686728 0.6375542 -0.7716442 -0.3194649 0.5500069 0.4635916 0.36896 0.8055752 0.2469493 0.8576455 0.4510657 0.2538803 0.7776353 0.5751766 -0.06914895 0.4972567 0.8648436 -0.4608643 0.5781838 0.6732813 -0.5151521 0.6091187 0.6029865 -0.7225716 0.2140551 0.657321 -0.7426817 0.209598 0.6359973 0.08355498 -0.7320616 0.676095 0.2163311 -0.9131219 0.3455565 0.3299416 -0.4421824 0.8340345 0.9203892 -0.3834239 0.07661646 0.5035136 -0.02006232 0.8637544 -0.5050006 -0.863119 3.2509e-5 -0.5018889 -0.8649322 -4.30027e-5 -0.492827 -0.8701071 -0.005931556 -0.5000008 -0.8660244 0.001010656 0.006713628 -0.3978416 -0.9174296 0.4937235 -0.869619 -1.15909e-5 0.4849295 -0.8745533 -3.62931e-5 0.5346202 -0.8447033 -0.02564674 0.4999825 -0.8659947 0.008411705 0.4390801 -0.468236 -0.766788 0.3290637 -0.2046245 -0.921871 0.9999839 0.005682051 -1.70815e-6 0.9999896 -0.002967715 -0.003497481 0.9999698 0.007727921 8.65174e-4 0.999987 0 -0.005115926 0.4269273 0.1671534 -0.8887029 0.601526 0.1237242 -0.789214 0.4012278 0.4516459 -0.7968892 0.3557639 0.2839788 -0.8903865 0.5049954 0.8631221 3.13308e-5 0.5072273 0.8618117 0.001126766 0.4999977 0.8660252 0.001629412 0.4908147 0.871159 -0.01353025 -0.006719231 0.3978314 -0.917434 -0.4849331 0.8745512 -2.41952e-5 -0.5072615 0.8617911 0.001367628 -0.4999815 0.8659953 0.008411705 -0.479512 0.7047168 -0.5229173 -0.3596352 0.3081928 -0.8807268 -0.4353283 0.1849753 -0.8810638 -0.9999819 0.00601226 4.63664e-5 -0.9987636 -0.04954004 -0.004130303 -0.9999666 0.008134603 9.5269e-4 -0.9997127 0 -0.02397406 -0.9864516 0.1320883 0.09729349 -0.3459208 -0.2043453 -0.9157412 0.004238009 2.51163e-4 -0.9999911 -0.004386007 -2.63645e-4 -0.9999904 0.009443819 -0.02060979 -0.9997431 -0.006166696 0.007704794 -0.9999514 -0.01161891 -0.01981842 -0.9997361 8.22171e-4 -6.78312e-4 -0.9999994 0.001522362 -3.82154e-4 -0.9999988 0.001978278 0.008975148 -0.9999579 0.001045644 -3.90132e-4 -0.9999995 9.61194e-4 -5.54812e-4 -0.9999994 0.003144264 0.004418373 -0.9999853 0.01037853 -0.01861262 -0.9997729 -0.001082658 -6.25171e-4 -0.9999992 -0.001135706 -4.23586e-4 -0.9999994 -2.39956e-4 0.009972453 -0.9999504 -0.01154386 0.01970285 -0.9997393 -0.002751767 -0.003615796 -0.9999898 0.007056117 -0.005880832 -0.9999579 -9.59984e-4 -7.92516e-4 -0.9999992 -0.004926621 -0.004294455 -0.9999787 0.008216321 0.01095056 -0.9999064 -0.007582783 0.008516371 -0.999935 0.00492382 0.004297971 -0.9999787 -0.0170955 -0.01448589 -0.999749 0.003262341 0.002905726 -0.9999905 0.8710917 0.07299858 -0.4856651 0.4066497 0.4485869 -0.795868 0.4146745 0.8464385 -0.3340466 -0.03928595 0.5416392 -0.8396927 -0.5661506 0.759366 -0.3206823 -0.5064879 0.4227893 -0.751478 -0.7034006 0.01924765 -0.710533 -0.8710879 -0.07302379 -0.4856682 -0.4066408 -0.4485889 -0.7958716 -0.4146705 -0.8464237 -0.3340889 0.03928112 -0.5416109 -0.8397111 0.5661451 -0.75937 -0.3206822 0.5064675 -0.4227843 -0.7514947 0.7034161 -0.01923817 -0.7105179 0.9996063 -0.02484267 0.01304548 0.7654142 -0.6432858 0.0180155 0.704791 -0.7090442 -0.02293568 0.1729568 -0.9849216 -0.003933966 0.07633656 -0.9964267 0.03615123 -0.4801576 -0.8761711 -0.04210776 -0.6729623 -0.7376052 0.05532157 -0.9913884 -0.115933 -0.06089937 -0.9996066 0.02483028 0.01305103 -0.7654183 0.6432814 0.01800131 -0.7048074 0.709028 -0.02293401 -0.1729333 0.9849257 -0.003939807 -0.07632648 0.9964277 0.03614223 0.480143 0.876178 -0.04212868 0.6729711 0.7375968 0.0553258 0.9913892 0.1159238 -0.06090372 -0.6088336 0.6014029 0.5173357 -0.5887987 0.5944288 0.5476956 -0.108352 0.605134 0.7887159 0.1805614 0.8783888 0.4425277 0.2848472 0.5211083 0.8045547 0.8716176 0.3242316 0.3676366 0.5629017 0.0656464 0.8239129 0.608831 -0.6014071 0.5173339 0.5887667 -0.59443 0.5477288 0.108368 -0.6051452 0.7887051 -0.180566 -0.878414 0.4424758 -0.2848621 -0.5211239 0.8045393 -0.871609 -0.3242318 0.3676571 -0.5629071 -0.06565135 0.8239088 -8.80212e-4 -0.00210911 0.9999974 -0.004262149 0 0.999991 6.5663e-5 0.001234471 0.9999992 9.72212e-4 0.00168389 0.9999982 -6.64651e-5 -0.001234412 0.9999992 -9.71865e-4 -0.001683294 0.9999982 -7.62385e-4 0.003361046 0.9999941 -8.4079e-4 0.00145626 0.9999986 8.80671e-4 0.00210911 0.9999974 0.004262685 0 0.999991 7.6248e-4 -0.003361463 0.9999942 8.40909e-4 -0.001456499 0.9999987 -0.001917421 -0.01064234 0.9999416 -0.002530872 -0.009394645 0.9999527 0.006190419 -0.008409023 0.9999455 0.006153762 -0.00897777 0.9999408 0.01680088 -0.002684235 0.9998553 0.01003658 0.002982735 0.9999452 0.01089519 0.009538829 0.9998952 0.003267586 0.009155213 0.9999529 -6.84244e-4 0.01495009 0.999888 -0.008085668 0.00858891 0.9999305 -0.007710278 0.008531808 0.9999339 -0.01254385 0.001140952 0.9999207 -0.009293138 -0.002676725 0.9999533 -0.01149529 -0.008954226 0.9998939 0.03850662 6.71822e-4 -0.9992582 0.02152013 0.01112371 -0.9997066 0.01971352 0.01676982 -0.9996651 -0.02312713 -0.01622396 -0.999601 -0.02314627 -0.02163046 -0.9994981 -0.009667038 -0.02768325 -0.9995701 -0.007339239 -0.02632218 -0.9996266 0.005074322 -0.02721005 -0.9996169 -0.006895601 -0.05206996 -0.9986197 0.02840763 -0.02429491 -0.9993011 0.02691042 -0.01976847 -0.9994424 0.01663178 0.01662296 -0.9997235 0.01059508 0.03034383 -0.9994834 -0.005919814 0.03174299 -0.9994785 -0.01392203 0.01500898 -0.9997904 -0.01625317 0.01499289 -0.9997555 -0.01566064 0.003421545 -0.9998716 -0.02758485 0.01602852 -0.999491 -0.03352558 -0.00921452 -0.9993954 -0.683451 0.7299795 -0.004971504 -0.6987 0.7154074 -0.003269731 -0.1470211 0.9891319 -0.001705467 -0.1471131 0.9891182 -0.001696348 0.4453979 0.8953323 -9.5429e-4 0.5097551 0.860293 -0.006768107 0.8801892 0.4745972 0.004953742 0.9733534 0.229079 -0.01030325 0.9976105 -0.06901407 0.003210246 0.8976572 -0.4406616 -0.005383193 0.898549 -0.4388387 -0.005504131 0.4659581 -0.8847783 -0.007102429 0.6078645 -0.7940407 5.58066e-4 0.2384534 -0.9711509 0.002429723 -0.1932596 -0.9811371 -0.004572629 -0.1616731 -0.9868424 -0.001964569 -0.694064 -0.719913 -6.77144e-4 -0.7497464 -0.6616882 -0.007006585 -0.9821751 -0.1879011 0.005027115 -0.9961833 0.08663636 -0.01063281 -0.9440557 0.3297824 0.001527249 0.002162992 -0.001230657 -0.999997 0.002164959 -0.001236081 -0.9999969 0.001482546 -7.73028e-4 -0.9999986 -0.002127528 -2.27501e-7 -0.9999977 -0.9827339 0.184916 0.00634402 -0.9642242 -0.2650002 -0.006837308 -0.9561027 -0.2929631 0.006345808 -0.7306202 -0.6827499 -0.006841361 -0.7104495 -0.7037196 0.006343185 -0.3296418 -0.9440814 -0.006841421 -0.3020253 -0.9532788 0.006347775 0.1833106 -0.9830235 -0.007877469 0.2186554 -0.975722 0.01250976 0.7598996 -0.6498883 -0.01406639 0.7861518 -0.6178721 0.01413321 0.999749 0.0174427 -0.01407122 0.9981679 0.0588321 0.01413708 0.7616352 0.6478841 -0.01257306 0.7383903 0.674332 0.00750041 0.3296361 0.9440833 -0.006832957 0.259788 0.9653098 0.02621662 -0.1831505 0.9821708 -0.04238462 -0.3684092 0.9286453 0.04350405 -0.7347436 0.6777692 -0.0279445 -0.784236 0.6204304 0.00634253 -0.9769335 0.2134346 -0.006834328 0.6251711 -0.5622109 0.5413687 0.498287 -0.39162 0.773527 0.1903396 -0.8532993 0.4854393 0.001276314 -0.5044932 0.8634148 -0.2559633 -0.8079029 0.5308257 -0.4296964 -0.4116167 0.8036994 -0.3993276 -0.3955451 0.8270922 -0.8817118 -0.2701662 0.3867745 -0.5074422 0.08108359 0.8578625 -0.5523646 0.1039314 0.8270984 -0.7232124 0.572163 0.3867731 -0.2808048 0.4863355 0.8274216 -0.294417 0.7393033 0.6055983 0.0710718 0.5556074 0.8284016 0.2205777 0.8160367 0.5342562 0.5782235 0.5295886 0.6206398 0.4181451 0.2901206 0.8608047 0.9261358 0.05458003 0.3732204 0.5758877 -0.07246339 0.8143111 -0.8987981 0.0841214 -0.4302158 -0.4555909 -0.3726315 -0.8084447 -0.4935896 -0.4467964 -0.7461518 -0.1284052 -0.8005753 -0.5853131 0.04003691 -0.5965029 -0.8016117 0.377234 -0.7207614 -0.5815476 0.4303575 -0.4135597 -0.802347 0.7506849 -0.3689496 -0.5480405 0.596637 0.1031048 -0.7958604 0.6610182 0.1473115 -0.7357679 0.4250532 0.7286856 -0.5369796 0.0996527 0.4783077 -0.8725201 -0.1201075 0.8080673 -0.5767161 -0.5429533 0.552151 -0.6327173 -0.4280356 0.2435782 -0.870319 -0.957292 -0.2253875 0.1810875 -0.2818646 -0.9441733 0.1705553 0.6711657 -0.6944268 0.259438 0.9569779 0.2259898 0.181995 0.2828755 0.9419645 0.1807882 -0.6743595 0.7164216 0.1788281 0.3718488 -0.3718904 0.8505446 -0.06456226 -0.4900824 0.8692819 -0.2359015 -0.4343217 0.8693189 -0.5217465 -0.07847881 0.8494832 -0.3573616 0.3970916 0.8453468 0.1937237 0.5031545 0.8422034 0.5235742 0.1345471 0.841289 -0.9670902 -0.2508074 0.04280537 -0.9816678 -0.1905941 0.001522421 -0.9794356 -0.2016915 -0.005145192 -0.2619633 -0.9650779 1.09394e-4 -0.3058643 -0.9515865 0.03049874 -0.2682344 -0.9614542 0.06046664 -0.3556352 -0.9346249 5.89991e-5 0.6674847 -0.7444812 0.01455783 0.7219023 -0.6911175 0.03483933 0.6820763 -0.7312793 0.00155735 0.9791386 0.2031837 0.002036392 0.9667922 0.2542438 0.02594506 0.9776434 0.2102516 -0.002770185 0.3139694 0.9494276 -0.003225922 0.2642124 0.9639037 0.03288638 0.3148653 0.9491328 -0.002615928 -0.6653978 0.7464868 -0.001841962 -0.7006172 0.7122042 0.04359853 -0.6578848 0.7531051 0.004523694 0.1191126 0.1722283 0.977829 0.7479651 -0.6565653 -0.09731566 -0.3469607 0.3738647 -0.8601415 -0.7807425 0.1934252 -0.5941616 0.5430667 -0.6129739 -0.5738829 0.6745734 -0.4199009 -0.6071524 0.7033807 -0.05450284 -0.7087208 0.8930773 0.09558659 -0.4396319 -0.936695 0.3365612 -0.09658819 -0.2667543 0.880223 -0.3924917 -0.1515904 0.7384563 -0.6570409 0.3156012 0.7058137 -0.6342104 0.3759934 0.7534272 -0.5394225 0.5208542 0.3836365 -0.7625839 0.7669815 0.4178503 -0.4869708 0.1807551 -0.7156524 -0.6746623 0.1111643 -0.8342373 -0.5400838 -0.1399334 -0.7163079 -0.6836093 -0.3340446 -0.8238531 -0.4579088 -0.4863303 -0.5021185 -0.7150944 -0.7916309 -0.4909612 -0.3636999 -0.6552976 -0.1317578 -0.7437909 0.8631226 -0.5049946 2.92113e-5 0.8649239 -0.5019031 -3.68584e-5 0.8701062 -0.4928285 -0.005934774 0.8660255 -0.4999991 0.001010656 0.4017487 0.003998577 -0.9157413 0.8698659 0.4932883 -1.08866e-5 0.8671169 0.4981046 -3.68616e-5 0.8611201 0.5083513 -0.007146894 0.8660246 0.5000005 0.001006662 0.2021316 0.3583012 -0.9114621 -0.00568664 0.9999839 -6.94103e-6 0.002953827 0.9999896 -0.003502309 -0.007701396 0.9999701 8.58585e-4 0 0.999987 -0.005107522 -0.1671627 0.4269309 -0.8886994 -0.1237182 0.601507 -0.7892296 -0.4516495 0.401211 -0.7968956 -0.2839823 0.35578 -0.890379 -0.8631174 0.5050035 2.65061e-5 -0.8618033 0.5072413 0.001138091 -0.8660243 0.4999992 0.001640379 -0.8711646 0.4908037 -0.01356101 -0.3978542 -0.006712734 -0.9174242 -0.874552 -0.4849318 -3.62924e-5 -0.8617933 -0.5072578 0.001376807 -0.8659961 -0.49998 0.008409678 -0.7046949 -0.479502 -0.522956 -0.3082129 -0.3596196 -0.8807262 -0.1849776 -0.4353677 -0.881044 -0.006011605 -0.9999819 4.50714e-5 0.04952895 -0.9987642 -0.004135429 -0.008152782 -0.9999663 9.67692e-4 0 -0.9997125 -0.02397739 -0.132089 -0.9864525 0.0972836 0.2043393 -0.3459111 -0.9157462 -2.50883e-4 0.004239201 -0.999991 2.63852e-4 -0.004384875 -0.9999904 0.02060663 0.009442687 -0.9997432 -0.007704019 -0.006166756 -0.9999514 0.01981955 -0.01161932 -0.9997361 6.78867e-4 8.21687e-4 -0.9999995 3.82467e-4 0.001522421 -0.9999988 -0.008979499 0.001978754 -0.9999577 3.90047e-4 0.001045703 -0.9999995 5.54665e-4 9.60903e-4 -0.9999995 -0.004417896 0.003143966 -0.9999854 0.01861327 0.01037847 -0.9997729 6.2507e-4 -0.001082658 -0.9999992 4.2356e-4 -0.001135289 -0.9999994 -0.009966433 -2.3964e-4 -0.9999504 -0.01969712 -0.01153761 -0.9997394 0.003611505 -0.002749562 -0.9999898 0.005874097 0.007045328 -0.999958 7.91818e-4 -9.59834e-4 -0.9999992 -2.85873e-4 -0.009823203 -0.9999518 0.005536913 0.008857429 -0.9999455 0.007127344 0.004072427 -0.9999664 -0.004294037 0.00492829 -0.9999787 -0.01745027 0.01113021 -0.9997859 0.001504242 0.001303851 -0.999998 -0.002892971 0.003256022 -0.9999906 -0.07300984 0.8710941 -0.485659 -0.4485947 0.4066455 -0.7958657 -0.8464345 0.4146881 -0.3340398 -0.5416272 -0.03927904 -0.8397008 -0.7593541 -0.5661394 -0.3207297 -0.4228026 -0.5064935 -0.7514668 -0.0192489 -0.7034277 -0.7105061 0.07301121 -0.8710898 -0.4856666 0.4485964 -0.4066485 -0.7958632 0.8464339 -0.4146723 -0.3340606 0.5416221 0.03927981 -0.8397039 0.759357 0.5661457 -0.3207117 0.4228245 0.5065003 -0.7514498 0.01923453 0.7034489 -0.7104856 0.02483218 0.9996065 0.01304608 0.6432904 0.7654107 0.01800584 0.7090317 0.7048036 -0.02293479 0.9849193 0.1729703 -0.003937005 0.9964262 0.07633966 0.03615671 0.8761792 -0.4801419 -0.04211825 0.7376011 -0.6729667 0.05532312 0.1159424 -0.9913864 -0.06091463 -0.02484697 -0.9996061 0.01304548 -0.6432833 -0.7654166 0.01800179 -0.709032 -0.7048034 -0.02293407 -0.9849232 -0.1729475 -0.003932595 -0.9964268 -0.07633084 0.03615725 -0.8761726 0.4801539 -0.04211908 -0.7375988 0.6729692 0.05532175 -0.6014138 -0.6088533 0.5173 -0.5944359 -0.5887905 0.5476967 -0.6051418 -0.108372 0.7887072 -0.8783916 0.1805549 0.4425247 -0.5210949 0.2848516 0.8045619 -0.3242509 0.8716545 0.367532 -0.06564122 0.5629237 0.8238983 0.6014089 0.608832 0.5173308 0.594437 0.5887961 0.5476896 0.6051239 0.108375 0.7887205 0.8784006 -0.180561 0.4425045 0.5211246 -0.2848526 0.8045422 0.3242251 -0.8715889 0.3677105 0.06565481 -0.5628776 0.8239287 0.002109587 -8.80364e-4 0.9999974 0 -0.004263043 0.9999909 -0.001234173 6.64995e-5 0.9999992 -0.001682937 9.71661e-4 0.9999982 0.001234471 -6.61107e-5 0.9999993 0.001683592 -9.72045e-4 0.9999981 -0.00336188 -7.6229e-4 0.9999941 -0.001456201 -8.4076e-4 0.9999986 -0.002109229 8.79905e-4 0.9999974 0 0.004262089 0.9999909 0.003360986 7.62485e-4 0.9999942 0.001456439 8.40883e-4 0.9999987 0.003945291 0.009931564 0.9999429 0.001192331 0.008213043 0.9999656 -0.004304349 0.0106936 0.9999337 -0.005402922 0.008203804 0.9999518 -0.0112096 0.007338106 0.9999102 -0.01129245 -0.003128349 0.9999313 -0.01106309 -0.003225088 0.9999336 -0.008701503 -0.01012229 0.999911 -0.003153026 -0.008768856 0.9999566 3.79273e-4 -0.01258915 0.9999207 0.006596207 -0.009657382 0.9999317 0.006753623 -0.00717467 0.9999515 0.01384884 -0.003397047 0.9998984 0.01040387 0.002938926 0.9999416 0.01213306 0.006236374 0.999907 -0.02104318 0.02201676 -0.9995362 -0.03428089 -0.002180397 -0.9994099 -0.01752227 -0.01551067 -0.9997262 -0.01738381 -0.01478695 -0.9997397 0.01661288 0.02087414 -0.9996441 0.01556336 0.01566106 -0.9997562 0.002417623 0.02330315 -0.9997255 -0.005355715 0.01196134 -0.9999142 -0.008997976 0.01361334 -0.9998669 -0.0153703 0.007553279 -0.9998534 -0.01501822 -0.01522219 -0.9997714 -0.009508311 -0.02723228 -0.9995839 0.005251765 -0.02816426 -0.9995895 4.57457e-4 -0.0381149 -0.9992733 0.02723926 -0.0231381 -0.9993612 0.02461564 -0.02270644 -0.9994391 0.03868132 -0.008451223 -0.9992159 0.03064984 0.009064614 -0.9994891 0.03036653 0.008346259 -0.999504 0.6431372 -0.7657152 -0.00741744 0.6987014 -0.7154126 -0.001150786 0.1492564 -0.9887974 -0.001521289 0.1471228 -0.9891169 -0.001696169 -0.4192082 -0.9078896 -0.001000225 -0.5097278 -0.8602913 -0.0087502 -0.8724653 -0.4886553 0.004509031 -0.9733455 -0.2290552 -0.01151168 -0.9963402 0.08542853 0.002845346 -0.8976557 0.4406649 -0.005382478 -0.898032 0.4398969 -0.005433678 -0.4659507 0.8847823 -0.007103681 -0.6155282 0.7881143 0.001000106 -0.2599588 0.9656186 0.001559078 0.1973732 0.9803097 -0.006048679 0.1616705 0.9868399 -0.003118515 0.6884695 0.7252635 -0.001642107 0.7497232 0.6616995 -0.008303523 0.9813307 0.1922556 0.005278885 0.9961818 -0.08665359 -0.01063299 0.937267 -0.3486035 0.002509355 -3.86234e-4 -1.77139e-4 -1 0.002299964 -4.84445e-4 -0.9999973 -0.00274384 -0.002767682 -0.9999924 0.003439903 0.004922866 -0.999982 0.9827319 -0.1849262 0.006345152 0.9642207 0.2650128 -0.006837248 0.9561055 0.2929539 0.006344616 0.704885 0.7092779 -0.007884323 0.678793 0.7342231 0.01250666 0.1031834 0.9945629 -0.01406621 0.06191444 0.9979814 0.01413559 -0.5513608 0.8341723 -0.01257306 -0.5804159 0.8142858 0.007496058 -0.8974642 0.4410344 -0.006837248 -0.9099211 0.4147329 0.006344437 -0.9979523 -0.06347632 -0.007883787 -0.9949635 -0.09945458 0.01251077 -0.7616333 -0.6478864 -0.01256978 -0.7383926 -0.6743295 0.007497906 -0.3296415 -0.9440815 -0.006837129 -0.3020238 -0.9532794 0.006343901 0.1833102 -0.9830235 -0.00788784 0.2186611 -0.9757208 0.01250755 0.734975 -0.6779776 -0.01257294 0.7584245 -0.6517179 0.007495701 0.976933 -0.2134368 -0.006836473 -0.6576997 0.2997696 0.691064 -0.4158361 0.561769 0.7151895 -0.4273509 0.5974234 0.6785694 0.002884387 0.6869412 0.7267073 0.05098474 0.8218029 0.5674863 0.3211402 0.4589447 0.8283953 0.5745455 0.62007 0.5342385 0.7508824 0.2300742 0.6190652 0.5438675 0.08833926 0.8345084 0.8066525 -0.1517809 0.5712044 0.4878004 -0.2600235 0.8333299 0.6899014 -0.5918477 0.4168363 0.1664518 -0.5742523 0.8015785 0.1582186 -0.711607 0.6845307 -0.2261099 -0.6613656 0.7151712 -0.1971365 -0.6222143 0.7576192 -0.6222447 -0.569577 0.5370229 -0.4189732 -0.2413046 0.8753477 -0.9553459 -0.09500712 0.2798 -0.532681 0.1778157 0.8274253 0.8897504 -0.08359259 -0.4487277 0.4815372 0.2211607 -0.8480625 0.6377072 0.5705304 -0.5175177 0.08823078 0.6080102 -0.7890114 0.0929625 0.590449 -0.8017032 -0.4153667 0.7921349 -0.4472055 -0.4686987 0.3350709 -0.8173427 -0.6644469 0.3267181 -0.6721352 -0.6789227 -0.1599372 -0.7165781 -0.6618701 -0.1475226 -0.7349593 -0.4239438 -0.7268807 -0.5402927 -0.09750366 -0.4785396 -0.8726356 0.1203674 -0.8097864 -0.5742452 0.5436319 -0.5528554 -0.6315183 0.4462214 -0.2875576 -0.8474651 0.9572979 0.2253889 0.1810546 0.2818565 0.944176 0.1705538 -0.6711753 0.6944193 0.2594332 -0.9569763 -0.2259781 0.1820174 -0.2828759 -0.941964 0.1807903 0.6743567 -0.716413 0.1788728 -0.3718493 0.3718899 0.8505446 0.06455665 0.4900727 0.8692877 0.2358999 0.4343162 0.869322 0.5217406 0.07847845 0.849487 0.3573638 -0.397094 0.8453447 -0.1937199 -0.5031542 0.8422046 -0.5235745 -0.134545 0.8412892 0.9670904 0.2508068 0.04280376 0.9816694 0.1905857 0.001522421 0.979436 0.2016895 -0.005147099 0.2619566 0.9650797 9.25647e-5 0.3058665 0.9515858 0.03049892 0.268229 0.9614561 0.06045907 0.3556434 0.9346218 4.21421e-5 -0.6674714 0.7444931 0.0145654 -0.7218973 0.6911227 0.03484106 -0.6820743 0.7312813 0.00155735 -0.9791374 -0.2031897 0.002030014 -0.9667875 -0.2542619 0.02594047 -0.9776456 -0.2102414 -0.002772629 -0.3139718 -0.9494269 -0.003225922 -0.2642045 -0.9639059 0.03288674 -0.3148608 -0.9491342 -0.002625703 0.6654025 -0.7464826 -0.001850247 0.7006152 -0.7122066 0.04358965 0.6578848 -0.7531051 0.004518926 -0.05251801 0.2036371 0.9776369 -0.3760916 0.5063204 -0.7760121 -0.5834481 0.1694266 -0.7942814 -0.8483557 -0.2632559 -0.4593356 0.7579213 -0.5865731 -0.28546 -0.5255938 0.5825793 -0.6199617 -0.8628203 0.4530164 -0.2243152 -0.6643944 -0.00717771 -0.7473477 0.5375182 -0.5410494 -0.646792 0.6307073 -0.3131077 -0.7100507 0.864107 0.02804327 -0.5025264 0.1371099 -0.774261 -0.6178356 0.1238826 -0.8161259 -0.5644392 -0.2461783 -0.6228948 -0.7425621 -0.3896169 -0.7594372 -0.5210122 -0.4931945 -0.2691893 -0.8272222 -0.146806 0.791601 -0.5931408 -0.09357666 0.9472433 -0.306551 0.1017417 0.5360798 -0.8380138 0.3675869 0.4365663 -0.8211515 0.7317785 0.5507053 -0.4015274 0.6589609 0.1590833 -0.735162 4.46963e-7 0 -1 1.50897e-7 0 -1 -7.5287e-7 0 -1 -2.18463e-7 0 -1 0 0 -1 -7.02041e-6 0 1 2.32542e-6 0 1 2.33452e-6 0 1 3.39632e-6 0 1 1.69502e-6 0 1 3.96016e-6 0 1 -1.3095e-6 0 1 -0.978743 -0.2050852 0.001465141 -0.6669805 -0.7450737 -0.001465201 -0.6179345 -0.7862284 0.001465201 -0.0320084 -0.9994866 -0.00146526 -0.0452696 -0.9989727 -0.002072274 0.4164019 -0.9091763 0.002829611 0.5791683 -0.8152033 -0.002829611 0.8877692 -0.4602842 0.002072274 0.881585 -0.4720231 0.001465201 0.9898602 0.1420379 -0.00146526 0.9787438 0.2050819 0.00146526 0.6669771 0.7450768 -0.001465141 0.6179355 0.7862275 0.001465082 0.08033877 0.9967669 -0.001247465 0.04527103 0.9989748 0 -0.3842108 0.9232454 0 -0.4164082 0.909177 0.001247286 -0.8495763 0.5274638 -0.00146526 -0.8815844 0.4720243 0.001465141 -0.9898607 -0.1420336 -0.001465201 0.9809067 0.1944743 0.001442849 0.9589254 0.283655 -0.001442909 0.3971729 0.9177428 0.001442849 0.3112908 0.9503136 -0.00144279 -0.4698227 0.8827599 0.001226246 -0.5135425 0.8580643 0 -0.913846 0.4060611 0 -0.9303677 0.3666266 -0.001056551 -0.9303677 -0.3666266 0.001056611 -0.5135408 -0.8580653 0 -0.4698212 -0.8827609 -0.001226246 0.2449169 -0.9695433 0.001226186 0.2932742 -0.9560284 0 0.7899054 -0.6132289 0 0.8196884 -0.5728084 -0.001226305 -0.04888427 0.02106779 0.9985823 -0.01898968 0.04459321 0.9988248 -0.02186763 0.02146053 0.9995305 -0.006366014 -0.01047742 0.9999249 -0.002298653 -0.008830666 0.9999585 -0.00936228 -0.002901971 0.999952 -0.009565591 -0.002823114 0.9999504 -0.006470859 0.006159543 0.9999602 -0.01008796 0.005164325 0.9999359 0.002150952 0.00893855 0.9999578 -0.005000591 0.01040881 0.9999334 0.008616447 0.002176284 0.9999606 0.01035809 0.005906224 0.999929 0.00335431 0.009833812 0.9999461 -0.006359457 0.03065729 0.9995098 -0.02064454 -0.004491746 -0.9997768 -0.01612335 -0.006723821 -0.9998475 -0.01426422 -0.009401619 -0.9998542 -0.01254326 -0.01912307 -0.9997385 5.77173e-4 -0.0186659 -0.9998256 0.001900851 -0.01952153 -0.9998077 7.05411e-5 -0.02171373 -0.9997643 0.01247406 -0.01480281 -0.9998127 0.01509612 -0.0145545 -0.9997802 0.01602995 -0.0102052 -0.9998195 0.02200478 -0.004992723 -0.9997455 0.01824116 0.003389775 -0.9998279 0.0192151 0.009260237 -0.9997726 0.01488608 0.01144617 -0.9998238 0.0119028 0.01692211 -0.999786 0.005334615 0.01688122 -0.9998433 0.001404643 0.01907575 -0.9998171 -0.003925681 0.01581686 -0.9998672 -0.006764292 0.01597279 -0.9998496 -0.007451236 0.01481443 -0.9998626 -0.01806855 0.01136958 -0.9997721 -0.01645177 0.003232359 -0.9998595 -0.06059908 0.9981069 -0.01050692 -0.0306642 0.9995089 -0.006459951 0.3620295 0.9321359 -0.00756973 0.4065624 0.9136208 -0.002042174 0.8161844 0.5777727 -0.004675626 0.8059319 0.5919718 -0.006572782 0.9356914 0.3525261 -0.01438909 0.994735 0.1023377 0.005419135 0.9713992 -0.2369228 -0.01585507 0.8959831 -0.4440881 2.96579e-4 0.7387061 -0.6737421 -0.01962321 0.5776265 -0.8162924 -0.003803133 0.3014759 -0.9534394 -0.008104681 0.2616764 -0.9650663 -0.01313555 -0.2718631 -0.9623047 -0.007762134 -0.2121616 -0.9772347 -7.18299e-5 -0.7327584 -0.6804141 -0.01008927 -0.6634765 -0.7481971 -2.56269e-4 -0.9260803 -0.3773013 0.004388034 -0.9839681 -0.1775304 -0.01702314 -0.9992887 0.03266829 -0.01884216 -0.9660567 0.2582195 0.007574796 -0.7828785 0.622005 -0.01452559 -0.637055 0.770817 0.001478195 -0.4248932 0.9049876 -0.02152103 -0.03206759 0.04542392 -0.998453 0.05737835 0.05888444 -0.9966145 0.01038789 -0.0349875 -0.9993338 0.01468575 -0.01046758 -0.9998375 0.01283705 0.0140385 -0.999819 0.004467308 0.02290636 -0.9997277 0.07344424 0.9969958 -0.02460992 0.2375878 0.9708068 0.0329591 0.5745444 0.8174585 -0.04074907 0.7846701 0.6182603 0.04524427 0.9002394 0.4335337 -0.04022282 0.9978244 -0.03606748 0.05518931 0.9745888 -0.2208971 -0.03716534 0.719685 -0.6941044 0.01651293 0.7536675 -0.6570079 -0.01805627 0.296628 -0.9542968 0.03646355 0.09701883 -0.9938482 -0.05341738 -0.3016283 -0.9522713 0.04690212 -0.5476662 -0.8344627 -0.06110483 -0.8140444 -0.5786886 0.04951262 -0.9758585 -0.2123816 -0.05093532 -0.9920551 -0.1257496 -0.003707647 -0.9058127 0.4230921 0.02227932 -0.8461319 0.5321388 -0.0298199 -0.6517692 0.7571973 0.04300308 -0.3900866 0.9206393 -0.01598966 -0.2583811 0.9657533 0.02366393 0.1955185 -0.4612208 0.8654755 0.7529729 -0.655805 0.05433028 0.3953334 -0.1804718 0.9006339 0.9993607 -0.03575325 -1.04547e-4 0.403901 0.1025858 0.9090326 0.7704254 0.6049314 -0.2012532 0.2065469 0.3401126 0.9174213 0.2344729 0.9560199 0.176206 -0.1080015 0.5911898 0.7992687 -0.4155495 0.1256015 0.9008569 -0.9781665 -0.1240888 0.1667104 -0.4058209 -0.2314514 0.8841604 -0.6099448 -0.436196 0.6615894 -0.2295191 -0.7178568 0.6572691 -0.169912 -0.5984178 0.7829599 0.23197 -0.7513864 0.6177447 -0.4219762 0.1892623 -0.8866317 -0.3625331 -0.3001729 -0.8823072 -0.4122923 -0.383148 -0.8265669 -0.2572771 -0.9109446 -0.3224723 0.0790292 -0.526084 -0.8467527 0.4563748 -8.6302e-5 -0.8897877 0.2885857 0.3864206 -0.8760123 -0.7125813 0.6774684 0.1823862 -0.9429985 -0.2783822 0.1823657 -0.2296254 -0.9572708 0.1757983 0.713958 -0.6766917 0.1798681 0.9423628 0.2785868 0.1853159 0.2304091 0.9558249 0.1825114 -0.1373441 -0.5256364 0.8395493 0.3522745 -0.4020032 0.8451604 -0.5154479 -0.1561473 0.8425744 -0.376016 0.3859294 0.8424195 0.1404718 0.5231565 0.8405802 0.5180994 0.1454368 0.8428649 -0.7063599 0.707799 0.008747458 -0.7409415 0.6707512 0.03314346 -0.7113177 0.7028585 0.004147112 -0.966234 -0.2575732 0.006933271 -0.9512373 -0.3072512 0.02728331 -0.9636698 -0.2670962 3.38113e-4 -0.2587596 -0.9659417 6.46547e-4 -0.209649 -0.9773702 0.02819383 -0.254639 -0.9670339 -0.00211364 0.6961033 -0.7166548 0.04296863 0.749373 -0.6608327 -0.04171788 0.7062515 -0.7079471 -0.00445193 0.966541 0.2565123 6.7357e-5 0.9730838 0.2297416 0.01807439 0.9510644 0.3014082 0.06804156 0.2608859 0.9653688 0.001305818 0.2106342 0.9769469 0.03475648 0.2602457 0.9655421 8.64395e-4 + + + + + + + + + + + + + + +

0 0 14 0 1 0 0 1 1 1 2 1 2 2 1 2 3 2 2 3 3 3 4 3 4 4 3 4 5 4 4 5 5 5 6 5 6 6 5 6 7 6 7 7 8 7 6 7 6 8 8 8 9 8 9 9 8 9 10 9 9 10 10 10 11 10 9 11 11 11 12 11 12 12 11 12 13 12 12 13 13 13 0 13 0 14 13 14 14 14 15 15 16 15 17 15 17 16 16 16 18 16 17 17 18 17 19 17 20 18 21 18 22 18 22 19 21 19 23 19 22 20 23 20 24 20 24 21 23 21 25 21 24 22 25 22 26 22 26 23 25 23 15 23 26 24 15 24 27 24 19 25 18 25 28 25 19 26 28 26 29 26 29 27 28 27 30 27 30 28 28 28 31 28 30 29 31 29 32 29 32 30 31 30 33 30 32 31 33 31 20 31 20 32 33 32 21 32 34 33 35 33 53 33 35 34 34 34 36 34 37 35 36 35 34 35 36 36 37 36 39 36 36 37 39 37 38 37 38 38 39 38 40 38 38 39 40 39 41 39 41 40 40 40 42 40 41 41 42 41 43 41 43 42 42 42 44 42 43 43 44 43 45 43 46 44 47 44 45 44 46 45 45 45 44 45 48 46 47 46 46 46 47 47 48 47 50 47 47 48 50 48 49 48 49 49 50 49 51 49 49 50 51 50 52 50 52 51 51 51 53 51 52 52 53 52 35 52 54 53 56 53 55 53 57 54 56 54 54 54 54 55 58 55 57 55 54 56 59 56 58 56 60 57 32 57 61 57 61 58 32 58 20 58 61 59 20 59 22 59 61 60 22 60 62 60 62 61 22 61 63 61 63 62 22 62 24 62 63 63 24 63 26 63 63 64 26 64 64 64 64 65 26 65 27 65 64 66 27 66 65 66 65 67 27 67 15 67 65 68 15 68 66 68 66 69 15 69 17 69 66 70 17 70 67 70 67 71 17 71 19 71 67 72 19 72 68 72 68 73 19 73 29 73 68 74 29 74 69 74 69 75 29 75 30 75 69 76 30 76 70 76 70 77 30 77 32 77 70 78 32 78 60 78 66 79 11 79 65 79 65 80 11 80 64 80 64 81 11 81 10 81 64 82 10 82 8 82 64 83 8 83 63 83 63 84 8 84 62 84 62 85 8 85 7 85 62 86 7 86 61 86 61 87 7 87 5 87 61 88 5 88 60 88 60 89 5 89 3 89 60 90 3 90 70 90 70 91 3 91 1 91 70 92 1 92 69 92 69 93 1 93 14 93 69 94 14 94 68 94 68 95 14 95 67 95 67 96 14 96 13 96 67 97 13 97 66 97 66 98 13 98 11 98 35 99 55 99 52 99 52 100 55 100 56 100 52 101 56 101 49 101 49 102 56 102 47 102 47 103 56 103 57 103 47 104 57 104 45 104 45 105 57 105 43 105 43 106 57 106 58 106 43 107 58 107 41 107 41 108 58 108 59 108 41 109 59 109 38 109 38 110 59 110 36 110 36 111 59 111 54 111 36 112 54 112 35 112 35 113 54 113 55 113 0 114 71 114 12 114 2 115 72 115 0 115 4 116 73 116 2 116 6 117 74 117 4 117 9 118 75 118 6 118 12 119 76 119 9 119 80 120 81 120 78 120 80 121 78 121 79 121 79 122 78 122 77 122 82 123 77 123 78 123 83 124 82 124 78 124 84 125 83 125 78 125 78 126 81 126 84 126 82 127 12 127 71 127 82 128 71 128 77 128 0 129 77 129 71 129 79 130 72 130 80 130 80 131 72 131 2 131 77 132 0 132 72 132 72 133 79 133 77 133 73 134 4 134 81 134 73 135 80 135 2 135 73 136 81 136 80 136 6 137 84 137 74 137 81 138 4 138 74 138 81 139 74 139 84 139 9 140 83 140 75 140 84 141 6 141 75 141 84 142 75 142 83 142 12 143 82 143 76 143 83 144 9 144 76 144 83 145 76 145 82 145 15 146 25 146 85 146 15 147 85 147 16 147 25 148 46 148 85 148 85 149 46 149 44 149 85 150 44 150 16 150 16 151 44 151 42 151 16 152 42 152 18 152 31 153 34 153 33 153 33 154 34 154 53 154 33 155 53 155 21 155 31 156 37 156 34 156 31 157 39 157 37 157 31 158 28 158 39 158 28 159 40 159 39 159 28 160 18 160 40 160 18 161 42 161 40 161 25 162 48 162 46 162 25 163 50 163 48 163 25 164 23 164 50 164 23 165 51 165 50 165 23 166 21 166 51 166 21 167 53 167 51 167 89 168 90 168 88 168 86 169 87 169 91 169 86 170 91 170 88 170 88 171 91 171 89 171 93 172 90 172 89 172 94 173 90 173 93 173 94 174 92 174 90 174 88 175 90 175 92 175 92 176 96 176 95 176 88 177 92 177 95 177 96 178 92 178 97 178 96 179 97 179 98 179 99 180 96 180 98 180 95 181 96 181 99 181 104 182 101 182 100 182 95 183 99 183 104 183 95 184 104 184 100 184 105 185 101 185 104 185 106 186 101 186 105 186 106 187 102 187 101 187 100 188 101 188 102 188 103 189 108 189 107 189 100 190 102 190 107 190 107 191 102 191 103 191 108 192 110 192 111 192 109 193 108 193 112 193 112 194 108 194 111 194 110 195 108 195 103 195 109 196 114 196 113 196 107 197 108 197 109 197 107 198 109 198 113 198 117 199 114 199 109 199 118 200 114 200 117 200 119 201 114 201 118 201 115 202 114 202 119 202 120 203 87 203 86 203 116 204 120 204 86 204 113 205 114 205 115 205 113 206 115 206 86 206 86 207 115 207 116 207 121 208 87 208 120 208 91 209 87 209 122 209 122 210 87 210 121 210 123 211 133 211 125 211 125 212 121 212 120 212 125 213 120 213 123 213 126 214 89 214 125 214 125 215 89 215 91 215 125 216 91 216 121 216 126 217 127 217 89 217 128 218 103 218 129 218 128 219 129 219 124 219 130 220 94 220 126 220 126 221 94 221 127 221 129 222 106 222 124 222 124 223 106 223 131 223 124 224 131 224 104 224 128 225 132 225 103 225 130 226 92 226 94 226 133 227 118 227 134 227 133 228 134 228 135 228 123 229 116 229 133 229 133 230 116 230 115 230 133 231 115 231 136 231 133 232 136 232 118 232 130 233 98 233 92 233 124 234 104 234 99 234 124 235 99 235 130 235 130 236 99 236 98 236 135 237 137 237 128 237 128 238 137 238 111 238 128 239 111 239 138 239 128 240 138 240 132 240 134 241 109 241 135 241 135 242 109 242 137 242 125 243 133 243 139 243 139 244 140 244 125 244 125 245 140 245 126 245 126 246 140 246 141 246 126 247 141 247 130 247 141 248 142 248 130 248 130 249 142 249 124 249 143 250 124 250 142 250 124 251 143 251 128 251 143 252 144 252 128 252 144 253 145 253 128 253 128 254 145 254 135 254 145 255 146 255 135 255 135 256 146 256 133 256 139 257 133 257 146 257 147 258 139 258 146 258 147 259 146 259 148 259 148 260 146 260 145 260 148 261 145 261 149 261 149 262 145 262 144 262 149 263 144 263 150 263 150 264 144 264 143 264 150 265 143 265 151 265 151 266 143 266 142 266 151 267 142 267 141 267 151 268 141 268 152 268 152 269 141 269 153 269 153 270 141 270 140 270 153 271 140 271 154 271 154 272 140 272 139 272 154 273 139 273 147 273 155 274 151 274 156 274 151 275 152 275 156 275 152 276 153 276 156 276 156 277 153 277 157 277 153 278 154 278 157 278 157 279 154 279 158 279 147 280 158 280 154 280 158 281 147 281 159 281 147 282 148 282 159 282 159 283 148 283 160 283 148 284 149 284 160 284 160 285 149 285 161 285 149 286 150 286 161 286 151 287 155 287 150 287 150 288 155 288 161 288 158 289 159 289 113 289 95 290 155 290 156 290 95 291 156 291 88 291 88 292 156 292 157 292 88 293 157 293 86 293 113 294 159 294 107 294 107 295 159 295 160 295 107 296 160 296 100 296 100 297 160 297 161 297 86 298 157 298 158 298 86 299 158 299 113 299 100 300 161 300 95 300 95 301 161 301 155 301 183 302 162 302 163 302 163 303 162 303 164 303 163 304 164 304 165 304 165 305 164 305 166 305 165 306 166 306 167 306 165 307 167 307 168 307 168 308 167 308 169 308 168 309 169 309 170 309 170 310 169 310 171 310 170 311 171 311 172 311 172 312 171 312 173 312 172 313 173 313 174 313 174 314 173 314 175 314 174 315 175 315 176 315 176 316 175 316 177 316 176 317 177 317 178 317 178 318 177 318 179 318 178 319 179 319 180 319 180 320 179 320 181 320 180 321 181 321 182 321 182 322 181 322 183 322 183 323 181 323 162 323 184 324 175 324 173 324 184 324 173 324 185 324 186 325 162 325 187 325 186 326 164 326 162 326 187 324 162 324 181 324 187 324 181 324 188 324 189 327 175 327 184 327 189 328 177 328 175 328 190 324 167 324 166 324 190 324 166 324 186 324 186 324 166 324 164 324 188 324 181 324 179 324 188 329 179 329 189 329 189 324 179 324 177 324 185 330 173 330 171 330 185 324 171 324 191 324 171 331 169 331 191 331 191 324 169 324 190 324 190 324 169 324 167 324 187 332 192 332 186 332 186 333 192 333 193 333 186 334 193 334 190 334 190 335 193 335 191 335 191 336 193 336 194 336 191 337 194 337 185 337 185 338 194 338 195 338 185 339 195 339 184 339 184 340 195 340 196 340 184 341 196 341 189 341 189 342 196 342 197 342 189 343 197 343 188 343 188 344 197 344 198 344 188 345 198 345 187 345 187 346 198 346 199 346 187 347 199 347 192 347 199 348 183 348 192 348 198 348 182 348 199 348 199 348 182 348 183 348 195 348 176 348 196 348 197 348 178 348 180 348 197 348 180 348 198 348 198 348 180 348 182 348 196 348 176 348 197 348 197 349 176 349 178 349 194 350 172 350 195 350 195 351 172 351 174 351 195 352 174 352 176 352 194 353 170 353 172 353 192 348 165 348 193 348 165 354 168 354 193 354 193 355 168 355 194 355 194 356 168 356 170 356 183 357 163 357 192 357 192 348 163 348 165 348 200 358 201 358 202 358 202 359 201 359 203 359 202 360 203 360 204 360 204 361 203 361 205 361 204 362 205 362 206 362 204 363 206 363 207 363 207 364 206 364 208 364 207 365 208 365 209 365 209 366 208 366 210 366 209 367 210 367 211 367 209 368 211 368 212 368 212 369 211 369 213 369 212 370 213 370 214 370 214 371 213 371 215 371 214 372 215 372 216 372 216 373 215 373 217 373 216 374 217 374 218 374 218 375 217 375 219 375 218 376 219 376 220 376 220 377 219 377 221 377 220 378 221 378 222 378 222 379 221 379 223 379 222 380 223 380 200 380 200 381 223 381 201 381 224 324 213 324 211 324 224 324 211 324 225 324 226 324 215 324 213 324 226 324 213 324 224 324 227 324 219 324 217 324 227 324 217 324 226 324 226 324 217 324 215 324 228 324 219 324 227 324 230 324 201 324 229 324 229 324 201 324 223 324 211 324 210 324 225 324 225 324 210 324 208 324 229 324 223 324 228 324 228 324 223 324 221 324 228 324 221 324 219 324 231 324 203 324 230 324 230 324 203 324 201 324 231 324 205 324 203 324 225 324 208 324 206 324 225 324 206 324 231 324 231 324 206 324 205 324 229 382 232 382 230 382 230 383 232 383 233 383 230 384 233 384 231 384 231 385 233 385 234 385 231 386 234 386 225 386 225 387 234 387 235 387 225 388 235 388 224 388 224 389 235 389 236 389 224 390 236 390 226 390 226 391 236 391 237 391 226 392 237 392 238 392 226 393 238 393 227 393 227 394 238 394 228 394 228 395 238 395 239 395 228 396 239 396 229 396 229 397 239 397 232 397 232 348 222 348 200 348 239 348 220 348 222 348 239 348 222 348 232 348 237 348 216 348 238 348 216 348 218 348 238 348 238 348 218 348 220 348 238 348 220 348 239 348 234 348 207 348 235 348 235 348 207 348 209 348 236 348 212 348 214 348 236 348 214 348 237 348 237 348 214 348 216 348 235 348 209 348 236 348 236 348 209 348 212 348 234 348 204 348 207 348 233 348 202 348 234 348 234 348 202 348 204 348 232 348 200 348 233 348 233 348 200 348 202 348 240 398 241 398 242 398 242 399 241 399 243 399 242 400 243 400 244 400 244 401 243 401 245 401 244 402 245 402 246 402 244 403 246 403 247 403 247 404 246 404 248 404 247 405 248 405 249 405 249 406 248 406 250 406 249 407 250 407 251 407 249 408 251 408 252 408 252 409 251 409 253 409 252 410 253 410 254 410 254 411 253 411 255 411 254 412 255 412 256 412 256 413 255 413 257 413 256 414 257 414 258 414 258 415 257 415 259 415 258 416 259 416 260 416 260 417 259 417 261 417 260 418 261 418 262 418 262 419 261 419 263 419 262 420 263 420 240 420 240 421 263 421 241 421 264 324 253 324 251 324 264 324 251 324 265 324 266 324 255 324 253 324 266 324 253 324 264 324 267 324 259 324 257 324 267 324 257 324 266 324 266 324 257 324 255 324 268 324 259 324 267 324 270 324 241 324 269 324 269 324 241 324 263 324 251 324 250 324 265 324 265 324 250 324 248 324 269 324 263 324 268 324 268 324 263 324 261 324 268 324 261 324 259 324 271 324 243 324 270 324 270 324 243 324 241 324 271 324 245 324 243 324 265 324 248 324 246 324 265 324 246 324 271 324 271 324 246 324 245 324 269 422 272 422 270 422 270 423 272 423 273 423 270 424 273 424 271 424 271 425 273 425 274 425 271 426 274 426 265 426 265 427 274 427 275 427 265 428 275 428 264 428 264 429 275 429 276 429 264 430 276 430 266 430 266 431 276 431 277 431 266 432 277 432 278 432 266 433 278 433 267 433 267 434 278 434 268 434 268 435 278 435 279 435 268 436 279 436 269 436 269 437 279 437 272 437 272 348 262 348 240 348 279 348 260 348 262 348 279 348 262 348 272 348 277 348 256 348 278 348 256 348 258 348 278 348 278 348 258 348 260 348 278 348 260 348 279 348 274 348 247 348 275 348 275 348 247 348 249 348 276 348 252 348 254 348 276 348 254 348 277 348 277 348 254 348 256 348 275 348 249 348 276 348 276 348 249 348 252 348 274 348 244 348 247 348 273 348 242 348 274 348 274 348 242 348 244 348 272 348 240 348 273 348 273 348 240 348 242 348 283 438 284 438 282 438 280 439 281 439 285 439 280 440 285 440 282 440 282 441 285 441 283 441 287 442 284 442 283 442 288 443 284 443 287 443 288 444 286 444 284 444 282 445 284 445 286 445 286 446 290 446 289 446 282 447 286 447 289 447 290 448 286 448 291 448 290 449 291 449 292 449 293 450 290 450 292 450 289 451 290 451 293 451 298 452 295 452 294 452 289 453 293 453 298 453 289 454 298 454 294 454 299 455 295 455 298 455 300 456 295 456 299 456 300 457 296 457 295 457 294 458 295 458 296 458 297 459 302 459 301 459 294 460 296 460 301 460 301 461 296 461 297 461 302 462 304 462 305 462 303 463 302 463 306 463 306 464 302 464 305 464 304 465 302 465 297 465 303 466 308 466 307 466 301 467 302 467 303 467 301 468 303 468 307 468 311 469 308 469 303 469 312 470 308 470 311 470 313 471 308 471 312 471 309 472 308 472 313 472 314 473 281 473 280 473 310 474 314 474 280 474 307 475 308 475 309 475 307 476 309 476 280 476 280 477 309 477 310 477 315 478 281 478 314 478 285 479 281 479 316 479 316 480 281 480 315 480 317 481 327 481 319 481 319 482 315 482 314 482 319 483 314 483 317 483 320 484 283 484 319 484 319 485 283 485 285 485 319 486 285 486 315 486 320 487 321 487 283 487 322 488 297 488 323 488 322 489 323 489 318 489 324 490 288 490 320 490 320 491 288 491 321 491 323 492 300 492 318 492 318 493 300 493 325 493 318 494 325 494 298 494 322 495 326 495 297 495 324 496 286 496 288 496 327 497 312 497 328 497 327 498 328 498 329 498 317 499 310 499 327 499 327 500 310 500 309 500 327 501 309 501 330 501 327 502 330 502 312 502 324 503 292 503 286 503 318 504 298 504 293 504 318 505 293 505 324 505 324 506 293 506 292 506 329 507 331 507 322 507 322 508 331 508 305 508 322 509 305 509 332 509 322 510 332 510 326 510 328 511 303 511 329 511 329 512 303 512 331 512 319 513 327 513 333 513 333 514 334 514 319 514 319 515 334 515 320 515 320 516 334 516 335 516 320 517 335 517 324 517 335 518 336 518 324 518 324 519 336 519 318 519 337 520 318 520 336 520 318 521 337 521 322 521 337 522 338 522 322 522 338 523 339 523 322 523 322 524 339 524 329 524 339 525 340 525 329 525 329 526 340 526 327 526 333 527 327 527 340 527 341 528 333 528 340 528 341 529 340 529 342 529 342 530 340 530 339 530 342 531 339 531 343 531 343 532 339 532 338 532 343 533 338 533 344 533 344 534 338 534 337 534 344 535 337 535 345 535 345 536 337 536 336 536 345 537 336 537 335 537 345 538 335 538 346 538 346 539 335 539 347 539 347 540 335 540 334 540 347 541 334 541 348 541 348 542 334 542 333 542 348 543 333 543 341 543 349 544 345 544 350 544 345 545 346 545 350 545 346 546 347 546 350 546 350 547 347 547 351 547 347 548 348 548 351 548 351 549 348 549 352 549 341 550 352 550 348 550 352 551 341 551 353 551 341 552 342 552 353 552 353 553 342 553 354 553 342 554 343 554 354 554 354 555 343 555 355 555 343 556 344 556 355 556 345 557 349 557 344 557 344 558 349 558 355 558 352 559 353 559 307 559 289 560 349 560 350 560 289 561 350 561 282 561 282 562 350 562 351 562 282 563 351 563 280 563 307 564 353 564 301 564 301 565 353 565 354 565 301 566 354 566 294 566 294 567 354 567 355 567 280 568 351 568 352 568 280 569 352 569 307 569 294 570 355 570 289 570 289 571 355 571 349 571 378 572 356 572 357 572 357 573 356 573 358 573 357 574 358 574 359 574 357 575 359 575 360 575 360 576 359 576 361 576 360 577 361 577 362 577 362 578 361 578 363 578 363 579 361 579 364 579 363 580 364 580 365 580 365 581 364 581 366 581 365 582 366 582 367 582 367 583 366 583 368 583 367 584 368 584 369 584 367 585 369 585 370 585 370 586 369 586 371 586 371 587 369 587 372 587 371 588 372 588 373 588 371 589 373 589 374 589 374 590 373 590 375 590 374 591 375 591 376 591 376 592 375 592 377 592 376 593 377 593 378 593 378 594 377 594 356 594 379 324 368 324 366 324 379 324 366 324 380 324 381 324 356 324 382 324 383 324 359 324 358 324 383 324 358 324 381 324 381 324 358 324 356 324 356 595 377 595 382 595 384 324 369 324 379 324 379 324 369 324 368 324 385 596 372 596 384 596 384 324 372 324 369 324 386 324 361 324 359 324 386 324 359 324 383 324 377 597 375 597 382 597 382 324 375 324 385 324 385 598 375 598 373 598 385 599 373 599 372 599 380 324 366 324 364 324 380 324 364 324 361 324 380 324 361 324 386 324 381 600 387 600 383 600 383 601 387 601 388 601 383 602 388 602 386 602 386 603 388 603 389 603 386 604 389 604 380 604 380 605 389 605 390 605 380 606 390 606 379 606 379 607 390 607 391 607 379 608 391 608 384 608 384 609 391 609 392 609 384 610 392 610 385 610 385 611 392 611 393 611 385 612 393 612 382 612 382 613 393 613 394 613 382 614 394 614 387 614 382 615 387 615 381 615 394 348 378 348 387 348 393 348 376 348 394 348 394 348 376 348 378 348 392 616 371 616 393 616 393 348 371 348 374 348 393 348 374 348 376 348 367 348 370 348 391 348 391 348 370 348 392 348 392 348 370 348 371 348 390 348 365 348 391 348 391 617 365 617 367 617 390 618 363 618 365 618 388 348 360 348 389 348 389 348 360 348 362 348 389 619 362 619 390 619 390 348 362 348 363 348 378 348 357 348 387 348 387 348 357 348 388 348 388 348 357 348 360 348 398 620 399 620 397 620 395 621 396 621 400 621 395 622 400 622 397 622 397 623 400 623 398 623 402 624 399 624 398 624 403 625 399 625 402 625 403 626 401 626 399 626 397 627 399 627 401 627 401 628 405 628 404 628 397 629 401 629 404 629 405 630 401 630 406 630 405 631 406 631 407 631 408 632 405 632 407 632 404 633 405 633 408 633 413 634 410 634 409 634 404 635 408 635 413 635 404 636 413 636 409 636 414 637 410 637 413 637 415 638 410 638 414 638 415 639 411 639 410 639 409 640 410 640 411 640 412 641 417 641 416 641 409 642 411 642 416 642 416 643 411 643 412 643 417 644 419 644 420 644 418 645 417 645 421 645 421 646 417 646 420 646 419 647 417 647 412 647 418 648 423 648 422 648 416 649 417 649 418 649 416 650 418 650 422 650 426 651 423 651 418 651 427 652 423 652 426 652 428 653 423 653 427 653 424 654 423 654 428 654 429 655 396 655 395 655 425 656 429 656 395 656 422 657 423 657 424 657 422 658 424 658 395 658 395 659 424 659 425 659 430 660 396 660 429 660 400 661 396 661 431 661 431 662 396 662 430 662 432 663 442 663 434 663 434 664 430 664 429 664 434 665 429 665 432 665 435 666 398 666 434 666 434 667 398 667 400 667 434 668 400 668 430 668 435 669 436 669 398 669 437 670 412 670 438 670 437 671 438 671 433 671 439 672 403 672 435 672 435 673 403 673 436 673 438 674 415 674 433 674 433 675 415 675 440 675 433 676 440 676 413 676 437 677 441 677 412 677 439 678 401 678 403 678 442 679 427 679 443 679 442 680 443 680 444 680 432 681 425 681 442 681 442 682 425 682 424 682 442 683 424 683 445 683 442 684 445 684 427 684 439 685 407 685 401 685 433 686 413 686 408 686 433 687 408 687 439 687 439 688 408 688 407 688 444 689 446 689 437 689 437 690 446 690 420 690 437 691 420 691 447 691 437 692 447 692 441 692 443 693 418 693 444 693 444 694 418 694 446 694 434 695 442 695 448 695 448 696 449 696 434 696 434 697 449 697 435 697 435 698 449 698 450 698 435 699 450 699 439 699 450 700 451 700 439 700 439 701 451 701 433 701 452 702 433 702 451 702 433 703 452 703 437 703 452 704 453 704 437 704 453 705 454 705 437 705 437 706 454 706 444 706 454 707 455 707 444 707 444 708 455 708 442 708 448 709 442 709 455 709 456 710 448 710 455 710 456 711 455 711 457 711 457 712 455 712 454 712 457 713 454 713 458 713 458 714 454 714 453 714 458 715 453 715 459 715 459 716 453 716 452 716 459 717 452 717 460 717 460 718 452 718 451 718 460 719 451 719 450 719 460 720 450 720 461 720 461 721 450 721 462 721 462 722 450 722 449 722 462 723 449 723 463 723 463 724 449 724 448 724 463 725 448 725 456 725 464 726 460 726 465 726 460 727 461 727 465 727 461 728 462 728 465 728 465 729 462 729 466 729 462 730 463 730 466 730 466 731 463 731 467 731 456 732 467 732 463 732 467 733 456 733 468 733 456 734 457 734 468 734 468 735 457 735 469 735 457 736 458 736 469 736 469 737 458 737 470 737 458 738 459 738 470 738 460 739 464 739 459 739 459 740 464 740 470 740 467 741 468 741 422 741 404 742 464 742 465 742 404 743 465 743 397 743 397 744 465 744 466 744 397 745 466 745 395 745 422 746 468 746 416 746 416 747 468 747 469 747 416 748 469 748 409 748 409 749 469 749 470 749 395 750 466 750 467 750 395 751 467 751 422 751 409 752 470 752 404 752 404 753 470 753 464 753 492 754 471 754 472 754 472 755 471 755 473 755 472 756 473 756 474 756 474 757 473 757 475 757 474 758 475 758 476 758 474 759 476 759 477 759 477 760 476 760 478 760 477 761 478 761 479 761 479 762 478 762 480 762 479 763 480 763 481 763 481 764 480 764 482 764 481 765 482 765 483 765 483 766 482 766 484 766 483 767 484 767 485 767 485 768 484 768 486 768 485 769 486 769 487 769 487 770 486 770 488 770 487 771 488 771 489 771 489 772 488 772 490 772 489 773 490 773 491 773 491 774 490 774 492 774 492 775 490 775 471 775 493 324 484 324 482 324 493 324 482 324 494 324 495 776 471 776 496 776 495 777 473 777 471 777 496 324 471 324 490 324 496 324 490 324 497 324 498 324 484 324 493 324 498 324 486 324 484 324 499 778 476 778 475 778 499 324 475 324 495 324 495 324 475 324 473 324 497 324 490 324 488 324 497 324 488 324 498 324 498 779 488 779 486 779 494 324 482 324 480 324 494 780 480 780 500 780 480 324 478 324 500 324 500 324 478 324 499 324 499 781 478 781 476 781 496 782 501 782 495 782 495 783 501 783 502 783 495 784 502 784 499 784 499 785 502 785 500 785 500 786 502 786 503 786 500 787 503 787 494 787 494 788 503 788 504 788 494 789 504 789 493 789 493 790 504 790 505 790 493 791 505 791 498 791 498 792 505 792 506 792 498 793 506 793 497 793 497 794 506 794 507 794 497 795 507 795 496 795 496 796 507 796 508 796 496 797 508 797 501 797 508 348 492 348 501 348 507 348 491 348 508 348 508 348 491 348 492 348 504 798 485 798 505 798 506 799 487 799 489 799 506 348 489 348 507 348 507 800 489 800 491 800 505 348 485 348 506 348 506 348 485 348 487 348 503 348 481 348 504 348 504 801 481 801 483 801 504 348 483 348 485 348 503 802 479 802 481 802 501 803 474 803 502 803 474 348 477 348 502 348 502 348 477 348 503 348 503 804 477 804 479 804 492 805 472 805 501 805 501 806 472 806 474 806 513 807 510 807 511 807 509 808 541 808 512 808 509 809 512 809 511 809 511 810 512 810 513 810 516 811 510 811 515 811 515 812 510 812 513 812 516 813 514 813 510 813 519 814 517 814 518 814 511 815 510 815 514 815 514 816 519 816 518 816 511 817 514 817 518 817 520 818 517 818 519 818 518 819 517 819 520 819 523 820 524 820 522 820 518 821 520 821 521 821 518 822 521 822 522 822 522 823 521 823 523 823 526 824 524 824 523 824 527 825 524 825 526 825 527 826 525 826 524 826 525 827 528 827 529 827 522 828 524 828 525 828 522 829 525 829 529 829 528 830 531 830 532 830 532 831 533 831 528 831 531 832 528 832 525 832 536 833 534 833 535 833 529 834 528 834 533 834 530 835 536 835 535 835 529 836 533 836 530 836 529 837 530 837 535 837 539 838 534 838 538 838 538 839 534 839 536 839 537 840 534 840 540 840 540 841 534 841 539 841 537 842 541 842 509 842 535 843 534 843 537 843 535 844 537 844 509 844 542 845 541 845 537 845 543 846 541 846 542 846 544 847 512 847 543 847 543 848 512 848 541 848 537 849 547 849 546 849 521 850 545 850 549 850 545 851 521 851 520 851 546 852 543 852 537 852 547 853 538 853 548 853 547 854 537 854 539 854 547 855 539 855 538 855 551 856 513 856 546 856 546 857 513 857 544 857 546 858 544 858 543 858 551 859 515 859 513 859 549 860 550 860 526 860 549 861 526 861 521 861 531 862 525 862 548 862 548 863 525 863 549 863 549 864 525 864 550 864 551 865 514 865 552 865 551 866 552 866 515 866 545 867 520 867 519 867 545 868 519 868 551 868 548 869 533 869 553 869 548 870 553 870 531 870 519 871 514 871 551 871 538 872 530 872 548 872 548 873 530 873 533 873 546 874 547 874 554 874 554 875 555 875 546 875 546 876 555 876 551 876 551 877 555 877 556 877 551 878 556 878 545 878 556 879 557 879 545 879 558 880 545 880 557 880 549 881 545 881 558 881 558 882 559 882 549 882 549 883 559 883 548 883 548 884 559 884 560 884 548 885 560 885 547 885 560 886 561 886 547 886 554 887 547 887 561 887 562 888 554 888 561 888 562 889 561 889 560 889 562 890 560 890 563 890 563 891 560 891 564 891 564 892 560 892 559 892 564 893 559 893 565 893 565 894 559 894 558 894 565 895 558 895 566 895 566 896 558 896 557 896 566 897 557 897 556 897 566 898 556 898 567 898 567 899 556 899 568 899 568 900 556 900 555 900 568 901 555 901 569 901 569 902 555 902 554 902 569 903 554 903 562 903 570 904 566 904 571 904 566 905 567 905 571 905 567 906 568 906 571 906 571 907 568 907 572 907 568 908 569 908 572 908 572 909 569 909 573 909 562 910 573 910 569 910 573 911 562 911 574 911 562 912 563 912 574 912 563 913 564 913 574 913 574 914 564 914 575 914 564 915 565 915 575 915 575 916 565 916 570 916 566 917 570 917 565 917 575 918 570 918 522 918 522 919 570 919 518 919 511 920 571 920 572 920 511 921 572 921 509 921 529 922 574 922 575 922 529 923 575 923 522 923 518 924 570 924 571 924 518 925 571 925 511 925 509 926 572 926 573 926 509 927 573 927 535 927 535 928 573 928 574 928 535 929 574 929 529 929 579 930 577 930 578 930 576 931 608 931 579 931 576 932 579 932 578 932 582 933 577 933 581 933 581 934 577 934 579 934 582 935 580 935 577 935 584 936 588 936 583 936 578 937 577 937 580 937 580 938 584 938 583 938 578 939 580 939 583 939 584 940 585 940 586 940 584 941 586 941 588 941 587 942 588 942 586 942 587 943 589 943 588 943 589 944 591 944 590 944 583 945 588 945 589 945 583 946 589 946 590 946 594 947 591 947 593 947 593 948 591 948 589 948 592 949 591 949 595 949 595 950 591 950 594 950 592 951 596 951 597 951 590 952 591 952 597 952 597 953 591 953 592 953 596 954 599 954 600 954 600 955 601 955 596 955 599 956 596 956 592 956 597 957 596 957 601 957 598 958 603 958 602 958 597 959 601 959 598 959 597 960 598 960 602 960 603 961 604 961 605 961 606 962 603 962 598 962 607 963 603 963 606 963 604 964 603 964 607 964 605 965 608 965 576 965 602 966 603 966 576 966 576 967 603 967 605 967 609 968 608 968 605 968 610 969 608 969 609 969 610 970 579 970 608 970 611 971 616 971 613 971 589 972 612 972 623 972 612 973 589 973 586 973 613 974 614 974 615 974 613 975 615 975 609 975 613 976 609 976 611 976 616 977 617 977 618 977 616 978 618 978 619 978 611 979 605 979 616 979 616 980 605 980 620 980 616 981 620 981 621 981 616 982 621 982 622 982 616 983 622 983 617 983 626 984 579 984 613 984 613 985 579 985 614 985 626 986 581 986 579 986 623 987 594 987 624 987 623 988 624 988 589 988 599 989 592 989 619 989 619 990 592 990 623 990 623 991 592 991 625 991 623 992 625 992 594 992 626 993 580 993 627 993 626 994 627 994 581 994 612 995 586 995 585 995 612 996 585 996 626 996 619 997 601 997 628 997 619 998 628 998 599 998 626 999 585 999 580 999 618 1000 598 1000 619 1000 619 1001 598 1001 601 1001 613 1002 616 1002 629 1002 629 1003 630 1003 613 1003 613 1004 630 1004 626 1004 626 1005 630 1005 631 1005 626 1006 631 1006 612 1006 631 1007 632 1007 612 1007 633 1008 612 1008 632 1008 623 1009 612 1009 633 1009 633 1010 634 1010 623 1010 623 1011 634 1011 619 1011 619 1012 634 1012 635 1012 619 1013 635 1013 616 1013 635 1014 636 1014 616 1014 629 1015 616 1015 636 1015 637 1016 629 1016 636 1016 637 1017 636 1017 635 1017 637 1018 635 1018 638 1018 638 1019 635 1019 639 1019 639 1020 635 1020 634 1020 639 1021 634 1021 640 1021 640 1022 634 1022 633 1022 640 1023 633 1023 641 1023 641 1024 633 1024 632 1024 641 1025 632 1025 631 1025 641 1026 631 1026 642 1026 642 1027 631 1027 643 1027 643 1028 631 1028 630 1028 643 1029 630 1029 644 1029 644 1030 630 1030 629 1030 644 1031 629 1031 637 1031 645 1032 641 1032 646 1032 641 1033 642 1033 646 1033 642 1034 643 1034 646 1034 646 1035 643 1035 647 1035 643 1036 644 1036 647 1036 647 1037 644 1037 648 1037 637 1038 648 1038 644 1038 648 1039 637 1039 649 1039 637 1040 638 1040 649 1040 638 1041 639 1041 649 1041 649 1042 639 1042 650 1042 639 1043 640 1043 650 1043 650 1044 640 1044 645 1044 641 1045 645 1045 640 1045 650 1046 645 1046 590 1046 590 1047 645 1047 583 1047 578 1048 646 1048 647 1048 578 1049 647 1049 576 1049 597 1050 649 1050 650 1050 597 1051 650 1051 590 1051 583 1052 645 1052 646 1052 583 1053 646 1053 578 1053 576 1054 647 1054 648 1054 576 1055 648 1055 602 1055 602 1056 648 1056 649 1056 602 1057 649 1057 597 1057 672 1058 651 1058 652 1058 652 1059 651 1059 653 1059 652 1060 653 1060 654 1060 654 1061 653 1061 655 1061 654 1062 655 1062 656 1062 654 1063 656 1063 657 1063 657 1064 656 1064 658 1064 657 1065 658 1065 659 1065 659 1066 658 1066 660 1066 659 1067 660 1067 661 1067 661 1068 660 1068 662 1068 661 1069 662 1069 663 1069 663 1070 662 1070 664 1070 663 1071 664 1071 665 1071 665 1072 664 1072 666 1072 665 1073 666 1073 667 1073 667 1074 666 1074 668 1074 667 1075 668 1075 669 1075 669 1076 668 1076 670 1076 669 1077 670 1077 671 1077 671 1078 670 1078 672 1078 672 1079 670 1079 651 1079 673 324 664 324 662 324 673 324 662 324 674 324 675 1080 651 1080 676 1080 675 1081 653 1081 651 1081 676 324 651 324 670 324 676 324 670 324 677 324 678 1082 664 1082 673 1082 678 1083 666 1083 664 1083 679 324 656 324 655 324 679 324 655 324 675 324 675 324 655 324 653 324 677 324 670 324 668 324 677 1084 668 1084 678 1084 678 324 668 324 666 324 674 1085 662 1085 660 1085 674 324 660 324 680 324 660 1086 658 1086 680 1086 680 324 658 324 679 324 679 324 658 324 656 324 676 1087 681 1087 675 1087 675 1088 681 1088 682 1088 675 1089 682 1089 679 1089 679 1090 682 1090 680 1090 680 1091 682 1091 683 1091 680 1092 683 1092 674 1092 674 1093 683 1093 684 1093 674 1094 684 1094 673 1094 673 1095 684 1095 685 1095 673 1096 685 1096 678 1096 678 1097 685 1097 686 1097 678 1098 686 1098 677 1098 677 1099 686 1099 687 1099 677 1100 687 1100 676 1100 676 1101 687 1101 688 1101 676 1102 688 1102 681 1102 688 348 672 348 681 348 687 348 671 348 688 348 688 348 671 348 672 348 684 348 665 348 685 348 686 348 667 348 669 348 686 348 669 348 687 348 687 348 669 348 671 348 685 348 665 348 686 348 686 1103 665 1103 667 1103 683 1104 661 1104 684 1104 684 1105 661 1105 663 1105 684 1106 663 1106 665 1106 683 1107 659 1107 661 1107 681 348 654 348 682 348 654 1108 657 1108 682 1108 682 1109 657 1109 683 1109 683 1110 657 1110 659 1110 672 1111 652 1111 681 1111 681 348 652 348 654 348 711 1112 689 1112 690 1112 690 1113 689 1113 691 1113 690 1114 691 1114 692 1114 690 1115 692 1115 693 1115 693 1116 692 1116 694 1116 693 1117 694 1117 695 1117 695 1118 694 1118 696 1118 696 1119 694 1119 697 1119 696 1120 697 1120 698 1120 698 1121 697 1121 699 1121 698 1122 699 1122 700 1122 700 1123 699 1123 701 1123 700 1124 701 1124 702 1124 700 1125 702 1125 703 1125 703 1126 702 1126 704 1126 704 1127 702 1127 705 1127 704 1128 705 1128 706 1128 704 1129 706 1129 707 1129 707 1130 706 1130 708 1130 707 1131 708 1131 709 1131 709 1132 708 1132 710 1132 709 1133 710 1133 711 1133 711 1134 710 1134 689 1134 712 324 701 324 699 324 712 324 699 324 713 324 714 324 689 324 715 324 716 324 692 324 691 324 716 324 691 324 714 324 714 324 691 324 689 324 689 1135 710 1135 715 1135 717 324 702 324 712 324 712 324 702 324 701 324 718 1136 705 1136 717 1136 717 324 705 324 702 324 719 324 694 324 692 324 719 324 692 324 716 324 710 1137 708 1137 715 1137 715 324 708 324 718 324 718 1138 708 1138 706 1138 718 1139 706 1139 705 1139 713 324 699 324 697 324 713 324 697 324 694 324 713 324 694 324 719 324 714 1140 720 1140 716 1140 716 1141 720 1141 721 1141 716 1142 721 1142 719 1142 719 1143 721 1143 722 1143 719 1144 722 1144 713 1144 713 1145 722 1145 723 1145 713 1146 723 1146 712 1146 712 1147 723 1147 724 1147 712 1148 724 1148 717 1148 717 1149 724 1149 725 1149 717 1150 725 1150 718 1150 718 1151 725 1151 726 1151 718 1152 726 1152 715 1152 715 1153 726 1153 727 1153 715 1154 727 1154 720 1154 715 1155 720 1155 714 1155 727 348 711 348 720 348 726 348 709 348 727 348 727 348 709 348 711 348 725 1156 704 1156 726 1156 726 348 704 348 707 348 726 348 707 348 709 348 700 348 703 348 724 348 724 348 703 348 725 348 725 348 703 348 704 348 723 348 698 348 724 348 724 1157 698 1157 700 1157 723 1158 696 1158 698 1158 721 348 693 348 722 348 722 348 693 348 695 348 722 1159 695 1159 723 1159 723 348 695 348 696 348 711 348 690 348 720 348 720 348 690 348 721 348 721 348 690 348 693 348 738 1160 728 1160 729 1160 729 1161 728 1161 730 1161 729 1162 730 1162 731 1162 731 1163 730 1163 732 1163 731 1164 732 1164 733 1164 733 1165 732 1165 734 1165 733 1166 734 1166 735 1166 736 1167 741 1167 737 1167 736 1168 737 1168 738 1168 738 1169 737 1169 728 1169 733 1170 735 1170 739 1170 739 1171 735 1171 740 1171 739 1172 740 1172 736 1172 736 1173 740 1173 741 1173 742 1174 749 1174 743 1174 743 1175 749 1175 744 1175 743 1176 744 1176 745 1176 746 1177 747 1177 748 1177 748 1178 747 1178 749 1178 748 1179 749 1179 742 1179 744 1180 750 1180 745 1180 745 1181 750 1181 751 1181 751 1182 750 1182 752 1182 752 1183 750 1183 753 1183 752 1184 753 1184 754 1184 754 1185 753 1185 755 1185 754 1186 755 1186 756 1186 756 1187 755 1187 757 1187 757 1188 755 1188 758 1188 757 1189 758 1189 759 1189 759 1190 758 1190 760 1190 759 1191 760 1191 761 1191 761 1192 760 1192 746 1192 746 1193 760 1193 747 1193 763 1194 762 1194 765 1194 763 1195 765 1195 764 1195 764 1196 765 1196 766 1196 764 1197 766 1197 767 1197 767 1198 766 1198 768 1198 767 1199 768 1199 813 1199 767 1200 813 1200 769 1200 770 1201 769 1201 813 1201 769 1202 770 1202 772 1202 769 1203 772 1203 771 1203 771 1204 772 1204 773 1204 771 1205 773 1205 774 1205 774 1206 773 1206 775 1206 774 1207 775 1207 776 1207 777 1208 776 1208 775 1208 776 1209 777 1209 779 1209 776 1210 779 1210 778 1210 778 1211 779 1211 780 1211 778 1212 780 1212 781 1212 781 1213 780 1213 814 1213 781 1214 814 1214 763 1214 763 1215 814 1215 762 1215 783 1216 782 1216 784 1216 783 1217 786 1217 785 1217 787 1218 786 1218 783 1218 784 1219 787 1219 783 1219 788 1220 761 1220 746 1220 788 1221 746 1221 789 1221 789 1222 746 1222 748 1222 789 1223 748 1223 790 1223 790 1224 748 1224 742 1224 790 1225 742 1225 791 1225 791 1226 742 1226 743 1226 791 1227 743 1227 792 1227 792 1228 743 1228 745 1228 792 1229 745 1229 793 1229 793 1230 745 1230 794 1230 794 1231 745 1231 751 1231 794 1232 751 1232 795 1232 795 1233 751 1233 752 1233 795 1234 752 1234 754 1234 795 1235 754 1235 796 1235 796 1236 754 1236 797 1236 797 1237 754 1237 756 1237 797 1238 756 1238 798 1238 798 1239 756 1239 757 1239 798 1240 757 1240 759 1240 798 1241 759 1241 799 1241 799 1242 759 1242 761 1242 799 1243 761 1243 788 1243 794 1244 737 1244 793 1244 793 1245 737 1245 741 1245 793 1246 741 1246 792 1246 792 1247 741 1247 791 1247 791 1248 741 1248 740 1248 791 1249 740 1249 790 1249 790 1250 740 1250 789 1250 789 1251 740 1251 735 1251 789 1252 735 1252 788 1252 788 1253 735 1253 734 1253 788 1254 734 1254 799 1254 799 1255 734 1255 732 1255 799 1256 732 1256 798 1256 798 1257 732 1257 730 1257 798 1258 730 1258 797 1258 797 1259 730 1259 796 1259 796 1260 730 1260 728 1260 796 1261 728 1261 795 1261 795 1262 728 1262 737 1262 795 1263 737 1263 794 1263 763 1264 782 1264 781 1264 781 1265 782 1265 778 1265 778 1266 782 1266 783 1266 778 1267 783 1267 776 1267 776 1268 783 1268 785 1268 776 1269 785 1269 774 1269 774 1270 785 1270 786 1270 774 1271 786 1271 771 1271 771 1272 786 1272 769 1272 769 1273 786 1273 787 1273 769 1274 787 1274 767 1274 767 1275 787 1275 784 1275 767 1276 784 1276 764 1276 764 1277 784 1277 763 1277 763 1278 784 1278 782 1278 729 1279 800 1279 738 1279 731 1280 801 1280 729 1280 733 1281 802 1281 731 1281 739 1282 803 1282 733 1282 736 1283 804 1283 739 1283 738 1284 805 1284 736 1284 807 1285 808 1285 809 1285 810 1286 806 1286 807 1286 811 1287 810 1287 807 1287 809 1288 811 1288 807 1288 807 1289 812 1289 808 1289 806 1290 812 1290 807 1290 729 1291 811 1291 800 1291 809 1292 738 1292 800 1292 809 1293 800 1293 811 1293 731 1294 810 1294 801 1294 811 1295 729 1295 801 1295 811 1296 801 1296 810 1296 733 1297 806 1297 802 1297 810 1298 731 1298 802 1298 810 1299 802 1299 806 1299 739 1300 812 1300 803 1300 806 1301 733 1301 803 1301 806 1302 803 1302 812 1302 736 1303 808 1303 804 1303 812 1304 739 1304 804 1304 812 1305 804 1305 808 1305 738 1306 809 1306 805 1306 808 1307 736 1307 805 1307 808 1308 805 1308 809 1308 755 1309 753 1309 813 1309 758 1310 765 1310 760 1310 753 1311 772 1311 770 1311 753 1312 770 1312 813 1312 749 1313 779 1313 777 1313 749 1314 777 1314 744 1314 744 1315 777 1315 775 1315 760 1316 765 1316 762 1316 760 1317 762 1317 814 1317 758 1318 766 1318 765 1318 758 1319 755 1319 768 1319 758 1320 768 1320 766 1320 755 1321 813 1321 768 1321 753 1322 750 1322 772 1322 750 1323 773 1323 772 1323 750 1324 744 1324 773 1324 744 1325 775 1325 773 1325 749 1326 747 1326 779 1326 747 1327 780 1327 779 1327 747 1328 814 1328 780 1328 747 1329 760 1329 814 1329 815 1330 816 1330 817 1330 817 1331 816 1331 818 1331 817 1332 818 1332 819 1332 819 1333 818 1333 820 1333 819 1334 820 1334 821 1334 819 1335 821 1335 822 1335 822 1336 821 1336 823 1336 822 1337 823 1337 824 1337 824 1338 823 1338 825 1338 824 1339 825 1339 826 1339 824 1340 826 1340 827 1340 827 1341 826 1341 828 1341 827 1342 828 1342 829 1342 829 1343 828 1343 830 1343 829 1344 830 1344 831 1344 831 1345 830 1345 832 1345 831 1346 832 1346 833 1346 833 1347 832 1347 834 1347 833 1348 834 1348 835 1348 835 1349 834 1349 836 1349 835 1350 836 1350 837 1350 837 1351 836 1351 838 1351 837 1352 838 1352 815 1352 815 1353 838 1353 816 1353 839 324 828 324 826 324 839 324 826 324 840 324 841 324 830 324 828 324 841 324 828 324 839 324 842 324 834 324 832 324 842 324 832 324 841 324 841 324 832 324 830 324 843 324 834 324 842 324 845 324 816 324 844 324 844 324 816 324 838 324 826 324 825 324 840 324 840 324 825 324 823 324 844 324 838 324 843 324 843 324 838 324 836 324 843 324 836 324 834 324 846 324 818 324 845 324 845 324 818 324 816 324 846 324 820 324 818 324 840 324 823 324 821 324 840 324 821 324 846 324 846 324 821 324 820 324 844 1354 847 1354 845 1354 845 1355 847 1355 848 1355 845 1356 848 1356 846 1356 846 1357 848 1357 849 1357 846 1358 849 1358 840 1358 840 1359 849 1359 850 1359 840 1360 850 1360 839 1360 839 1361 850 1361 851 1361 839 1362 851 1362 841 1362 841 1363 851 1363 852 1363 841 1364 852 1364 853 1364 841 1365 853 1365 842 1365 842 1366 853 1366 843 1366 843 1367 853 1367 854 1367 843 1368 854 1368 844 1368 844 1369 854 1369 847 1369 847 348 837 348 815 348 854 348 835 348 837 348 854 348 837 348 847 348 852 348 831 348 853 348 831 348 833 348 853 348 853 348 833 348 835 348 853 348 835 348 854 348 849 348 822 348 850 348 850 348 822 348 824 348 851 348 827 348 829 348 851 348 829 348 852 348 852 348 829 348 831 348 850 348 824 348 851 348 851 348 824 348 827 348 849 348 819 348 822 348 848 348 817 348 849 348 849 348 817 348 819 348 847 348 815 348 848 348 848 348 815 348 817 348 865 1370 855 1370 856 1370 856 1371 855 1371 857 1371 856 1372 857 1372 858 1372 858 1373 857 1373 859 1373 858 1374 859 1374 860 1374 860 1375 859 1375 861 1375 860 1376 861 1376 862 1376 863 1377 868 1377 864 1377 863 1378 864 1378 865 1378 865 1379 864 1379 855 1379 860 1380 862 1380 866 1380 866 1381 862 1381 867 1381 866 1382 867 1382 863 1382 863 1383 867 1383 868 1383 869 1384 876 1384 870 1384 870 1385 876 1385 871 1385 870 1386 871 1386 872 1386 873 1387 874 1387 875 1387 875 1388 874 1388 876 1388 875 1389 876 1389 869 1389 871 1390 877 1390 872 1390 872 1391 877 1391 878 1391 878 1392 877 1392 879 1392 879 1393 877 1393 880 1393 879 1394 880 1394 881 1394 881 1395 880 1395 882 1395 881 1396 882 1396 883 1396 883 1397 882 1397 884 1397 884 1398 882 1398 885 1398 884 1399 885 1399 886 1399 886 1400 885 1400 887 1400 886 1401 887 1401 888 1401 888 1402 887 1402 873 1402 873 1403 887 1403 874 1403 890 1404 889 1404 892 1404 890 1405 892 1405 891 1405 891 1406 892 1406 893 1406 891 1407 893 1407 894 1407 894 1408 893 1408 895 1408 894 1409 895 1409 940 1409 894 1410 940 1410 896 1410 897 1411 896 1411 940 1411 896 1412 897 1412 899 1412 896 1413 899 1413 898 1413 898 1414 899 1414 900 1414 898 1415 900 1415 901 1415 901 1416 900 1416 902 1416 901 1417 902 1417 903 1417 904 1418 903 1418 902 1418 903 1419 904 1419 906 1419 903 1420 906 1420 905 1420 905 1421 906 1421 907 1421 905 1422 907 1422 908 1422 908 1423 907 1423 941 1423 908 1424 941 1424 890 1424 890 1425 941 1425 889 1425 910 1426 909 1426 911 1426 910 1427 913 1427 912 1427 914 1428 913 1428 910 1428 911 1429 914 1429 910 1429 915 1430 888 1430 873 1430 915 1431 873 1431 916 1431 916 1432 873 1432 875 1432 916 1433 875 1433 917 1433 917 1434 875 1434 869 1434 917 1435 869 1435 918 1435 918 1436 869 1436 870 1436 918 1437 870 1437 919 1437 919 1438 870 1438 872 1438 919 1439 872 1439 920 1439 920 1440 872 1440 921 1440 921 1441 872 1441 878 1441 921 1442 878 1442 922 1442 922 1443 878 1443 879 1443 922 1444 879 1444 881 1444 922 1445 881 1445 923 1445 923 1446 881 1446 924 1446 924 1447 881 1447 883 1447 924 1448 883 1448 925 1448 925 1449 883 1449 884 1449 925 1450 884 1450 886 1450 925 1451 886 1451 926 1451 926 1452 886 1452 888 1452 926 1453 888 1453 915 1453 921 1454 864 1454 920 1454 920 1455 864 1455 868 1455 920 1456 868 1456 919 1456 919 1457 868 1457 918 1457 918 1458 868 1458 867 1458 918 1459 867 1459 917 1459 917 1460 867 1460 916 1460 916 1461 867 1461 862 1461 916 1462 862 1462 915 1462 915 1463 862 1463 861 1463 915 1464 861 1464 926 1464 926 1465 861 1465 859 1465 926 1466 859 1466 925 1466 925 1467 859 1467 857 1467 925 1468 857 1468 924 1468 924 1469 857 1469 923 1469 923 1470 857 1470 855 1470 923 1471 855 1471 922 1471 922 1472 855 1472 864 1472 922 1473 864 1473 921 1473 890 1474 909 1474 908 1474 908 1475 909 1475 905 1475 905 1476 909 1476 910 1476 905 1477 910 1477 903 1477 903 1478 910 1478 912 1478 903 1479 912 1479 901 1479 901 1480 912 1480 913 1480 901 1481 913 1481 898 1481 898 1482 913 1482 896 1482 896 1483 913 1483 914 1483 896 1484 914 1484 894 1484 894 1485 914 1485 911 1485 894 1486 911 1486 891 1486 891 1487 911 1487 890 1487 890 1488 911 1488 909 1488 856 1489 927 1489 865 1489 858 1490 928 1490 856 1490 860 1491 929 1491 858 1491 866 1492 930 1492 860 1492 863 1493 931 1493 866 1493 865 1494 932 1494 863 1494 934 1495 935 1495 936 1495 937 1496 933 1496 934 1496 938 1497 937 1497 934 1497 936 1498 938 1498 934 1498 934 1499 939 1499 935 1499 933 1500 939 1500 934 1500 856 1501 938 1501 927 1501 936 1502 865 1502 927 1502 936 1503 927 1503 938 1503 858 1504 937 1504 928 1504 938 1505 856 1505 928 1505 938 1506 928 1506 937 1506 860 1507 933 1507 929 1507 937 1508 858 1508 929 1508 937 1509 929 1509 933 1509 866 1510 939 1510 930 1510 933 1511 860 1511 930 1511 933 1512 930 1512 939 1512 863 1513 935 1513 931 1513 939 1514 866 1514 931 1514 939 1515 931 1515 935 1515 865 1516 936 1516 932 1516 935 1517 863 1517 932 1517 935 1518 932 1518 936 1518 882 1519 880 1519 940 1519 885 1520 892 1520 887 1520 880 1521 899 1521 897 1521 880 1522 897 1522 940 1522 876 1523 906 1523 904 1523 876 1524 904 1524 871 1524 871 1525 904 1525 902 1525 887 1526 892 1526 889 1526 887 1527 889 1527 941 1527 885 1528 893 1528 892 1528 885 1529 882 1529 895 1529 885 1530 895 1530 893 1530 882 1531 940 1531 895 1531 880 1532 877 1532 899 1532 877 1533 900 1533 899 1533 877 1534 871 1534 900 1534 871 1535 902 1535 900 1535 876 1536 874 1536 906 1536 874 1537 907 1537 906 1537 874 1538 941 1538 907 1538 874 1539 887 1539 941 1539 952 1540 942 1540 943 1540 943 1541 942 1541 944 1541 943 1542 944 1542 945 1542 945 1543 944 1543 946 1543 945 1544 946 1544 947 1544 947 1545 946 1545 948 1545 947 1546 948 1546 949 1546 950 1547 955 1547 951 1547 950 1548 951 1548 952 1548 952 1549 951 1549 942 1549 947 1550 949 1550 953 1550 953 1551 949 1551 954 1551 953 1552 954 1552 950 1552 950 1553 954 1553 955 1553 956 1554 963 1554 957 1554 957 1555 963 1555 958 1555 957 1556 958 1556 959 1556 960 1557 961 1557 962 1557 962 1558 961 1558 963 1558 962 1559 963 1559 956 1559 958 1560 964 1560 959 1560 959 1561 964 1561 965 1561 965 1562 964 1562 966 1562 966 1563 964 1563 967 1563 966 1564 967 1564 968 1564 968 1565 967 1565 969 1565 968 1566 969 1566 970 1566 970 1567 969 1567 971 1567 971 1568 969 1568 972 1568 971 1569 972 1569 973 1569 973 1570 972 1570 974 1570 973 1571 974 1571 975 1571 975 1572 974 1572 960 1572 960 1573 974 1573 961 1573 977 1574 976 1574 979 1574 977 1575 979 1575 978 1575 978 1576 979 1576 980 1576 978 1577 980 1577 981 1577 981 1578 980 1578 982 1578 981 1579 982 1579 1027 1579 981 1580 1027 1580 983 1580 984 1581 983 1581 1027 1581 983 1582 984 1582 986 1582 983 1583 986 1583 985 1583 985 1584 986 1584 987 1584 985 1585 987 1585 988 1585 988 1586 987 1586 989 1586 988 1587 989 1587 990 1587 991 1588 990 1588 989 1588 990 1589 991 1589 993 1589 990 1590 993 1590 992 1590 992 1591 993 1591 994 1591 992 1592 994 1592 995 1592 995 1593 994 1593 1028 1593 995 1594 1028 1594 977 1594 977 1595 1028 1595 976 1595 997 1596 996 1596 998 1596 997 1597 1000 1597 999 1597 1001 1598 1000 1598 997 1598 998 1599 1001 1599 997 1599 1002 1600 975 1600 960 1600 1002 1601 960 1601 1003 1601 1003 1602 960 1602 962 1602 1003 1603 962 1603 1004 1603 1004 1604 962 1604 956 1604 1004 1605 956 1605 1005 1605 1005 1606 956 1606 957 1606 1005 1607 957 1607 1006 1607 1006 1608 957 1608 959 1608 1006 1609 959 1609 1007 1609 1007 1610 959 1610 1008 1610 1008 1611 959 1611 965 1611 1008 1612 965 1612 1009 1612 1009 1613 965 1613 966 1613 1009 1614 966 1614 968 1614 1009 1615 968 1615 1010 1615 1010 1616 968 1616 1011 1616 1011 1617 968 1617 970 1617 1011 1618 970 1618 1012 1618 1012 1619 970 1619 971 1619 1012 1620 971 1620 973 1620 1012 1621 973 1621 1013 1621 1013 1622 973 1622 975 1622 1013 1623 975 1623 1002 1623 1008 1624 951 1624 1007 1624 1007 1625 951 1625 955 1625 1007 1626 955 1626 1006 1626 1006 1627 955 1627 1005 1627 1005 1628 955 1628 954 1628 1005 1629 954 1629 1004 1629 1004 1630 954 1630 1003 1630 1003 1631 954 1631 949 1631 1003 1632 949 1632 1002 1632 1002 1633 949 1633 948 1633 1002 1634 948 1634 1013 1634 1013 1635 948 1635 946 1635 1013 1636 946 1636 1012 1636 1012 1637 946 1637 944 1637 1012 1638 944 1638 1011 1638 1011 1639 944 1639 1010 1639 1010 1640 944 1640 942 1640 1010 1641 942 1641 1009 1641 1009 1642 942 1642 951 1642 1009 1643 951 1643 1008 1643 977 1644 996 1644 995 1644 995 1645 996 1645 992 1645 992 1646 996 1646 997 1646 992 1647 997 1647 990 1647 990 1648 997 1648 999 1648 990 1649 999 1649 988 1649 988 1650 999 1650 1000 1650 988 1651 1000 1651 985 1651 985 1652 1000 1652 983 1652 983 1653 1000 1653 1001 1653 983 1654 1001 1654 981 1654 981 1655 1001 1655 998 1655 981 1656 998 1656 978 1656 978 1657 998 1657 977 1657 977 1658 998 1658 996 1658 943 1659 1014 1659 952 1659 945 1660 1015 1660 943 1660 947 1661 1016 1661 945 1661 953 1662 1017 1662 947 1662 950 1663 1018 1663 953 1663 952 1664 1019 1664 950 1664 1021 1665 1022 1665 1023 1665 1024 1666 1020 1666 1021 1666 1025 1667 1024 1667 1021 1667 1023 1668 1025 1668 1021 1668 1021 1669 1026 1669 1022 1669 1020 1670 1026 1670 1021 1670 943 1671 1025 1671 1014 1671 1023 1672 952 1672 1014 1672 1023 1673 1014 1673 1025 1673 945 1674 1024 1674 1015 1674 1025 1675 943 1675 1015 1675 1025 1676 1015 1676 1024 1676 947 1677 1020 1677 1016 1677 1024 1678 945 1678 1016 1678 1024 1679 1016 1679 1020 1679 953 1680 1026 1680 1017 1680 1020 1681 947 1681 1017 1681 1020 1682 1017 1682 1026 1682 950 1683 1022 1683 1018 1683 1026 1684 953 1684 1018 1684 1026 1685 1018 1685 1022 1685 952 1686 1023 1686 1019 1686 1022 1687 950 1687 1019 1687 1022 1688 1019 1688 1023 1688 969 1689 967 1689 1027 1689 972 1690 979 1690 974 1690 967 1691 986 1691 984 1691 967 1692 984 1692 1027 1692 963 1693 993 1693 991 1693 963 1694 991 1694 958 1694 958 1695 991 1695 989 1695 974 1696 979 1696 976 1696 974 1697 976 1697 1028 1697 972 1698 980 1698 979 1698 972 1699 969 1699 982 1699 972 1700 982 1700 980 1700 969 1701 1027 1701 982 1701 967 1702 964 1702 986 1702 964 1703 987 1703 986 1703 964 1704 958 1704 987 1704 958 1705 989 1705 987 1705 963 1706 961 1706 993 1706 961 1707 994 1707 993 1707 961 1708 1028 1708 994 1708 961 1709 974 1709 1028 1709 1051 1710 1029 1710 1030 1710 1030 1711 1029 1711 1031 1711 1030 1712 1031 1712 1032 1712 1030 1713 1032 1713 1033 1713 1033 1714 1032 1714 1034 1714 1033 1715 1034 1715 1035 1715 1035 1716 1034 1716 1036 1716 1036 1717 1034 1717 1037 1717 1036 1718 1037 1718 1038 1718 1038 1719 1037 1719 1039 1719 1038 1720 1039 1720 1040 1720 1040 1721 1039 1721 1041 1721 1040 1722 1041 1722 1042 1722 1040 1723 1042 1723 1043 1723 1043 1724 1042 1724 1044 1724 1044 1725 1042 1725 1045 1725 1044 1726 1045 1726 1046 1726 1044 1727 1046 1727 1047 1727 1047 1728 1046 1728 1048 1728 1047 1729 1048 1729 1049 1729 1049 1730 1048 1730 1050 1730 1049 1731 1050 1731 1051 1731 1051 1732 1050 1732 1029 1732 1052 1733 1041 1733 1039 1733 1052 324 1039 324 1053 324 1054 324 1029 324 1055 324 1056 324 1032 324 1031 324 1056 324 1031 324 1054 324 1054 324 1031 324 1029 324 1029 324 1050 324 1055 324 1057 1734 1042 1734 1052 1734 1052 1735 1042 1735 1041 1735 1058 324 1045 324 1057 324 1057 1736 1045 1736 1042 1736 1059 324 1034 324 1032 324 1059 324 1032 324 1056 324 1050 324 1048 324 1055 324 1055 324 1048 324 1058 324 1058 324 1048 324 1046 324 1058 1737 1046 1737 1045 1737 1053 324 1039 324 1037 324 1053 324 1037 324 1034 324 1053 1738 1034 1738 1059 1738 1054 1739 1060 1739 1056 1739 1056 1740 1060 1740 1061 1740 1056 1741 1061 1741 1059 1741 1059 1742 1061 1742 1062 1742 1059 1743 1062 1743 1053 1743 1053 1744 1062 1744 1063 1744 1053 1745 1063 1745 1052 1745 1052 1746 1063 1746 1064 1746 1052 1747 1064 1747 1057 1747 1057 1748 1064 1748 1065 1748 1057 1749 1065 1749 1058 1749 1058 1750 1065 1750 1066 1750 1058 1751 1066 1751 1055 1751 1055 1752 1066 1752 1067 1752 1055 1753 1067 1753 1060 1753 1055 1754 1060 1754 1054 1754 1067 348 1051 348 1060 348 1066 1755 1049 1755 1067 1755 1067 348 1049 348 1051 348 1065 348 1044 348 1066 348 1066 1756 1044 1756 1047 1756 1066 1757 1047 1757 1049 1757 1040 348 1043 348 1064 348 1064 348 1043 348 1065 348 1065 1758 1043 1758 1044 1758 1063 348 1038 348 1064 348 1064 1759 1038 1759 1040 1759 1063 1760 1036 1760 1038 1760 1061 1761 1033 1761 1062 1761 1062 348 1033 348 1035 348 1062 348 1035 348 1063 348 1063 1762 1035 1762 1036 1762 1051 1763 1030 1763 1060 1763 1060 1764 1030 1764 1061 1764 1061 1765 1030 1765 1033 1765 1068 1766 1081 1766 1069 1766 1069 1767 1081 1767 1070 1767 1069 1768 1070 1768 1071 1768 1071 1769 1070 1769 1072 1769 1071 1770 1072 1770 1073 1770 1071 1771 1073 1771 1074 1771 1073 1772 1075 1772 1074 1772 1074 1773 1075 1773 1076 1773 1076 1774 1075 1774 1077 1774 1076 1775 1077 1775 1078 1775 1076 1776 1078 1776 1079 1776 1079 1777 1078 1777 1080 1777 1079 1778 1080 1778 1068 1778 1068 1779 1080 1779 1081 1779 1082 1780 1083 1780 1084 1780 1084 1781 1083 1781 1085 1781 1084 1782 1085 1782 1086 1782 1087 1783 1088 1783 1089 1783 1087 1784 1089 1784 1090 1784 1090 1785 1089 1785 1091 1785 1090 1786 1091 1786 1092 1786 1092 1787 1091 1787 1093 1787 1092 1788 1093 1788 1094 1788 1094 1789 1093 1789 1082 1789 1082 1790 1093 1790 1083 1790 1086 1791 1085 1791 1095 1791 1086 1792 1095 1792 1096 1792 1096 1793 1095 1793 1097 1793 1095 1794 1098 1794 1097 1794 1097 1795 1098 1795 1099 1795 1099 1796 1098 1796 1100 1796 1099 1797 1100 1797 1101 1797 1101 1798 1100 1798 1088 1798 1101 1799 1088 1799 1087 1799 1103 1800 1102 1800 1104 1800 1105 1801 1104 1801 1102 1801 1104 1802 1105 1802 1107 1802 1104 1803 1107 1803 1106 1803 1106 1804 1107 1804 1108 1804 1106 1805 1108 1805 1109 1805 1109 1806 1108 1806 1110 1806 1109 1807 1110 1807 1111 1807 1111 1808 1110 1808 1112 1808 1111 1809 1112 1809 1113 1809 1114 1810 1115 1810 1113 1810 1114 1811 1113 1811 1112 1811 1116 1812 1115 1812 1114 1812 1115 1813 1116 1813 1118 1813 1115 1814 1118 1814 1117 1814 1117 1815 1118 1815 1119 1815 1117 1816 1119 1816 1120 1816 1120 1817 1119 1817 1121 1817 1120 1818 1121 1818 1103 1818 1103 1819 1121 1819 1102 1819 1125 1820 1124 1820 1123 1820 1126 1821 1125 1821 1123 1821 1123 1822 1127 1822 1126 1822 1123 1823 1122 1823 1127 1823 1128 1824 1101 1824 1129 1824 1129 1825 1101 1825 1087 1825 1129 1826 1087 1826 1130 1826 1130 1827 1087 1827 1131 1827 1131 1828 1087 1828 1090 1828 1131 1829 1090 1829 1092 1829 1131 1830 1092 1830 1132 1830 1132 1831 1092 1831 1094 1831 1132 1832 1094 1832 1133 1832 1133 1833 1094 1833 1082 1833 1133 1834 1082 1834 1134 1834 1134 1835 1082 1835 1084 1835 1134 1836 1084 1836 1135 1836 1135 1837 1084 1837 1086 1837 1135 1838 1086 1838 1136 1838 1136 1839 1086 1839 1096 1839 1136 1840 1096 1840 1137 1840 1137 1841 1096 1841 1097 1841 1137 1842 1097 1842 1138 1842 1138 1843 1097 1843 1099 1843 1138 1844 1099 1844 1128 1844 1128 1845 1099 1845 1101 1845 1134 1846 1078 1846 1133 1846 1133 1847 1078 1847 1132 1847 1132 1848 1078 1848 1077 1848 1132 1849 1077 1849 1075 1849 1132 1850 1075 1850 1131 1850 1131 1851 1075 1851 1073 1851 1131 1852 1073 1852 1130 1852 1130 1853 1073 1853 1129 1853 1129 1854 1073 1854 1072 1854 1129 1855 1072 1855 1128 1855 1128 1856 1072 1856 1070 1856 1128 1857 1070 1857 1138 1857 1138 1858 1070 1858 1137 1858 1137 1859 1070 1859 1081 1859 1137 1860 1081 1860 1136 1860 1136 1861 1081 1861 1135 1861 1135 1862 1081 1862 1080 1862 1135 1863 1080 1863 1134 1863 1134 1864 1080 1864 1078 1864 1103 1865 1123 1865 1120 1865 1120 1866 1123 1866 1124 1866 1120 1867 1124 1867 1117 1867 1117 1868 1124 1868 1115 1868 1115 1869 1124 1869 1125 1869 1115 1870 1125 1870 1113 1870 1113 1871 1125 1871 1126 1871 1113 1872 1126 1872 1111 1872 1111 1873 1126 1873 1109 1873 1109 1874 1126 1874 1127 1874 1109 1875 1127 1875 1106 1875 1106 1876 1127 1876 1104 1876 1104 1877 1127 1877 1122 1877 1104 1878 1122 1878 1103 1878 1103 1879 1122 1879 1123 1879 1068 1880 1139 1880 1079 1880 1069 1881 1140 1881 1068 1881 1071 1882 1141 1882 1069 1882 1074 1883 1142 1883 1071 1883 1076 1884 1143 1884 1074 1884 1079 1885 1144 1885 1076 1885 1148 1886 1149 1886 1146 1886 1148 1887 1146 1887 1147 1887 1147 1888 1146 1888 1145 1888 1150 1889 1145 1889 1146 1889 1151 1890 1150 1890 1146 1890 1152 1891 1151 1891 1146 1891 1146 1892 1149 1892 1152 1892 1150 1893 1079 1893 1139 1893 1150 1894 1139 1894 1145 1894 1068 1895 1145 1895 1139 1895 1147 1896 1140 1896 1148 1896 1148 1897 1140 1897 1069 1897 1145 1898 1068 1898 1140 1898 1140 1899 1147 1899 1145 1899 1141 1900 1071 1900 1149 1900 1141 1901 1148 1901 1069 1901 1141 1902 1149 1902 1148 1902 1074 1903 1152 1903 1142 1903 1149 1904 1071 1904 1142 1904 1149 1905 1142 1905 1152 1905 1076 1906 1151 1906 1143 1906 1152 1907 1074 1907 1143 1907 1152 1908 1143 1908 1151 1908 1079 1909 1150 1909 1144 1909 1151 1910 1076 1910 1144 1910 1151 1911 1144 1911 1150 1911 1098 1912 1102 1912 1100 1912 1091 1913 1114 1913 1093 1913 1093 1914 1114 1914 1112 1914 1093 1915 1112 1915 1083 1915 1083 1916 1112 1916 1110 1916 1083 1917 1110 1917 1085 1917 1100 1918 1102 1918 1121 1918 1100 1919 1121 1919 1088 1919 1102 1920 1098 1920 1105 1920 1098 1921 1095 1921 1107 1921 1098 1922 1107 1922 1105 1922 1095 1923 1108 1923 1107 1923 1095 1924 1085 1924 1108 1924 1085 1925 1110 1925 1108 1925 1091 1926 1116 1926 1114 1926 1091 1927 1089 1927 1118 1927 1091 1928 1118 1928 1116 1928 1089 1929 1088 1929 1119 1929 1089 1930 1119 1930 1118 1930 1088 1931 1121 1931 1119 1931 1157 1932 1154 1932 1155 1932 1153 1933 1185 1933 1156 1933 1153 1934 1156 1934 1155 1934 1155 1935 1156 1935 1157 1935 1160 1936 1154 1936 1159 1936 1159 1937 1154 1937 1157 1937 1160 1938 1158 1938 1154 1938 1163 1939 1161 1939 1162 1939 1155 1940 1154 1940 1158 1940 1158 1941 1163 1941 1162 1941 1155 1942 1158 1942 1162 1942 1164 1943 1161 1943 1163 1943 1162 1944 1161 1944 1164 1944 1167 1945 1168 1945 1166 1945 1162 1946 1164 1946 1165 1946 1162 1947 1165 1947 1166 1947 1166 1948 1165 1948 1167 1948 1168 1949 1169 1949 1170 1949 1171 1950 1168 1950 1167 1950 1172 1951 1168 1951 1171 1951 1169 1952 1168 1952 1172 1952 1170 1953 1174 1953 1173 1953 1166 1954 1168 1954 1173 1954 1173 1955 1168 1955 1170 1955 1174 1956 1175 1956 1176 1956 1175 1957 1174 1957 1177 1957 1178 1958 1174 1958 1170 1958 1177 1959 1174 1959 1178 1959 1176 1960 1180 1960 1179 1960 1173 1961 1174 1961 1179 1961 1179 1962 1174 1962 1176 1962 1182 1963 1180 1963 1176 1963 1183 1964 1180 1964 1182 1964 1181 1965 1180 1965 1184 1965 1184 1966 1180 1966 1183 1966 1181 1967 1185 1967 1153 1967 1179 1968 1180 1968 1181 1968 1179 1969 1181 1969 1153 1969 1186 1970 1185 1970 1181 1970 1187 1971 1185 1971 1186 1971 1188 1972 1156 1972 1187 1972 1187 1973 1156 1973 1185 1973 1181 1974 1192 1974 1190 1974 1165 1975 1189 1975 1197 1975 1189 1976 1165 1976 1164 1976 1190 1977 1187 1977 1181 1977 1192 1978 1193 1978 1194 1978 1192 1979 1194 1979 1195 1979 1192 1980 1181 1980 1196 1980 1192 1981 1196 1981 1183 1981 1192 1982 1183 1982 1193 1982 1201 1983 1157 1983 1190 1983 1190 1984 1157 1984 1188 1984 1190 1985 1188 1985 1187 1985 1201 1986 1159 1986 1157 1986 1197 1987 1198 1987 1171 1987 1197 1988 1171 1988 1165 1988 1191 1989 1170 1989 1195 1989 1195 1990 1170 1990 1197 1990 1197 1991 1170 1991 1199 1991 1197 1992 1199 1992 1200 1992 1197 1993 1200 1993 1198 1993 1201 1994 1158 1994 1202 1994 1201 1995 1202 1995 1159 1995 1189 1996 1164 1996 1163 1996 1189 1997 1163 1997 1201 1997 1195 1998 1203 1998 1204 1998 1195 1999 1204 1999 1205 1999 1195 2000 1205 2000 1191 2000 1163 2001 1158 2001 1201 2001 1194 2002 1176 2002 1195 2002 1195 2003 1176 2003 1206 2003 1195 2004 1206 2004 1203 2004 1190 2005 1192 2005 1207 2005 1207 2006 1208 2006 1190 2006 1190 2007 1208 2007 1201 2007 1201 2008 1208 2008 1209 2008 1201 2009 1209 2009 1189 2009 1209 2010 1210 2010 1189 2010 1211 2011 1189 2011 1210 2011 1197 2012 1189 2012 1211 2012 1211 2013 1212 2013 1197 2013 1197 2014 1212 2014 1195 2014 1195 2015 1212 2015 1213 2015 1195 2016 1213 2016 1192 2016 1213 2017 1214 2017 1192 2017 1207 2018 1192 2018 1214 2018 1215 2019 1207 2019 1214 2019 1215 2020 1214 2020 1213 2020 1215 2021 1213 2021 1216 2021 1216 2022 1213 2022 1217 2022 1217 2023 1213 2023 1212 2023 1217 2024 1212 2024 1218 2024 1218 2025 1212 2025 1211 2025 1218 2026 1211 2026 1219 2026 1219 2027 1211 2027 1210 2027 1219 2028 1210 2028 1209 2028 1219 2029 1209 2029 1220 2029 1220 2030 1209 2030 1221 2030 1221 2031 1209 2031 1208 2031 1221 2032 1208 2032 1222 2032 1222 2033 1208 2033 1207 2033 1222 2034 1207 2034 1215 2034 1223 2035 1219 2035 1224 2035 1219 2036 1220 2036 1224 2036 1220 2037 1221 2037 1224 2037 1224 2038 1221 2038 1225 2038 1221 2039 1222 2039 1225 2039 1225 2040 1222 2040 1226 2040 1215 2041 1226 2041 1222 2041 1226 2042 1215 2042 1227 2042 1215 2043 1216 2043 1227 2043 1216 2044 1217 2044 1227 2044 1227 2045 1217 2045 1228 2045 1217 2046 1218 2046 1228 2046 1228 2047 1218 2047 1223 2047 1219 2048 1223 2048 1218 2048 1228 2049 1223 2049 1166 2049 1166 2050 1223 2050 1162 2050 1155 2051 1224 2051 1225 2051 1155 2052 1225 2052 1153 2052 1173 2053 1227 2053 1228 2053 1173 2054 1228 2054 1166 2054 1162 2055 1223 2055 1224 2055 1162 2056 1224 2056 1155 2056 1153 2057 1225 2057 1226 2057 1153 2058 1226 2058 1179 2058 1179 2059 1226 2059 1227 2059 1179 2060 1227 2060 1173 2060 1238 2061 1229 2061 1230 2061 1230 2062 1229 2062 1231 2062 1230 2063 1231 2063 1232 2063 1231 2064 1233 2064 1232 2064 1232 2065 1233 2065 1234 2065 1232 2066 1234 2066 1235 2066 1236 2067 1242 2067 1237 2067 1236 2068 1237 2068 1238 2068 1238 2069 1237 2069 1239 2069 1238 2070 1239 2070 1229 2070 1240 2071 1244 2071 1241 2071 1240 2072 1241 2072 1236 2072 1236 2073 1241 2073 1242 2073 1234 2074 1243 2074 1235 2074 1235 2075 1243 2075 1244 2075 1235 2076 1244 2076 1240 2076 1245 2077 1246 2077 1247 2077 1247 2078 1246 2078 1248 2078 1247 2079 1248 2079 1249 2079 1249 2080 1248 2080 1250 2080 1251 2081 1264 2081 1252 2081 1251 2082 1252 2082 1253 2082 1254 2083 1262 2083 1255 2083 1255 2084 1262 2084 1256 2084 1255 2085 1256 2085 1257 2085 1252 2086 1258 2086 1253 2086 1253 2087 1258 2087 1259 2087 1259 2088 1258 2088 1245 2088 1245 2089 1258 2089 1246 2089 1250 2090 1248 2090 1260 2090 1250 2091 1260 2091 1261 2091 1261 2092 1260 2092 1262 2092 1261 2093 1262 2093 1254 2093 1257 2094 1256 2094 1263 2094 1263 2095 1256 2095 1264 2095 1263 2096 1264 2096 1251 2096 1266 2097 1265 2097 1317 2097 1266 2098 1317 2098 1267 2098 1267 2099 1317 2099 1268 2099 1267 2100 1268 2100 1269 2100 1270 2101 1269 2101 1268 2101 1269 2102 1270 2102 1272 2102 1269 2103 1272 2103 1271 2103 1271 2104 1272 2104 1274 2104 1274 2105 1272 2105 1319 2105 1274 2106 1319 2106 1273 2106 1274 2107 1273 2107 1275 2107 1276 2108 1275 2108 1273 2108 1275 2109 1276 2109 1277 2109 1277 2110 1276 2110 1278 2110 1277 2111 1278 2111 1279 2111 1277 2112 1279 2112 1280 2112 1281 2113 1280 2113 1279 2113 1280 2114 1281 2114 1283 2114 1280 2115 1283 2115 1282 2115 1282 2116 1283 2116 1318 2116 1282 2117 1318 2117 1266 2117 1266 2118 1318 2118 1265 2118 1285 2119 1286 2119 1284 2119 1288 2120 1287 2120 1285 2120 1289 2121 1288 2121 1285 2121 1285 2122 1284 2122 1289 2122 1290 2123 1257 2123 1263 2123 1257 2124 1290 2124 1291 2124 1257 2125 1291 2125 1255 2125 1255 2126 1291 2126 1292 2126 1255 2127 1292 2127 1254 2127 1254 2128 1292 2128 1293 2128 1254 2129 1293 2129 1261 2129 1261 2130 1293 2130 1294 2130 1261 2131 1294 2131 1250 2131 1250 2132 1294 2132 1295 2132 1250 2133 1295 2133 1249 2133 1249 2134 1295 2134 1296 2134 1249 2135 1296 2135 1247 2135 1247 2136 1296 2136 1297 2136 1247 2137 1297 2137 1245 2137 1245 2138 1297 2138 1298 2138 1245 2139 1298 2139 1259 2139 1259 2140 1298 2140 1299 2140 1259 2141 1299 2141 1253 2141 1253 2142 1299 2142 1300 2142 1253 2143 1300 2143 1301 2143 1253 2144 1301 2144 1251 2144 1251 2145 1301 2145 1302 2145 1251 2146 1302 2146 1263 2146 1263 2147 1302 2147 1290 2147 1296 2148 1295 2148 1239 2148 1239 2149 1295 2149 1229 2149 1295 2150 1294 2150 1229 2150 1229 2151 1294 2151 1231 2151 1294 2152 1293 2152 1231 2152 1231 2153 1293 2153 1233 2153 1293 2154 1292 2154 1233 2154 1292 2155 1291 2155 1233 2155 1233 2156 1291 2156 1234 2156 1234 2157 1291 2157 1290 2157 1234 2158 1290 2158 1243 2158 1290 2159 1302 2159 1243 2159 1243 2160 1302 2160 1244 2160 1302 2161 1301 2161 1244 2161 1244 2162 1301 2162 1300 2162 1244 2163 1300 2163 1241 2163 1300 2164 1299 2164 1241 2164 1241 2165 1299 2165 1242 2165 1299 2166 1298 2166 1242 2166 1242 2167 1298 2167 1297 2167 1242 2168 1297 2168 1237 2168 1297 2169 1296 2169 1237 2169 1237 2170 1296 2170 1239 2170 1266 2171 1284 2171 1286 2171 1266 2172 1286 2172 1282 2172 1282 2173 1286 2173 1280 2173 1280 2174 1286 2174 1285 2174 1280 2175 1285 2175 1277 2175 1277 2176 1285 2176 1287 2176 1277 2177 1287 2177 1275 2177 1275 2178 1287 2178 1274 2178 1274 2179 1287 2179 1288 2179 1274 2180 1288 2180 1271 2180 1271 2181 1288 2181 1289 2181 1271 2182 1289 2182 1269 2182 1269 2183 1289 2183 1284 2183 1269 2184 1284 2184 1267 2184 1267 2185 1284 2185 1266 2185 1230 2186 1303 2186 1238 2186 1232 2187 1304 2187 1230 2187 1235 2188 1305 2188 1232 2188 1240 2189 1306 2189 1235 2189 1236 2190 1307 2190 1240 2190 1238 2191 1308 2191 1236 2191 1312 2192 1310 2192 1311 2192 1310 2193 1313 2193 1309 2193 1314 2194 1313 2194 1310 2194 1314 2195 1310 2195 1312 2195 1315 2196 1311 2196 1310 2196 1315 2197 1310 2197 1309 2197 1312 2198 1238 2198 1303 2198 1312 2199 1303 2199 1314 2199 1314 2200 1303 2200 1230 2200 1232 2201 1313 2201 1304 2201 1304 2202 1313 2202 1314 2202 1304 2203 1314 2203 1230 2203 1235 2204 1309 2204 1305 2204 1313 2205 1232 2205 1305 2205 1309 2206 1313 2206 1305 2206 1309 2207 1235 2207 1306 2207 1309 2208 1306 2208 1315 2208 1315 2209 1306 2209 1240 2209 1236 2210 1311 2210 1307 2210 1307 2211 1311 2211 1315 2211 1307 2212 1315 2212 1240 2212 1238 2213 1312 2213 1308 2213 1311 2214 1236 2214 1308 2214 1312 2215 1311 2215 1308 2215 1262 2216 1316 2216 1256 2216 1252 2217 1281 2217 1258 2217 1256 2218 1317 2218 1265 2218 1256 2219 1265 2219 1264 2219 1264 2220 1265 2220 1318 2220 1262 2221 1272 2221 1270 2221 1262 2222 1270 2222 1316 2222 1316 2223 1270 2223 1268 2223 1316 2224 1268 2224 1256 2224 1252 2225 1283 2225 1281 2225 1281 2226 1279 2226 1258 2226 1317 2227 1256 2227 1268 2227 1262 2228 1260 2228 1272 2228 1260 2229 1319 2229 1272 2229 1260 2230 1248 2230 1319 2230 1248 2231 1273 2231 1319 2231 1248 2232 1276 2232 1273 2232 1248 2233 1246 2233 1276 2233 1276 2234 1246 2234 1278 2234 1246 2235 1258 2235 1279 2235 1246 2236 1279 2236 1278 2236 1252 2237 1318 2237 1283 2237 1252 2238 1264 2238 1318 2238 1328 2239 1320 2239 1321 2239 1321 2240 1320 2240 1322 2240 1321 2241 1322 2241 1323 2241 1323 2242 1322 2242 1324 2242 1323 2243 1324 2243 1325 2243 1326 2244 1332 2244 1327 2244 1326 2245 1327 2245 1328 2245 1328 2246 1327 2246 1329 2246 1328 2247 1329 2247 1320 2247 1330 2248 1334 2248 1331 2248 1330 2249 1331 2249 1326 2249 1326 2250 1331 2250 1332 2250 1324 2251 1333 2251 1325 2251 1325 2252 1333 2252 1334 2252 1325 2253 1334 2253 1330 2253 1335 2254 1336 2254 1337 2254 1337 2255 1336 2255 1338 2255 1337 2256 1338 2256 1339 2256 1340 2257 1341 2257 1342 2257 1342 2258 1341 2258 1343 2258 1342 2259 1343 2259 1344 2259 1345 2260 1346 2260 1347 2260 1347 2261 1346 2261 1348 2261 1344 2262 1343 2262 1349 2262 1349 2263 1343 2263 1350 2263 1349 2264 1350 2264 1351 2264 1351 2265 1350 2265 1336 2265 1351 2266 1336 2266 1335 2266 1338 2267 1352 2267 1339 2267 1339 2268 1352 2268 1353 2268 1353 2269 1352 2269 1354 2269 1353 2270 1354 2270 1345 2270 1345 2271 1354 2271 1346 2271 1346 2272 1355 2272 1348 2272 1348 2273 1355 2273 1356 2273 1356 2274 1355 2274 1340 2274 1340 2275 1355 2275 1341 2275 1358 2276 1357 2276 1360 2276 1358 2277 1360 2277 1359 2277 1359 2278 1360 2278 1407 2278 1359 2279 1407 2279 1361 2279 1362 2280 1361 2280 1407 2280 1361 2281 1362 2281 1363 2281 1364 2282 1363 2282 1362 2282 1363 2283 1364 2283 1366 2283 1366 2284 1364 2284 1408 2284 1366 2285 1408 2285 1365 2285 1366 2286 1365 2286 1367 2286 1368 2287 1367 2287 1365 2287 1367 2288 1368 2288 1369 2288 1369 2289 1368 2289 1370 2289 1369 2290 1370 2290 1372 2290 1369 2291 1372 2291 1371 2291 1371 2292 1372 2292 1374 2292 1371 2293 1374 2293 1373 2293 1373 2294 1374 2294 1375 2294 1373 2295 1375 2295 1358 2295 1358 2296 1375 2296 1357 2296 1377 2297 1378 2297 1376 2297 1377 2298 1379 2298 1378 2298 1380 2299 1379 2299 1377 2299 1356 2300 1381 2300 1348 2300 1348 2301 1381 2301 1382 2301 1348 2302 1382 2302 1347 2302 1347 2303 1382 2303 1383 2303 1347 2304 1383 2304 1345 2304 1345 2305 1383 2305 1384 2305 1345 2306 1384 2306 1353 2306 1353 2307 1384 2307 1385 2307 1353 2308 1385 2308 1339 2308 1339 2309 1385 2309 1386 2309 1339 2310 1386 2310 1337 2310 1337 2311 1386 2311 1387 2311 1337 2312 1387 2312 1335 2312 1335 2313 1387 2313 1388 2313 1335 2314 1388 2314 1351 2314 1351 2315 1388 2315 1389 2315 1351 2316 1389 2316 1390 2316 1351 2317 1390 2317 1349 2317 1349 2318 1390 2318 1344 2318 1344 2319 1390 2319 1391 2319 1344 2320 1391 2320 1392 2320 1344 2321 1392 2321 1342 2321 1342 2322 1392 2322 1340 2322 1340 2323 1392 2323 1393 2323 1340 2324 1393 2324 1356 2324 1356 2325 1393 2325 1381 2325 1329 2326 1387 2326 1386 2326 1329 2327 1386 2327 1320 2327 1386 2328 1385 2328 1320 2328 1385 2329 1384 2329 1320 2329 1320 2330 1384 2330 1322 2330 1384 2331 1383 2331 1322 2331 1383 2332 1382 2332 1322 2332 1322 2333 1382 2333 1324 2333 1324 2334 1382 2334 1381 2334 1324 2335 1381 2335 1333 2335 1381 2336 1393 2336 1333 2336 1333 2337 1393 2337 1334 2337 1393 2338 1392 2338 1334 2338 1334 2339 1392 2339 1391 2339 1334 2340 1391 2340 1331 2340 1391 2341 1390 2341 1331 2341 1331 2342 1390 2342 1332 2342 1390 2343 1389 2343 1332 2343 1332 2344 1389 2344 1388 2344 1332 2345 1388 2345 1327 2345 1388 2346 1387 2346 1327 2346 1327 2347 1387 2347 1329 2347 1358 2348 1378 2348 1373 2348 1373 2349 1378 2349 1371 2349 1371 2350 1378 2350 1379 2350 1371 2351 1379 2351 1369 2351 1369 2352 1379 2352 1380 2352 1369 2353 1380 2353 1367 2353 1367 2354 1380 2354 1366 2354 1366 2355 1380 2355 1377 2355 1366 2356 1377 2356 1363 2356 1363 2357 1377 2357 1361 2357 1361 2358 1377 2358 1376 2358 1361 2359 1376 2359 1359 2359 1359 2360 1376 2360 1358 2360 1358 2361 1376 2361 1378 2361 1321 2362 1394 2362 1328 2362 1323 2363 1395 2363 1321 2363 1325 2364 1396 2364 1323 2364 1330 2365 1397 2365 1325 2365 1326 2366 1398 2366 1330 2366 1328 2367 1399 2367 1326 2367 1403 2368 1401 2368 1402 2368 1401 2369 1404 2369 1400 2369 1405 2370 1404 2370 1401 2370 1405 2371 1401 2371 1403 2371 1406 2372 1402 2372 1401 2372 1406 2373 1401 2373 1400 2373 1403 2374 1328 2374 1394 2374 1403 2375 1394 2375 1405 2375 1405 2376 1394 2376 1321 2376 1323 2377 1404 2377 1395 2377 1395 2378 1404 2378 1405 2378 1395 2379 1405 2379 1321 2379 1325 2380 1400 2380 1396 2380 1404 2381 1323 2381 1396 2381 1400 2382 1404 2382 1396 2382 1400 2383 1325 2383 1397 2383 1400 2384 1397 2384 1406 2384 1406 2385 1397 2385 1330 2385 1326 2386 1402 2386 1398 2386 1398 2387 1402 2387 1406 2387 1398 2388 1406 2388 1330 2388 1328 2389 1403 2389 1399 2389 1402 2390 1326 2390 1399 2390 1403 2391 1402 2391 1399 2391 1354 2392 1362 2392 1407 2392 1354 2393 1407 2393 1346 2393 1343 2394 1374 2394 1372 2394 1343 2395 1372 2395 1350 2395 1355 2396 1360 2396 1357 2396 1355 2397 1357 2397 1341 2397 1350 2398 1372 2398 1370 2398 1357 2399 1375 2399 1341 2399 1355 2400 1346 2400 1360 2400 1346 2401 1407 2401 1360 2401 1354 2402 1352 2402 1362 2402 1362 2403 1352 2403 1364 2403 1352 2404 1338 2404 1408 2404 1352 2405 1408 2405 1364 2405 1338 2406 1365 2406 1408 2406 1338 2407 1336 2407 1365 2407 1336 2408 1368 2408 1365 2408 1336 2409 1350 2409 1370 2409 1336 2410 1370 2410 1368 2410 1343 2411 1341 2411 1374 2411 1341 2412 1375 2412 1374 2412 1418 2413 1409 2413 1410 2413 1410 2414 1409 2414 1411 2414 1410 2415 1411 2415 1412 2415 1411 2416 1413 2416 1412 2416 1412 2417 1413 2417 1414 2417 1412 2418 1414 2418 1415 2418 1416 2419 1421 2419 1417 2419 1416 2420 1417 2420 1418 2420 1418 2421 1417 2421 1409 2421 1419 2422 1423 2422 1420 2422 1419 2423 1420 2423 1416 2423 1416 2424 1420 2424 1421 2424 1414 2425 1422 2425 1415 2425 1415 2426 1422 2426 1423 2426 1415 2427 1423 2427 1419 2427 1424 2428 1425 2428 1426 2428 1424 2429 1426 2429 1427 2429 1427 2430 1426 2430 1428 2430 1427 2431 1428 2431 1429 2431 1430 2432 1431 2432 1432 2432 1432 2433 1431 2433 1433 2433 1432 2434 1433 2434 1434 2434 1435 2435 1436 2435 1437 2435 1437 2436 1436 2436 1438 2436 1437 2437 1438 2437 1439 2437 1434 2438 1433 2438 1440 2438 1440 2439 1433 2439 1425 2439 1440 2440 1425 2440 1424 2440 1429 2441 1428 2441 1441 2441 1441 2442 1428 2442 1435 2442 1435 2443 1428 2443 1436 2443 1439 2444 1438 2444 1442 2444 1442 2445 1438 2445 1431 2445 1442 2446 1431 2446 1430 2446 1444 2447 1443 2447 1493 2447 1444 2448 1493 2448 1445 2448 1445 2449 1493 2449 1446 2449 1445 2450 1446 2450 1447 2450 1448 2451 1447 2451 1446 2451 1447 2452 1448 2452 1450 2452 1447 2453 1450 2453 1449 2453 1449 2454 1450 2454 1451 2454 1449 2455 1451 2455 1453 2455 1453 2456 1451 2456 1496 2456 1453 2457 1496 2457 1452 2457 1453 2458 1452 2458 1454 2458 1455 2459 1454 2459 1452 2459 1454 2460 1455 2460 1456 2460 1456 2461 1455 2461 1457 2461 1456 2462 1457 2462 1494 2462 1456 2463 1494 2463 1458 2463 1459 2464 1458 2464 1494 2464 1458 2465 1459 2465 1461 2465 1458 2466 1461 2466 1460 2466 1460 2467 1461 2467 1495 2467 1460 2468 1495 2468 1444 2468 1444 2469 1495 2469 1443 2469 1464 2470 1463 2470 1462 2470 1462 2471 1465 2471 1464 2471 1466 2472 1465 2472 1462 2472 1467 2473 1466 2473 1462 2473 1468 2474 1439 2474 1442 2474 1439 2475 1468 2475 1469 2475 1439 2476 1469 2476 1437 2476 1437 2477 1469 2477 1470 2477 1437 2478 1470 2478 1471 2478 1437 2479 1471 2479 1435 2479 1435 2480 1471 2480 1472 2480 1435 2481 1472 2481 1441 2481 1441 2482 1472 2482 1473 2482 1441 2483 1473 2483 1429 2483 1429 2484 1473 2484 1427 2484 1427 2485 1473 2485 1474 2485 1427 2486 1474 2486 1424 2486 1424 2487 1474 2487 1475 2487 1424 2488 1475 2488 1440 2488 1440 2489 1475 2489 1476 2489 1440 2490 1476 2490 1434 2490 1434 2491 1476 2491 1477 2491 1434 2492 1477 2492 1432 2492 1432 2493 1477 2493 1478 2493 1432 2494 1478 2494 1430 2494 1430 2495 1478 2495 1479 2495 1430 2496 1479 2496 1442 2496 1442 2497 1479 2497 1468 2497 1417 2498 1474 2498 1409 2498 1474 2499 1473 2499 1409 2499 1473 2500 1472 2500 1409 2500 1409 2501 1472 2501 1411 2501 1472 2502 1471 2502 1411 2502 1411 2503 1471 2503 1413 2503 1471 2504 1470 2504 1413 2504 1413 2505 1470 2505 1414 2505 1414 2506 1470 2506 1469 2506 1414 2507 1469 2507 1468 2507 1414 2508 1468 2508 1422 2508 1468 2509 1479 2509 1422 2509 1422 2510 1479 2510 1423 2510 1479 2511 1478 2511 1423 2511 1423 2512 1478 2512 1420 2512 1478 2513 1477 2513 1420 2513 1420 2514 1477 2514 1421 2514 1477 2515 1476 2515 1421 2515 1421 2516 1476 2516 1475 2516 1421 2517 1475 2517 1417 2517 1475 2518 1474 2518 1417 2518 1444 2519 1462 2519 1463 2519 1444 2520 1463 2520 1460 2520 1460 2521 1463 2521 1458 2521 1458 2522 1463 2522 1464 2522 1458 2523 1464 2523 1456 2523 1456 2524 1464 2524 1454 2524 1454 2525 1464 2525 1465 2525 1454 2526 1465 2526 1453 2526 1453 2527 1465 2527 1449 2527 1449 2528 1465 2528 1466 2528 1449 2529 1466 2529 1447 2529 1447 2530 1466 2530 1467 2530 1447 2531 1467 2531 1445 2531 1445 2532 1467 2532 1462 2532 1445 2533 1462 2533 1444 2533 1410 2534 1480 2534 1418 2534 1412 2535 1481 2535 1410 2535 1415 2536 1482 2536 1412 2536 1419 2537 1483 2537 1415 2537 1416 2538 1484 2538 1419 2538 1418 2539 1485 2539 1416 2539 1489 2540 1487 2540 1488 2540 1487 2541 1490 2541 1486 2541 1491 2542 1490 2542 1487 2542 1491 2543 1487 2543 1489 2543 1492 2544 1488 2544 1487 2544 1492 2545 1487 2545 1486 2545 1489 2546 1418 2546 1480 2546 1489 2547 1480 2547 1491 2547 1491 2548 1480 2548 1410 2548 1412 2549 1490 2549 1481 2549 1481 2550 1490 2550 1491 2550 1481 2551 1491 2551 1410 2551 1415 2552 1486 2552 1482 2552 1490 2553 1412 2553 1482 2553 1486 2554 1490 2554 1482 2554 1486 2555 1415 2555 1483 2555 1486 2556 1483 2556 1492 2556 1492 2557 1483 2557 1419 2557 1416 2558 1488 2558 1484 2558 1484 2559 1488 2559 1492 2559 1484 2560 1492 2560 1419 2560 1418 2561 1489 2561 1485 2561 1488 2562 1416 2562 1485 2562 1489 2563 1488 2563 1485 2563 1428 2564 1448 2564 1436 2564 1431 2565 1459 2565 1433 2565 1431 2566 1461 2566 1459 2566 1433 2567 1459 2567 1494 2567 1433 2568 1494 2568 1425 2568 1438 2569 1495 2569 1431 2569 1436 2570 1448 2570 1446 2570 1425 2571 1494 2571 1457 2571 1438 2572 1493 2572 1443 2572 1438 2573 1443 2573 1495 2573 1438 2574 1436 2574 1493 2574 1493 2575 1436 2575 1446 2575 1448 2576 1428 2576 1451 2576 1448 2577 1451 2577 1450 2577 1428 2578 1496 2578 1451 2578 1428 2579 1452 2579 1496 2579 1428 2580 1426 2580 1452 2580 1426 2581 1455 2581 1452 2581 1426 2582 1425 2582 1455 2582 1455 2583 1425 2583 1457 2583 1431 2584 1495 2584 1461 2584 1497 2585 1498 2585 1499 2585 1499 2586 1501 2586 1497 2586 1502 2587 1498 2587 1497 2587 1500 2588 1503 2588 1497 2588 1497 2589 1501 2589 1500 2589 1497 2590 1504 2590 1505 2590 1505 2591 1506 2591 1497 2591 1503 2592 1504 2592 1497 2592 1497 2593 1506 2593 1502 2593 1509 2594 1508 2594 1507 2594 1508 2595 1510 2595 1507 2595 1507 2596 1510 2596 1512 2596 1507 2597 1512 2597 1511 2597 1507 2598 1511 2598 1513 2598 1507 2599 1513 2599 1514 2599 1514 2600 1515 2600 1507 2600 1516 2601 1509 2601 1507 2601 1515 2602 1516 2602 1507 2602 1517 2603 1518 2603 1519 2603 1517 2604 1521 2604 1522 2604 1520 2605 1521 2605 1517 2605 1517 2606 1519 2606 1520 2606 1517 2607 1522 2607 1523 2607 1517 2608 1525 2608 1518 2608 1524 2609 1525 2609 1517 2609 1517 2610 1523 2610 1524 2610 1526 2611 1527 2611 1528 2611 1528 2612 1529 2612 1526 2612 1530 2613 1527 2613 1526 2613 1529 2614 1531 2614 1526 2614 1531 2615 1532 2615 1526 2615 1533 2616 1530 2616 1526 2616 1526 2617 1532 2617 1534 2617 1526 2618 1534 2618 1535 2618 1526 2619 1535 2619 1533 2619 1537 2620 1538 2620 1539 2620 1539 2621 1538 2621 1540 2621 1536 2622 1541 2622 1542 2622 1536 2623 1542 2623 1537 2623 1537 2624 1542 2624 1538 2624 1540 2625 1544 2625 1543 2625 1544 2626 1542 2626 1545 2626 1545 2627 1542 2627 1541 2627 1542 2628 1544 2628 1538 2628 1538 2629 1544 2629 1540 2629 1540 2630 1543 2630 1539 2630 1498 2631 1553 2631 1546 2631 1499 2632 1546 2632 1547 2632 1502 2633 1553 2633 1498 2633 1498 2634 1546 2634 1499 2634 1501 2635 1499 2635 1547 2635 1501 2636 1547 2636 1548 2636 1501 2637 1548 2637 1500 2637 1500 2638 1548 2638 1549 2638 1500 2639 1549 2639 1503 2639 1503 2640 1549 2640 1550 2640 1503 2641 1550 2641 1504 2641 1504 2642 1550 2642 1505 2642 1505 2643 1550 2643 1551 2643 1505 2644 1551 2644 1506 2644 1506 2645 1551 2645 1552 2645 1506 2646 1552 2646 1553 2646 1506 2647 1553 2647 1502 2647 1509 2648 1554 2648 1555 2648 1512 2649 1556 2649 1557 2649 1511 2650 1557 2650 1558 2650 1508 2651 1509 2651 1555 2651 1508 2652 1555 2652 1510 2652 1510 2653 1555 2653 1556 2653 1510 2654 1556 2654 1512 2654 1511 2655 1512 2655 1557 2655 1513 2656 1511 2656 1558 2656 1515 2657 1560 2657 1561 2657 1515 2658 1561 2658 1516 2658 1516 2659 1561 2659 1554 2659 1513 2660 1558 2660 1559 2660 1513 2661 1559 2661 1514 2661 1514 2662 1559 2662 1560 2662 1514 2663 1560 2663 1515 2663 1509 2664 1516 2664 1554 2664 1518 2665 1562 2665 1563 2665 1520 2666 1563 2666 1564 2666 1520 2667 1564 2667 1565 2667 1522 2668 1565 2668 1566 2668 1519 2669 1518 2669 1563 2669 1519 2670 1563 2670 1520 2670 1521 2671 1520 2671 1565 2671 1521 2672 1565 2672 1522 2672 1524 2673 1567 2673 1568 2673 1525 2674 1568 2674 1562 2674 1522 2675 1566 2675 1523 2675 1523 2676 1566 2676 1567 2676 1523 2677 1567 2677 1524 2677 1525 2678 1524 2678 1568 2678 1518 2679 1525 2679 1562 2679 1530 2680 1569 2680 1527 2680 1527 2681 1569 2681 1528 2681 1528 2682 1569 2682 1570 2682 1528 2683 1570 2683 1529 2683 1529 2684 1570 2684 1571 2684 1529 2685 1571 2685 1531 2685 1531 2686 1571 2686 1572 2686 1531 2687 1572 2687 1573 2687 1532 2688 1573 2688 1574 2688 1532 2689 1574 2689 1534 2689 1534 2690 1574 2690 1575 2690 1533 2691 1576 2691 1577 2691 1531 2692 1573 2692 1532 2692 1535 2693 1534 2693 1575 2693 1535 2694 1575 2694 1533 2694 1533 2695 1575 2695 1576 2695 1530 2696 1533 2696 1577 2696 1530 2697 1577 2697 1569 2697 1580 2698 1581 2698 1582 2698 1582 2699 1583 2699 1580 2699 1580 2700 1583 2700 1584 2700 1578 2701 1579 2701 1583 2701 1578 2702 1583 2702 1585 2702 1581 2703 1586 2703 1582 2703 1582 2704 1586 2704 1585 2704 1582 2705 1585 2705 1583 2705 1583 2706 1579 2706 1584 2706 1584 2707 1579 2707 1578 2707 1587 2708 1588 2708 1578 2708 1589 2709 1587 2709 1586 2709 1586 2710 1587 2710 1585 2710 1587 2711 1578 2711 1585 2711 1591 2712 1590 2712 1592 2712 1587 2713 1592 2713 1588 2713 1593 2714 1590 2714 1591 2714 1591 2715 1592 2715 1587 2715 1594 2716 1595 2716 1597 2716 1595 2717 1590 2717 1597 2717 1590 2718 1593 2718 1596 2718 1590 2719 1596 2719 1597 2719 1598 2720 1599 2720 1600 2720 1602 2721 1598 2721 1603 2721 1603 2722 1598 2722 1601 2722 1598 2723 1600 2723 1601 2723 1607 2724 1604 2724 1605 2724 1607 2725 1605 2725 1606 2725 1606 2726 1605 2726 1599 2726 1606 2727 1599 2727 1598 2727 1536 2728 1537 2728 1604 2728 1539 2729 1604 2729 1537 2729 1536 2730 1604 2730 1607 2730 1536 2731 1607 2731 1608 2731 1610 2732 1611 2732 1545 2732 1545 2733 1611 2733 1609 2733 1545 2734 1609 2734 1544 2734 1609 2735 1543 2735 1544 2735 1613 2736 1612 2736 1614 2736 1613 2737 1614 2737 1609 2737 1615 2738 1612 2738 1613 2738 1611 2739 1613 2739 1609 2739 1616 2740 1617 2740 1619 2740 1617 2741 1612 2741 1619 2741 1612 2742 1615 2742 1618 2742 1612 2743 1618 2743 1619 2743 1575 2744 1578 2744 1588 2744 1575 324 1588 324 1576 324 1576 324 1588 324 1577 324 1621 324 1622 324 1590 324 1590 324 1622 324 1592 324 1592 324 1622 324 1623 324 1569 324 1577 324 1620 324 1620 324 1577 324 1588 324 1620 324 1588 324 1623 324 1623 324 1588 324 1592 324 1553 2745 1552 2745 1600 2745 1600 2746 1552 2746 1551 2746 1600 2747 1551 2747 1595 2747 1595 2748 1551 2748 1550 2748 1595 2749 1550 2749 1590 2749 1590 324 1550 324 1549 324 1590 324 1549 324 1548 324 1590 324 1548 324 1621 324 1621 324 1548 324 1547 324 1621 324 1547 324 1599 324 1599 324 1547 324 1546 324 1599 324 1546 324 1553 324 1599 2750 1553 2750 1600 2750 1561 2751 1560 2751 1539 2751 1539 2752 1560 2752 1604 2752 1604 324 1560 324 1559 324 1621 324 1599 324 1605 324 1621 2753 1605 2753 1624 2753 1624 2754 1605 2754 1604 2754 1624 2755 1604 2755 1559 2755 1624 2756 1559 2756 1558 2756 1557 324 1609 324 1558 324 1558 2757 1609 2757 1624 2757 1556 2758 1543 2758 1609 2758 1556 324 1609 324 1557 324 1556 2759 1555 2759 1543 2759 1543 2760 1555 2760 1554 2760 1543 2761 1554 2761 1539 2761 1539 2762 1554 2762 1561 2762 1625 324 1614 324 1626 324 1614 324 1625 324 1609 324 1609 2763 1625 2763 1624 2763 1567 324 1566 324 1627 324 1612 324 1568 324 1626 324 1612 324 1626 324 1614 324 1565 2764 1633 2764 1566 2764 1566 2765 1633 2765 1627 2765 1633 2766 1565 2766 1564 2766 1633 2767 1564 2767 1563 2767 1633 2768 1563 2768 1617 2768 1563 2769 1562 2769 1617 2769 1617 2770 1562 2770 1612 2770 1612 324 1562 324 1568 324 1628 324 1627 324 1629 324 1568 324 1567 324 1626 324 1626 324 1567 324 1627 324 1626 324 1627 324 1628 324 1575 2771 1574 2771 1578 2771 1578 2772 1574 2772 1573 2772 1578 2773 1573 2773 1584 2773 1584 2774 1573 2774 1572 2774 1584 2775 1572 2775 1571 2775 1584 2776 1571 2776 1570 2776 1584 2777 1570 2777 1630 2777 1630 324 1570 324 1569 324 1627 324 1631 324 1629 324 1629 324 1631 324 1630 324 1629 324 1630 324 1620 324 1620 324 1630 324 1569 324 1632 2778 1627 2778 1633 2778 1635 2779 1632 2779 1636 2779 1636 2780 1632 2780 1634 2780 1632 2781 1633 2781 1634 2781 1637 2782 1630 2782 1631 2782 1637 2783 1631 2783 1638 2783 1638 2784 1631 2784 1627 2784 1638 2785 1627 2785 1632 2785 1630 2786 1637 2786 1584 2786 1584 2787 1637 2787 1580 2787 1637 2788 1639 2788 1580 2788 1640 2789 1596 2789 1593 2789 1641 2790 1593 2790 1642 2790 1593 2791 1641 2791 1640 2791 1642 2792 1593 2792 1591 2792 1642 2793 1591 2793 1587 2793 1642 324 1587 324 1643 324 1643 2794 1587 2794 1589 2794 1597 2795 1646 2795 1594 2795 1646 2796 1645 2796 1594 2796 1594 2797 1645 2797 1595 2797 1600 2798 1644 2798 1645 2798 1600 2799 1645 2799 1601 2799 1646 2800 1603 2800 1601 2800 1646 2801 1601 2801 1645 2801 1645 2802 1644 2802 1595 2802 1595 2803 1644 2803 1600 2803 1607 324 1606 324 1647 324 1608 2804 1607 2804 1648 2804 1607 2805 1647 2805 1648 2805 1598 2806 1602 2806 1649 2806 1598 2807 1649 2807 1650 2807 1598 2808 1650 2808 1651 2808 1647 324 1606 324 1598 324 1647 324 1598 324 1651 324 1652 324 1653 324 1615 324 1615 324 1653 324 1654 324 1654 2809 1655 2809 1615 2809 1615 2810 1655 2810 1618 2810 1615 324 1613 324 1652 324 1652 2811 1613 2811 1656 2811 1656 324 1613 324 1611 324 1656 2812 1611 2812 1610 2812 1619 2813 1659 2813 1616 2813 1659 2814 1658 2814 1616 2814 1616 2815 1658 2815 1617 2815 1633 2816 1657 2816 1658 2816 1633 2817 1658 2817 1634 2817 1659 2818 1636 2818 1634 2818 1659 2819 1634 2819 1658 2819 1658 2820 1657 2820 1617 2820 1617 2821 1657 2821 1633 2821 1637 324 1660 324 1661 324 1637 2822 1661 2822 1639 2822 1638 324 1632 324 1660 324 1638 324 1660 324 1637 324 1635 2823 1662 2823 1632 2823 1632 2824 1662 2824 1663 2824 1663 324 1664 324 1632 324 1632 324 1664 324 1660 324 1665 2825 1589 2825 1586 2825 1665 2826 1586 2826 1666 2826 1666 2827 1586 2827 1581 2827 1667 2828 1640 2828 1641 2828 1667 2829 1641 2829 1668 2829 1668 2830 1641 2830 1642 2830 1668 2831 1642 2831 1669 2831 1669 2832 1642 2832 1670 2832 1670 2833 1642 2833 1643 2833 1671 2834 1643 2834 1589 2834 1671 2835 1589 2835 1665 2835 1672 2836 1596 2836 1640 2836 1673 2837 1674 2837 1602 2837 1602 2838 1674 2838 1649 2838 1649 2839 1674 2839 1675 2839 1649 2840 1675 2840 1650 2840 1650 2841 1676 2841 1651 2841 1651 2842 1676 2842 1677 2842 1651 2843 1677 2843 1647 2843 1647 2844 1678 2844 1648 2844 1608 2845 1679 2845 1536 2845 1679 2846 1541 2846 1536 2846 1643 2847 1671 2847 1670 2847 1640 2848 1667 2848 1672 2848 1650 2849 1675 2849 1676 2849 1647 2850 1677 2850 1678 2850 1648 2851 1678 2851 1680 2851 1648 2852 1680 2852 1608 2852 1608 2853 1680 2853 1679 2853 1597 2854 1596 2854 1672 2854 1597 2855 1672 2855 1646 2855 1646 2856 1672 2856 1673 2856 1646 2857 1673 2857 1603 2857 1603 2858 1673 2858 1602 2858 1610 2859 1545 2859 1541 2859 1679 2860 1610 2860 1541 2860 1681 2861 1655 2861 1654 2861 1653 2862 1652 2862 1682 2862 1682 2863 1652 2863 1683 2863 1683 2864 1652 2864 1656 2864 1684 2865 1618 2865 1655 2865 1685 2866 1686 2866 1635 2866 1635 2867 1686 2867 1662 2867 1663 2868 1687 2868 1664 2868 1664 2869 1687 2869 1688 2869 1664 2870 1688 2870 1660 2870 1660 2871 1689 2871 1661 2871 1661 2872 1689 2872 1690 2872 1661 2873 1690 2873 1639 2873 1639 2874 1666 2874 1580 2874 1666 2875 1581 2875 1580 2875 1610 2876 1679 2876 1691 2876 1610 2877 1691 2877 1656 2877 1656 2878 1691 2878 1683 2878 1653 2879 1682 2879 1692 2879 1653 2880 1692 2880 1654 2880 1654 2881 1692 2881 1681 2881 1655 2882 1681 2882 1684 2882 1662 2883 1686 2883 1693 2883 1662 2884 1693 2884 1663 2884 1663 2885 1693 2885 1687 2885 1660 2886 1688 2886 1689 2886 1639 2887 1690 2887 1666 2887 1619 2888 1618 2888 1684 2888 1619 2889 1684 2889 1659 2889 1659 2890 1684 2890 1685 2890 1659 2891 1685 2891 1636 2891 1636 2892 1685 2892 1635 2892 1694 348 1681 348 1695 348 1695 2893 1681 2893 1692 2893 1695 348 1692 348 1696 348 1696 348 1692 348 1682 348 1696 2894 1682 2894 1697 2894 1697 348 1682 348 1683 348 1697 348 1683 348 1698 348 1699 2895 1693 2895 1700 2895 1700 2896 1693 2896 1701 2896 1701 348 1693 348 1686 348 1701 2897 1686 2897 1685 2897 1701 2898 1685 2898 1702 2898 1702 2899 1685 2899 1694 2899 1694 2900 1685 2900 1684 2900 1694 2901 1684 2901 1681 2901 1703 2902 1690 2902 1689 2902 1703 2903 1689 2903 1704 2903 1704 2904 1689 2904 1688 2904 1704 2905 1688 2905 1699 2905 1699 348 1688 348 1687 348 1699 2906 1687 2906 1693 2906 1705 2907 1671 2907 1665 2907 1705 2908 1665 2908 1706 2908 1706 2909 1665 2909 1666 2909 1706 2910 1666 2910 1703 2910 1703 2911 1666 2911 1690 2911 1707 348 1667 348 1708 348 1708 2912 1667 2912 1668 2912 1708 348 1668 348 1669 348 1708 348 1669 348 1709 348 1709 2913 1669 2913 1710 2913 1710 2914 1669 2914 1670 2914 1710 348 1670 348 1705 348 1705 348 1670 348 1671 348 1715 2915 1674 2915 1711 2915 1711 2916 1674 2916 1673 2916 1711 2917 1673 2917 1712 2917 1712 2918 1673 2918 1672 2918 1712 2919 1672 2919 1707 2919 1707 2920 1672 2920 1667 2920 1713 348 1680 348 1678 348 1713 348 1678 348 1714 348 1714 348 1678 348 1677 348 1714 2921 1677 2921 1715 2921 1715 2922 1677 2922 1676 2922 1715 2923 1676 2923 1675 2923 1715 2924 1675 2924 1674 2924 1698 348 1683 348 1691 348 1698 348 1691 348 1716 348 1716 2925 1691 2925 1679 2925 1716 2926 1679 2926 1717 2926 1717 2927 1679 2927 1713 2927 1713 2928 1679 2928 1680 2928 1705 2929 1718 2929 1719 2929 1705 2930 1719 2930 1710 2930 1710 2931 1719 2931 1720 2931 1709 2932 1720 2932 1721 2932 1709 2933 1721 2933 1708 2933 1708 2934 1721 2934 1722 2934 1707 2935 1722 2935 1723 2935 1711 2936 1724 2936 1725 2936 1713 2937 1729 2937 1730 2937 1706 2938 1718 2938 1705 2938 1710 2939 1720 2939 1709 2939 1708 2940 1722 2940 1707 2940 1707 2941 1723 2941 1712 2941 1712 2942 1723 2942 1724 2942 1712 2943 1724 2943 1711 2943 1711 2944 1725 2944 1715 2944 1715 2945 1725 2945 1726 2945 1715 2946 1726 2946 1727 2946 1715 2947 1727 2947 1714 2947 1714 2948 1727 2948 1728 2948 1714 2949 1728 2949 1713 2949 1713 2950 1728 2950 1729 2950 1717 2951 1713 2951 1730 2951 1717 2952 1730 2952 1731 2952 1698 2953 1732 2953 1733 2953 1698 2954 1733 2954 1697 2954 1697 2955 1733 2955 1734 2955 1696 2956 1734 2956 1735 2956 1696 2957 1735 2957 1695 2957 1695 2958 1735 2958 1736 2958 1694 2959 1736 2959 1737 2959 1702 2960 1737 2960 1738 2960 1700 2961 1739 2961 1740 2961 1704 2962 1741 2962 1742 2962 1703 2963 1742 2963 1743 2963 1703 2964 1743 2964 1706 2964 1706 2965 1743 2965 1718 2965 1717 2966 1731 2966 1716 2966 1716 2967 1731 2967 1732 2967 1716 2968 1732 2968 1698 2968 1697 2969 1734 2969 1696 2969 1695 2970 1736 2970 1694 2970 1694 2971 1737 2971 1702 2971 1701 2972 1702 2972 1738 2972 1701 2973 1738 2973 1739 2973 1701 2974 1739 2974 1700 2974 1699 2975 1700 2975 1740 2975 1699 2976 1740 2976 1741 2976 1699 2977 1741 2977 1704 2977 1704 2978 1742 2978 1703 2978 1733 2979 1744 2979 1745 2979 1746 2980 1735 2980 1745 2980 1745 2981 1735 2981 1734 2981 1745 348 1734 348 1733 348 1746 348 1736 348 1735 348 1747 2982 1737 2982 1746 2982 1746 2983 1737 2983 1736 2983 1747 2984 1738 2984 1737 2984 1748 348 1740 348 1747 348 1747 2985 1740 2985 1739 2985 1747 2986 1739 2986 1738 2986 1748 2987 1741 2987 1740 2987 1749 2988 1742 2988 1748 2988 1748 2989 1742 2989 1741 2989 1750 348 1743 348 1749 348 1749 348 1743 348 1742 348 1751 348 1719 348 1750 348 1750 2990 1719 2990 1718 2990 1750 348 1718 348 1743 348 1751 2991 1720 2991 1719 2991 1752 2992 1721 2992 1751 2992 1751 2993 1721 2993 1720 2993 1753 2994 1723 2994 1752 2994 1752 2995 1723 2995 1722 2995 1752 348 1722 348 1721 348 1753 2996 1724 2996 1723 2996 1754 348 1725 348 1753 348 1753 2997 1725 2997 1724 2997 1755 2998 1726 2998 1754 2998 1754 2999 1726 2999 1725 2999 1755 3000 1727 3000 1726 3000 1756 348 1728 348 1755 348 1755 3001 1728 3001 1727 3001 1756 348 1730 348 1729 348 1756 348 1729 348 1728 348 1744 3002 1733 3002 1732 3002 1744 348 1732 348 1731 348 1744 3003 1731 3003 1756 3003 1756 348 1731 348 1730 348 1751 3004 1757 3004 1758 3004 1752 3005 1758 3005 1759 3005 1752 3006 1759 3006 1753 3006 1753 3007 1759 3007 1760 3007 1754 3008 1760 3008 1761 3008 1756 3009 1762 3009 1763 3009 1750 3010 1757 3010 1751 3010 1751 3011 1758 3011 1752 3011 1753 3012 1760 3012 1754 3012 1755 3013 1754 3013 1761 3013 1755 3014 1761 3014 1762 3014 1755 3015 1762 3015 1756 3015 1765 348 1764 348 1766 348 1766 348 1767 348 1765 348 1765 348 1767 348 1763 348 1768 348 1765 348 1757 348 1757 348 1765 348 1763 348 1757 3016 1763 3016 1762 3016 1760 348 1759 348 1762 348 1762 348 1759 348 1758 348 1762 3017 1758 3017 1757 3017 1762 348 1761 348 1760 348 1744 3018 1763 3018 1767 3018 1745 3019 1767 3019 1766 3019 1747 3020 1764 3020 1765 3020 1749 3021 1768 3021 1750 3021 1750 3022 1768 3022 1757 3022 1756 3023 1763 3023 1744 3023 1744 3024 1767 3024 1745 3024 1746 3025 1745 3025 1766 3025 1746 3026 1766 3026 1764 3026 1746 3027 1764 3027 1747 3027 1748 3028 1747 3028 1765 3028 1748 3029 1765 3029 1768 3029 1748 3030 1768 3030 1749 3030 1621 3031 1624 3031 1769 3031 1769 3032 1624 3032 1770 3032 1770 3033 1624 3033 1625 3033 1770 3034 1625 3034 1771 3034 1771 3035 1625 3035 1626 3035 1771 3036 1626 3036 1772 3036 1772 3037 1626 3037 1628 3037 1772 3038 1628 3038 1773 3038 1773 3039 1628 3039 1629 3039 1773 3040 1629 3040 1774 3040 1774 3041 1629 3041 1620 3041 1774 3042 1620 3042 1775 3042 1775 3043 1620 3043 1623 3043 1775 3044 1623 3044 1622 3044 1775 3045 1622 3045 1776 3045 1776 3046 1622 3046 1777 3046 1777 3047 1622 3047 1621 3047 1777 3048 1621 3048 1769 3048 1769 324 1773 324 1774 324 1771 324 1772 324 1769 324 1769 324 1772 324 1773 324 1769 3049 1770 3049 1771 3049 1776 324 1777 324 1769 324 1774 324 1775 324 1769 324 1769 324 1775 324 1776 324 1778 3050 1779 3050 1780 3050 1780 3051 1779 3051 1781 3051 1780 3052 1781 3052 1782 3052 1780 3053 1782 3053 1783 3053 1783 3054 1782 3054 1784 3054 1783 3055 1784 3055 1785 3055 1784 3056 1786 3056 1785 3056 1785 3057 1786 3057 1787 3057 1787 3058 1786 3058 1788 3058 1787 3059 1788 3059 1789 3059 1789 3060 1788 3060 1790 3060 1789 3061 1790 3061 1791 3061 1789 3062 1791 3062 1778 3062 1778 3063 1791 3063 1779 3063 1792 3064 1793 3064 1794 3064 1794 3065 1793 3065 1795 3065 1794 3066 1795 3066 1796 3066 1797 3067 1810 3067 1798 3067 1797 3068 1798 3068 1799 3068 1799 3069 1798 3069 1800 3069 1800 3070 1798 3070 1801 3070 1800 3071 1801 3071 1802 3071 1802 3072 1801 3072 1803 3072 1802 3073 1803 3073 1792 3073 1792 3074 1803 3074 1793 3074 1796 3075 1795 3075 1804 3075 1796 3076 1804 3076 1805 3076 1805 3077 1804 3077 1806 3077 1806 3078 1804 3078 1807 3078 1806 3079 1807 3079 1808 3079 1808 3080 1807 3080 1809 3080 1809 3081 1807 3081 1810 3081 1809 3082 1810 3082 1797 3082 1812 3083 1811 3083 1813 3083 1812 3084 1813 3084 1814 3084 1814 3085 1813 3085 1816 3085 1814 3086 1816 3086 1815 3086 1815 3087 1816 3087 1817 3087 1815 3088 1817 3088 1818 3088 1818 3089 1817 3089 1819 3089 1818 3090 1819 3090 1820 3090 1820 3091 1819 3091 1821 3091 1820 3092 1821 3092 1822 3092 1821 3093 1863 3093 1822 3093 1823 3094 1824 3094 1822 3094 1823 3095 1822 3095 1863 3095 1825 3096 1824 3096 1823 3096 1824 3097 1825 3097 1827 3097 1824 3098 1827 3098 1826 3098 1826 3099 1827 3099 1828 3099 1826 3100 1828 3100 1829 3100 1829 3101 1828 3101 1830 3101 1829 3102 1830 3102 1812 3102 1812 3103 1830 3103 1811 3103 1831 3104 1832 3104 1833 3104 1834 3105 1831 3105 1833 3105 1835 3106 1834 3106 1833 3106 1833 3107 1836 3107 1835 3107 1837 3108 1809 3108 1838 3108 1838 3109 1809 3109 1797 3109 1838 3110 1797 3110 1839 3110 1839 3111 1797 3111 1799 3111 1839 3112 1799 3112 1840 3112 1840 3113 1799 3113 1800 3113 1840 3114 1800 3114 1841 3114 1841 3115 1800 3115 1802 3115 1841 3116 1802 3116 1842 3116 1842 3117 1802 3117 1792 3117 1842 3118 1792 3118 1843 3118 1843 3119 1792 3119 1794 3119 1843 3120 1794 3120 1844 3120 1844 3121 1794 3121 1796 3121 1844 3122 1796 3122 1845 3122 1845 3123 1796 3123 1805 3123 1845 3124 1805 3124 1846 3124 1846 3125 1805 3125 1806 3125 1846 3126 1806 3126 1847 3126 1847 3127 1806 3127 1808 3127 1847 3128 1808 3128 1837 3128 1837 3129 1808 3129 1809 3129 1843 3130 1790 3130 1788 3130 1843 3131 1788 3131 1842 3131 1842 3132 1788 3132 1841 3132 1841 3133 1788 3133 1786 3133 1841 3134 1786 3134 1840 3134 1840 3135 1786 3135 1784 3135 1840 3136 1784 3136 1839 3136 1839 3137 1784 3137 1838 3137 1838 3138 1784 3138 1782 3138 1838 3139 1782 3139 1837 3139 1837 3140 1782 3140 1847 3140 1847 3141 1782 3141 1781 3141 1847 3142 1781 3142 1846 3142 1846 3143 1781 3143 1779 3143 1846 3144 1779 3144 1845 3144 1845 3145 1779 3145 1844 3145 1844 3146 1779 3146 1791 3146 1844 3147 1791 3147 1843 3147 1843 3148 1791 3148 1790 3148 1812 3149 1831 3149 1829 3149 1829 3150 1831 3150 1834 3150 1829 3151 1834 3151 1826 3151 1826 3152 1834 3152 1824 3152 1824 3153 1834 3153 1835 3153 1824 3154 1835 3154 1822 3154 1822 3155 1835 3155 1836 3155 1822 3156 1836 3156 1820 3156 1820 3157 1836 3157 1833 3157 1820 3158 1833 3158 1818 3158 1818 3159 1833 3159 1815 3159 1815 3160 1833 3160 1832 3160 1815 3161 1832 3161 1814 3161 1814 3162 1832 3162 1812 3162 1812 3163 1832 3163 1831 3163 1778 3164 1848 3164 1789 3164 1780 3165 1849 3165 1778 3165 1783 3166 1850 3166 1780 3166 1785 3167 1851 3167 1783 3167 1787 3168 1852 3168 1785 3168 1789 3169 1853 3169 1787 3169 1857 3170 1858 3170 1855 3170 1857 3171 1855 3171 1856 3171 1856 3172 1855 3172 1854 3172 1859 3173 1854 3173 1855 3173 1860 3174 1859 3174 1855 3174 1861 3175 1860 3175 1855 3175 1855 3176 1858 3176 1861 3176 1859 3177 1789 3177 1848 3177 1859 3178 1848 3178 1854 3178 1778 3179 1854 3179 1848 3179 1856 3180 1849 3180 1857 3180 1857 3181 1849 3181 1780 3181 1854 3182 1778 3182 1849 3182 1849 3183 1856 3183 1854 3183 1850 3184 1783 3184 1858 3184 1850 3185 1857 3185 1780 3185 1850 3186 1858 3186 1857 3186 1785 3187 1861 3187 1851 3187 1858 3188 1783 3188 1851 3188 1858 3189 1851 3189 1861 3189 1787 3190 1860 3190 1852 3190 1861 3191 1785 3191 1852 3191 1861 3192 1852 3192 1860 3192 1789 3193 1859 3193 1853 3193 1860 3194 1787 3194 1853 3194 1860 3195 1853 3195 1859 3195 1804 3196 1795 3196 1862 3196 1803 3197 1863 3197 1793 3197 1807 3198 1813 3198 1811 3198 1807 3199 1811 3199 1810 3199 1803 3200 1823 3200 1863 3200 1863 3201 1821 3201 1793 3201 1793 3202 1821 3202 1819 3202 1793 3203 1819 3203 1795 3203 1811 3204 1830 3204 1810 3204 1807 3205 1804 3205 1813 3205 1813 3206 1804 3206 1816 3206 1804 3207 1862 3207 1817 3207 1804 3208 1817 3208 1816 3208 1862 3209 1795 3209 1819 3209 1862 3210 1819 3210 1817 3210 1803 3211 1825 3211 1823 3211 1803 3212 1801 3212 1825 3212 1801 3213 1827 3213 1825 3213 1801 3214 1798 3214 1827 3214 1798 3215 1828 3215 1827 3215 1798 3216 1810 3216 1828 3216 1810 3217 1830 3217 1828 3217 1864 3218 1865 3218 1866 3218 1866 3219 1865 3219 1867 3219 1868 3220 1864 3220 1869 3220 1869 3221 1864 3221 1866 3221 1870 3222 1868 3222 1871 3222 1871 3223 1868 3223 1869 3223 1865 3224 1870 3224 1867 3224 1867 3225 1870 3225 1871 3225 1868 3226 1870 3226 1864 3226 1864 3227 1870 3227 1865 3227 1871 324 1869 324 1867 324 1867 324 1869 324 1866 324 1877 3228 1874 3228 1875 3228 1872 3229 1873 3229 1876 3229 1876 3230 1877 3230 1875 3230 1872 3231 1876 3231 1875 3231 1878 3232 1874 3232 1877 3232 1881 3233 1879 3233 1880 3233 1875 3234 1874 3234 1878 3234 1878 3235 1881 3235 1880 3235 1875 3236 1878 3236 1880 3236 1881 3237 1882 3237 1879 3237 1883 3238 1879 3238 1882 3238 1880 3239 1879 3239 1883 3239 1884 3240 1886 3240 1885 3240 1880 3241 1883 3241 1884 3241 1880 3242 1884 3242 1885 3242 1889 3243 1886 3243 1888 3243 1888 3244 1886 3244 1884 3244 1887 3245 1886 3245 1890 3245 1890 3246 1886 3246 1889 3246 1893 3247 1891 3247 1892 3247 1887 3248 1893 3248 1892 3248 1885 3249 1886 3249 1892 3249 1892 3250 1886 3250 1887 3250 1891 3251 1893 3251 1894 3251 1892 3252 1891 3252 1894 3252 1894 3253 1896 3253 1895 3253 1892 3254 1894 3254 1895 3254 1899 3255 1896 3255 1894 3255 1900 3256 1896 3256 1899 3256 1900 3257 1897 3257 1896 3257 1901 3258 1873 3258 1872 3258 1895 3259 1896 3259 1897 3259 1898 3260 1901 3260 1872 3260 1895 3261 1897 3261 1872 3261 1872 3262 1897 3262 1898 3262 1876 3263 1873 3263 1901 3263 1898 3264 1904 3264 1903 3264 1884 3265 1902 3265 1910 3265 1902 3266 1884 3266 1883 3266 1903 3267 1876 3267 1901 3267 1903 3268 1901 3268 1898 3268 1904 3269 1905 3269 1906 3269 1904 3270 1906 3270 1907 3270 1904 3271 1898 3271 1908 3271 1904 3272 1908 3272 1909 3272 1904 3273 1909 3273 1905 3273 1915 3274 1876 3274 1903 3274 1915 3275 1877 3275 1876 3275 1910 3276 1911 3276 1912 3276 1910 3277 1912 3277 1913 3277 1910 3278 1913 3278 1884 3278 1893 3279 1887 3279 1907 3279 1907 3280 1887 3280 1910 3280 1910 3281 1887 3281 1914 3281 1910 3282 1914 3282 1911 3282 1915 3283 1878 3283 1877 3283 1902 3284 1883 3284 1882 3284 1902 3285 1882 3285 1915 3285 1907 3286 1894 3286 1893 3286 1915 3287 1882 3287 1878 3287 1906 3288 1916 3288 1907 3288 1907 3289 1916 3289 1894 3289 1903 3290 1904 3290 1917 3290 1917 3291 1918 3291 1903 3291 1903 3292 1918 3292 1915 3292 1915 3293 1918 3293 1919 3293 1915 3294 1919 3294 1902 3294 1919 3295 1920 3295 1902 3295 1921 3296 1902 3296 1920 3296 1910 3297 1902 3297 1921 3297 1921 3298 1922 3298 1910 3298 1910 3299 1922 3299 1907 3299 1907 3300 1922 3300 1923 3300 1907 3301 1923 3301 1904 3301 1923 3302 1924 3302 1904 3302 1917 3303 1904 3303 1924 3303 1925 3304 1917 3304 1924 3304 1925 3305 1924 3305 1923 3305 1925 3306 1923 3306 1926 3306 1926 3307 1923 3307 1927 3307 1927 3308 1923 3308 1922 3308 1927 3309 1922 3309 1928 3309 1928 3310 1922 3310 1921 3310 1928 3311 1921 3311 1929 3311 1929 3312 1921 3312 1920 3312 1929 3313 1920 3313 1919 3313 1929 3314 1919 3314 1930 3314 1930 3315 1919 3315 1931 3315 1931 3316 1919 3316 1918 3316 1931 3317 1918 3317 1932 3317 1932 3318 1918 3318 1917 3318 1932 3319 1917 3319 1925 3319 1933 3320 1929 3320 1934 3320 1929 3321 1930 3321 1934 3321 1934 3322 1930 3322 1935 3322 1930 3323 1931 3323 1935 3323 1935 3324 1931 3324 1936 3324 1931 3325 1932 3325 1936 3325 1925 3326 1937 3326 1932 3326 1932 3327 1937 3327 1936 3327 1937 3328 1925 3328 1938 3328 1925 3329 1926 3329 1938 3329 1926 3330 1927 3330 1938 3330 1938 3331 1927 3331 1939 3331 1927 3332 1928 3332 1939 3332 1939 3333 1928 3333 1933 3333 1929 3334 1933 3334 1928 3334 1939 3335 1933 3335 1885 3335 1885 3336 1933 3336 1880 3336 1880 3337 1933 3337 1934 3337 1875 3338 1935 3338 1872 3338 1872 3339 1935 3339 1936 3339 1892 3340 1938 3340 1939 3340 1892 3341 1939 3341 1885 3341 1880 3342 1934 3342 1875 3342 1875 3343 1934 3343 1935 3343 1872 3344 1936 3344 1895 3344 1895 3345 1936 3345 1937 3345 1895 3346 1937 3346 1938 3346 1895 3347 1938 3347 1892 3347 1945 3348 1942 3348 1943 3348 1940 3349 1941 3349 1944 3349 1944 3350 1945 3350 1943 3350 1940 3351 1944 3351 1943 3351 1946 3352 1942 3352 1945 3352 1949 3353 1947 3353 1948 3353 1943 3354 1942 3354 1946 3354 1946 3355 1949 3355 1948 3355 1943 3356 1946 3356 1948 3356 1950 3357 1947 3357 1949 3357 1948 3358 1947 3358 1950 3358 1951 3359 1953 3359 1952 3359 1948 3360 1950 3360 1951 3360 1948 3361 1951 3361 1952 3361 1956 3362 1953 3362 1955 3362 1955 3363 1953 3363 1951 3363 1954 3364 1953 3364 1957 3364 1957 3365 1953 3365 1956 3365 1960 3366 1958 3366 1959 3366 1954 3367 1960 3367 1959 3367 1952 3368 1953 3368 1959 3368 1959 3369 1953 3369 1954 3369 1958 3370 1960 3370 1961 3370 1959 3371 1958 3371 1961 3371 1961 3372 1963 3372 1962 3372 1959 3373 1961 3373 1962 3373 1966 3374 1963 3374 1961 3374 1967 3375 1963 3375 1966 3375 1967 3376 1964 3376 1963 3376 1968 3377 1941 3377 1940 3377 1962 3378 1963 3378 1964 3378 1965 3379 1968 3379 1940 3379 1962 3380 1964 3380 1940 3380 1940 3381 1964 3381 1965 3381 1944 3382 1941 3382 1968 3382 1965 3383 1971 3383 1970 3383 1951 3384 1969 3384 1977 3384 1969 3385 1951 3385 1950 3385 1970 3386 1944 3386 1968 3386 1970 3387 1968 3387 1965 3387 1971 3388 1972 3388 1973 3388 1971 3389 1973 3389 1974 3389 1971 3390 1965 3390 1975 3390 1971 3391 1975 3391 1976 3391 1971 3392 1976 3392 1972 3392 1982 3393 1944 3393 1970 3393 1982 3394 1945 3394 1944 3394 1977 3395 1978 3395 1979 3395 1977 3396 1979 3396 1980 3396 1977 3397 1980 3397 1951 3397 1960 3398 1954 3398 1974 3398 1974 3399 1954 3399 1977 3399 1977 3400 1954 3400 1981 3400 1977 3401 1981 3401 1978 3401 1982 3402 1946 3402 1945 3402 1969 3403 1950 3403 1949 3403 1969 3404 1949 3404 1982 3404 1974 3405 1961 3405 1960 3405 1949 3406 1946 3406 1982 3406 1973 3407 1983 3407 1974 3407 1974 3408 1983 3408 1961 3408 1970 3409 1971 3409 1984 3409 1984 3410 1985 3410 1970 3410 1970 3411 1985 3411 1982 3411 1982 3412 1985 3412 1986 3412 1982 3413 1986 3413 1969 3413 1986 3414 1987 3414 1969 3414 1988 3415 1969 3415 1987 3415 1977 3416 1969 3416 1988 3416 1988 3417 1989 3417 1977 3417 1977 3418 1989 3418 1974 3418 1974 3419 1989 3419 1990 3419 1974 3420 1990 3420 1971 3420 1990 3421 1991 3421 1971 3421 1984 3422 1971 3422 1991 3422 1992 3423 1984 3423 1991 3423 1992 3424 1991 3424 1990 3424 1992 3425 1990 3425 1993 3425 1993 3426 1990 3426 1994 3426 1994 3427 1990 3427 1989 3427 1994 3428 1989 3428 1995 3428 1995 3429 1989 3429 1988 3429 1995 3430 1988 3430 1996 3430 1996 3431 1988 3431 1987 3431 1996 3432 1987 3432 1986 3432 1996 3433 1986 3433 1997 3433 1997 3434 1986 3434 1998 3434 1998 3435 1986 3435 1985 3435 1998 3436 1985 3436 1999 3436 1999 3437 1985 3437 1984 3437 1999 3438 1984 3438 1992 3438 2000 3439 1996 3439 2001 3439 1996 3440 1997 3440 2001 3440 1997 3441 1998 3441 2001 3441 2001 3442 1998 3442 2002 3442 1998 3443 1999 3443 2002 3443 2002 3444 1999 3444 2003 3444 1992 3445 2003 3445 1999 3445 2003 3446 1992 3446 2004 3446 1992 3447 1993 3447 2004 3447 1993 3448 1994 3448 2004 3448 2004 3449 1994 3449 2005 3449 1994 3450 1995 3450 2005 3450 2005 3451 1995 3451 2000 3451 1996 3452 2000 3452 1995 3452 2005 3453 2000 3453 1952 3453 1952 3454 2000 3454 1948 3454 1943 3455 2001 3455 2002 3455 1943 3456 2002 3456 1940 3456 1959 3457 2004 3457 2005 3457 1959 3458 2005 3458 1952 3458 1948 3459 2000 3459 2001 3459 1948 3460 2001 3460 1943 3460 1940 3461 2002 3461 2003 3461 1940 3462 2003 3462 1962 3462 1962 3463 2003 3463 2004 3463 1962 3464 2004 3464 1959 3464 2006 3465 2007 3465 2008 3465 2006 3466 2008 3466 2009 3466 2010 3467 2011 3467 2006 3467 2006 3468 2011 3468 2007 3468 2012 3469 2013 3469 2010 3469 2010 3470 2013 3470 2011 3470 2014 3471 2015 3471 2012 3471 2012 3472 2015 3472 2016 3472 2012 3473 2016 3473 2013 3473 2019 3474 2020 3474 2014 3474 2014 3475 2020 3475 2017 3475 2014 3476 2017 3476 2015 3476 2009 3477 2018 3477 2019 3477 2019 3478 2018 3478 2020 3478 2009 3479 2008 3479 2021 3479 2009 3480 2021 3480 2018 3480 2022 3481 2023 3481 2024 3481 2024 3482 2023 3482 2025 3482 2024 3483 2025 3483 2026 3483 2026 3484 2025 3484 2027 3484 2026 3485 2027 3485 2028 3485 2028 3486 2027 3486 2029 3486 2029 3487 2027 3487 2030 3487 2029 3488 2030 3488 2031 3488 2031 3489 2030 3489 2032 3489 2031 3490 2032 3490 2033 3490 2033 3491 2032 3491 2034 3491 2034 3492 2032 3492 2035 3492 2034 3493 2035 3493 2036 3493 2036 3494 2035 3494 2037 3494 2037 3495 2035 3495 2038 3495 2037 3496 2038 3496 2039 3496 2038 3497 2040 3497 2039 3497 2039 3498 2040 3498 2041 3498 2041 3499 2040 3499 2042 3499 2041 3500 2042 3500 2043 3500 2043 3501 2042 3501 2044 3501 2044 3502 2042 3502 2045 3502 2044 3503 2045 3503 2046 3503 2046 3504 2045 3504 2047 3504 2046 3505 2047 3505 2048 3505 2048 3506 2047 3506 2049 3506 2049 3507 2047 3507 2050 3507 2049 3508 2050 3508 2051 3508 2051 3509 2050 3509 2052 3509 2051 3510 2052 3510 2053 3510 2053 3511 2052 3511 2054 3511 2054 3512 2052 3512 2055 3512 2054 3513 2055 3513 2056 3513 2056 3514 2055 3514 2057 3514 2056 3515 2057 3515 2058 3515 2058 3516 2057 3516 2059 3516 2058 3517 2059 3517 2060 3517 2060 3518 2059 3518 2061 3518 2061 3519 2059 3519 2062 3519 2061 3520 2062 3520 2063 3520 2063 3521 2062 3521 2064 3521 2063 3522 2064 3522 2065 3522 2065 3523 2064 3523 2066 3523 2066 3524 2064 3524 2067 3524 2066 3525 2067 3525 2068 3525 2068 3526 2067 3526 2069 3526 2069 3527 2067 3527 2070 3527 2069 3528 2070 3528 2071 3528 2071 3529 2070 3529 2072 3529 2072 3530 2070 3530 2073 3530 2072 3531 2073 3531 2022 3531 2022 3532 2073 3532 2023 3532 2075 3533 2074 3533 2076 3533 2076 3534 2074 3534 2077 3534 2076 3535 2077 3535 2078 3535 2078 3536 2077 3536 2079 3536 2079 3537 2080 3537 2078 3537 2080 3538 2079 3538 2081 3538 2081 3539 2082 3539 2080 3539 2082 3540 2081 3540 2083 3540 2083 3541 2084 3541 2082 3541 2084 3542 2083 3542 2085 3542 2085 3543 2086 3543 2084 3543 2086 3544 2085 3544 2087 3544 2087 3545 2088 3545 2086 3545 2088 3546 2087 3546 2089 3546 2089 3547 2090 3547 2088 3547 2090 3548 2089 3548 2091 3548 2091 3549 2092 3549 2090 3549 2092 3550 2091 3550 2131 3550 2092 3551 2131 3551 2093 3551 2094 3552 2093 3552 2131 3552 2093 3553 2094 3553 2095 3553 2095 3554 2094 3554 2127 3554 2095 3555 2127 3555 2075 3555 2075 3556 2127 3556 2074 3556 2075 3557 2076 3557 2084 3557 2092 3558 2095 3558 2084 3558 2084 3559 2095 3559 2075 3559 2088 3560 2092 3560 2084 3560 2086 3561 2088 3561 2084 3561 2076 3562 2078 3562 2084 3562 2084 3563 2078 3563 2082 3563 2096 3564 2097 3564 2098 3564 2097 3565 2099 3565 2098 3565 2099 3566 2100 3566 2098 3566 2098 3567 2100 3567 2101 3567 2100 3568 2013 3568 2101 3568 2101 3569 2013 3569 2102 3569 2102 3570 2013 3570 2016 3570 2102 3571 2016 3571 2103 3571 2102 3572 2103 3572 2104 3572 2104 3573 2103 3573 2105 3573 2104 3574 2105 3574 2106 3574 2106 3575 2105 3575 2017 3575 2106 3576 2017 3576 2107 3576 2107 3577 2017 3577 2020 3577 2107 3578 2020 3578 2108 3578 2107 3579 2108 3579 2109 3579 2109 3580 2108 3580 2110 3580 2108 3581 2021 3581 2110 3581 2110 3582 2021 3582 2008 3582 2110 3583 2008 3583 2111 3583 2111 3584 2008 3584 2112 3584 2111 3585 2112 3585 2096 3585 2096 3586 2112 3586 2097 3586 2015 3587 2017 3587 2105 3587 2015 3588 2105 3588 2103 3588 2015 3589 2103 3589 2016 3589 2013 3590 2100 3590 2011 3590 2100 3591 2099 3591 2011 3591 2011 3592 2099 3592 2007 3592 2099 3593 2097 3593 2007 3593 2007 3594 2097 3594 2112 3594 2007 3595 2112 3595 2008 3595 2021 3596 2108 3596 2018 3596 2018 3597 2108 3597 2020 3597 2093 3598 2095 3598 2092 3598 2090 3599 2092 3599 2088 3599 2080 3600 2082 3600 2078 3600 2012 3601 2113 3601 2014 3601 2010 3602 2114 3602 2012 3602 2006 3603 2115 3603 2010 3603 2009 3604 2116 3604 2006 3604 2019 3605 2117 3605 2009 3605 2014 3606 2118 3606 2019 3606 2120 3607 2124 3607 2125 3607 2119 3608 2120 3608 2125 3608 2120 3609 2123 3609 2124 3609 2122 3610 2123 3610 2120 3610 2121 3611 2122 3611 2120 3611 2119 3612 2121 3612 2120 3612 2012 3613 2123 3613 2113 3613 2122 3614 2014 3614 2113 3614 2113 3615 2123 3615 2122 3615 2114 3616 2010 3616 2124 3616 2123 3617 2012 3617 2114 3617 2124 3618 2123 3618 2114 3618 2125 3619 2115 3619 2006 3619 2124 3620 2010 3620 2115 3620 2124 3621 2115 3621 2125 3621 2125 3622 2006 3622 2119 3622 2119 3623 2006 3623 2116 3623 2119 3624 2116 3624 2009 3624 2019 3625 2121 3625 2117 3625 2117 3626 2121 3626 2119 3626 2117 3627 2119 3627 2009 3627 2014 3628 2122 3628 2118 3628 2121 3629 2019 3629 2118 3629 2118 3630 2122 3630 2121 3630 2126 3631 2094 3631 2130 3631 2130 3632 2094 3632 2131 3632 2131 3633 2091 3633 2132 3633 2132 3634 2091 3634 2133 3634 2133 3635 2091 3635 2089 3635 2133 3636 2089 3636 2134 3636 2134 3637 2089 3637 2135 3637 2135 3638 2089 3638 2087 3638 2135 3639 2087 3639 2136 3639 2136 3640 2087 3640 2085 3640 2136 3641 2085 3641 2137 3641 2137 3642 2085 3642 2138 3642 2138 3643 2085 3643 2083 3643 2138 3644 2083 3644 2139 3644 2139 3645 2083 3645 2140 3645 2140 3646 2083 3646 2081 3646 2140 3647 2081 3647 2141 3647 2141 3648 2081 3648 2142 3648 2142 3649 2081 3649 2079 3649 2142 3650 2079 3650 2143 3650 2143 3651 2079 3651 2144 3651 2144 3652 2079 3652 2077 3652 2144 3653 2077 3653 2129 3653 2128 3654 2074 3654 2145 3654 2145 3655 2074 3655 2127 3655 2128 3656 2129 3656 2074 3656 2129 3657 2077 3657 2074 3657 2126 3658 2127 3658 2094 3658 2146 3659 2147 3659 2148 3659 2148 324 2147 324 2149 324 2150 324 2151 324 2146 324 2146 324 2151 324 2152 324 2146 324 2152 324 2147 324 2147 324 2153 324 2149 324 2149 3660 2153 3660 2154 3660 2149 324 2154 324 2155 324 2155 324 2154 324 2156 324 2155 3661 2156 3661 2157 3661 2157 324 2156 324 2158 324 2157 324 2158 324 2159 324 2159 324 2158 324 2160 324 2159 3662 2160 3662 2161 3662 2160 324 2162 324 2161 324 2161 3663 2162 3663 2163 3663 2161 324 2163 324 2150 324 2150 324 2163 324 2151 324 2164 348 2165 348 2166 348 2166 348 2165 348 2167 348 2166 348 2167 348 2168 348 2169 348 2170 348 2171 348 2169 3664 2171 3664 2164 3664 2164 3665 2171 3665 2165 3665 2172 3666 2173 3666 2174 3666 2172 348 2174 348 2175 348 2175 348 2174 348 2176 348 2176 348 2174 348 2177 348 2176 348 2177 348 2178 348 2176 3667 2178 3667 2179 3667 2179 348 2178 348 2169 348 2169 348 2178 348 2170 348 2167 3668 2180 3668 2168 3668 2168 3669 2180 3669 2181 3669 2168 348 2181 348 2172 348 2172 3670 2181 3670 2173 3670 2167 3671 2151 3671 2180 3671 2180 3672 2151 3672 2163 3672 2180 3673 2163 3673 2181 3673 2181 3674 2163 3674 2162 3674 2181 3675 2162 3675 2173 3675 2173 3676 2162 3676 2174 3676 2174 3677 2162 3677 2160 3677 2174 3678 2160 3678 2158 3678 2174 3679 2158 3679 2177 3679 2177 3680 2158 3680 2156 3680 2177 3681 2156 3681 2178 3681 2178 3682 2156 3682 2154 3682 2178 3683 2154 3683 2170 3683 2170 3684 2154 3684 2153 3684 2170 3685 2153 3685 2171 3685 2171 3686 2153 3686 2147 3686 2171 3687 2147 3687 2165 3687 2165 3688 2147 3688 2152 3688 2165 3689 2152 3689 2167 3689 2167 3690 2152 3690 2151 3690 2146 3691 2166 3691 2150 3691 2150 3692 2166 3692 2168 3692 2150 3693 2168 3693 2161 3693 2161 3694 2168 3694 2172 3694 2161 3695 2172 3695 2159 3695 2159 3696 2172 3696 2175 3696 2159 3697 2175 3697 2157 3697 2157 3698 2175 3698 2176 3698 2157 3699 2176 3699 2155 3699 2155 3700 2176 3700 2179 3700 2155 3701 2179 3701 2149 3701 2149 3702 2179 3702 2169 3702 2149 3703 2169 3703 2148 3703 2148 3704 2169 3704 2164 3704 2148 3705 2164 3705 2146 3705 2146 3706 2164 3706 2166 3706 2182 3707 2187 3707 2183 3707 2182 3708 2183 3708 2184 3708 2182 3709 2184 3709 2185 3709 2186 3710 2189 3710 2187 3710 2186 3711 2187 3711 2182 3711 2188 3712 2192 3712 2189 3712 2188 3713 2189 3713 2186 3713 2190 3714 2191 3714 2188 3714 2188 3715 2191 3715 2192 3715 2194 3716 2193 3716 2190 3716 2190 3717 2193 3717 2191 3717 2185 3718 2196 3718 2194 3718 2194 3719 2196 3719 2195 3719 2194 3720 2195 3720 2193 3720 2185 3721 2184 3721 2196 3721 2197 3722 2227 3722 2198 3722 2198 3723 2227 3723 2225 3723 2198 3724 2225 3724 2223 3724 2198 3725 2223 3725 2199 3725 2199 3726 2223 3726 2221 3726 2199 3727 2221 3727 2200 3727 2200 3728 2221 3728 2220 3728 2200 3729 2220 3729 2218 3729 2200 3730 2218 3730 2201 3730 2201 3731 2218 3731 2216 3731 2201 3732 2216 3732 2202 3732 2202 3733 2216 3733 2214 3733 2202 3734 2214 3734 2203 3734 2214 3735 2204 3735 2203 3735 2203 3736 2204 3736 2205 3736 2205 3737 2204 3737 2211 3737 2205 3738 2211 3738 2206 3738 2206 3739 2211 3739 2207 3739 2206 3740 2207 3740 2208 3740 2208 3741 2207 3741 2230 3741 2208 3742 2230 3742 2197 3742 2197 3743 2230 3743 2227 3743 2207 3744 2209 3744 2210 3744 2209 3745 2207 3745 2211 3745 2209 3746 2211 3746 2212 3746 2212 3747 2211 3747 2204 3747 2212 3748 2204 3748 2213 3748 2213 3749 2204 3749 2214 3749 2214 3750 2215 3750 2213 3750 2215 3751 2214 3751 2216 3751 2216 3752 2217 3752 2215 3752 2217 3753 2216 3753 2218 3753 2218 3754 2219 3754 2217 3754 2219 3755 2218 3755 2220 3755 2221 3756 2222 3756 2219 3756 2221 3757 2219 3757 2220 3757 2223 3758 2224 3758 2222 3758 2223 3759 2222 3759 2221 3759 2225 3760 2226 3760 2224 3760 2225 3761 2224 3761 2223 3761 2226 3762 2225 3762 2227 3762 2227 3763 2228 3763 2226 3763 2228 3764 2227 3764 2229 3764 2230 3765 2229 3765 2227 3765 2229 3766 2230 3766 2231 3766 2231 3767 2230 3767 2207 3767 2231 3768 2207 3768 2210 3768 2210 3769 2228 3769 2231 3769 2228 3770 2219 3770 2232 3770 2228 3771 2217 3771 2219 3771 2228 3772 2213 3772 2217 3772 2210 3773 2209 3773 2228 3773 2228 3774 2209 3774 2213 3774 2206 3775 2233 3775 2205 3775 2205 3776 2233 3776 2234 3776 2205 3777 2234 3777 2203 3777 2234 3778 2235 3778 2203 3778 2203 3779 2235 3779 2202 3779 2202 3780 2235 3780 2236 3780 2202 3781 2236 3781 2201 3781 2201 3782 2236 3782 2200 3782 2236 3783 2237 3783 2200 3783 2200 3784 2237 3784 2238 3784 2200 3785 2238 3785 2199 3785 2199 3786 2238 3786 2239 3786 2199 3787 2239 3787 2198 3787 2239 3788 2240 3788 2198 3788 2198 3789 2240 3789 2197 3789 2240 3790 2241 3790 2197 3790 2241 3791 2184 3791 2197 3791 2197 3792 2184 3792 2208 3792 2184 3793 2183 3793 2208 3793 2208 3794 2183 3794 2206 3794 2206 3795 2183 3795 2233 3795 2191 3796 2193 3796 2237 3796 2237 3797 2236 3797 2191 3797 2191 3798 2236 3798 2192 3798 2192 3799 2236 3799 2235 3799 2192 3800 2235 3800 2189 3800 2235 3801 2234 3801 2189 3801 2189 3802 2234 3802 2187 3802 2187 3803 2234 3803 2233 3803 2187 3804 2233 3804 2183 3804 2184 3805 2241 3805 2196 3805 2241 3806 2240 3806 2196 3806 2196 3807 2240 3807 2195 3807 2240 3808 2239 3808 2195 3808 2195 3809 2239 3809 2238 3809 2195 3810 2238 3810 2193 3810 2193 3811 2238 3811 2237 3811 2229 3812 2231 3812 2228 3812 2226 3813 2228 3813 2232 3813 2226 3814 2232 3814 2224 3814 2224 3815 2232 3815 2222 3815 2222 3816 2232 3816 2219 3816 2215 3817 2217 3817 2213 3817 2212 3818 2213 3818 2209 3818 2188 3819 2242 3819 2190 3819 2186 3820 2243 3820 2188 3820 2182 3821 2244 3821 2186 3821 2185 3822 2245 3822 2182 3822 2194 3823 2246 3823 2185 3823 2190 3824 2247 3824 2194 3824 2249 3825 2253 3825 2254 3825 2248 3826 2249 3826 2254 3826 2249 3827 2252 3827 2253 3827 2251 3828 2252 3828 2249 3828 2250 3829 2251 3829 2249 3829 2248 3830 2250 3830 2249 3830 2188 3831 2252 3831 2242 3831 2251 3832 2190 3832 2242 3832 2242 3833 2252 3833 2251 3833 2243 3834 2186 3834 2253 3834 2252 3835 2188 3835 2243 3835 2253 3836 2252 3836 2243 3836 2254 3837 2244 3837 2182 3837 2253 3838 2186 3838 2244 3838 2253 3839 2244 3839 2254 3839 2254 3840 2182 3840 2248 3840 2248 3841 2182 3841 2245 3841 2248 3842 2245 3842 2185 3842 2194 3843 2250 3843 2246 3843 2246 3844 2250 3844 2248 3844 2246 3845 2248 3845 2185 3845 2190 3846 2251 3846 2247 3846 2250 3847 2194 3847 2247 3847 2247 3848 2251 3848 2250 3848 2255 3849 2256 3849 2257 3849 2258 3850 2256 3850 2255 3850 2255 3851 2259 3851 2260 3851 2257 3852 2259 3852 2255 3852 2260 3853 2261 3853 2255 3853 2255 3854 2262 3854 2263 3854 2255 3855 2264 3855 2265 3855 2263 3856 2264 3856 2255 3856 2255 3857 2261 3857 2262 3857 2255 3858 2265 3858 2258 3858 2266 3859 2267 3859 2268 3859 2266 3860 2269 3860 2270 3860 2268 3861 2269 3861 2266 3861 2271 3862 2267 3862 2266 3862 2270 3863 2272 3863 2266 3863 2266 3864 2273 3864 2274 3864 2274 3865 2275 3865 2266 3865 2272 3866 2273 3866 2266 3866 2275 3867 2271 3867 2266 3867 2276 3868 2278 3868 2279 3868 2277 3869 2278 3869 2276 3869 2279 3870 2281 3870 2276 3870 2276 3871 2280 3871 2277 3871 2276 3872 2282 3872 2283 3872 2281 3866 2282 3866 2276 3866 2276 3873 2285 3873 2280 3873 2284 3874 2285 3874 2276 3874 2276 3875 2283 3875 2284 3875 2286 3876 2287 3876 2288 3876 2286 3877 2289 3877 2290 3877 2288 3878 2289 3878 2286 3878 2291 3879 2287 3879 2286 3879 2290 3880 2292 3880 2286 3880 2286 3881 2294 3881 2295 3881 2292 3882 2293 3882 2286 3882 2286 3883 2293 3883 2294 3883 2286 3884 2295 3884 2291 3884 2297 3885 2298 3885 2299 3885 2299 3886 2298 3886 2300 3886 2296 3887 2301 3887 2302 3887 2296 3888 2302 3888 2297 3888 2297 3889 2302 3889 2298 3889 2300 3890 2304 3890 2303 3890 2304 3891 2302 3891 2305 3891 2305 3892 2302 3892 2301 3892 2302 3893 2304 3893 2298 3893 2298 3894 2304 3894 2300 3894 2300 3895 2303 3895 2299 3895 2259 3896 2308 3896 2309 3896 2259 3897 2309 3897 2260 3897 2260 3898 2309 3898 2310 3898 2258 3899 2306 3899 2256 3899 2256 3900 2306 3900 2307 3900 2256 3901 2307 3901 2257 3901 2257 3902 2307 3902 2308 3902 2257 3903 2308 3903 2259 3903 2260 3904 2310 3904 2261 3904 2261 3905 2310 3905 2311 3905 2264 3906 2313 3906 2314 3906 2258 3907 2314 3907 2306 3907 2261 3908 2311 3908 2262 3908 2262 3909 2311 3909 2312 3909 2262 3910 2312 3910 2263 3910 2263 3911 2312 3911 2313 3911 2263 3912 2313 3912 2264 3912 2265 3913 2264 3913 2314 3913 2265 3914 2314 3914 2258 3914 2268 3915 2315 3915 2316 3915 2270 3916 2317 3916 2318 3916 2271 3917 2315 3917 2267 3917 2267 3918 2315 3918 2268 3918 2269 3919 2268 3919 2316 3919 2269 3920 2316 3920 2317 3920 2269 3921 2317 3921 2270 3921 2272 3922 2270 3922 2318 3922 2272 3923 2318 3923 2319 3923 2274 3924 2320 3924 2321 3924 2272 3925 2319 3925 2273 3925 2273 3926 2319 3926 2320 3926 2273 3927 2320 3927 2274 3927 2275 3928 2274 3928 2321 3928 2275 3929 2321 3929 2271 3929 2271 3930 2321 3930 2322 3930 2271 3931 2322 3931 2315 3931 2280 3932 2323 3932 2277 3932 2277 3933 2323 3933 2324 3933 2277 3934 2324 3934 2278 3934 2278 3935 2324 3935 2325 3935 2278 3936 2325 3936 2279 3936 2279 3937 2325 3937 2326 3937 2279 3938 2326 3938 2281 3938 2281 3939 2326 3939 2327 3939 2283 3940 2327 3940 2328 3940 2283 3941 2328 3941 2329 3941 2280 3942 2330 3942 2323 3942 2281 3943 2327 3943 2282 3943 2282 3944 2327 3944 2283 3944 2284 3945 2283 3945 2329 3945 2284 3946 2329 3946 2285 3946 2285 3947 2329 3947 2330 3947 2285 3948 2330 3948 2280 3948 2288 3949 2331 3949 2332 3949 2291 3950 2331 3950 2287 3950 2287 3951 2331 3951 2288 3951 2289 3952 2288 3952 2332 3952 2289 3953 2332 3953 2333 3953 2289 3954 2333 3954 2290 3954 2290 3955 2333 3955 2334 3955 2290 3956 2334 3956 2292 3956 2292 3957 2334 3957 2335 3957 2293 3958 2335 3958 2336 3958 2294 3959 2336 3959 2337 3959 2292 3960 2335 3960 2293 3960 2293 3961 2336 3961 2294 3961 2294 3962 2337 3962 2295 3962 2295 3963 2337 3963 2338 3963 2295 3964 2338 3964 2291 3964 2291 3965 2338 3965 2331 3965 2341 3966 2343 3966 2344 3966 2339 3967 2340 3967 2343 3967 2339 3968 2343 3968 2345 3968 2345 3969 2346 3969 2347 3969 2345 3970 2347 3970 2348 3970 2342 3971 2347 3971 2346 3971 2346 3972 2345 3972 2343 3972 2342 3973 2346 3973 2341 3973 2341 3974 2346 3974 2343 3974 2343 3975 2340 3975 2344 3975 2344 3976 2340 3976 2339 3976 2350 3977 2351 3977 2348 3977 2348 3978 2351 3978 2349 3978 2348 3979 2349 3979 2345 3979 2349 3980 2339 3980 2345 3980 2353 3981 2352 3981 2354 3981 2351 3982 2354 3982 2349 3982 2355 3983 2352 3983 2353 3983 2353 3984 2354 3984 2351 3984 2356 3985 2357 3985 2359 3985 2357 3986 2352 3986 2359 3986 2352 3987 2355 3987 2358 3987 2352 3988 2358 3988 2359 3988 2364 3989 2360 3989 2365 3989 2365 3990 2360 3990 2361 3990 2365 3991 2361 3991 2363 3991 2361 3992 2362 3992 2363 3992 2368 3993 2367 3993 2369 3993 2366 3994 2367 3994 2368 3994 2368 3995 2369 3995 2360 3995 2360 3996 2369 3996 2361 3996 2296 3997 2297 3997 2366 3997 2299 3998 2367 3998 2297 3998 2297 3999 2367 3999 2366 3999 2296 4000 2366 4000 2370 4000 2372 4001 2373 4001 2305 4001 2305 4002 2373 4002 2371 4002 2305 4003 2371 4003 2304 4003 2371 4004 2303 4004 2304 4004 2374 4005 2375 4005 2376 4005 2374 4006 2376 4006 2377 4006 2377 4007 2376 4007 2371 4007 2373 4008 2377 4008 2371 4008 2378 4009 2379 4009 2381 4009 2375 4010 2374 4010 2379 4010 2379 4011 2374 4011 2381 4011 2374 4012 2380 4012 2381 4012 2337 4013 2339 4013 2349 4013 2337 324 2349 324 2338 324 2352 324 2383 324 2384 324 2352 324 2384 324 2354 324 2331 324 2338 324 2382 324 2382 324 2338 324 2349 324 2382 324 2349 324 2385 324 2385 324 2349 324 2384 324 2384 324 2349 324 2354 324 2362 4014 2314 4014 2313 4014 2362 4015 2313 4015 2357 4015 2357 4016 2313 4016 2312 4016 2312 4017 2311 4017 2357 4017 2357 4018 2311 4018 2352 4018 2352 324 2311 324 2310 324 2352 324 2310 324 2309 324 2352 324 2309 324 2383 324 2383 324 2309 324 2308 324 2383 324 2308 324 2361 324 2361 324 2308 324 2307 324 2307 324 2306 324 2361 324 2361 4019 2306 4019 2362 4019 2362 4020 2306 4020 2314 4020 2299 4021 2321 4021 2367 4021 2367 324 2321 324 2320 324 2361 324 2369 324 2383 324 2383 4022 2369 4022 2386 4022 2386 4023 2369 4023 2367 4023 2386 4024 2367 4024 2320 4024 2386 4025 2320 4025 2319 4025 2318 4026 2371 4026 2386 4026 2318 4027 2386 4027 2319 4027 2316 4028 2303 4028 2317 4028 2317 4029 2303 4029 2371 4029 2317 324 2371 324 2318 324 2303 4030 2316 4030 2315 4030 2303 4031 2315 4031 2299 4031 2299 4032 2315 4032 2322 4032 2299 4033 2322 4033 2321 4033 2387 324 2371 324 2376 324 2387 324 2376 324 2388 324 2371 4034 2387 4034 2386 4034 2328 324 2327 324 2389 324 2330 324 2329 324 2375 324 2375 324 2329 324 2388 324 2375 324 2388 324 2376 324 2326 4035 2394 4035 2327 4035 2327 4036 2394 4036 2389 4036 2394 4037 2326 4037 2325 4037 2394 4038 2325 4038 2324 4038 2394 4039 2324 4039 2379 4039 2379 4040 2324 4040 2323 4040 2379 4041 2323 4041 2375 4041 2375 324 2323 324 2330 324 2389 324 2390 324 2391 324 2329 324 2328 324 2388 324 2388 324 2328 324 2389 324 2388 324 2389 324 2391 324 2337 4042 2336 4042 2339 4042 2339 4043 2336 4043 2335 4043 2339 4044 2335 4044 2344 4044 2344 4045 2335 4045 2334 4045 2344 4046 2334 4046 2333 4046 2344 4047 2333 4047 2332 4047 2344 4048 2332 4048 2392 4048 2392 324 2332 324 2331 324 2391 324 2390 324 2392 324 2391 324 2392 324 2382 324 2382 324 2392 324 2331 324 2396 4049 2393 4049 2397 4049 2397 4050 2393 4050 2389 4050 2397 4051 2389 4051 2395 4051 2389 4052 2394 4052 2395 4052 2398 4053 2392 4053 2390 4053 2398 4054 2390 4054 2389 4054 2399 4055 2392 4055 2398 4055 2393 4056 2398 4056 2389 4056 2344 4057 2392 4057 2341 4057 2399 4058 2400 4058 2392 4058 2392 4059 2400 4059 2341 4059 2401 4060 2355 4060 2402 4060 2401 324 2403 324 2355 324 2355 4061 2403 4061 2358 4061 2402 324 2355 324 2404 324 2404 4062 2355 4062 2353 4062 2404 4063 2353 4063 2351 4063 2404 324 2351 324 2405 324 2405 4064 2351 4064 2350 4064 2359 4065 2408 4065 2356 4065 2408 4066 2407 4066 2356 4066 2356 4067 2407 4067 2357 4067 2362 4068 2406 4068 2407 4068 2362 4069 2407 4069 2363 4069 2408 4070 2365 4070 2363 4070 2408 4071 2363 4071 2407 4071 2407 4072 2406 4072 2357 4072 2357 4073 2406 4073 2362 4073 2366 324 2368 324 2409 324 2370 4074 2366 4074 2410 4074 2366 324 2409 324 2410 324 2360 4075 2364 4075 2411 4075 2360 324 2411 324 2412 324 2409 324 2368 324 2360 324 2409 324 2360 324 2413 324 2413 324 2360 324 2412 324 2374 4076 2414 4076 2415 4076 2415 4077 2416 4077 2374 4077 2374 4078 2416 4078 2380 4078 2414 4079 2374 4079 2417 4079 2374 324 2377 324 2417 324 2417 4080 2377 4080 2373 4080 2417 4081 2373 4081 2418 4081 2418 4082 2373 4082 2372 4082 2381 4083 2421 4083 2378 4083 2421 4084 2420 4084 2378 4084 2378 4085 2420 4085 2379 4085 2394 4086 2419 4086 2420 4086 2394 4087 2420 4087 2395 4087 2421 4088 2397 4088 2395 4088 2421 4089 2395 4089 2420 4089 2420 4090 2419 4090 2379 4090 2379 4091 2419 4091 2394 4091 2399 4092 2422 4092 2423 4092 2399 4093 2423 4093 2400 4093 2398 324 2393 324 2422 324 2398 324 2422 324 2399 324 2396 4094 2424 4094 2393 4094 2393 324 2424 324 2425 324 2425 324 2426 324 2393 324 2393 324 2426 324 2422 324 2350 4095 2348 4095 2347 4095 2401 4096 2402 4096 2427 4096 2427 4097 2402 4097 2428 4097 2428 4098 2402 4098 2404 4098 2405 4099 2350 4099 2429 4099 2429 4100 2350 4100 2347 4100 2431 4101 2432 4101 2364 4101 2364 4102 2432 4102 2411 4102 2411 4103 2432 4103 2433 4103 2411 4104 2433 4104 2412 4104 2370 4105 2434 4105 2296 4105 2434 4106 2301 4106 2296 4106 2342 4107 2435 4107 2347 4107 2347 4108 2435 4108 2429 4108 2405 4109 2429 4109 2436 4109 2405 4110 2436 4110 2404 4110 2404 4111 2436 4111 2428 4111 2401 4112 2427 4112 2403 4112 2403 4113 2427 4113 2437 4113 2403 4114 2437 4114 2358 4114 2358 4115 2437 4115 2430 4115 2412 4116 2433 4116 2438 4116 2412 4117 2438 4117 2413 4117 2413 4118 2438 4118 2439 4118 2413 4119 2439 4119 2409 4119 2409 4120 2439 4120 2440 4120 2409 4121 2440 4121 2410 4121 2410 4122 2440 4122 2370 4122 2370 4123 2440 4123 2434 4123 2359 4124 2358 4124 2430 4124 2359 4125 2430 4125 2408 4125 2408 4126 2430 4126 2431 4126 2408 4127 2431 4127 2365 4127 2365 4128 2431 4128 2364 4128 2372 4129 2305 4129 2301 4129 2434 4130 2372 4130 2301 4130 2441 4131 2415 4131 2414 4131 2441 4132 2414 4132 2442 4132 2442 4133 2414 4133 2417 4133 2442 4134 2417 4134 2443 4134 2443 4135 2417 4135 2418 4135 2445 4136 2446 4136 2396 4136 2396 4137 2446 4137 2424 4137 2425 4138 2447 4138 2426 4138 2426 4139 2447 4139 2448 4139 2426 4140 2448 4140 2422 4140 2422 4141 2449 4141 2423 4141 2400 4142 2435 4142 2341 4142 2435 4143 2342 4143 2341 4143 2372 4144 2434 4144 2450 4144 2372 4145 2450 4145 2418 4145 2418 4146 2450 4146 2443 4146 2415 4147 2441 4147 2416 4147 2416 4148 2441 4148 2451 4148 2416 4149 2451 4149 2380 4149 2380 4150 2451 4150 2444 4150 2424 4151 2446 4151 2452 4151 2424 4152 2452 4152 2425 4152 2425 4153 2452 4153 2447 4153 2422 4154 2448 4154 2449 4154 2423 4155 2449 4155 2453 4155 2423 4156 2453 4156 2400 4156 2400 4157 2453 4157 2435 4157 2381 4158 2380 4158 2444 4158 2381 4159 2444 4159 2421 4159 2421 4160 2444 4160 2397 4160 2397 4161 2444 4161 2445 4161 2397 4162 2445 4162 2396 4162 2454 4163 2451 4163 2441 4163 2454 348 2441 348 2455 348 2455 4164 2441 4164 2456 4164 2456 4165 2441 4165 2442 4165 2456 348 2442 348 2457 348 2457 4166 2442 4166 2443 4166 2458 348 2452 348 2459 348 2459 4167 2452 4167 2446 4167 2459 348 2446 348 2460 348 2460 4168 2446 4168 2445 4168 2460 4169 2445 4169 2444 4169 2460 4170 2444 4170 2461 4170 2461 4171 2444 4171 2454 4171 2454 4172 2444 4172 2451 4172 2462 348 2453 348 2449 348 2462 4173 2449 4173 2463 4173 2463 348 2449 348 2448 348 2463 4174 2448 4174 2458 4174 2458 348 2448 348 2447 348 2458 4175 2447 4175 2452 4175 2464 4176 2429 4176 2435 4176 2464 4177 2435 4177 2465 4177 2465 4178 2435 4178 2462 4178 2462 4179 2435 4179 2453 4179 2466 348 2437 348 2467 348 2467 348 2437 348 2427 348 2467 348 2427 348 2468 348 2468 4180 2427 4180 2428 4180 2468 348 2428 348 2469 348 2469 348 2428 348 2436 348 2469 348 2436 348 2464 348 2464 4181 2436 4181 2429 4181 2470 348 2432 348 2471 348 2471 4182 2432 4182 2431 4182 2471 4183 2431 4183 2472 4183 2472 4184 2431 4184 2430 4184 2472 4185 2430 4185 2466 4185 2466 4186 2430 4186 2437 4186 2473 348 2440 348 2474 348 2474 348 2440 348 2439 348 2474 4187 2439 4187 2475 4187 2475 4188 2439 4188 2438 4188 2475 348 2438 348 2476 348 2476 4189 2438 4189 2470 4189 2470 4190 2438 4190 2433 4190 2470 4191 2433 4191 2432 4191 2457 348 2443 348 2450 348 2457 348 2450 348 2477 348 2477 4192 2450 4192 2434 4192 2477 4193 2434 4193 2478 4193 2478 4194 2434 4194 2473 4194 2473 4195 2434 4195 2440 4195 2465 4196 2479 4196 2480 4196 2469 4197 2480 4197 2481 4197 2469 4198 2481 4198 2482 4198 2467 4199 2482 4199 2483 4199 2467 4200 2483 4200 2466 4200 2466 4201 2483 4201 2484 4201 2472 4202 2484 4202 2485 4202 2471 4203 2485 4203 2486 4203 2476 4204 2487 4204 2488 4204 2476 4205 2488 4205 2475 4205 2475 4206 2488 4206 2489 4206 2474 4207 2489 4207 2490 4207 2473 4208 2490 4208 2491 4208 2464 4209 2465 4209 2480 4209 2464 4210 2480 4210 2469 4210 2468 4211 2469 4211 2482 4211 2468 4212 2482 4212 2467 4212 2466 4213 2484 4213 2472 4213 2472 4214 2485 4214 2471 4214 2470 4215 2471 4215 2486 4215 2470 4216 2486 4216 2487 4216 2470 4217 2487 4217 2476 4217 2475 4218 2489 4218 2474 4218 2474 4219 2490 4219 2473 4219 2478 4220 2473 4220 2491 4220 2478 4221 2491 4221 2492 4221 2477 4222 2492 4222 2493 4222 2457 4223 2493 4223 2494 4223 2456 4224 2494 4224 2495 4224 2455 4225 2495 4225 2496 4225 2461 4226 2497 4226 2498 4226 2459 4227 2499 4227 2500 4227 2458 4228 2500 4228 2501 4228 2458 4229 2501 4229 2502 4229 2465 4230 2503 4230 2479 4230 2478 4231 2492 4231 2477 4231 2477 4232 2493 4232 2457 4232 2457 4233 2494 4233 2456 4233 2456 4234 2495 4234 2455 4234 2454 4235 2455 4235 2496 4235 2454 4236 2496 4236 2497 4236 2454 4237 2497 4237 2461 4237 2460 4238 2461 4238 2498 4238 2460 4239 2498 4239 2499 4239 2460 4240 2499 4240 2459 4240 2459 4241 2500 4241 2458 4241 2463 4242 2458 4242 2502 4242 2463 4243 2502 4243 2462 4243 2462 4244 2502 4244 2503 4244 2462 4245 2503 4245 2465 4245 2505 348 2495 348 2504 348 2504 348 2495 348 2494 348 2505 4246 2496 4246 2495 4246 2506 348 2498 348 2505 348 2505 4247 2498 4247 2497 4247 2505 4248 2497 4248 2496 4248 2506 4249 2499 4249 2498 4249 2507 4250 2500 4250 2506 4250 2506 4251 2500 4251 2499 4251 2508 4252 2501 4252 2507 4252 2507 4253 2501 4253 2500 4253 2508 4254 2502 4254 2501 4254 2510 4255 2503 4255 2508 4255 2508 348 2503 348 2502 348 2509 348 2480 348 2510 348 2510 348 2480 348 2479 348 2510 348 2479 348 2503 348 2509 4256 2481 4256 2480 4256 2511 348 2482 348 2509 348 2509 4257 2482 4257 2481 4257 2512 348 2483 348 2511 348 2511 4258 2483 4258 2482 4258 2512 4259 2485 4259 2484 4259 2512 4260 2484 4260 2483 4260 2513 348 2486 348 2512 348 2512 4261 2486 4261 2485 4261 2513 4262 2487 4262 2486 4262 2514 348 2488 348 2513 348 2513 4263 2488 4263 2487 4263 2514 348 2490 348 2489 348 2514 4264 2489 4264 2488 4264 2515 348 2491 348 2514 348 2514 348 2491 348 2490 348 2504 348 2494 348 2493 348 2504 348 2493 348 2515 348 2515 348 2493 348 2492 348 2515 348 2492 348 2491 348 2510 4265 2526 4265 2516 4265 2510 4266 2516 4266 2509 4266 2511 4267 2516 4267 2517 4267 2513 4268 2518 4268 2519 4268 2513 4269 2519 4269 2514 4269 2514 4270 2519 4270 2520 4270 2515 4271 2520 4271 2521 4271 2509 4272 2516 4272 2511 4272 2512 4273 2511 4273 2517 4273 2512 4274 2517 4274 2518 4274 2512 4275 2518 4275 2513 4275 2514 4276 2520 4276 2515 4276 2522 348 2523 348 2524 348 2524 348 2521 348 2522 348 2525 348 2522 348 2526 348 2526 4277 2522 4277 2521 4277 2518 4278 2517 4278 2521 4278 2521 4279 2517 4279 2516 4279 2521 348 2516 348 2526 348 2520 348 2519 348 2521 348 2521 4280 2519 4280 2518 4280 2515 4281 2521 4281 2504 4281 2504 4282 2521 4282 2524 4282 2506 4283 2523 4283 2522 4283 2507 4284 2522 4284 2525 4284 2505 4285 2504 4285 2524 4285 2505 4286 2524 4286 2523 4286 2505 4287 2523 4287 2506 4287 2506 4288 2522 4288 2507 4288 2508 4289 2507 4289 2525 4289 2508 4290 2525 4290 2526 4290 2508 4291 2526 4291 2510 4291 2527 4292 2386 4292 2528 4292 2528 4293 2386 4293 2387 4293 2528 4294 2387 4294 2529 4294 2529 4295 2387 4295 2388 4295 2529 4296 2388 4296 2530 4296 2530 4297 2388 4297 2391 4297 2530 4298 2391 4298 2531 4298 2531 4299 2391 4299 2382 4299 2531 4300 2382 4300 2532 4300 2532 4301 2382 4301 2385 4301 2532 4302 2385 4302 2533 4302 2533 4303 2385 4303 2384 4303 2533 4304 2384 4304 2534 4304 2534 4305 2384 4305 2383 4305 2534 4306 2383 4306 2527 4306 2527 4307 2383 4307 2386 4307 2530 324 2531 324 2529 324 2529 324 2531 324 2532 324 2527 4308 2528 4308 2529 4308 2529 4309 2534 4309 2527 4309 2532 324 2533 324 2529 324 2529 4310 2533 4310 2534 4310 2535 4311 2536 4311 2537 4311 2537 4312 2536 4312 2538 4312 2537 4313 2538 4313 2539 4313 2539 4314 2538 4314 2540 4314 2539 4315 2540 4315 2541 4315 2541 4316 2540 4316 2542 4316 2541 4317 2542 4317 2543 4317 2541 4318 2543 4318 2544 4318 2544 4319 2543 4319 2545 4319 2544 4320 2545 4320 2546 4320 2546 4321 2545 4321 2547 4321 2546 4322 2547 4322 2548 4322 2546 4323 2548 4323 2535 4323 2535 4324 2548 4324 2536 4324 2561 4325 2549 4325 2550 4325 2550 4326 2549 4326 2551 4326 2550 4327 2551 4327 2552 4327 2552 4328 2551 4328 2553 4328 2554 4329 2555 4329 2556 4329 2556 4330 2555 4330 2557 4330 2556 4331 2557 4331 2558 4331 2558 4332 2557 4332 2559 4332 2558 4333 2559 4333 2560 4333 2560 4334 2559 4334 2561 4334 2561 4335 2559 4335 2549 4335 2553 4336 2551 4336 2562 4336 2553 4337 2562 4337 2563 4337 2563 4338 2562 4338 2564 4338 2562 4339 2565 4339 2564 4339 2564 4340 2565 4340 2566 4340 2566 4341 2565 4341 2567 4341 2566 4342 2567 4342 2568 4342 2568 4343 2567 4343 2554 4343 2554 4344 2567 4344 2555 4344 2570 4345 2569 4345 2572 4345 2570 4346 2572 4346 2571 4346 2571 4347 2572 4347 2574 4347 2571 4348 2574 4348 2573 4348 2573 4349 2574 4349 2575 4349 2573 4350 2575 4350 2576 4350 2576 4351 2575 4351 2620 4351 2576 4352 2620 4352 2577 4352 2577 4353 2620 4353 2578 4353 2577 4354 2578 4354 2579 4354 2580 4355 2581 4355 2579 4355 2580 4356 2579 4356 2578 4356 2582 4357 2581 4357 2580 4357 2581 4358 2582 4358 2584 4358 2581 4359 2584 4359 2583 4359 2583 4360 2584 4360 2585 4360 2583 4361 2585 4361 2586 4361 2586 4362 2585 4362 2587 4362 2586 4363 2587 4363 2570 4363 2570 4364 2587 4364 2569 4364 2588 4365 2589 4365 2590 4365 2592 4366 2591 4366 2589 4366 2593 4367 2592 4367 2589 4367 2589 4368 2588 4368 2593 4368 2594 4369 2568 4369 2554 4369 2594 4370 2554 4370 2595 4370 2595 4371 2554 4371 2556 4371 2595 4372 2556 4372 2596 4372 2596 4373 2556 4373 2558 4373 2596 4374 2558 4374 2597 4374 2597 4375 2558 4375 2560 4375 2597 4376 2560 4376 2561 4376 2597 4377 2561 4377 2598 4377 2598 4378 2561 4378 2550 4378 2598 4379 2550 4379 2599 4379 2599 4380 2550 4380 2552 4380 2599 4381 2552 4381 2600 4381 2600 4382 2552 4382 2553 4382 2600 4383 2553 4383 2601 4383 2601 4384 2553 4384 2563 4384 2601 4385 2563 4385 2602 4385 2602 4386 2563 4386 2564 4386 2602 4387 2564 4387 2603 4387 2603 4388 2564 4388 2566 4388 2603 4389 2566 4389 2604 4389 2604 4390 2566 4390 2568 4390 2604 4391 2568 4391 2594 4391 2598 4392 2547 4392 2545 4392 2598 4393 2545 4393 2597 4393 2597 4394 2545 4394 2543 4394 2597 4395 2543 4395 2596 4395 2596 4396 2543 4396 2542 4396 2596 4397 2542 4397 2595 4397 2595 4398 2542 4398 2540 4398 2595 4399 2540 4399 2594 4399 2594 4400 2540 4400 2604 4400 2604 4401 2540 4401 2538 4401 2604 4402 2538 4402 2603 4402 2603 4403 2538 4403 2536 4403 2603 4404 2536 4404 2602 4404 2602 4405 2536 4405 2601 4405 2601 4406 2536 4406 2548 4406 2601 4407 2548 4407 2600 4407 2600 4408 2548 4408 2599 4408 2599 4409 2548 4409 2547 4409 2599 4410 2547 4410 2598 4410 2570 4411 2590 4411 2586 4411 2586 4412 2590 4412 2589 4412 2586 4413 2589 4413 2583 4413 2583 4414 2589 4414 2591 4414 2583 4415 2591 4415 2581 4415 2581 4416 2591 4416 2579 4416 2579 4417 2591 4417 2592 4417 2579 4418 2592 4418 2577 4418 2577 4419 2592 4419 2576 4419 2576 4420 2592 4420 2593 4420 2576 4421 2593 4421 2573 4421 2573 4422 2593 4422 2588 4422 2573 4423 2588 4423 2571 4423 2571 4424 2588 4424 2570 4424 2570 4425 2588 4425 2590 4425 2535 4426 2605 4426 2546 4426 2537 4427 2606 4427 2535 4427 2539 4428 2607 4428 2537 4428 2541 4429 2608 4429 2539 4429 2544 4430 2609 4430 2541 4430 2546 4431 2610 4431 2544 4431 2614 4432 2615 4432 2612 4432 2614 4433 2612 4433 2613 4433 2613 4434 2612 4434 2611 4434 2616 4435 2611 4435 2612 4435 2617 4436 2616 4436 2612 4436 2618 4437 2617 4437 2612 4437 2612 4438 2615 4438 2618 4438 2616 4439 2546 4439 2605 4439 2616 4440 2605 4440 2611 4440 2535 4441 2611 4441 2605 4441 2613 4442 2606 4442 2614 4442 2614 4443 2606 4443 2537 4443 2611 4444 2535 4444 2606 4444 2606 4445 2613 4445 2611 4445 2607 4446 2539 4446 2615 4446 2607 4447 2614 4447 2537 4447 2607 4448 2615 4448 2614 4448 2541 4449 2618 4449 2608 4449 2615 4450 2539 4450 2608 4450 2615 4451 2608 4451 2618 4451 2544 4452 2617 4452 2609 4452 2618 4453 2541 4453 2609 4453 2618 4454 2609 4454 2617 4454 2546 4455 2616 4455 2610 4455 2617 4456 2544 4456 2610 4456 2617 4457 2610 4457 2616 4457 2562 4458 2551 4458 2619 4458 2565 4459 2569 4459 2567 4459 2565 4460 2572 4460 2569 4460 2559 4461 2580 4461 2549 4461 2549 4462 2580 4462 2578 4462 2549 4463 2578 4463 2551 4463 2551 4464 2578 4464 2620 4464 2567 4465 2569 4465 2587 4465 2565 4466 2574 4466 2572 4466 2565 4467 2562 4467 2574 4467 2562 4468 2619 4468 2575 4468 2562 4469 2575 4469 2574 4469 2619 4470 2620 4470 2575 4470 2619 4471 2551 4471 2620 4471 2559 4472 2582 4472 2580 4472 2559 4473 2584 4473 2582 4473 2559 4474 2557 4474 2584 4474 2557 4475 2585 4475 2584 4475 2557 4476 2555 4476 2585 4476 2555 4477 2567 4477 2587 4477 2555 4478 2587 4478 2585 4478 2621 4479 2622 4479 2623 4479 2623 4480 2622 4480 2624 4480 2623 4481 2624 4481 2625 4481 2625 4482 2624 4482 2626 4482 2625 4483 2626 4483 2627 4483 2625 4484 2627 4484 2628 4484 2628 4485 2627 4485 2629 4485 2628 4486 2629 4486 2630 4486 2628 4487 2630 4487 2631 4487 2631 4488 2630 4488 2632 4488 2631 4489 2632 4489 2633 4489 2631 4490 2633 4490 2634 4490 2634 4491 2633 4491 2635 4491 2634 4492 2635 4492 2621 4492 2621 4493 2635 4493 2636 4493 2621 4494 2636 4494 2622 4494 2637 4495 2648 4495 2638 4495 2637 4496 2638 4496 2639 4496 2639 4497 2638 4497 2640 4497 2641 4498 2642 4498 2643 4498 2641 4499 2643 4499 2644 4499 2644 4500 2643 4500 2645 4500 2643 4501 2646 4501 2645 4501 2645 4502 2646 4502 2647 4502 2647 4503 2646 4503 2648 4503 2647 4504 2648 4504 2637 4504 2638 4505 2649 4505 2640 4505 2640 4506 2649 4506 2650 4506 2650 4507 2649 4507 2651 4507 2650 4508 2651 4508 2652 4508 2652 4509 2651 4509 2653 4509 2653 4510 2651 4510 2654 4510 2653 4511 2654 4511 2655 4511 2655 4512 2654 4512 2656 4512 2656 4513 2654 4513 2642 4513 2656 4514 2642 4514 2641 4514 2658 4515 2657 4515 2659 4515 2708 4516 2659 4516 2657 4516 2659 4517 2708 4517 2661 4517 2659 4518 2661 4518 2660 4518 2660 4519 2661 4519 2662 4519 2660 4520 2662 4520 2663 4520 2663 4521 2662 4521 2664 4521 2663 4522 2664 4522 2665 4522 2665 4523 2664 4523 2666 4523 2665 4524 2666 4524 2667 4524 2668 4525 2669 4525 2667 4525 2668 4526 2667 4526 2666 4526 2670 4527 2669 4527 2668 4527 2669 4528 2670 4528 2671 4528 2672 4529 2671 4529 2670 4529 2671 4530 2672 4530 2673 4530 2673 4531 2672 4531 2706 4531 2673 4532 2706 4532 2707 4532 2673 4533 2707 4533 2658 4533 2658 4534 2707 4534 2657 4534 2675 4535 2677 4535 2676 4535 2675 4536 2678 4536 2677 4536 2675 4537 2679 4537 2678 4537 2674 4538 2679 4538 2675 4538 2680 4539 2656 4539 2681 4539 2681 4540 2656 4540 2641 4540 2681 4541 2641 4541 2682 4541 2682 4542 2641 4542 2644 4542 2682 4543 2644 4543 2683 4543 2683 4544 2644 4544 2645 4544 2683 4545 2645 4545 2684 4545 2684 4546 2645 4546 2647 4546 2684 4547 2647 4547 2632 4547 2632 4548 2647 4548 2685 4548 2685 4549 2647 4549 2637 4549 2685 4550 2637 4550 2686 4550 2686 4551 2637 4551 2639 4551 2686 4552 2639 4552 2687 4552 2687 4553 2639 4553 2640 4553 2687 4554 2640 4554 2688 4554 2688 4555 2640 4555 2650 4555 2688 4556 2650 4556 2689 4556 2689 4557 2650 4557 2652 4557 2689 4558 2652 4558 2690 4558 2690 4559 2652 4559 2653 4559 2690 4560 2653 4560 2691 4560 2691 4561 2653 4561 2655 4561 2691 4562 2655 4562 2680 4562 2680 4563 2655 4563 2656 4563 2686 4564 2633 4564 2685 4564 2685 4565 2633 4565 2632 4565 2684 4566 2632 4566 2630 4566 2684 4567 2630 4567 2683 4567 2683 4568 2630 4568 2629 4568 2683 4569 2629 4569 2682 4569 2682 4570 2629 4570 2627 4570 2682 4571 2627 4571 2681 4571 2681 4572 2627 4572 2680 4572 2680 4573 2627 4573 2626 4573 2680 4574 2626 4574 2624 4574 2680 4575 2624 4575 2691 4575 2691 4576 2624 4576 2690 4576 2690 4577 2624 4577 2622 4577 2690 4578 2622 4578 2689 4578 2689 4579 2622 4579 2688 4579 2688 4580 2622 4580 2636 4580 2688 4581 2636 4581 2687 4581 2687 4582 2636 4582 2635 4582 2687 4583 2635 4583 2686 4583 2686 4584 2635 4584 2633 4584 2658 4585 2674 4585 2673 4585 2673 4586 2674 4586 2675 4586 2673 4587 2675 4587 2671 4587 2671 4588 2675 4588 2676 4588 2671 4589 2676 4589 2669 4589 2669 4590 2676 4590 2677 4590 2669 4591 2677 4591 2667 4591 2667 4592 2677 4592 2665 4592 2665 4593 2677 4593 2678 4593 2665 4594 2678 4594 2663 4594 2663 4595 2678 4595 2679 4595 2663 4596 2679 4596 2660 4596 2660 4597 2679 4597 2659 4597 2659 4598 2679 4598 2674 4598 2659 4599 2674 4599 2658 4599 2621 4600 2692 4600 2634 4600 2623 4601 2693 4601 2621 4601 2625 4602 2694 4602 2623 4602 2628 4603 2695 4603 2625 4603 2631 4604 2696 4604 2628 4604 2634 4605 2697 4605 2631 4605 2701 4606 2702 4606 2699 4606 2701 4607 2699 4607 2700 4607 2700 4608 2699 4608 2698 4608 2703 4609 2698 4609 2699 4609 2704 4610 2703 4610 2699 4610 2705 4611 2704 4611 2699 4611 2699 4612 2702 4612 2705 4612 2703 4613 2634 4613 2692 4613 2703 4614 2692 4614 2698 4614 2621 4615 2698 4615 2692 4615 2700 4616 2693 4616 2701 4616 2701 4617 2693 4617 2623 4617 2698 4618 2621 4618 2693 4618 2693 4619 2700 4619 2698 4619 2694 4620 2625 4620 2702 4620 2694 4621 2701 4621 2623 4621 2694 4622 2702 4622 2701 4622 2628 4623 2705 4623 2695 4623 2702 4624 2625 4624 2695 4624 2702 4625 2695 4625 2705 4625 2631 4626 2704 4626 2696 4626 2705 4627 2628 4627 2696 4627 2705 4628 2696 4628 2704 4628 2634 4629 2703 4629 2697 4629 2704 4630 2631 4630 2697 4630 2704 4631 2697 4631 2703 4631 2643 4632 2642 4632 2706 4632 2642 4633 2654 4633 2707 4633 2646 4634 2668 4634 2666 4634 2646 4635 2666 4635 2648 4635 2648 4636 2666 4636 2638 4636 2638 4637 2666 4637 2664 4637 2654 4638 2657 4638 2707 4638 2654 4639 2651 4639 2708 4639 2654 4640 2708 4640 2657 4640 2651 4641 2661 4641 2708 4641 2651 4642 2662 4642 2661 4642 2651 4643 2649 4643 2662 4643 2649 4644 2638 4644 2664 4644 2649 4645 2664 4645 2662 4645 2646 4646 2670 4646 2668 4646 2646 4647 2643 4647 2670 4647 2670 4648 2643 4648 2672 4648 2643 4649 2706 4649 2672 4649 2642 4650 2707 4650 2706 4650 2714 4651 2711 4651 2712 4651 2709 4652 2710 4652 2713 4652 2713 4653 2714 4653 2712 4653 2709 4654 2713 4654 2712 4654 2715 4655 2711 4655 2714 4655 2718 4656 2716 4656 2717 4656 2712 4657 2711 4657 2715 4657 2715 4658 2718 4658 2717 4658 2712 4659 2715 4659 2717 4659 2718 4660 2719 4660 2716 4660 2720 4661 2716 4661 2719 4661 2717 4662 2716 4662 2720 4662 2721 4663 2723 4663 2722 4663 2717 4664 2720 4664 2721 4664 2717 4665 2721 4665 2722 4665 2726 4666 2723 4666 2725 4666 2725 4667 2723 4667 2721 4667 2724 4668 2723 4668 2727 4668 2727 4669 2723 4669 2726 4669 2730 4670 2728 4670 2729 4670 2724 4671 2730 4671 2729 4671 2722 4672 2723 4672 2729 4672 2729 4673 2723 4673 2724 4673 2728 4674 2730 4674 2731 4674 2729 4675 2728 4675 2731 4675 2731 4676 2733 4676 2732 4676 2729 4677 2731 4677 2732 4677 2736 4678 2733 4678 2731 4678 2737 4679 2733 4679 2736 4679 2737 4680 2734 4680 2733 4680 2738 4681 2710 4681 2709 4681 2732 4682 2733 4682 2734 4682 2735 4683 2738 4683 2709 4683 2732 4684 2734 4684 2709 4684 2709 4685 2734 4685 2735 4685 2713 4686 2710 4686 2738 4686 2735 4687 2741 4687 2740 4687 2721 4688 2739 4688 2747 4688 2739 4689 2721 4689 2720 4689 2740 4690 2713 4690 2738 4690 2740 4691 2738 4691 2735 4691 2741 4692 2742 4692 2743 4692 2741 4693 2743 4693 2744 4693 2741 4694 2735 4694 2745 4694 2741 4695 2745 4695 2746 4695 2741 4696 2746 4696 2742 4696 2752 4697 2713 4697 2740 4697 2752 4698 2714 4698 2713 4698 2747 4699 2748 4699 2749 4699 2747 4700 2749 4700 2750 4700 2747 4701 2750 4701 2721 4701 2730 4702 2724 4702 2744 4702 2744 4703 2724 4703 2747 4703 2747 4704 2724 4704 2751 4704 2747 4705 2751 4705 2748 4705 2752 4706 2715 4706 2714 4706 2739 4707 2720 4707 2719 4707 2739 4708 2719 4708 2752 4708 2744 4709 2731 4709 2730 4709 2752 4710 2719 4710 2715 4710 2743 4711 2753 4711 2744 4711 2744 4712 2753 4712 2731 4712 2740 4713 2741 4713 2754 4713 2754 4714 2755 4714 2740 4714 2740 4715 2755 4715 2752 4715 2752 4716 2755 4716 2756 4716 2752 4717 2756 4717 2739 4717 2756 4718 2757 4718 2739 4718 2758 4719 2739 4719 2757 4719 2747 4720 2739 4720 2758 4720 2758 4721 2759 4721 2747 4721 2747 4722 2759 4722 2744 4722 2744 4723 2759 4723 2760 4723 2744 4724 2760 4724 2741 4724 2760 4725 2761 4725 2741 4725 2754 4726 2741 4726 2761 4726 2762 4727 2754 4727 2761 4727 2762 4728 2761 4728 2760 4728 2762 4729 2760 4729 2763 4729 2763 4730 2760 4730 2764 4730 2764 4731 2760 4731 2759 4731 2764 4732 2759 4732 2765 4732 2765 4733 2759 4733 2758 4733 2765 4734 2758 4734 2766 4734 2766 4735 2758 4735 2757 4735 2766 4736 2757 4736 2756 4736 2766 4737 2756 4737 2767 4737 2767 4738 2756 4738 2768 4738 2768 4739 2756 4739 2755 4739 2768 4740 2755 4740 2769 4740 2769 4741 2755 4741 2754 4741 2769 4742 2754 4742 2762 4742 2770 4743 2766 4743 2771 4743 2766 4744 2767 4744 2771 4744 2767 4745 2768 4745 2771 4745 2771 4746 2768 4746 2772 4746 2768 4747 2769 4747 2772 4747 2772 4748 2769 4748 2773 4748 2762 4749 2773 4749 2769 4749 2773 4750 2762 4750 2774 4750 2762 4751 2763 4751 2774 4751 2763 4752 2764 4752 2774 4752 2774 4753 2764 4753 2775 4753 2764 4754 2765 4754 2775 4754 2775 4755 2765 4755 2770 4755 2766 4756 2770 4756 2765 4756 2775 4757 2770 4757 2722 4757 2722 4758 2770 4758 2717 4758 2712 4759 2771 4759 2772 4759 2712 4760 2772 4760 2709 4760 2729 4761 2774 4761 2775 4761 2729 4762 2775 4762 2722 4762 2717 4763 2770 4763 2771 4763 2717 4764 2771 4764 2712 4764 2709 4765 2772 4765 2773 4765 2709 4766 2773 4766 2732 4766 2732 4767 2773 4767 2774 4767 2732 4768 2774 4768 2729 4768 2776 4769 2789 4769 2777 4769 2776 4770 2777 4770 2778 4770 2778 4771 2777 4771 2779 4771 2778 4772 2779 4772 2780 4772 2780 4773 2779 4773 2781 4773 2780 4774 2781 4774 2782 4774 2781 4775 2783 4775 2782 4775 2782 4776 2783 4776 2784 4776 2784 4777 2783 4777 2785 4777 2784 4778 2785 4778 2786 4778 2784 4779 2786 4779 2787 4779 2787 4780 2786 4780 2788 4780 2787 4781 2788 4781 2776 4781 2776 4782 2788 4782 2789 4782 2790 4783 2791 4783 2792 4783 2792 4784 2791 4784 2793 4784 2792 4785 2793 4785 2794 4785 2795 4786 2796 4786 2797 4786 2797 4787 2796 4787 2798 4787 2797 4788 2798 4788 2799 4788 2799 4789 2798 4789 2800 4789 2799 4790 2800 4790 2790 4790 2790 4791 2800 4791 2791 4791 2794 4792 2793 4792 2801 4792 2801 4793 2793 4793 2802 4793 2801 4794 2802 4794 2803 4794 2803 4795 2802 4795 2804 4795 2803 4796 2804 4796 2805 4796 2805 4797 2804 4797 2806 4797 2805 4798 2806 4798 2807 4798 2807 4799 2806 4799 2795 4799 2795 4800 2806 4800 2796 4800 2809 4801 2808 4801 2811 4801 2809 4802 2811 4802 2810 4802 2810 4803 2811 4803 2813 4803 2810 4804 2813 4804 2812 4804 2812 4805 2813 4805 2814 4805 2812 4806 2814 4806 2815 4806 2815 4807 2814 4807 2857 4807 2815 4808 2857 4808 2816 4808 2816 4809 2857 4809 2817 4809 2816 4810 2817 4810 2818 4810 2819 4811 2820 4811 2818 4811 2819 4812 2818 4812 2817 4812 2821 4813 2820 4813 2819 4813 2820 4814 2821 4814 2823 4814 2820 4815 2823 4815 2822 4815 2822 4816 2823 4816 2824 4816 2822 4817 2824 4817 2825 4817 2825 4818 2824 4818 2858 4818 2825 4819 2858 4819 2809 4819 2809 4820 2858 4820 2808 4820 2826 4821 2828 4821 2827 4821 2829 4822 2828 4822 2826 4822 2830 4823 2831 4823 2826 4823 2826 4824 2831 4824 2829 4824 2832 4825 2807 4825 2833 4825 2833 4826 2807 4826 2795 4826 2833 4827 2795 4827 2834 4827 2834 4828 2795 4828 2797 4828 2834 4829 2797 4829 2835 4829 2835 4830 2797 4830 2836 4830 2836 4831 2797 4831 2799 4831 2836 4832 2799 4832 2837 4832 2837 4833 2799 4833 2790 4833 2837 4834 2790 4834 2838 4834 2838 4835 2790 4835 2792 4835 2838 4836 2792 4836 2839 4836 2839 4837 2792 4837 2840 4837 2840 4838 2792 4838 2794 4838 2840 4839 2794 4839 2801 4839 2840 4840 2801 4840 2841 4840 2841 4841 2801 4841 2803 4841 2841 4842 2803 4842 2842 4842 2842 4843 2803 4843 2805 4843 2842 4844 2805 4844 2832 4844 2832 4845 2805 4845 2807 4845 2838 4846 2786 4846 2837 4846 2837 4847 2786 4847 2836 4847 2836 4848 2786 4848 2785 4848 2836 4849 2785 4849 2783 4849 2836 4850 2783 4850 2835 4850 2835 4851 2783 4851 2834 4851 2834 4852 2783 4852 2781 4852 2834 4853 2781 4853 2833 4853 2833 4854 2781 4854 2779 4854 2833 4855 2779 4855 2832 4855 2832 4856 2779 4856 2842 4856 2842 4857 2779 4857 2777 4857 2842 4858 2777 4858 2841 4858 2841 4859 2777 4859 2789 4859 2841 4860 2789 4860 2840 4860 2840 4861 2789 4861 2839 4861 2839 4862 2789 4862 2788 4862 2839 4863 2788 4863 2838 4863 2838 4864 2788 4864 2786 4864 2809 4865 2826 4865 2825 4865 2825 4866 2826 4866 2827 4866 2825 4867 2827 4867 2822 4867 2822 4868 2827 4868 2828 4868 2822 4869 2828 4869 2820 4869 2820 4870 2828 4870 2818 4870 2818 4871 2828 4871 2829 4871 2818 4872 2829 4872 2816 4872 2816 4873 2829 4873 2815 4873 2815 4874 2829 4874 2831 4874 2815 4875 2831 4875 2812 4875 2812 4876 2831 4876 2830 4876 2812 4877 2830 4877 2810 4877 2810 4878 2830 4878 2826 4878 2810 4879 2826 4879 2809 4879 2776 4880 2843 4880 2787 4880 2778 4881 2844 4881 2776 4881 2780 4882 2845 4882 2778 4882 2782 4883 2846 4883 2780 4883 2784 4884 2847 4884 2782 4884 2787 4885 2848 4885 2784 4885 2852 4886 2853 4886 2850 4886 2852 4887 2850 4887 2851 4887 2851 4888 2850 4888 2849 4888 2854 4889 2849 4889 2850 4889 2855 4890 2854 4890 2850 4890 2856 4891 2855 4891 2850 4891 2850 4892 2853 4892 2856 4892 2854 4893 2787 4893 2843 4893 2854 4894 2843 4894 2849 4894 2776 4895 2849 4895 2843 4895 2851 4896 2844 4896 2852 4896 2852 4897 2844 4897 2778 4897 2849 4898 2776 4898 2844 4898 2844 4899 2851 4899 2849 4899 2845 4900 2780 4900 2853 4900 2845 4901 2852 4901 2778 4901 2845 4902 2853 4902 2852 4902 2782 4903 2856 4903 2846 4903 2853 4904 2780 4904 2846 4904 2853 4905 2846 4905 2856 4905 2784 4906 2855 4906 2847 4906 2856 4907 2782 4907 2847 4907 2856 4908 2847 4908 2855 4908 2787 4909 2854 4909 2848 4909 2855 4910 2784 4910 2848 4910 2855 4911 2848 4911 2854 4911 2793 4912 2791 4912 2857 4912 2800 4913 2819 4913 2817 4913 2800 4914 2817 4914 2791 4914 2791 4915 2817 4915 2857 4915 2804 4916 2811 4916 2808 4916 2804 4917 2808 4917 2806 4917 2806 4918 2808 4918 2858 4918 2804 4919 2802 4919 2813 4919 2804 4920 2813 4920 2811 4920 2802 4921 2793 4921 2814 4921 2802 4922 2814 4922 2813 4922 2793 4923 2857 4923 2814 4923 2800 4924 2798 4924 2821 4924 2800 4925 2821 4925 2819 4925 2798 4926 2823 4926 2821 4926 2798 4927 2796 4927 2823 4927 2796 4928 2824 4928 2823 4928 2796 4929 2806 4929 2858 4929 2796 4930 2858 4930 2824 4930 2859 4931 2873 4931 2860 4931 2859 4932 2860 4932 2861 4932 2861 4933 2860 4933 2862 4933 2861 4934 2862 4934 2863 4934 2863 4935 2862 4935 2864 4935 2863 4936 2864 4936 2865 4936 2863 4937 2865 4937 2866 4937 2866 4938 2865 4938 2867 4938 2866 4939 2867 4939 2868 4939 2868 4940 2867 4940 2869 4940 2868 4941 2869 4941 2870 4941 2868 4942 2870 4942 2871 4942 2871 4943 2870 4943 2872 4943 2871 4944 2872 4944 2859 4944 2859 4945 2872 4945 2873 4945 2874 4946 2883 4946 2875 4946 2874 4947 2875 4947 2876 4947 2876 4948 2875 4948 2877 4948 2876 4949 2877 4949 2878 4949 2879 4950 2892 4950 2880 4950 2879 4951 2880 4951 2881 4951 2881 4952 2880 4952 2882 4952 2882 4953 2880 4953 2883 4953 2882 4954 2883 4954 2884 4954 2884 4955 2883 4955 2874 4955 2878 4956 2877 4956 2885 4956 2878 4957 2885 4957 2886 4957 2886 4958 2885 4958 2887 4958 2887 4959 2885 4959 2888 4959 2887 4960 2888 4960 2889 4960 2887 4961 2889 4961 2890 4961 2890 4962 2889 4962 2891 4962 2891 4963 2889 4963 2892 4963 2891 4964 2892 4964 2879 4964 2894 4965 2893 4965 2896 4965 2894 4966 2896 4966 2895 4966 2895 4967 2896 4967 2898 4967 2895 4968 2898 4968 2897 4968 2897 4969 2898 4969 2899 4969 2897 4970 2899 4970 2900 4970 2900 4971 2899 4971 2944 4971 2900 4972 2944 4972 2901 4972 2901 4973 2944 4973 2902 4973 2901 4974 2902 4974 2903 4974 2902 4975 2943 4975 2903 4975 2904 4976 2905 4976 2903 4976 2904 4977 2903 4977 2943 4977 2945 4978 2905 4978 2904 4978 2905 4979 2945 4979 2907 4979 2905 4980 2907 4980 2906 4980 2906 4981 2907 4981 2908 4981 2906 4982 2908 4982 2909 4982 2909 4983 2908 4983 2910 4983 2909 4984 2910 4984 2894 4984 2894 4985 2910 4985 2893 4985 2912 4986 2913 4986 2911 4986 2912 4987 2914 4987 2913 4987 2915 4988 2914 4988 2912 4988 2912 4989 2916 4989 2915 4989 2917 4990 2891 4990 2918 4990 2918 4991 2891 4991 2879 4991 2918 4992 2879 4992 2919 4992 2919 4993 2879 4993 2881 4993 2919 4994 2881 4994 2920 4994 2920 4995 2881 4995 2882 4995 2920 4996 2882 4996 2921 4996 2921 4997 2882 4997 2884 4997 2921 4998 2884 4998 2922 4998 2922 4999 2884 4999 2874 4999 2922 5000 2874 5000 2923 5000 2923 5001 2874 5001 2876 5001 2923 5002 2876 5002 2924 5002 2924 5003 2876 5003 2878 5003 2924 5004 2878 5004 2925 5004 2925 5005 2878 5005 2886 5005 2925 5006 2886 5006 2926 5006 2926 5007 2886 5007 2887 5007 2926 5008 2887 5008 2927 5008 2927 5009 2887 5009 2890 5009 2927 5010 2890 5010 2917 5010 2917 5011 2890 5011 2891 5011 2923 5012 2870 5012 2922 5012 2922 5013 2870 5013 2869 5013 2922 5014 2869 5014 2921 5014 2921 5015 2869 5015 2867 5015 2921 5016 2867 5016 2920 5016 2920 5017 2867 5017 2865 5017 2920 5018 2865 5018 2919 5018 2919 5019 2865 5019 2918 5019 2918 5020 2865 5020 2864 5020 2918 5021 2864 5021 2917 5021 2917 5022 2864 5022 2862 5022 2917 5023 2862 5023 2927 5023 2927 5024 2862 5024 2860 5024 2927 5025 2860 5025 2926 5025 2926 5026 2860 5026 2873 5026 2926 5027 2873 5027 2925 5027 2925 5028 2873 5028 2924 5028 2924 5029 2873 5029 2872 5029 2924 5030 2872 5030 2923 5030 2923 5031 2872 5031 2870 5031 2894 5032 2911 5032 2909 5032 2909 5033 2911 5033 2913 5033 2909 5034 2913 5034 2906 5034 2906 5035 2913 5035 2914 5035 2906 5036 2914 5036 2905 5036 2905 5037 2914 5037 2903 5037 2903 5038 2914 5038 2915 5038 2903 5039 2915 5039 2901 5039 2901 5040 2915 5040 2916 5040 2901 5041 2916 5041 2900 5041 2900 5042 2916 5042 2897 5042 2897 5043 2916 5043 2912 5043 2897 5044 2912 5044 2895 5044 2895 5045 2912 5045 2894 5045 2894 5046 2912 5046 2911 5046 2859 5047 2928 5047 2871 5047 2861 5048 2929 5048 2859 5048 2863 5049 2930 5049 2861 5049 2866 5050 2931 5050 2863 5050 2868 5051 2932 5051 2866 5051 2871 5052 2933 5052 2868 5052 2937 5053 2938 5053 2935 5053 2937 5054 2935 5054 2936 5054 2936 5055 2935 5055 2934 5055 2939 5056 2934 5056 2935 5056 2940 5057 2939 5057 2935 5057 2941 5058 2940 5058 2935 5058 2935 5059 2938 5059 2941 5059 2939 5060 2871 5060 2928 5060 2939 5061 2928 5061 2934 5061 2859 5062 2934 5062 2928 5062 2936 5063 2929 5063 2937 5063 2937 5064 2929 5064 2861 5064 2934 5065 2859 5065 2929 5065 2929 5066 2936 5066 2934 5066 2930 5067 2863 5067 2938 5067 2930 5068 2937 5068 2861 5068 2930 5069 2938 5069 2937 5069 2866 5070 2941 5070 2931 5070 2938 5071 2863 5071 2931 5071 2938 5072 2931 5072 2941 5072 2868 5073 2940 5073 2932 5073 2941 5074 2866 5074 2932 5074 2941 5075 2932 5075 2940 5075 2871 5076 2939 5076 2933 5076 2940 5077 2868 5077 2933 5077 2940 5078 2933 5078 2939 5078 2880 5079 2942 5079 2883 5079 2883 5080 2942 5080 2943 5080 2883 5081 2943 5081 2875 5081 2875 5082 2944 5082 2877 5082 2888 5083 2893 5083 2889 5083 2942 5084 2904 5084 2943 5084 2943 5085 2902 5085 2875 5085 2875 5086 2902 5086 2944 5086 2888 5087 2896 5087 2893 5087 2889 5088 2893 5088 2910 5088 2889 5089 2910 5089 2892 5089 2888 5090 2885 5090 2898 5090 2888 5091 2898 5091 2896 5091 2885 5092 2877 5092 2899 5092 2885 5093 2899 5093 2898 5093 2877 5094 2944 5094 2899 5094 2942 5095 2945 5095 2904 5095 2942 5096 2880 5096 2945 5096 2880 5097 2907 5097 2945 5097 2880 5098 2908 5098 2907 5098 2880 5099 2892 5099 2908 5099 2892 5100 2910 5100 2908 5100 2946 348 2947 348 2948 348 2948 5101 2947 5101 2949 5101 2950 348 2951 348 2946 348 2946 348 2951 348 2952 348 2946 348 2952 348 2947 348 2947 5102 2953 5102 2949 5102 2949 5103 2953 5103 2954 5103 2949 348 2954 348 2955 348 2955 348 2954 348 2956 348 2955 5104 2956 5104 2957 5104 2957 5105 2956 5105 2958 5105 2957 348 2958 348 2959 348 2959 348 2958 348 2960 348 2959 348 2960 348 2961 348 2960 348 2962 348 2961 348 2961 5106 2962 5106 2963 5106 2961 5107 2963 5107 2950 5107 2950 348 2963 348 2951 348 2964 324 2965 324 2966 324 2966 324 2965 324 2967 324 2966 324 2967 324 2968 324 2969 324 2970 324 2971 324 2969 324 2971 324 2964 324 2964 324 2971 324 2965 324 2972 324 2973 324 2974 324 2972 324 2974 324 2975 324 2975 324 2974 324 2976 324 2976 324 2974 324 2977 324 2976 324 2977 324 2978 324 2976 324 2978 324 2979 324 2979 324 2978 324 2969 324 2969 324 2978 324 2970 324 2967 324 2980 324 2968 324 2968 324 2980 324 2981 324 2968 324 2981 324 2972 324 2972 324 2981 324 2973 324 2967 5108 2951 5108 2980 5108 2980 5109 2951 5109 2963 5109 2980 5110 2963 5110 2981 5110 2981 5111 2963 5111 2962 5111 2981 5112 2962 5112 2973 5112 2973 5113 2962 5113 2974 5113 2974 5114 2962 5114 2960 5114 2974 5115 2960 5115 2958 5115 2974 5116 2958 5116 2977 5116 2977 5117 2958 5117 2956 5117 2977 5118 2956 5118 2978 5118 2978 5119 2956 5119 2954 5119 2978 5120 2954 5120 2970 5120 2970 5121 2954 5121 2953 5121 2970 5122 2953 5122 2971 5122 2971 5123 2953 5123 2947 5123 2971 5124 2947 5124 2965 5124 2965 5125 2947 5125 2952 5125 2965 5126 2952 5126 2967 5126 2967 5127 2952 5127 2951 5127 2946 5128 2966 5128 2950 5128 2950 5129 2966 5129 2968 5129 2950 5130 2968 5130 2961 5130 2961 5131 2968 5131 2972 5131 2961 5132 2972 5132 2959 5132 2959 5133 2972 5133 2975 5133 2959 3700 2975 3700 2957 3700 2957 5134 2975 5134 2976 5134 2957 5135 2976 5135 2955 5135 2955 5136 2976 5136 2979 5136 2955 5137 2979 5137 2949 5137 2949 5138 2979 5138 2969 5138 2949 5139 2969 5139 2948 5139 2948 5140 2969 5140 2964 5140 2948 5141 2964 5141 2946 5141 2946 5142 2964 5142 2966 5142 2982 5143 2983 5143 2984 5143 2984 5144 2983 5144 2985 5144 2986 5145 2982 5145 2987 5145 2987 5146 2982 5146 2984 5146 2988 5147 2986 5147 2989 5147 2989 5147 2986 5147 2987 5147 2983 5148 2988 5148 2985 5148 2985 5149 2988 5149 2989 5149 2986 324 2988 324 2982 324 2982 324 2988 324 2983 324 2989 348 2987 348 2985 348 2985 348 2987 348 2984 348 2990 5150 3003 5150 2991 5150 2990 5151 2991 5151 2992 5151 2992 5152 2991 5152 2993 5152 2992 5153 2993 5153 2994 5153 2994 5154 2993 5154 2995 5154 2994 5155 2995 5155 2996 5155 2995 5156 2997 5156 2996 5156 2996 5157 2997 5157 2998 5157 2998 5158 2997 5158 2999 5158 2998 5159 2999 5159 3000 5159 2998 5160 3000 5160 3001 5160 3001 5161 3000 5161 3002 5161 3001 5162 3002 5162 2990 5162 2990 5163 3002 5163 3003 5163 3004 5164 3005 5164 3006 5164 3006 5165 3005 5165 3007 5165 3006 5166 3007 5166 3008 5166 3009 5167 3010 5167 3011 5167 3011 5168 3010 5168 3012 5168 3012 5169 3010 5169 3013 5169 3012 5170 3013 5170 3014 5170 3014 5171 3013 5171 3015 5171 3014 5172 3015 5172 3016 5172 3016 5173 3015 5173 3004 5173 3004 5174 3015 5174 3005 5174 3008 5175 3007 5175 3017 5175 3008 5176 3017 5176 3018 5176 3018 5177 3017 5177 3019 5177 3019 5178 3017 5178 3020 5178 3019 5179 3020 5179 3021 5179 3021 5180 3020 5180 3009 5180 3009 5181 3020 5181 3010 5181 3023 5182 3022 5182 3025 5182 3023 5183 3025 5183 3024 5183 3024 5184 3025 5184 3026 5184 3024 5185 3026 5185 3027 5185 3027 5186 3026 5186 3028 5186 3027 5187 3028 5187 3029 5187 3029 5188 3028 5188 3074 5188 3029 5189 3074 5189 3030 5189 3030 5190 3074 5190 3031 5190 3030 5191 3031 5191 3032 5191 3031 5192 3071 5192 3032 5192 3033 5193 3034 5193 3032 5193 3033 5194 3032 5194 3071 5194 3035 5195 3034 5195 3033 5195 3034 5196 3035 5196 3036 5196 3076 5197 3036 5197 3035 5197 3036 5198 3076 5198 3037 5198 3036 5199 3037 5199 3038 5199 3038 5200 3037 5200 3075 5200 3038 5201 3075 5201 3023 5201 3023 5202 3075 5202 3022 5202 3039 5203 3040 5203 3041 5203 3042 5204 3039 5204 3041 5204 3041 5205 3043 5205 3042 5205 3041 5206 3040 5206 3044 5206 3045 5207 3021 5207 3009 5207 3045 5208 3009 5208 3046 5208 3046 5209 3009 5209 3011 5209 3046 5210 3011 5210 3047 5210 3047 5211 3011 5211 3012 5211 3047 5212 3012 5212 3048 5212 3048 5213 3012 5213 3014 5213 3048 5214 3014 5214 3049 5214 3049 5215 3014 5215 3016 5215 3049 5216 3016 5216 3050 5216 3050 5217 3016 5217 3004 5217 3050 5218 3004 5218 3051 5218 3051 5219 3004 5219 3052 5219 3052 5220 3004 5220 3006 5220 3052 5221 3006 5221 3053 5221 3053 5222 3006 5222 3008 5222 3053 5223 3008 5223 3054 5223 3054 5224 3008 5224 3018 5224 3054 5225 3018 5225 3055 5225 3055 5226 3018 5226 3019 5226 3055 5227 3019 5227 3056 5227 3056 5228 3019 5228 3021 5228 3056 5229 3021 5229 3045 5229 3051 5230 3000 5230 3050 5230 3050 5231 3000 5231 2999 5231 3050 5232 2999 5232 3049 5232 3049 5233 2999 5233 2997 5233 3049 5234 2997 5234 3048 5234 3048 5235 2997 5235 3047 5235 3047 5236 2997 5236 2995 5236 3047 5237 2995 5237 3046 5237 3046 5238 2995 5238 3045 5238 3045 5239 2995 5239 2993 5239 3045 5240 2993 5240 3056 5240 3056 5241 2993 5241 3055 5241 3055 5242 2993 5242 2991 5242 3055 5243 2991 5243 3054 5243 3054 5244 2991 5244 3003 5244 3054 5245 3003 5245 3053 5245 3053 5246 3003 5246 3002 5246 3053 5247 3002 5247 3052 5247 3052 5248 3002 5248 3000 5248 3052 5249 3000 5249 3051 5249 3023 5250 3039 5250 3038 5250 3038 5251 3039 5251 3042 5251 3038 5252 3042 5252 3036 5252 3036 5253 3042 5253 3043 5253 3036 5254 3043 5254 3034 5254 3034 5255 3043 5255 3032 5255 3032 5256 3043 5256 3041 5256 3032 5257 3041 5257 3030 5257 3030 5258 3041 5258 3029 5258 3029 5259 3041 5259 3044 5259 3029 5260 3044 5260 3027 5260 3027 5261 3044 5261 3040 5261 3027 5262 3040 5262 3024 5262 3024 5263 3040 5263 3023 5263 3023 5264 3040 5264 3039 5264 2990 5265 3057 5265 3001 5265 2992 5266 3058 5266 2990 5266 2994 5267 3059 5267 2992 5267 2996 5268 3060 5268 2994 5268 2998 5269 3061 5269 2996 5269 3001 5270 3062 5270 2998 5270 3066 5271 3067 5271 3064 5271 3066 5272 3064 5272 3065 5272 3065 5273 3064 5273 3063 5273 3068 5274 3063 5274 3064 5274 3069 5275 3068 5275 3064 5275 3070 5276 3069 5276 3064 5276 3064 5277 3067 5277 3070 5277 3068 5278 3001 5278 3057 5278 3068 5279 3057 5279 3063 5279 2990 5280 3063 5280 3057 5280 3065 5281 3058 5281 3066 5281 3066 5282 3058 5282 2992 5282 3063 5283 2990 5283 3058 5283 3058 5284 3065 5284 3063 5284 3059 5285 2994 5285 3067 5285 3059 5286 3066 5286 2992 5286 3059 5287 3067 5287 3066 5287 2996 5288 3070 5288 3060 5288 3067 5289 2994 5289 3060 5289 3067 5290 3060 5290 3070 5290 2998 5291 3069 5291 3061 5291 3070 5292 2996 5292 3061 5292 3070 5293 3061 5293 3069 5293 3001 5294 3068 5294 3062 5294 3069 5295 2998 5295 3062 5295 3069 5296 3062 5296 3068 5296 3017 5297 3007 5297 3028 5297 3005 5298 3015 5298 3071 5298 3005 5299 3071 5299 3072 5299 3005 5300 3072 5300 3007 5300 3017 5301 3073 5301 3020 5301 3020 5302 3073 5302 3010 5302 3007 5303 3072 5303 3074 5303 3017 5304 3025 5304 3073 5304 3015 5305 3033 5305 3071 5305 3071 5306 3031 5306 3072 5306 3072 5307 3031 5307 3074 5307 3073 5308 3025 5308 3022 5308 3073 5309 3022 5309 3075 5309 3017 5310 3026 5310 3025 5310 3017 5311 3028 5311 3026 5311 3007 5312 3074 5312 3028 5312 3015 5313 3035 5313 3033 5313 3015 5314 3013 5314 3035 5314 3013 5315 3076 5315 3035 5315 3013 5316 3010 5316 3076 5316 3076 5317 3010 5317 3037 5317 3010 5318 3075 5318 3037 5318 3010 5319 3073 5319 3075 5319 3077 5320 3091 5320 3078 5320 3077 5321 3078 5321 3079 5321 3079 5322 3078 5322 3080 5322 3079 5323 3080 5323 3081 5323 3081 5324 3080 5324 3082 5324 3081 5325 3082 5325 3083 5325 3083 5326 3082 5326 3084 5326 3084 5327 3085 5327 3083 5327 3083 5328 3085 5328 3086 5328 3086 5329 3085 5329 3087 5329 3086 5330 3087 5330 3088 5330 3086 5331 3088 5331 3089 5331 3089 5332 3088 5332 3090 5332 3089 5333 3090 5333 3077 5333 3077 5334 3090 5334 3091 5334 3092 5335 3093 5335 3094 5335 3094 5336 3093 5336 3095 5336 3094 5337 3095 5337 3096 5337 3097 5338 3098 5338 3099 5338 3099 5339 3098 5339 3100 5339 3099 5340 3100 5340 3101 5340 3101 5341 3100 5341 3102 5341 3101 5342 3102 5342 3103 5342 3103 5343 3102 5343 3092 5343 3103 5344 3092 5344 3104 5344 3096 5345 3095 5345 3105 5345 3096 5346 3105 5346 3106 5346 3106 5347 3105 5347 3107 5347 3107 5348 3105 5348 3108 5348 3107 5349 3108 5349 3109 5349 3109 5350 3108 5350 3110 5350 3109 5351 3110 5351 3097 5351 3097 5352 3110 5352 3098 5352 3111 5353 3112 5353 3130 5353 3112 5354 3111 5354 3113 5354 3114 5355 3113 5355 3111 5355 3113 5356 3114 5356 3116 5356 3113 5357 3116 5357 3115 5357 3115 5358 3116 5358 3117 5358 3115 5359 3117 5359 3118 5359 3118 5360 3117 5360 3119 5360 3118 5361 3119 5361 3120 5361 3120 5362 3119 5362 3121 5362 3120 5363 3121 5363 3122 5363 3123 5364 3124 5364 3122 5364 3123 5365 3122 5365 3121 5365 3125 5366 3124 5366 3123 5366 3124 5367 3125 5367 3127 5367 3124 5368 3127 5368 3126 5368 3126 5369 3127 5369 3128 5369 3126 5370 3128 5370 3129 5370 3129 5371 3128 5371 3130 5371 3129 5372 3130 5372 3112 5372 3131 5373 3133 5373 3132 5373 3134 5374 3133 5374 3131 5374 3131 5375 3135 5375 3134 5375 3131 5376 3136 5376 3135 5376 3137 5377 3109 5377 3138 5377 3138 5378 3109 5378 3097 5378 3138 5379 3097 5379 3099 5379 3138 5380 3099 5380 3139 5380 3139 5381 3099 5381 3140 5381 3140 5382 3099 5382 3101 5382 3140 5383 3101 5383 3103 5383 3140 5384 3103 5384 3141 5384 3141 5385 3103 5385 3104 5385 3141 5386 3104 5386 3142 5386 3142 5387 3104 5387 3092 5387 3142 5388 3092 5388 3143 5388 3143 5389 3092 5389 3094 5389 3143 5390 3094 5390 3144 5390 3144 5391 3094 5391 3096 5391 3144 5392 3096 5392 3145 5392 3145 5393 3096 5393 3106 5393 3145 5394 3106 5394 3146 5394 3146 5395 3106 5395 3107 5395 3146 5396 3107 5396 3147 5396 3147 5397 3107 5397 3109 5397 3147 5398 3109 5398 3137 5398 3143 5399 3088 5399 3142 5399 3142 5400 3088 5400 3141 5400 3141 5401 3088 5401 3087 5401 3141 5402 3087 5402 3085 5402 3141 5403 3085 5403 3140 5403 3140 5404 3085 5404 3139 5404 3139 5405 3085 5405 3084 5405 3139 5406 3084 5406 3138 5406 3138 5407 3084 5407 3082 5407 3138 5408 3082 5408 3137 5408 3137 5409 3082 5409 3080 5409 3137 5410 3080 5410 3147 5410 3147 5411 3080 5411 3078 5411 3147 5412 3078 5412 3146 5412 3146 5413 3078 5413 3091 5413 3146 5414 3091 5414 3145 5414 3145 5415 3091 5415 3144 5415 3144 5416 3091 5416 3090 5416 3144 5417 3090 5417 3143 5417 3143 5418 3090 5418 3088 5418 3112 5419 3132 5419 3129 5419 3129 5420 3132 5420 3133 5420 3129 5421 3133 5421 3126 5421 3126 5422 3133 5422 3124 5422 3124 5423 3133 5423 3134 5423 3124 5424 3134 5424 3122 5424 3122 5425 3134 5425 3120 5425 3120 5426 3134 5426 3135 5426 3120 5427 3135 5427 3118 5427 3118 5428 3135 5428 3136 5428 3118 5429 3136 5429 3115 5429 3115 5430 3136 5430 3113 5430 3113 5431 3136 5431 3131 5431 3113 5432 3131 5432 3112 5432 3112 5433 3131 5433 3132 5433 3077 5434 3148 5434 3089 5434 3079 5435 3149 5435 3077 5435 3081 5436 3150 5436 3079 5436 3083 5437 3151 5437 3081 5437 3086 5438 3152 5438 3083 5438 3089 5439 3153 5439 3086 5439 3157 5440 3158 5440 3155 5440 3157 5441 3155 5441 3156 5441 3156 5442 3155 5442 3154 5442 3159 5443 3154 5443 3155 5443 3160 5444 3159 5444 3155 5444 3161 5445 3160 5445 3155 5445 3155 5446 3158 5446 3161 5446 3159 5447 3089 5447 3148 5447 3159 5448 3148 5448 3154 5448 3077 5449 3154 5449 3148 5449 3156 5450 3149 5450 3157 5450 3157 5451 3149 5451 3079 5451 3154 5452 3077 5452 3149 5452 3149 5453 3156 5453 3154 5453 3150 5454 3081 5454 3158 5454 3150 5455 3157 5455 3079 5455 3150 5456 3158 5456 3157 5456 3083 5457 3161 5457 3151 5457 3158 5458 3081 5458 3151 5458 3158 5459 3151 5459 3161 5459 3086 5460 3160 5460 3152 5460 3161 5461 3083 5461 3152 5461 3161 5462 3152 5462 3160 5462 3089 5463 3159 5463 3153 5463 3160 5464 3086 5464 3153 5464 3160 5465 3153 5465 3159 5465 3092 5466 3102 5466 3162 5466 3092 5467 3162 5467 3093 5467 3102 5468 3123 5468 3162 5468 3162 5469 3123 5469 3121 5469 3162 5470 3121 5470 3093 5470 3093 5471 3121 5471 3119 5471 3093 5472 3119 5472 3095 5472 3108 5473 3111 5473 3110 5473 3110 5474 3111 5474 3130 5474 3110 5475 3130 5475 3098 5475 3108 5476 3114 5476 3111 5476 3108 5477 3116 5477 3114 5477 3108 5478 3105 5478 3116 5478 3105 5479 3117 5479 3116 5479 3105 5480 3095 5480 3117 5480 3095 5481 3119 5481 3117 5481 3102 5482 3125 5482 3123 5482 3102 5483 3127 5483 3125 5483 3102 5484 3100 5484 3127 5484 3100 5485 3128 5485 3127 5485 3100 5486 3098 5486 3128 5486 3098 5487 3130 5487 3128 5487 3163 5488 3164 5488 3165 5488 3165 5489 3164 5489 3166 5489 3165 5490 3166 5490 3167 5490 3165 5491 3167 5491 3168 5491 3168 5492 3167 5492 3169 5492 3168 5493 3169 5493 3170 5493 3170 5494 3169 5494 3171 5494 3170 5495 3171 5495 3172 5495 3170 5496 3172 5496 3173 5496 3173 5497 3172 5497 3174 5497 3173 5498 3174 5498 3175 5498 3173 5499 3175 5499 3176 5499 3176 5500 3175 5500 3177 5500 3176 5501 3177 5501 3163 5501 3163 5502 3177 5502 3164 5502 3178 5503 3190 5503 3179 5503 3178 5504 3179 5504 3180 5504 3180 5505 3179 5505 3181 5505 3180 5506 3181 5506 3182 5506 3183 5507 3184 5507 3185 5507 3185 5508 3184 5508 3186 5508 3185 5509 3186 5509 3187 5509 3187 5510 3186 5510 3188 5510 3187 5511 3188 5511 3189 5511 3189 5512 3188 5512 3190 5512 3189 5513 3190 5513 3178 5513 3182 5514 3181 5514 3191 5514 3182 5515 3191 5515 3192 5515 3192 5516 3191 5516 3193 5516 3192 5517 3193 5517 3194 5517 3194 5518 3193 5518 3195 5518 3194 5519 3195 5519 3196 5519 3196 5520 3195 5520 3197 5520 3196 5521 3197 5521 3183 5521 3183 5522 3197 5522 3184 5522 3199 5523 3198 5523 3200 5523 3201 5524 3200 5524 3198 5524 3200 5525 3201 5525 3202 5525 3248 5526 3202 5526 3201 5526 3202 5527 3248 5527 3203 5527 3202 5528 3203 5528 3204 5528 3204 5529 3203 5529 3205 5529 3204 5530 3205 5530 3206 5530 3206 5531 3205 5531 3207 5531 3206 5532 3207 5532 3208 5532 3209 5533 3210 5533 3208 5533 3209 5534 3208 5534 3207 5534 3211 5535 3210 5535 3209 5535 3210 5536 3211 5536 3213 5536 3210 5537 3213 5537 3212 5537 3212 5538 3213 5538 3214 5538 3212 5539 3214 5539 3215 5539 3215 5540 3214 5540 3247 5540 3215 5541 3247 5541 3199 5541 3199 5542 3247 5542 3198 5542 3217 5543 3218 5543 3216 5543 3217 5544 3220 5544 3219 5544 3217 5545 3221 5545 3220 5545 3216 5546 3221 5546 3217 5546 3222 5547 3196 5547 3223 5547 3223 5548 3196 5548 3183 5548 3223 5549 3183 5549 3224 5549 3224 5550 3183 5550 3185 5550 3224 5551 3185 5551 3225 5551 3225 5552 3185 5552 3187 5552 3225 5553 3187 5553 3226 5553 3226 5554 3187 5554 3189 5554 3226 5555 3189 5555 3227 5555 3227 5556 3189 5556 3178 5556 3227 5557 3178 5557 3228 5557 3228 5558 3178 5558 3180 5558 3228 5559 3180 5559 3229 5559 3229 5560 3180 5560 3182 5560 3229 5561 3182 5561 3230 5561 3230 5562 3182 5562 3192 5562 3230 5563 3192 5563 3231 5563 3231 5564 3192 5564 3194 5564 3231 5565 3194 5565 3232 5565 3232 5566 3194 5566 3222 5566 3222 5567 3194 5567 3196 5567 3228 5568 3175 5568 3227 5568 3227 5569 3175 5569 3174 5569 3227 5570 3174 5570 3226 5570 3226 5571 3174 5571 3225 5571 3225 5572 3174 5572 3172 5572 3225 5573 3172 5573 3224 5573 3224 5574 3172 5574 3171 5574 3224 5575 3171 5575 3223 5575 3223 5576 3171 5576 3169 5576 3223 5577 3169 5577 3222 5577 3222 5578 3169 5578 3167 5578 3222 5579 3167 5579 3232 5579 3232 5580 3167 5580 3166 5580 3232 5581 3166 5581 3231 5581 3231 5582 3166 5582 3164 5582 3231 5583 3164 5583 3230 5583 3230 5584 3164 5584 3177 5584 3230 5585 3177 5585 3229 5585 3229 5586 3177 5586 3175 5586 3229 5587 3175 5587 3228 5587 3199 5588 3216 5588 3215 5588 3215 5589 3216 5589 3218 5589 3215 5590 3218 5590 3212 5590 3212 5591 3218 5591 3217 5591 3212 5592 3217 5592 3210 5592 3210 5593 3217 5593 3219 5593 3210 5594 3219 5594 3208 5594 3208 5595 3219 5595 3206 5595 3206 5596 3219 5596 3220 5596 3206 5597 3220 5597 3204 5597 3204 5598 3220 5598 3221 5598 3204 5599 3221 5599 3202 5599 3202 5600 3221 5600 3200 5600 3200 5601 3221 5601 3216 5601 3200 5602 3216 5602 3199 5602 3163 5603 3233 5603 3176 5603 3165 5604 3234 5604 3163 5604 3168 5605 3235 5605 3165 5605 3170 5606 3236 5606 3168 5606 3173 5607 3237 5607 3170 5607 3176 5608 3238 5608 3173 5608 3242 5609 3243 5609 3240 5609 3242 5610 3240 5610 3241 5610 3241 5611 3240 5611 3239 5611 3244 5612 3239 5612 3240 5612 3245 5613 3244 5613 3240 5613 3246 5614 3245 5614 3240 5614 3240 5615 3243 5615 3246 5615 3244 5616 3176 5616 3233 5616 3244 5617 3233 5617 3239 5617 3163 5618 3239 5618 3233 5618 3241 5619 3234 5619 3242 5619 3242 5620 3234 5620 3165 5620 3239 5621 3163 5621 3234 5621 3234 5622 3241 5622 3239 5622 3235 5623 3168 5623 3243 5623 3235 5624 3242 5624 3165 5624 3235 5625 3243 5625 3242 5625 3170 5626 3246 5626 3236 5626 3243 5627 3168 5627 3236 5627 3243 5628 3236 5628 3246 5628 3173 5629 3245 5629 3237 5629 3246 5630 3170 5630 3237 5630 3246 5631 3237 5631 3245 5631 3176 5632 3244 5632 3238 5632 3245 5633 3173 5633 3238 5633 3245 5634 3238 5634 3244 5634 3188 5635 3209 5635 3190 5635 3179 5636 3190 5636 3205 5636 3179 5637 3205 5637 3181 5637 3197 5638 3195 5638 3247 5638 3209 5639 3207 5639 3190 5639 3190 5640 3207 5640 3205 5640 3195 5641 3198 5641 3247 5641 3195 5642 3193 5642 3201 5642 3195 5643 3201 5643 3198 5643 3191 5644 3248 5644 3193 5644 3193 5645 3248 5645 3201 5645 3191 5646 3181 5646 3248 5646 3248 5647 3181 5647 3203 5647 3181 5648 3205 5648 3203 5648 3188 5649 3211 5649 3209 5649 3188 5650 3186 5650 3211 5650 3186 5651 3213 5651 3211 5651 3186 5652 3184 5652 3213 5652 3184 5653 3214 5653 3213 5653 3184 5654 3197 5654 3214 5654 3197 5655 3247 5655 3214 5655 3254 5656 3251 5656 3252 5656 3249 5657 3250 5657 3253 5657 3253 5658 3254 5658 3252 5658 3249 5659 3253 5659 3252 5659 3255 5660 3251 5660 3254 5660 3258 5661 3256 5661 3257 5661 3252 5662 3251 5662 3255 5662 3255 5663 3258 5663 3257 5663 3252 5664 3255 5664 3257 5664 3258 5665 3259 5665 3256 5665 3260 5666 3256 5666 3259 5666 3257 5667 3256 5667 3260 5667 3261 5668 3263 5668 3262 5668 3257 5669 3260 5669 3261 5669 3257 5670 3261 5670 3262 5670 3266 5671 3263 5671 3265 5671 3265 5672 3263 5672 3261 5672 3264 5673 3263 5673 3267 5673 3267 5674 3263 5674 3266 5674 3270 5675 3268 5675 3269 5675 3264 5676 3270 5676 3269 5676 3262 5677 3263 5677 3269 5677 3269 5678 3263 5678 3264 5678 3268 5679 3270 5679 3271 5679 3269 5680 3268 5680 3271 5680 3271 5681 3273 5681 3272 5681 3269 5682 3271 5682 3272 5682 3276 5683 3273 5683 3271 5683 3277 5684 3273 5684 3276 5684 3277 5685 3274 5685 3273 5685 3278 5686 3250 5686 3249 5686 3272 5687 3273 5687 3274 5687 3275 5688 3278 5688 3249 5688 3272 5689 3274 5689 3249 5689 3249 5690 3274 5690 3275 5690 3253 5691 3250 5691 3278 5691 3275 5692 3281 5692 3280 5692 3261 5693 3279 5693 3287 5693 3279 5694 3261 5694 3260 5694 3280 5695 3253 5695 3278 5695 3280 5696 3278 5696 3275 5696 3281 5697 3282 5697 3283 5697 3281 5698 3283 5698 3284 5698 3281 5699 3275 5699 3285 5699 3281 5700 3285 5700 3286 5700 3281 5701 3286 5701 3282 5701 3292 5702 3253 5702 3280 5702 3292 5703 3254 5703 3253 5703 3287 5704 3288 5704 3289 5704 3287 5705 3289 5705 3290 5705 3287 5706 3290 5706 3261 5706 3270 5707 3264 5707 3284 5707 3284 5708 3264 5708 3287 5708 3287 5709 3264 5709 3291 5709 3287 5710 3291 5710 3288 5710 3292 5711 3255 5711 3254 5711 3279 5712 3260 5712 3259 5712 3279 5713 3259 5713 3292 5713 3284 5714 3271 5714 3270 5714 3292 5715 3259 5715 3255 5715 3283 5716 3293 5716 3284 5716 3284 5717 3293 5717 3271 5717 3280 5718 3281 5718 3294 5718 3294 5719 3295 5719 3280 5719 3280 5720 3295 5720 3292 5720 3292 5721 3295 5721 3296 5721 3292 5722 3296 5722 3279 5722 3296 5723 3297 5723 3279 5723 3298 5724 3279 5724 3297 5724 3287 5725 3279 5725 3298 5725 3298 5726 3299 5726 3287 5726 3287 5727 3299 5727 3284 5727 3284 5728 3299 5728 3300 5728 3284 5729 3300 5729 3281 5729 3300 5730 3301 5730 3281 5730 3294 5731 3281 5731 3301 5731 3302 5732 3294 5732 3301 5732 3302 5733 3301 5733 3300 5733 3302 5734 3300 5734 3303 5734 3303 5735 3300 5735 3304 5735 3304 5736 3300 5736 3299 5736 3304 5737 3299 5737 3305 5737 3305 5738 3299 5738 3298 5738 3305 5739 3298 5739 3306 5739 3306 5740 3298 5740 3297 5740 3306 5741 3297 5741 3296 5741 3306 5742 3296 5742 3307 5742 3307 5743 3296 5743 3308 5743 3308 5744 3296 5744 3295 5744 3308 5745 3295 5745 3309 5745 3309 5746 3295 5746 3294 5746 3309 5747 3294 5747 3302 5747 3310 5748 3306 5748 3311 5748 3306 5749 3307 5749 3311 5749 3311 5750 3307 5750 3312 5750 3307 5751 3308 5751 3312 5751 3312 5752 3308 5752 3313 5752 3308 5753 3309 5753 3313 5753 3302 5754 3314 5754 3309 5754 3309 5755 3314 5755 3313 5755 3314 5756 3302 5756 3315 5756 3302 5757 3303 5757 3315 5757 3303 5758 3304 5758 3315 5758 3315 5759 3304 5759 3316 5759 3304 5760 3305 5760 3316 5760 3316 5761 3305 5761 3310 5761 3306 5762 3310 5762 3305 5762 3316 5763 3310 5763 3262 5763 3262 5764 3310 5764 3257 5764 3257 5765 3310 5765 3311 5765 3252 5766 3312 5766 3249 5766 3249 5767 3312 5767 3313 5767 3269 5768 3315 5768 3316 5768 3269 5769 3316 5769 3262 5769 3257 5770 3311 5770 3252 5770 3252 5771 3311 5771 3312 5771 3249 5772 3313 5772 3272 5772 3272 5773 3313 5773 3314 5773 3272 5774 3314 5774 3315 5774 3272 5775 3315 5775 3269 5775 3321 5776 3319 5776 3320 5776 3317 5777 3318 5777 3322 5777 3317 5778 3322 5778 3320 5778 3320 5779 3322 5779 3321 5779 3323 5780 3319 5780 3321 5780 3320 5781 3319 5781 3323 5781 3324 5782 3326 5782 3325 5782 3320 5783 3323 5783 3325 5783 3325 5784 3323 5784 3324 5784 3326 5785 3324 5785 3327 5785 3326 5786 3327 5786 3328 5786 3329 5787 3326 5787 3328 5787 3325 5788 3326 5788 3329 5788 3329 5789 3331 5789 3330 5789 3325 5790 3329 5790 3330 5790 3334 5791 3331 5791 3333 5791 3333 5792 3331 5792 3329 5792 3332 5793 3331 5793 3335 5793 3335 5794 3331 5794 3334 5794 3338 5795 3336 5795 3337 5795 3332 5796 3338 5796 3337 5796 3330 5797 3331 5797 3337 5797 3337 5798 3331 5798 3332 5798 3336 5799 3338 5799 3339 5799 3337 5800 3336 5800 3339 5800 3339 5801 3341 5801 3340 5801 3337 5802 3339 5802 3340 5802 3343 5803 3341 5803 3339 5803 3344 5804 3341 5804 3343 5804 3342 5805 3341 5805 3345 5805 3345 5806 3341 5806 3344 5806 3342 5807 3318 5807 3317 5807 3340 5808 3341 5808 3317 5808 3317 5809 3341 5809 3342 5809 3346 5810 3318 5810 3342 5810 3322 5811 3318 5811 3347 5811 3347 5812 3318 5812 3346 5812 3342 5813 3350 5813 3349 5813 3329 5814 3348 5814 3356 5814 3348 5815 3329 5815 3328 5815 3349 5816 3346 5816 3342 5816 3350 5817 3351 5817 3352 5817 3350 5818 3352 5818 3353 5818 3350 5819 3342 5819 3354 5819 3350 5820 3354 5820 3355 5820 3350 5821 3355 5821 3351 5821 3361 5822 3321 5822 3349 5822 3349 5823 3321 5823 3322 5823 3349 5824 3322 5824 3346 5824 3356 5825 3357 5825 3358 5825 3356 5826 3358 5826 3359 5826 3356 5827 3359 5827 3329 5827 3338 5828 3332 5828 3353 5828 3353 5829 3332 5829 3356 5829 3356 5830 3332 5830 3360 5830 3356 5831 3360 5831 3357 5831 3361 5832 3323 5832 3321 5832 3348 5833 3328 5833 3324 5833 3348 5834 3324 5834 3361 5834 3353 5835 3339 5835 3338 5835 3361 5836 3324 5836 3323 5836 3352 5837 3362 5837 3353 5837 3353 5838 3362 5838 3339 5838 3349 5839 3350 5839 3363 5839 3363 5840 3364 5840 3349 5840 3349 5841 3364 5841 3361 5841 3361 5842 3364 5842 3365 5842 3361 5843 3365 5843 3348 5843 3365 5844 3366 5844 3348 5844 3367 5845 3348 5845 3366 5845 3356 5846 3348 5846 3367 5846 3367 5847 3368 5847 3356 5847 3356 5848 3368 5848 3353 5848 3353 5849 3368 5849 3369 5849 3353 5850 3369 5850 3350 5850 3369 5851 3370 5851 3350 5851 3363 5852 3350 5852 3370 5852 3371 5853 3363 5853 3370 5853 3371 5854 3370 5854 3369 5854 3371 5855 3369 5855 3372 5855 3372 5856 3369 5856 3373 5856 3373 5857 3369 5857 3368 5857 3373 5858 3368 5858 3374 5858 3374 5859 3368 5859 3367 5859 3374 5860 3367 5860 3375 5860 3375 5861 3367 5861 3366 5861 3375 5862 3366 5862 3365 5862 3375 5863 3365 5863 3376 5863 3376 5864 3365 5864 3377 5864 3377 5865 3365 5865 3364 5865 3377 5866 3364 5866 3378 5866 3378 5867 3364 5867 3363 5867 3378 5868 3363 5868 3371 5868 3379 5869 3375 5869 3380 5869 3375 5870 3376 5870 3380 5870 3376 5871 3377 5871 3380 5871 3380 5872 3377 5872 3381 5872 3377 5873 3378 5873 3381 5873 3381 5874 3378 5874 3382 5874 3371 5875 3382 5875 3378 5875 3382 5876 3371 5876 3383 5876 3371 5877 3372 5877 3383 5877 3372 5878 3373 5878 3383 5878 3383 5879 3373 5879 3384 5879 3373 5880 3374 5880 3384 5880 3384 5881 3374 5881 3379 5881 3375 5882 3379 5882 3374 5882 3384 5883 3379 5883 3330 5883 3330 5884 3379 5884 3325 5884 3320 5885 3380 5885 3381 5885 3320 5886 3381 5886 3317 5886 3337 5887 3383 5887 3384 5887 3337 5888 3384 5888 3330 5888 3325 5889 3379 5889 3380 5889 3325 5890 3380 5890 3320 5890 3317 5891 3381 5891 3382 5891 3317 5892 3382 5892 3340 5892 3340 5893 3382 5893 3383 5893 3340 5894 3383 5894 3337 5894 3385 5895 3386 5895 3387 5895 3388 5896 3392 5896 3389 5896 3388 5897 3389 5897 3385 5897 3385 5898 3389 5898 3386 5898 3390 5899 3391 5899 3392 5899 3390 5900 3392 5900 3388 5900 3393 5901 3394 5901 3390 5901 3390 5902 3394 5902 3391 5902 3398 5903 3395 5903 3393 5903 3393 5904 3395 5904 3396 5904 3393 5905 3396 5905 3394 5905 3387 5906 3397 5906 3398 5906 3398 5907 3397 5907 3399 5907 3398 5908 3399 5908 3395 5908 3386 5909 3400 5909 3387 5909 3387 5910 3400 5910 3397 5910 3401 5911 3402 5911 3403 5911 3403 5912 3402 5912 3404 5912 3404 5913 3402 5913 3405 5913 3404 5914 3405 5914 3406 5914 3406 5915 3405 5915 3407 5915 3406 5916 3407 5916 3408 5916 3408 5917 3407 5917 3409 5917 3409 5918 3407 5918 3410 5918 3409 5919 3410 5919 3411 5919 3411 5920 3410 5920 3412 5920 3411 5921 3412 5921 3413 5921 3413 5922 3412 5922 3414 5922 3414 5923 3412 5923 3415 5923 3414 5924 3415 5924 3416 5924 3416 5925 3415 5925 3417 5925 3416 5926 3417 5926 3418 5926 3418 5927 3417 5927 3419 5927 3418 5928 3419 5928 3420 5928 3420 5929 3419 5929 3421 5929 3421 5930 3419 5930 3422 5930 3421 5931 3422 5931 3423 5931 3423 5932 3422 5932 3424 5932 3423 5933 3424 5933 3425 5933 3425 5934 3424 5934 3426 5934 3426 5935 3424 5935 3427 5935 3426 5936 3427 5936 3428 5936 3428 5937 3427 5937 3429 5937 3429 5938 3427 5938 3430 5938 3429 5939 3430 5939 3431 5939 3431 5940 3430 5940 3432 5940 3431 5941 3432 5941 3433 5941 3433 5942 3432 5942 3434 5942 3434 5943 3432 5943 3435 5943 3434 5944 3435 5944 3436 5944 3435 5945 3437 5945 3436 5945 3436 5946 3437 5946 3438 5946 3438 5947 3437 5947 3439 5947 3438 5948 3439 5948 3440 5948 3440 5949 3439 5949 3441 5949 3440 5950 3441 5950 3442 5950 3442 5951 3441 5951 3443 5951 3443 5952 3441 5952 3444 5952 3443 5953 3444 5953 3445 5953 3445 5954 3444 5954 3446 5954 3446 5955 3444 5955 3447 5955 3446 5956 3447 5956 3448 5956 3448 5957 3447 5957 3449 5957 3449 5958 3447 5958 3450 5958 3449 5959 3450 5959 3451 5959 3451 5960 3450 5960 3452 5960 3451 5961 3452 5961 3401 5961 3401 5962 3452 5962 3402 5962 3453 5963 3454 5963 3455 5963 3454 5964 3453 5964 3456 5964 3456 5965 3453 5965 3457 5965 3456 5966 3457 5966 3458 5966 3458 5967 3457 5967 3459 5967 3459 5968 3460 5968 3458 5968 3460 5969 3459 5969 3461 5969 3461 5970 3462 5970 3460 5970 3462 5971 3461 5971 3463 5971 3463 5972 3464 5972 3462 5972 3464 5973 3463 5973 3465 5973 3465 5974 3466 5974 3464 5974 3466 5975 3465 5975 3467 5975 3467 5976 3468 5976 3466 5976 3468 5977 3467 5977 3469 5977 3469 5978 3470 5978 3468 5978 3470 5979 3469 5979 3471 5979 3470 5980 3471 5980 3472 5980 3470 5981 3472 5981 3473 5981 3474 5982 3473 5982 3472 5982 3473 5983 3474 5983 3475 5983 3475 5984 3474 5984 3476 5984 3475 5985 3476 5985 3455 5985 3455 5986 3476 5986 3453 5986 3455 5987 3477 5987 3475 5987 3477 5988 3473 5988 3475 5988 3477 5989 3479 5989 3478 5989 3477 5990 3458 5990 3479 5990 3455 5991 3454 5991 3477 5991 3477 5992 3454 5992 3458 5992 3496 5993 3389 5993 3480 5993 3480 5994 3389 5994 3481 5994 3389 5995 3482 5995 3481 5995 3481 5996 3482 5996 3483 5996 3482 5997 3484 5997 3483 5997 3483 5998 3484 5998 3485 5998 3483 5999 3485 5999 3486 5999 3486 6000 3485 6000 3391 6000 3486 6001 3391 6001 3487 6001 3391 6002 3394 6002 3487 6002 3394 6003 3396 6003 3487 6003 3487 6004 3396 6004 3488 6004 3396 6005 3395 6005 3488 6005 3488 6006 3395 6006 3489 6006 3395 6007 3399 6007 3489 6007 3489 6008 3399 6008 3490 6008 3399 6009 3491 6009 3490 6009 3490 6010 3491 6010 3397 6010 3490 6011 3397 6011 3492 6011 3397 6012 3493 6012 3492 6012 3492 6013 3493 6013 3494 6013 3493 6014 3495 6014 3494 6014 3494 6015 3495 6015 3496 6015 3494 6016 3496 6016 3480 6016 3391 6017 3485 6017 3392 6017 3392 6018 3485 6018 3484 6018 3484 6019 3482 6019 3392 6019 3392 6020 3482 6020 3389 6020 3389 6021 3496 6021 3386 6021 3386 6022 3496 6022 3495 6022 3386 6023 3495 6023 3400 6023 3495 6024 3493 6024 3400 6024 3400 6025 3493 6025 3397 6025 3397 6026 3491 6026 3399 6026 3470 6027 3473 6027 3477 6027 3470 6028 3477 6028 3468 6028 3468 6029 3477 6029 3478 6029 3468 6030 3478 6030 3466 6030 3466 6031 3478 6031 3464 6031 3464 6032 3478 6032 3479 6032 3464 6033 3479 6033 3462 6033 3462 6034 3479 6034 3460 6034 3460 6035 3479 6035 3458 6035 3456 6036 3458 6036 3454 6036 3390 6037 3497 6037 3393 6037 3388 6038 3498 6038 3390 6038 3385 6039 3499 6039 3388 6039 3387 6040 3500 6040 3385 6040 3398 6041 3501 6041 3387 6041 3393 6042 3502 6042 3398 6042 3504 6043 3508 6043 3509 6043 3503 6044 3504 6044 3509 6044 3504 6045 3507 6045 3508 6045 3506 6046 3507 6046 3504 6046 3505 6047 3506 6047 3504 6047 3503 6048 3505 6048 3504 6048 3390 6049 3507 6049 3497 6049 3506 6050 3393 6050 3497 6050 3497 6051 3507 6051 3506 6051 3498 6052 3388 6052 3508 6052 3507 6053 3390 6053 3498 6053 3508 6054 3507 6054 3498 6054 3509 6055 3499 6055 3385 6055 3508 6056 3388 6056 3499 6056 3508 6057 3499 6057 3509 6057 3509 6058 3385 6058 3503 6058 3503 6059 3385 6059 3500 6059 3503 6060 3500 6060 3387 6060 3398 6061 3505 6061 3501 6061 3501 6062 3505 6062 3503 6062 3501 6063 3503 6063 3387 6063 3393 6064 3506 6064 3502 6064 3505 6065 3398 6065 3502 6065 3502 6066 3506 6066 3505 6066 3510 6067 3474 6067 3513 6067 3513 6068 3474 6068 3514 6068 3514 6069 3474 6069 3472 6069 3472 6070 3471 6070 3515 6070 3515 6071 3471 6071 3469 6071 3515 6072 3469 6072 3516 6072 3516 6073 3469 6073 3517 6073 3517 6074 3469 6074 3467 6074 3517 6075 3467 6075 3518 6075 3518 6076 3467 6076 3519 6076 3519 6077 3467 6077 3465 6077 3519 6078 3465 6078 3520 6078 3520 6079 3465 6079 3463 6079 3520 6080 3463 6080 3521 6080 3521 6081 3463 6081 3522 6081 3522 6082 3463 6082 3461 6082 3522 6083 3461 6083 3523 6083 3523 6084 3461 6084 3524 6084 3524 6085 3461 6085 3459 6085 3524 6086 3459 6086 3525 6086 3525 6087 3459 6087 3457 6087 3525 6088 3457 6088 3526 6088 3527 6089 3453 6089 3511 6089 3511 6090 3453 6090 3476 6090 3453 6091 3527 6091 3512 6091 3512 6092 3526 6092 3457 6092 3512 6093 3457 6093 3453 6093 3510 6094 3511 6094 3476 6094 3510 6095 3476 6095 3474 6095 3528 6096 3529 6096 3530 6096 3528 6097 3530 6097 3531 6097 3532 6098 3533 6098 3528 6098 3528 6099 3533 6099 3529 6099 3534 6100 3535 6100 3532 6100 3532 6101 3535 6101 3533 6101 3536 6102 3537 6102 3534 6102 3534 6103 3537 6103 3538 6103 3534 6104 3538 6104 3535 6104 3541 6105 3539 6105 3536 6105 3536 6106 3539 6106 3537 6106 3531 6107 3540 6107 3541 6107 3541 6108 3540 6108 3539 6108 3531 6109 3530 6109 3542 6109 3531 6110 3542 6110 3540 6110 3543 6111 3573 6111 3571 6111 3543 6112 3571 6112 3544 6112 3544 6113 3571 6113 3569 6113 3544 6114 3569 6114 3545 6114 3545 6115 3569 6115 3546 6115 3546 6116 3569 6116 3567 6116 3567 6117 3565 6117 3546 6117 3546 6118 3565 6118 3547 6118 3547 6119 3565 6119 3563 6119 3547 6120 3563 6120 3561 6120 3547 6121 3561 6121 3548 6121 3548 6122 3561 6122 3560 6122 3548 6123 3560 6123 3549 6123 3549 6124 3560 6124 3559 6124 3549 6125 3559 6125 3550 6125 3559 6126 3557 6126 3550 6126 3550 6127 3557 6127 3551 6127 3550 6128 3551 6128 3552 6128 3552 6129 3551 6129 3553 6129 3552 6130 3553 6130 3554 6130 3554 6131 3553 6131 3543 6131 3543 6132 3553 6132 3573 6132 3555 6133 3599 6133 3551 6133 3555 6134 3551 6134 3556 6134 3556 6135 3551 6135 3557 6135 3556 6136 3557 6136 3558 6136 3558 6137 3557 6137 3559 6137 3558 6138 3559 6138 3560 6138 3561 6139 3562 6139 3558 6139 3561 6140 3558 6140 3560 6140 3563 6141 3564 6141 3562 6141 3563 6142 3562 6142 3561 6142 3564 6143 3563 6143 3565 6143 3565 6144 3566 6144 3564 6144 3566 6145 3565 6145 3567 6145 3567 6146 3568 6146 3566 6146 3568 6147 3567 6147 3569 6147 3569 6148 3570 6148 3568 6148 3570 6149 3569 6149 3571 6149 3571 6150 3572 6150 3570 6150 3572 6151 3571 6151 3573 6151 3572 6152 3573 6152 3553 6152 3572 6153 3553 6153 3574 6153 3574 6154 3553 6154 3555 6154 3555 6155 3553 6155 3599 6155 3555 6156 3575 6156 3574 6156 3572 6157 3574 6157 3575 6157 3575 6158 3576 6158 3572 6158 3566 6159 3576 6159 3575 6159 3575 6160 3564 6160 3566 6160 3555 6161 3556 6161 3575 6161 3552 6162 3577 6162 3550 6162 3550 6163 3577 6163 3578 6163 3550 6164 3578 6164 3549 6164 3578 6165 3535 6165 3549 6165 3535 6166 3579 6166 3549 6166 3549 6167 3579 6167 3548 6167 3579 6168 3538 6168 3548 6168 3548 6169 3538 6169 3547 6169 3538 6170 3580 6170 3547 6170 3547 6171 3580 6171 3581 6171 3547 6172 3581 6172 3546 6172 3546 6173 3581 6173 3582 6173 3546 6174 3582 6174 3545 6174 3582 6175 3583 6175 3545 6175 3545 6176 3583 6176 3544 6176 3544 6177 3583 6177 3584 6177 3544 6178 3584 6178 3543 6178 3543 6179 3584 6179 3530 6179 3543 6180 3530 6180 3554 6180 3554 6181 3530 6181 3585 6181 3554 6182 3585 6182 3552 6182 3552 6183 3585 6183 3577 6183 3537 6184 3581 6184 3580 6184 3537 6185 3580 6185 3538 6185 3538 6186 3579 6186 3535 6186 3535 6187 3578 6187 3533 6187 3533 6188 3578 6188 3577 6188 3533 6189 3577 6189 3529 6189 3529 6190 3577 6190 3585 6190 3529 6191 3585 6191 3530 6191 3530 6192 3584 6192 3542 6192 3542 6193 3584 6193 3583 6193 3542 6194 3583 6194 3540 6194 3540 6195 3583 6195 3539 6195 3583 6196 3582 6196 3539 6196 3539 6197 3582 6197 3581 6197 3539 6198 3581 6198 3537 6198 3572 6199 3576 6199 3570 6199 3570 6200 3576 6200 3568 6200 3568 6201 3576 6201 3566 6201 3562 6202 3564 6202 3575 6202 3562 6203 3575 6203 3558 6203 3558 6204 3575 6204 3556 6204 3534 6205 3586 6205 3536 6205 3532 6206 3587 6206 3534 6206 3528 6207 3588 6207 3532 6207 3531 6208 3589 6208 3528 6208 3541 6209 3590 6209 3531 6209 3536 6210 3591 6210 3541 6210 3593 6211 3597 6211 3598 6211 3592 6212 3593 6212 3598 6212 3593 6213 3596 6213 3597 6213 3595 6214 3596 6214 3593 6214 3594 6215 3595 6215 3593 6215 3592 6216 3594 6216 3593 6216 3534 6217 3596 6217 3586 6217 3595 6218 3536 6218 3586 6218 3586 6219 3596 6219 3595 6219 3587 6220 3532 6220 3597 6220 3596 6221 3534 6221 3587 6221 3597 6222 3596 6222 3587 6222 3598 6223 3588 6223 3528 6223 3597 6224 3532 6224 3588 6224 3597 6225 3588 6225 3598 6225 3598 6226 3528 6226 3592 6226 3592 6227 3528 6227 3589 6227 3592 6228 3589 6228 3531 6228 3541 6229 3594 6229 3590 6229 3590 6230 3594 6230 3592 6230 3590 6231 3592 6231 3531 6231 3536 6232 3595 6232 3591 6232 3594 6233 3541 6233 3591 6233 3591 6234 3595 6234 3594 6234 3551 6235 3599 6235 3553 6235 3605 6236 3602 6236 3603 6236 3600 6237 3601 6237 3604 6237 3604 6238 3605 6238 3603 6238 3600 6239 3604 6239 3603 6239 3606 6240 3602 6240 3605 6240 3609 6241 3607 6241 3608 6241 3603 6242 3602 6242 3606 6242 3606 6243 3609 6243 3608 6243 3603 6244 3606 6244 3608 6244 3609 6245 3610 6245 3607 6245 3611 6246 3607 6246 3610 6246 3608 6247 3607 6247 3611 6247 3612 6248 3614 6248 3613 6248 3608 6249 3611 6249 3612 6249 3608 6250 3612 6250 3613 6250 3617 6251 3614 6251 3616 6251 3616 6252 3614 6252 3612 6252 3615 6253 3614 6253 3618 6253 3618 6254 3614 6254 3617 6254 3621 6255 3619 6255 3620 6255 3615 6256 3621 6256 3620 6256 3613 6257 3614 6257 3620 6257 3620 6258 3614 6258 3615 6258 3619 6259 3621 6259 3622 6259 3620 6260 3619 6260 3622 6260 3622 6261 3624 6261 3623 6261 3620 6262 3622 6262 3623 6262 3627 6263 3624 6263 3622 6263 3628 6264 3624 6264 3627 6264 3628 6265 3625 6265 3624 6265 3629 6266 3601 6266 3600 6266 3623 6267 3624 6267 3625 6267 3626 6268 3629 6268 3600 6268 3623 6269 3625 6269 3600 6269 3600 6270 3625 6270 3626 6270 3604 6271 3601 6271 3629 6271 3626 6272 3632 6272 3631 6272 3612 6273 3630 6273 3638 6273 3630 6274 3612 6274 3611 6274 3631 6275 3604 6275 3629 6275 3631 6276 3629 6276 3626 6276 3632 6277 3633 6277 3634 6277 3632 6278 3634 6278 3635 6278 3632 6279 3626 6279 3636 6279 3632 6280 3636 6280 3637 6280 3632 6281 3637 6281 3633 6281 3643 6282 3604 6282 3631 6282 3643 6283 3605 6283 3604 6283 3638 6284 3639 6284 3640 6284 3638 6285 3640 6285 3641 6285 3638 6286 3641 6286 3612 6286 3621 6287 3615 6287 3635 6287 3635 6288 3615 6288 3638 6288 3638 6289 3615 6289 3642 6289 3638 6290 3642 6290 3639 6290 3643 6291 3606 6291 3605 6291 3630 6292 3611 6292 3610 6292 3630 6293 3610 6293 3643 6293 3635 6294 3622 6294 3621 6294 3643 6295 3610 6295 3606 6295 3634 6296 3644 6296 3635 6296 3635 6297 3644 6297 3622 6297 3631 6298 3632 6298 3645 6298 3645 6299 3646 6299 3631 6299 3631 6300 3646 6300 3643 6300 3643 6301 3646 6301 3647 6301 3643 6302 3647 6302 3630 6302 3647 6303 3648 6303 3630 6303 3649 6304 3630 6304 3648 6304 3638 6305 3630 6305 3649 6305 3649 6306 3650 6306 3638 6306 3638 6307 3650 6307 3635 6307 3635 6308 3650 6308 3651 6308 3635 6309 3651 6309 3632 6309 3651 6310 3652 6310 3632 6310 3645 6311 3632 6311 3652 6311 3653 6312 3645 6312 3652 6312 3653 6313 3652 6313 3651 6313 3653 6314 3651 6314 3654 6314 3654 6315 3651 6315 3655 6315 3655 6316 3651 6316 3650 6316 3655 6317 3650 6317 3656 6317 3656 6318 3650 6318 3649 6318 3656 6319 3649 6319 3657 6319 3657 6320 3649 6320 3648 6320 3657 6321 3648 6321 3647 6321 3657 6322 3647 6322 3658 6322 3658 6323 3647 6323 3659 6323 3659 6324 3647 6324 3646 6324 3659 6325 3646 6325 3660 6325 3660 6326 3646 6326 3645 6326 3660 6327 3645 6327 3653 6327 3661 6328 3657 6328 3662 6328 3657 6329 3658 6329 3662 6329 3658 6330 3659 6330 3662 6330 3662 6331 3659 6331 3663 6331 3659 6332 3660 6332 3663 6332 3663 6333 3660 6333 3664 6333 3653 6334 3664 6334 3660 6334 3664 6335 3653 6335 3665 6335 3653 6336 3654 6336 3665 6336 3654 6337 3655 6337 3665 6337 3665 6338 3655 6338 3666 6338 3655 6339 3656 6339 3666 6339 3666 6340 3656 6340 3661 6340 3657 6341 3661 6341 3656 6341 3666 6342 3661 6342 3613 6342 3613 6343 3661 6343 3608 6343 3603 6344 3662 6344 3663 6344 3603 6345 3663 6345 3600 6345 3620 6346 3665 6346 3666 6346 3620 6347 3666 6347 3613 6347 3608 6348 3661 6348 3662 6348 3608 6349 3662 6349 3603 6349 3600 6350 3663 6350 3664 6350 3600 6351 3664 6351 3623 6351 3623 6352 3664 6352 3665 6352 3623 6353 3665 6353 3620 6353 3667 6354 3680 6354 3668 6354 3667 6355 3668 6355 3669 6355 3669 6356 3668 6356 3670 6356 3669 6357 3670 6357 3671 6357 3671 6358 3670 6358 3672 6358 3671 6359 3672 6359 3673 6359 3673 6360 3672 6360 3674 6360 3673 6361 3674 6361 3675 6361 3673 6362 3675 6362 3676 6362 3676 6363 3675 6363 3677 6363 3676 6364 3677 6364 3678 6364 3678 6365 3677 6365 3679 6365 3678 6366 3679 6366 3667 6366 3667 6367 3679 6367 3680 6367 3681 6368 3682 6368 3683 6368 3683 6369 3682 6369 3684 6369 3684 6370 3682 6370 3685 6370 3686 6371 3687 6371 3688 6371 3688 6372 3687 6372 3689 6372 3688 6373 3689 6373 3690 6373 3690 6374 3689 6374 3691 6374 3691 6375 3689 6375 3692 6375 3691 6376 3692 6376 3693 6376 3693 6377 3692 6377 3681 6377 3681 6378 3692 6378 3682 6378 3684 6379 3685 6379 3694 6379 3694 6380 3685 6380 3695 6380 3694 6381 3695 6381 3696 6381 3696 6382 3695 6382 3697 6382 3696 6383 3697 6383 3698 6383 3698 6384 3697 6384 3699 6384 3698 6385 3699 6385 3700 6385 3700 6386 3699 6386 3686 6386 3686 6387 3699 6387 3687 6387 3702 6388 3701 6388 3704 6388 3702 6389 3704 6389 3703 6389 3703 6390 3704 6390 3706 6390 3703 6391 3706 6391 3705 6391 3705 6392 3706 6392 3707 6392 3705 6393 3707 6393 3708 6393 3708 6394 3707 6394 3709 6394 3708 6395 3709 6395 3710 6395 3710 6396 3709 6396 3711 6396 3710 6397 3711 6397 3712 6397 3713 6398 3714 6398 3712 6398 3713 6399 3712 6399 3711 6399 3715 6400 3714 6400 3713 6400 3714 6401 3715 6401 3717 6401 3714 6402 3717 6402 3716 6402 3716 6403 3717 6403 3718 6403 3716 6404 3718 6404 3719 6404 3719 6405 3718 6405 3720 6405 3719 6406 3720 6406 3702 6406 3702 6407 3720 6407 3701 6407 3721 6408 3722 6408 3723 6408 3723 6409 3724 6409 3721 6409 3726 6410 3725 6410 3723 6410 3722 6411 3726 6411 3723 6411 3727 6412 3700 6412 3686 6412 3727 6413 3686 6413 3728 6413 3728 6414 3686 6414 3688 6414 3728 6415 3688 6415 3729 6415 3729 6416 3688 6416 3690 6416 3729 6417 3690 6417 3730 6417 3730 6418 3690 6418 3691 6418 3730 6419 3691 6419 3731 6419 3731 6420 3691 6420 3693 6420 3731 6421 3693 6421 3732 6421 3732 6422 3693 6422 3681 6422 3732 6423 3681 6423 3733 6423 3733 6424 3681 6424 3683 6424 3733 6425 3683 6425 3734 6425 3734 6426 3683 6426 3684 6426 3734 6427 3684 6427 3735 6427 3735 6428 3684 6428 3694 6428 3735 6429 3694 6429 3736 6429 3736 6430 3694 6430 3696 6430 3736 6431 3696 6431 3737 6431 3737 6432 3696 6432 3738 6432 3738 6433 3696 6433 3698 6433 3738 6434 3698 6434 3727 6434 3727 6435 3698 6435 3700 6435 3733 6436 3677 6436 3732 6436 3732 6437 3677 6437 3731 6437 3731 6438 3677 6438 3675 6438 3731 6439 3675 6439 3730 6439 3730 6440 3675 6440 3674 6440 3730 6441 3674 6441 3729 6441 3729 6442 3674 6442 3728 6442 3728 6443 3674 6443 3672 6443 3728 6444 3672 6444 3727 6444 3727 6445 3672 6445 3670 6445 3727 6446 3670 6446 3738 6446 3738 6447 3670 6447 3668 6447 3738 6448 3668 6448 3737 6448 3737 6449 3668 6449 3736 6449 3736 6450 3668 6450 3680 6450 3736 6451 3680 6451 3735 6451 3735 6452 3680 6452 3734 6452 3734 6453 3680 6453 3679 6453 3734 6454 3679 6454 3733 6454 3733 6455 3679 6455 3677 6455 3702 6456 3721 6456 3719 6456 3719 6457 3721 6457 3724 6457 3719 6458 3724 6458 3716 6458 3716 6459 3724 6459 3723 6459 3716 6460 3723 6460 3714 6460 3714 6461 3723 6461 3712 6461 3712 6462 3723 6462 3725 6462 3712 6463 3725 6463 3710 6463 3710 6464 3725 6464 3708 6464 3708 6465 3725 6465 3726 6465 3708 6466 3726 6466 3705 6466 3705 6467 3726 6467 3722 6467 3705 6468 3722 6468 3703 6468 3703 6469 3722 6469 3702 6469 3702 6470 3722 6470 3721 6470 3667 6471 3739 6471 3678 6471 3669 6472 3740 6472 3667 6472 3671 6473 3741 6473 3669 6473 3673 6474 3742 6474 3671 6474 3676 6475 3743 6475 3673 6475 3678 6476 3744 6476 3676 6476 3748 6477 3749 6477 3746 6477 3748 6478 3746 6478 3747 6478 3747 6479 3746 6479 3745 6479 3750 6480 3745 6480 3746 6480 3751 6481 3750 6481 3746 6481 3752 6482 3751 6482 3746 6482 3746 6483 3749 6483 3752 6483 3750 6484 3678 6484 3739 6484 3750 6485 3739 6485 3745 6485 3667 6486 3745 6486 3739 6486 3747 6487 3740 6487 3748 6487 3748 6488 3740 6488 3669 6488 3745 6489 3667 6489 3740 6489 3740 6490 3747 6490 3745 6490 3741 6491 3671 6491 3749 6491 3741 6492 3748 6492 3669 6492 3741 6493 3749 6493 3748 6493 3673 6494 3752 6494 3742 6494 3749 6495 3671 6495 3742 6495 3749 6496 3742 6496 3752 6496 3676 6497 3751 6497 3743 6497 3752 6498 3673 6498 3743 6498 3752 6499 3743 6499 3751 6499 3678 6500 3750 6500 3744 6500 3751 6501 3676 6501 3744 6501 3751 6502 3744 6502 3750 6502 3689 6503 3687 6503 3753 6503 3697 6504 3701 6504 3699 6504 3689 6505 3713 6505 3692 6505 3692 6506 3713 6506 3711 6506 3692 6507 3711 6507 3682 6507 3682 6508 3711 6508 3709 6508 3682 6509 3709 6509 3685 6509 3697 6510 3704 6510 3701 6510 3699 6511 3701 6511 3720 6511 3697 6512 3695 6512 3704 6512 3695 6513 3706 6513 3704 6513 3695 6514 3685 6514 3707 6514 3695 6515 3707 6515 3706 6515 3685 6516 3709 6516 3707 6516 3689 6517 3715 6517 3713 6517 3689 6518 3717 6518 3715 6518 3689 6519 3753 6519 3717 6519 3753 6520 3718 6520 3717 6520 3753 6521 3687 6521 3718 6521 3687 6522 3699 6522 3720 6522 3687 6523 3720 6523 3718 6523 3755 6524 3754 6524 3756 6524 3755 6525 3756 6525 3757 6525 3757 6526 3756 6526 3758 6526 3757 6527 3758 6527 3759 6527 3759 6528 3758 6528 3760 6528 3759 6529 3760 6529 3761 6529 3761 6530 3760 6530 3762 6530 3761 6531 3762 6531 3763 6531 3763 6532 3762 6532 3764 6532 3763 6533 3764 6533 3765 6533 3765 6534 3764 6534 3766 6534 3765 6535 3766 6535 3767 6535 3767 6536 3766 6536 3768 6536 3767 6537 3768 6537 3769 6537 3769 6538 3768 6538 3770 6538 3769 6539 3770 6539 3771 6539 3771 6540 3770 6540 3772 6540 3771 6541 3772 6541 3773 6541 3773 6542 3772 6542 3754 6542 3773 6543 3754 6543 3755 6543 3774 324 3754 324 3772 324 3774 324 3772 324 3775 324 3776 324 3756 324 3774 324 3774 324 3756 324 3754 324 3777 324 3762 324 3778 324 3778 324 3762 324 3760 324 3778 324 3760 324 3779 324 3775 324 3772 324 3780 324 3781 324 3764 324 3777 324 3777 324 3764 324 3762 324 3782 324 3766 324 3764 324 3782 324 3764 324 3781 324 3779 324 3760 324 3758 324 3779 324 3758 324 3776 324 3776 324 3758 324 3756 324 3772 324 3770 324 3780 324 3780 324 3770 324 3783 324 3783 324 3770 324 3768 324 3783 324 3768 324 3766 324 3783 324 3766 324 3782 324 3784 6544 3785 6544 3786 6544 3786 6545 3785 6545 3787 6545 3786 6546 3787 6546 3788 6546 3788 6547 3787 6547 3789 6547 3788 6548 3789 6548 3790 6548 3790 6549 3789 6549 3791 6549 3790 6550 3791 6550 3792 6550 3792 6551 3791 6551 3793 6551 3793 6552 3791 6552 3794 6552 3793 6553 3794 6553 3795 6553 3795 6554 3794 6554 3796 6554 3795 6555 3796 6555 3797 6555 3795 6556 3797 6556 3798 6556 3798 6557 3797 6557 3799 6557 3799 6558 3797 6558 3800 6558 3799 6559 3800 6559 3801 6559 3801 6560 3800 6560 3802 6560 3801 6561 3802 6561 3803 6561 3801 6562 3803 6562 3804 6562 3804 6563 3803 6563 3805 6563 3804 6564 3805 6564 3806 6564 3806 6565 3805 6565 3807 6565 3806 6566 3807 6566 3808 6566 3808 6567 3807 6567 3809 6567 3808 6568 3809 6568 3810 6568 3810 6569 3809 6569 3811 6569 3810 6570 3811 6570 3812 6570 3812 6571 3811 6571 3813 6571 3812 6572 3813 6572 3814 6572 3814 6573 3813 6573 3815 6573 3814 6574 3815 6574 3816 6574 3816 6575 3815 6575 3817 6575 3816 6576 3817 6576 3784 6576 3784 6577 3817 6577 3785 6577 3818 348 3802 348 3819 348 3819 348 3802 348 3800 348 3819 348 3800 348 3820 348 3821 348 3815 348 3822 348 3822 348 3815 348 3813 348 3822 348 3813 348 3823 348 3824 348 3794 348 3791 348 3824 348 3791 348 3825 348 3813 348 3811 348 3823 348 3823 348 3811 348 3809 348 3823 348 3809 348 3807 348 3823 348 3807 348 3826 348 3820 348 3800 348 3797 348 3820 348 3797 348 3824 348 3824 348 3797 348 3796 348 3824 348 3796 348 3794 348 3826 348 3807 348 3805 348 3826 348 3805 348 3818 348 3818 348 3805 348 3803 348 3818 348 3803 348 3802 348 3825 348 3791 348 3789 348 3825 348 3789 348 3827 348 3827 348 3789 348 3787 348 3827 348 3787 348 3785 348 3827 348 3785 348 3821 348 3821 348 3785 348 3817 348 3821 348 3817 348 3815 348 3767 324 3798 324 3799 324 3767 324 3799 324 3765 324 3765 324 3799 324 3801 324 3769 324 3793 324 3795 324 3769 324 3795 324 3767 324 3767 324 3795 324 3798 324 3761 324 3808 324 3810 324 3761 324 3810 324 3759 324 3759 324 3810 324 3812 324 3759 324 3812 324 3757 324 3765 324 3801 324 3804 324 3765 324 3804 324 3763 324 3763 324 3804 324 3806 324 3763 324 3806 324 3761 324 3761 324 3806 324 3808 324 3773 324 3788 324 3771 324 3771 324 3788 324 3790 324 3771 324 3790 324 3792 324 3771 324 3792 324 3769 324 3769 324 3792 324 3793 324 3757 324 3812 324 3814 324 3757 324 3814 324 3816 324 3757 324 3816 324 3755 324 3755 324 3816 324 3784 324 3755 324 3784 324 3786 324 3755 324 3786 324 3773 324 3773 324 3786 324 3788 324 3828 6578 3819 6578 3829 6578 3829 6579 3819 6579 3820 6579 3829 6580 3820 6580 3830 6580 3830 6581 3820 6581 3824 6581 3830 6582 3824 6582 3831 6582 3831 6583 3824 6583 3825 6583 3831 6584 3825 6584 3827 6584 3831 6585 3827 6585 3832 6585 3832 6586 3827 6586 3833 6586 3833 6587 3827 6587 3821 6587 3833 6588 3821 6588 3834 6588 3834 6589 3821 6589 3822 6589 3834 6590 3822 6590 3835 6590 3835 6591 3822 6591 3823 6591 3835 6592 3823 6592 3836 6592 3836 6593 3823 6593 3826 6593 3836 6594 3826 6594 3837 6594 3837 6595 3826 6595 3818 6595 3837 6596 3818 6596 3828 6596 3828 6597 3818 6597 3819 6597 3838 348 3837 348 3839 348 3839 348 3837 348 3828 348 3839 348 3828 348 3840 348 3841 348 3836 348 3837 348 3841 348 3837 348 3838 348 3828 348 3829 348 3840 348 3840 348 3829 348 3842 348 3842 348 3829 348 3830 348 3843 348 3835 348 3836 348 3843 348 3836 348 3841 348 3844 348 3832 348 3845 348 3845 348 3832 348 3833 348 3846 348 3831 348 3844 348 3844 348 3831 348 3832 348 3845 348 3833 348 3834 348 3845 348 3834 348 3847 348 3847 348 3834 348 3843 348 3843 348 3834 348 3835 348 3842 348 3830 348 3846 348 3846 348 3830 348 3831 348 3781 6598 3839 6598 3782 6598 3782 6599 3839 6599 3840 6599 3782 6600 3840 6600 3783 6600 3783 6601 3840 6601 3842 6601 3783 6602 3842 6602 3780 6602 3780 6603 3842 6603 3846 6603 3780 6604 3846 6604 3775 6604 3775 6605 3846 6605 3844 6605 3775 6606 3844 6606 3774 6606 3774 6607 3844 6607 3845 6607 3774 6608 3845 6608 3776 6608 3776 6609 3845 6609 3847 6609 3776 6610 3847 6610 3779 6610 3779 6611 3847 6611 3843 6611 3779 6612 3843 6612 3778 6612 3778 6613 3843 6613 3841 6613 3778 6614 3841 6614 3777 6614 3777 6615 3841 6615 3838 6615 3777 6616 3838 6616 3781 6616 3781 6617 3838 6617 3839 6617 3848 6618 3849 6618 3850 6618 3849 6619 3851 6619 3850 6619 3850 6620 3851 6620 3852 6620 3852 6621 3851 6621 3853 6621 3852 6622 3853 6622 3854 6622 3854 6623 3853 6623 3855 6623 3854 6624 3855 6624 3856 6624 3856 6625 3855 6625 3857 6625 3856 6626 3857 6626 3858 6626 3856 6627 3858 6627 3859 6627 3859 6628 3858 6628 3860 6628 3859 6629 3860 6629 3861 6629 3861 6630 3860 6630 3862 6630 3861 6631 3862 6631 3848 6631 3848 6632 3862 6632 3849 6632 3879 6633 3880 6633 3863 6633 3863 6634 3880 6634 3864 6634 3863 6635 3864 6635 3865 6635 3864 6636 3866 6636 3865 6636 3865 6637 3866 6637 3867 6637 3867 6638 3866 6638 3868 6638 3868 6639 3866 6639 3869 6639 3868 6640 3869 6640 3870 6640 3870 6641 3869 6641 3871 6641 3869 6642 3872 6642 3871 6642 3871 6643 3872 6643 3873 6643 3873 6644 3872 6644 3874 6644 3874 6645 3872 6645 3875 6645 3874 6646 3875 6646 3876 6646 3876 6647 3875 6647 3877 6647 3876 6648 3877 6648 3878 6648 3878 6649 3877 6649 3879 6649 3879 6650 3877 6650 3880 6650 3882 6651 3881 6651 3883 6651 3884 6652 3883 6652 3926 6652 3926 6653 3883 6653 3881 6653 3883 6654 3884 6654 3885 6654 3886 6655 3885 6655 3884 6655 3885 6656 3886 6656 3888 6656 3885 6657 3888 6657 3887 6657 3887 6658 3888 6658 3890 6658 3887 6659 3890 6659 3889 6659 3889 6660 3890 6660 3891 6660 3889 6661 3891 6661 3892 6661 3893 6662 3894 6662 3891 6662 3891 6663 3894 6663 3892 6663 3894 6664 3893 6664 3895 6664 3895 6665 3893 6665 3896 6665 3895 6666 3896 6666 3897 6666 3895 6667 3897 6667 3898 6667 3898 6668 3897 6668 3927 6668 3898 6669 3927 6669 3899 6669 3898 6670 3899 6670 3882 6670 3882 6671 3899 6671 3881 6671 3902 6672 3900 6672 3901 6672 3904 6673 3903 6673 3901 6673 3900 6674 3905 6674 3901 6674 3901 6675 3905 6675 3904 6675 3878 6676 3906 6676 3876 6676 3876 6677 3906 6677 3907 6677 3876 6678 3907 6678 3874 6678 3874 6679 3907 6679 3873 6679 3873 6680 3907 6680 3908 6680 3873 6681 3908 6681 3871 6681 3871 6682 3908 6682 3909 6682 3871 6683 3909 6683 3870 6683 3870 6684 3909 6684 3868 6684 3868 6685 3909 6685 3910 6685 3868 6686 3910 6686 3867 6686 3867 6687 3910 6687 3911 6687 3867 6688 3911 6688 3865 6688 3865 6689 3911 6689 3912 6689 3865 6690 3912 6690 3863 6690 3863 6691 3912 6691 3913 6691 3863 6692 3913 6692 3879 6692 3879 6693 3913 6693 3914 6693 3879 6694 3914 6694 3878 6694 3878 6695 3914 6695 3906 6695 3857 6696 3910 6696 3909 6696 3857 6697 3909 6697 3858 6697 3909 6698 3908 6698 3858 6698 3858 6699 3908 6699 3860 6699 3860 6700 3908 6700 3907 6700 3860 6701 3907 6701 3862 6701 3907 6702 3906 6702 3862 6702 3862 6703 3906 6703 3849 6703 3906 6704 3914 6704 3849 6704 3849 6705 3914 6705 3851 6705 3914 6706 3913 6706 3851 6706 3851 6707 3913 6707 3853 6707 3913 6708 3912 6708 3853 6708 3853 6709 3912 6709 3855 6709 3912 6710 3911 6710 3855 6710 3855 6711 3911 6711 3910 6711 3855 6712 3910 6712 3857 6712 3882 6713 3902 6713 3898 6713 3898 6714 3902 6714 3901 6714 3898 6715 3901 6715 3895 6715 3895 6716 3901 6716 3903 6716 3895 6717 3903 6717 3894 6717 3894 6718 3903 6718 3892 6718 3892 6719 3903 6719 3904 6719 3892 6720 3904 6720 3889 6720 3889 6721 3904 6721 3887 6721 3887 6722 3904 6722 3905 6722 3887 6723 3905 6723 3885 6723 3885 6724 3905 6724 3900 6724 3885 6725 3900 6725 3883 6725 3883 6726 3900 6726 3882 6726 3882 6727 3900 6727 3902 6727 3859 6728 3915 6728 3856 6728 3861 6729 3916 6729 3859 6729 3856 6730 3917 6730 3854 6730 3918 6731 3920 6731 3919 6731 3918 6732 3919 6732 3921 6732 3921 6733 3919 6733 3922 6733 3922 6734 3919 6734 3923 6734 3919 6735 3924 6735 3923 6735 3924 6736 3919 6736 3920 6736 3859 6737 3921 6737 3915 6737 3915 6738 3921 6738 3922 6738 3922 6739 3856 6739 3915 6739 3861 6740 3918 6740 3916 6740 3916 6741 3918 6741 3921 6741 3921 6742 3859 6742 3916 6742 3918 6743 3861 6743 3848 6743 3918 6744 3848 6744 3920 6744 3850 6745 3920 6745 3848 6745 3852 6746 3924 6746 3850 6746 3850 6747 3924 6747 3920 6747 3854 6748 3923 6748 3852 6748 3924 6749 3852 6749 3923 6749 3856 6750 3922 6750 3917 6750 3917 6751 3922 6751 3923 6751 3923 6752 3854 6752 3917 6752 3869 6753 3866 6753 3891 6753 3875 6754 3925 6754 3877 6754 3877 6755 3925 6755 3880 6755 3925 6756 3926 6756 3881 6756 3925 6757 3881 6757 3899 6757 3925 6758 3899 6758 3880 6758 3925 6759 3875 6759 3926 6759 3926 6760 3875 6760 3884 6760 3875 6761 3872 6761 3886 6761 3875 6762 3886 6762 3884 6762 3872 6763 3888 6763 3886 6763 3872 6764 3869 6764 3888 6764 3869 6765 3890 6765 3888 6765 3869 6766 3891 6766 3890 6766 3866 6767 3893 6767 3891 6767 3866 6768 3864 6768 3896 6768 3866 6769 3896 6769 3893 6769 3896 6770 3864 6770 3897 6770 3880 6771 3927 6771 3864 6771 3864 6772 3927 6772 3897 6772 3927 6773 3880 6773 3899 6773 3928 6774 3929 6774 3930 6774 3930 6775 3929 6775 3931 6775 3930 6776 3931 6776 3932 6776 3930 6777 3932 6777 3933 6777 3933 6778 3932 6778 3934 6778 3933 6779 3934 6779 3935 6779 3935 6780 3934 6780 3936 6780 3935 6781 3936 6781 3937 6781 3935 6782 3937 6782 3938 6782 3938 6783 3937 6783 3939 6783 3938 6784 3939 6784 3940 6784 3938 6785 3940 6785 3941 6785 3941 6786 3940 6786 3942 6786 3941 6787 3942 6787 3928 6787 3928 6788 3942 6788 3929 6788 3943 6789 3955 6789 3944 6789 3943 6790 3944 6790 3945 6790 3945 6791 3944 6791 3946 6791 3945 6792 3946 6792 3947 6792 3948 6793 3949 6793 3950 6793 3950 6794 3949 6794 3951 6794 3950 6795 3951 6795 3952 6795 3952 6796 3951 6796 3953 6796 3952 6797 3953 6797 3954 6797 3954 6798 3953 6798 3955 6798 3954 6799 3955 6799 3943 6799 3947 6800 3946 6800 3956 6800 3947 6801 3956 6801 3957 6801 3957 6802 3956 6802 3958 6802 3957 6803 3958 6803 3959 6803 3959 6804 3958 6804 3960 6804 3959 6805 3960 6805 3961 6805 3961 6806 3960 6806 3962 6806 3961 6807 3962 6807 3948 6807 3948 6808 3962 6808 3949 6808 3964 6809 3963 6809 3965 6809 3966 6810 3965 6810 3963 6810 3965 6811 3966 6811 3967 6811 4013 6812 3967 6812 3966 6812 3967 6813 4013 6813 3968 6813 3967 6814 3968 6814 3969 6814 3969 6815 3968 6815 3970 6815 3969 6816 3970 6816 3971 6816 3971 6817 3970 6817 3972 6817 3971 6818 3972 6818 3973 6818 3974 6819 3975 6819 3973 6819 3974 6820 3973 6820 3972 6820 3976 6821 3975 6821 3974 6821 3975 6822 3976 6822 3978 6822 3975 6823 3978 6823 3977 6823 3977 6824 3978 6824 3979 6824 3977 6825 3979 6825 3980 6825 3980 6826 3979 6826 4012 6826 3980 6827 4012 6827 3964 6827 3964 6828 4012 6828 3963 6828 3982 6829 3983 6829 3981 6829 3982 6830 3985 6830 3984 6830 3982 6831 3986 6831 3985 6831 3981 6832 3986 6832 3982 6832 3987 6833 3961 6833 3988 6833 3988 6834 3961 6834 3948 6834 3988 6835 3948 6835 3989 6835 3989 6836 3948 6836 3950 6836 3989 6837 3950 6837 3990 6837 3990 6838 3950 6838 3952 6838 3990 6839 3952 6839 3991 6839 3991 6840 3952 6840 3954 6840 3991 6841 3954 6841 3992 6841 3992 6842 3954 6842 3943 6842 3992 6843 3943 6843 3993 6843 3993 6844 3943 6844 3945 6844 3993 6845 3945 6845 3994 6845 3994 6846 3945 6846 3947 6846 3994 6847 3947 6847 3995 6847 3995 6848 3947 6848 3957 6848 3995 6849 3957 6849 3996 6849 3996 6850 3957 6850 3959 6850 3996 6851 3959 6851 3997 6851 3997 6852 3959 6852 3987 6852 3987 6853 3959 6853 3961 6853 3993 6854 3940 6854 3992 6854 3992 6855 3940 6855 3939 6855 3992 6856 3939 6856 3991 6856 3991 6857 3939 6857 3990 6857 3990 6858 3939 6858 3937 6858 3990 6859 3937 6859 3989 6859 3989 6860 3937 6860 3936 6860 3989 6861 3936 6861 3988 6861 3988 6862 3936 6862 3934 6862 3988 6863 3934 6863 3987 6863 3987 6864 3934 6864 3932 6864 3987 6865 3932 6865 3997 6865 3997 6866 3932 6866 3931 6866 3997 6867 3931 6867 3996 6867 3996 6868 3931 6868 3929 6868 3996 6869 3929 6869 3995 6869 3995 6870 3929 6870 3942 6870 3995 6871 3942 6871 3994 6871 3994 6872 3942 6872 3940 6872 3994 6873 3940 6873 3993 6873 3964 6874 3981 6874 3980 6874 3980 6875 3981 6875 3983 6875 3980 6876 3983 6876 3977 6876 3977 6877 3983 6877 3982 6877 3977 6878 3982 6878 3975 6878 3975 6879 3982 6879 3984 6879 3975 6880 3984 6880 3973 6880 3973 6881 3984 6881 3971 6881 3971 6882 3984 6882 3985 6882 3971 6883 3985 6883 3969 6883 3969 6884 3985 6884 3986 6884 3969 6885 3986 6885 3967 6885 3967 6886 3986 6886 3965 6886 3965 6887 3986 6887 3981 6887 3965 6888 3981 6888 3964 6888 3928 6889 3998 6889 3941 6889 3930 6890 3999 6890 3928 6890 3933 6891 4000 6891 3930 6891 3935 6892 4001 6892 3933 6892 3938 6893 4002 6893 3935 6893 3941 6894 4003 6894 3938 6894 4007 6895 4008 6895 4005 6895 4007 6896 4005 6896 4006 6896 4006 6897 4005 6897 4004 6897 4009 6898 4004 6898 4005 6898 4010 6899 4009 6899 4005 6899 4011 6900 4010 6900 4005 6900 4005 6901 4008 6901 4011 6901 4009 6902 3941 6902 3998 6902 4009 6903 3998 6903 4004 6903 3928 6904 4004 6904 3998 6904 4006 6905 3999 6905 4007 6905 4007 6906 3999 6906 3930 6906 4004 6907 3928 6907 3999 6907 3999 6908 4006 6908 4004 6908 4000 6909 3933 6909 4008 6909 4000 6910 4007 6910 3930 6910 4000 6911 4008 6911 4007 6911 3935 6912 4011 6912 4001 6912 4008 6913 3933 6913 4001 6913 4008 6914 4001 6914 4011 6914 3938 6915 4010 6915 4002 6915 4011 6916 3935 6916 4002 6916 4011 6917 4002 6917 4010 6917 3941 6918 4009 6918 4003 6918 4010 6919 3938 6919 4003 6919 4010 6920 4003 6920 4009 6920 3953 6921 3974 6921 3955 6921 3944 6922 3955 6922 3970 6922 3944 6923 3970 6923 3946 6923 3962 6924 3960 6924 4012 6924 3974 6925 3972 6925 3955 6925 3955 6926 3972 6926 3970 6926 3960 6927 3963 6927 4012 6927 3960 6928 3958 6928 3966 6928 3960 6929 3966 6929 3963 6929 3956 6930 4013 6930 3958 6930 3958 6931 4013 6931 3966 6931 3956 6932 3946 6932 4013 6932 4013 6933 3946 6933 3968 6933 3946 6934 3970 6934 3968 6934 3953 6935 3976 6935 3974 6935 3953 6936 3951 6936 3976 6936 3951 6937 3978 6937 3976 6937 3951 6938 3949 6938 3978 6938 3949 6939 3979 6939 3978 6939 3949 6940 3962 6940 3979 6940 3962 6941 4012 6941 3979 6941 4014 6942 4015 6942 4016 6942 4014 6943 4016 6943 4017 6943 4018 6944 4019 6944 4014 6944 4014 6945 4019 6945 4015 6945 4020 6946 4024 6946 4021 6946 4020 6947 4021 6947 4018 6947 4018 6948 4021 6948 4019 6948 4022 6949 4023 6949 4020 6949 4020 6950 4023 6950 4024 6950 4027 6951 4025 6951 4022 6951 4022 6952 4025 6952 4023 6952 4017 6953 4026 6953 4027 6953 4027 6954 4026 6954 4025 6954 4016 6955 4028 6955 4017 6955 4017 6956 4028 6956 4026 6956 4029 6957 4030 6957 4031 6957 4031 6958 4030 6958 4032 6958 4031 6959 4032 6959 4033 6959 4033 6960 4032 6960 4034 6960 4034 6961 4032 6961 4035 6961 4034 6962 4035 6962 4036 6962 4036 6963 4035 6963 4037 6963 4037 6964 4035 6964 4038 6964 4037 6965 4038 6965 4039 6965 4039 6966 4038 6966 4040 6966 4039 6967 4040 6967 4041 6967 4041 6968 4040 6968 4042 6968 4042 6969 4040 6969 4043 6969 4042 6970 4043 6970 4044 6970 4044 6971 4043 6971 4045 6971 4043 6972 4046 6972 4045 6972 4045 6973 4046 6973 4047 6973 4047 6974 4046 6974 4048 6974 4047 6975 4048 6975 4049 6975 4049 6976 4048 6976 4050 6976 4050 6977 4048 6977 4051 6977 4050 6978 4051 6978 4052 6978 4052 6979 4051 6979 4053 6979 4053 6980 4051 6980 4054 6980 4053 6981 4054 6981 4055 6981 4055 6982 4054 6982 4056 6982 4056 6983 4054 6983 4057 6983 4056 6984 4057 6984 4058 6984 4058 6985 4057 6985 4059 6985 4058 6986 4059 6986 4060 6986 4060 6987 4059 6987 4061 6987 4061 6988 4059 6988 4062 6988 4061 6989 4062 6989 4063 6989 4063 6990 4062 6990 4064 6990 4063 6991 4064 6991 4065 6991 4065 6992 4064 6992 4066 6992 4066 6993 4064 6993 4067 6993 4066 6994 4067 6994 4068 6994 4068 6995 4067 6995 4069 6995 4068 6996 4069 6996 4070 6996 4070 6997 4069 6997 4071 6997 4071 6998 4069 6998 4072 6998 4071 6999 4072 6999 4073 6999 4073 7000 4072 7000 4074 7000 4074 7001 4072 7001 4075 7001 4074 7002 4075 7002 4076 7002 4076 7003 4075 7003 4077 7003 4077 7004 4075 7004 4078 7004 4077 7005 4078 7005 4029 7005 4029 7006 4078 7006 4030 7006 4080 7007 4079 7007 4081 7007 4081 7008 4079 7008 4082 7008 4081 7009 4082 7009 4083 7009 4083 7010 4082 7010 4084 7010 4084 7011 4085 7011 4083 7011 4085 7012 4084 7012 4086 7012 4086 7013 4087 7013 4085 7013 4087 7014 4086 7014 4088 7014 4088 7015 4089 7015 4087 7015 4089 7016 4088 7016 4090 7016 4090 7017 4091 7017 4089 7017 4091 7018 4090 7018 4092 7018 4092 7019 4093 7019 4091 7019 4093 7020 4092 7020 4094 7020 4094 7021 4095 7021 4093 7021 4095 7022 4094 7022 4096 7022 4096 7023 4097 7023 4095 7023 4097 7024 4096 7024 4137 7024 4098 7025 4097 7025 4137 7025 4097 7026 4098 7026 4099 7026 4099 7027 4098 7027 4100 7027 4099 7028 4100 7028 4080 7028 4080 7029 4100 7029 4079 7029 4080 7030 4081 7030 4089 7030 4097 7031 4099 7031 4089 7031 4089 7032 4099 7032 4080 7032 4089 7033 4095 7033 4097 7033 4089 7034 4093 7034 4095 7034 4081 7035 4083 7035 4089 7035 4089 7036 4083 7036 4087 7036 4015 7037 4102 7037 4101 7037 4101 7038 4102 7038 4103 7038 4102 7039 4104 7039 4103 7039 4103 7040 4104 7040 4105 7040 4105 7041 4104 7041 4021 7041 4105 7042 4021 7042 4106 7042 4106 7043 4021 7043 4107 7043 4107 7044 4108 7044 4106 7044 4106 7045 4108 7045 4109 7045 4109 7046 4108 7046 4023 7046 4109 7047 4023 7047 4110 7047 4110 7048 4023 7048 4111 7048 4110 7049 4111 7049 4112 7049 4112 7050 4111 7050 4113 7050 4113 7051 4114 7051 4112 7051 4112 7052 4114 7052 4115 7052 4115 7053 4114 7053 4116 7053 4114 7054 4117 7054 4116 7054 4116 7055 4117 7055 4028 7055 4116 7056 4028 7056 4118 7056 4118 7057 4028 7057 4016 7057 4118 7058 4016 7058 4101 7058 4016 7059 4015 7059 4101 7059 4023 7060 4108 7060 4024 7060 4108 7061 4107 7061 4024 7061 4024 7062 4107 7062 4021 7062 4021 7063 4104 7063 4019 7063 4104 7064 4102 7064 4019 7064 4019 7065 4102 7065 4015 7065 4028 7066 4117 7066 4026 7066 4117 7067 4114 7067 4026 7067 4026 7068 4114 7068 4025 7068 4114 7069 4113 7069 4025 7069 4025 7070 4113 7070 4111 7070 4025 7071 4111 7071 4023 7071 4091 7072 4093 7072 4089 7072 4085 7073 4087 7073 4083 7073 4020 7074 4119 7074 4022 7074 4018 7075 4120 7075 4020 7075 4014 7076 4121 7076 4018 7076 4017 7077 4122 7077 4014 7077 4027 7078 4123 7078 4017 7078 4022 7079 4124 7079 4027 7079 4126 7080 4130 7080 4131 7080 4125 7081 4126 7081 4131 7081 4126 7082 4129 7082 4130 7082 4128 7083 4129 7083 4126 7083 4127 7084 4128 7084 4126 7084 4125 7085 4127 7085 4126 7085 4020 7086 4129 7086 4119 7086 4128 7087 4022 7087 4119 7087 4119 7088 4129 7088 4128 7088 4120 7089 4018 7089 4130 7089 4129 7090 4020 7090 4120 7090 4130 7091 4129 7091 4120 7091 4131 7092 4121 7092 4014 7092 4130 7093 4018 7093 4121 7093 4130 7094 4121 7094 4131 7094 4131 7095 4014 7095 4125 7095 4125 7096 4014 7096 4122 7096 4125 7097 4122 7097 4017 7097 4027 7098 4127 7098 4123 7098 4123 7099 4127 7099 4125 7099 4123 7100 4125 7100 4017 7100 4022 7101 4128 7101 4124 7101 4127 7102 4027 7102 4124 7102 4124 7103 4128 7103 4127 7103 4132 7104 4098 7104 4136 7104 4136 7105 4098 7105 4137 7105 4137 7106 4096 7106 4138 7106 4138 7107 4096 7107 4139 7107 4139 7108 4096 7108 4094 7108 4139 7109 4094 7109 4140 7109 4140 7110 4094 7110 4141 7110 4141 7111 4094 7111 4092 7111 4141 7112 4092 7112 4142 7112 4142 7113 4092 7113 4090 7113 4142 7114 4090 7114 4143 7114 4143 7115 4090 7115 4144 7115 4144 7116 4090 7116 4088 7116 4144 7117 4088 7117 4145 7117 4145 7118 4088 7118 4086 7118 4145 7119 4086 7119 4146 7119 4146 7120 4086 7120 4147 7120 4147 7121 4086 7121 4084 7121 4147 7122 4084 7122 4148 7122 4148 7123 4084 7123 4149 7123 4149 7124 4084 7124 4082 7124 4149 7125 4082 7125 4135 7125 4150 7126 4079 7126 4133 7126 4133 7127 4079 7127 4100 7127 4079 7128 4150 7128 4134 7128 4134 7129 4135 7129 4082 7129 4134 7130 4082 7130 4079 7130 4132 7131 4133 7131 4100 7131 4132 7132 4100 7132 4098 7132 4151 7133 4152 7133 4153 7133 4153 7134 4155 7134 4151 7134 4156 7135 4152 7135 4151 7135 4154 7136 4157 7136 4151 7136 4151 7137 4155 7137 4154 7137 4151 7138 4158 7138 4159 7138 4159 7139 4160 7139 4151 7139 4157 7140 4158 7140 4151 7140 4151 7141 4160 7141 4156 7141 4163 7142 4162 7142 4161 7142 4162 7143 4164 7143 4161 7143 4161 7144 4164 7144 4166 7144 4161 7145 4166 7145 4165 7145 4161 7146 4165 7146 4167 7146 4161 7147 4167 7147 4168 7147 4168 7148 4169 7148 4161 7148 4170 7149 4163 7149 4161 7149 4169 7150 4170 7150 4161 7150 4171 7151 4172 7151 4173 7151 4171 7152 4175 7152 4176 7152 4174 7153 4175 7153 4171 7153 4171 7154 4173 7154 4174 7154 4176 7155 4177 7155 4171 7155 4177 7156 4179 7156 4171 7156 4171 7157 4180 7157 4172 7157 4178 7158 4180 7158 4171 7158 4171 7159 4179 7159 4178 7159 4181 7160 4182 7160 4183 7160 4183 7161 4184 7161 4181 7161 4185 7162 4182 7162 4181 7162 4187 7163 4186 7163 4181 7163 4184 7164 4187 7164 4181 7164 4186 7165 4188 7165 4181 7165 4189 7166 4185 7166 4181 7166 4181 7167 4188 7167 4190 7167 4181 7168 4190 7168 4189 7168 4192 7169 4193 7169 4194 7169 4194 7170 4193 7170 4195 7170 4191 7171 4196 7171 4197 7171 4191 7172 4197 7172 4192 7172 4192 7173 4197 7173 4193 7173 4195 7174 4199 7174 4198 7174 4199 7175 4197 7175 4200 7175 4200 7176 4197 7176 4196 7176 4197 7177 4199 7177 4193 7177 4193 7178 4199 7178 4195 7178 4195 7179 4198 7179 4194 7179 4153 7180 4201 7180 4202 7180 4156 7181 4201 7181 4152 7181 4152 7182 4201 7182 4153 7182 4155 7183 4153 7183 4202 7183 4155 7184 4202 7184 4203 7184 4155 7185 4203 7185 4154 7185 4154 7186 4203 7186 4204 7186 4154 7187 4204 7187 4157 7187 4157 7188 4204 7188 4205 7188 4157 7189 4205 7189 4158 7189 4158 7190 4205 7190 4159 7190 4159 7191 4205 7191 4206 7191 4159 7192 4206 7192 4160 7192 4160 7193 4206 7193 4207 7193 4160 7194 4207 7194 4208 7194 4160 7195 4208 7195 4156 7195 4156 7196 4208 7196 4201 7196 4163 7197 4209 7197 4210 7197 4166 7198 4211 7198 4212 7198 4165 7199 4212 7199 4213 7199 4162 7200 4163 7200 4210 7200 4162 7201 4210 7201 4164 7201 4164 7202 4210 7202 4211 7202 4164 7203 4211 7203 4166 7203 4165 7204 4166 7204 4212 7204 4167 7205 4165 7205 4213 7205 4169 7206 4215 7206 4216 7206 4169 7207 4216 7207 4170 7207 4170 7208 4216 7208 4209 7208 4167 7209 4213 7209 4214 7209 4167 7210 4214 7210 4168 7210 4168 7211 4214 7211 4215 7211 4168 7212 4215 7212 4169 7212 4163 7213 4170 7213 4209 7213 4172 7214 4217 7214 4218 7214 4174 7215 4218 7215 4219 7215 4174 7216 4219 7216 4220 7216 4176 7217 4220 7217 4221 7217 4173 7218 4172 7218 4218 7218 4173 7219 4218 7219 4174 7219 4175 7220 4174 7220 4220 7220 4175 7221 4220 7221 4176 7221 4179 7222 4222 7222 4223 7222 4179 7223 4223 7223 4178 7223 4178 7224 4223 7224 4224 7224 4180 7225 4224 7225 4217 7225 4180 7226 4217 7226 4172 7226 4176 7227 4221 7227 4177 7227 4177 7228 4221 7228 4222 7228 4177 7229 4222 7229 4179 7229 4180 7230 4178 7230 4224 7230 4185 7231 4225 7231 4182 7231 4182 7232 4225 7232 4183 7232 4183 7233 4225 7233 4226 7233 4183 7234 4226 7234 4184 7234 4184 7235 4226 7235 4227 7235 4184 7236 4227 7236 4187 7236 4187 7237 4227 7237 4228 7237 4187 7238 4228 7238 4186 7238 4186 7239 4228 7239 4229 7239 4188 7240 4229 7240 4230 7240 4189 7241 4232 7241 4233 7241 4186 7242 4229 7242 4188 7242 4188 7243 4230 7243 4190 7243 4190 7244 4230 7244 4231 7244 4190 7245 4231 7245 4189 7245 4189 7246 4231 7246 4232 7246 4185 7247 4189 7247 4233 7247 4185 7248 4233 7248 4225 7248 4236 7249 4237 7249 4238 7249 4238 7250 4239 7250 4236 7250 4236 7251 4239 7251 4240 7251 4234 7252 4235 7252 4239 7252 4234 7253 4239 7253 4241 7253 4237 7254 4242 7254 4238 7254 4238 7255 4242 7255 4241 7255 4238 7256 4241 7256 4239 7256 4239 7257 4235 7257 4240 7257 4240 7258 4235 7258 4234 7258 4243 7259 4244 7259 4234 7259 4245 7260 4243 7260 4242 7260 4242 7261 4243 7261 4241 7261 4243 7262 4234 7262 4241 7262 4247 7263 4246 7263 4248 7263 4243 7264 4248 7264 4244 7264 4249 7265 4246 7265 4247 7265 4247 7266 4248 7266 4243 7266 4250 7267 4251 7267 4253 7267 4251 7268 4246 7268 4253 7268 4246 7269 4249 7269 4252 7269 4246 7270 4252 7270 4253 7270 4254 7271 4255 7271 4256 7271 4258 7272 4254 7272 4259 7272 4259 7273 4254 7273 4257 7273 4254 7274 4256 7274 4257 7274 4263 7275 4260 7275 4261 7275 4263 7276 4261 7276 4262 7276 4262 7277 4261 7277 4255 7277 4262 7278 4255 7278 4254 7278 4191 7279 4192 7279 4260 7279 4194 7280 4260 7280 4192 7280 4191 7281 4260 7281 4263 7281 4191 7282 4263 7282 4264 7282 4266 7283 4267 7283 4200 7283 4200 7284 4267 7284 4265 7284 4200 7285 4265 7285 4199 7285 4265 7286 4198 7286 4199 7286 4269 7287 4268 7287 4270 7287 4269 7288 4270 7288 4265 7288 4271 7289 4268 7289 4269 7289 4267 7290 4269 7290 4265 7290 4272 7291 4273 7291 4275 7291 4273 7292 4268 7292 4275 7292 4268 7293 4271 7293 4274 7293 4268 7294 4274 7294 4275 7294 4231 7295 4234 7295 4244 7295 4231 324 4244 324 4232 324 4232 324 4244 324 4233 324 4277 324 4278 324 4246 324 4246 324 4278 324 4248 324 4248 324 4278 324 4279 324 4225 324 4233 324 4276 324 4276 324 4233 324 4244 324 4276 324 4244 324 4279 324 4279 324 4244 324 4248 324 4208 7296 4207 7296 4256 7296 4256 7297 4207 7297 4206 7297 4256 7298 4206 7298 4251 7298 4251 7299 4206 7299 4205 7299 4251 7300 4205 7300 4246 7300 4246 324 4205 324 4204 324 4246 324 4204 324 4203 324 4246 324 4203 324 4277 324 4277 324 4203 324 4202 324 4277 324 4202 324 4255 324 4255 324 4202 324 4201 324 4255 7301 4201 7301 4256 7301 4256 7302 4201 7302 4208 7302 4216 7303 4215 7303 4194 7303 4194 7304 4215 7304 4260 7304 4260 324 4215 324 4214 324 4277 324 4255 324 4261 324 4277 7305 4261 7305 4280 7305 4280 7306 4261 7306 4260 7306 4280 7307 4260 7307 4214 7307 4280 7308 4214 7308 4213 7308 4212 324 4265 324 4213 324 4213 7309 4265 7309 4280 7309 4211 7310 4198 7310 4265 7310 4211 324 4265 324 4212 324 4211 7311 4210 7311 4198 7311 4198 7312 4210 7312 4209 7312 4198 7313 4209 7313 4194 7313 4194 7314 4209 7314 4216 7314 4281 324 4270 324 4282 324 4270 324 4281 324 4265 324 4265 7315 4281 7315 4280 7315 4224 324 4223 324 4282 324 4268 324 4224 324 4282 324 4268 324 4282 324 4270 324 4222 324 4283 324 4223 324 4220 7316 4289 7316 4221 7316 4221 7317 4289 7317 4283 7317 4221 324 4283 324 4222 324 4289 7318 4220 7318 4219 7318 4289 7319 4219 7319 4218 7319 4289 7320 4218 7320 4273 7320 4218 7321 4217 7321 4273 7321 4273 7322 4217 7322 4268 7322 4268 324 4217 324 4224 324 4284 324 4283 324 4285 324 4282 324 4223 324 4283 324 4282 324 4283 324 4284 324 4231 7323 4230 7323 4234 7323 4234 7324 4230 7324 4229 7324 4234 7325 4229 7325 4240 7325 4240 7326 4229 7326 4228 7326 4240 7327 4228 7327 4227 7327 4240 7328 4227 7328 4226 7328 4240 7329 4226 7329 4286 7329 4286 324 4226 324 4225 324 4283 324 4287 324 4285 324 4285 324 4287 324 4286 324 4285 324 4286 324 4276 324 4276 324 4286 324 4225 324 4288 7330 4283 7330 4289 7330 4291 7331 4288 7331 4292 7331 4292 7332 4288 7332 4290 7332 4288 7333 4289 7333 4290 7333 4293 7334 4286 7334 4287 7334 4288 7335 4287 7335 4283 7335 4294 7336 4293 7336 4287 7336 4294 7337 4287 7337 4288 7337 4286 7338 4293 7338 4240 7338 4240 7339 4293 7339 4236 7339 4293 7340 4295 7340 4236 7340 4296 7341 4252 7341 4249 7341 4297 7342 4249 7342 4298 7342 4249 7343 4297 7343 4296 7343 4298 7344 4249 7344 4247 7344 4298 7345 4247 7345 4243 7345 4298 324 4243 324 4299 324 4299 7346 4243 7346 4245 7346 4253 7347 4302 7347 4250 7347 4302 7348 4301 7348 4250 7348 4250 7349 4301 7349 4251 7349 4256 7350 4300 7350 4301 7350 4256 7351 4301 7351 4257 7351 4302 7352 4259 7352 4257 7352 4302 7353 4257 7353 4301 7353 4301 7354 4300 7354 4251 7354 4251 7355 4300 7355 4256 7355 4263 324 4262 324 4303 324 4264 7356 4263 7356 4304 7356 4263 324 4303 324 4304 324 4254 7357 4258 7357 4305 7357 4254 7358 4305 7358 4306 7358 4254 7359 4306 7359 4307 7359 4303 324 4262 324 4254 324 4303 324 4254 324 4307 324 4308 324 4309 324 4271 324 4271 324 4309 324 4310 324 4310 7360 4311 7360 4271 7360 4271 7361 4311 7361 4274 7361 4271 324 4269 324 4308 324 4308 7362 4269 7362 4312 7362 4312 324 4269 324 4267 324 4312 7363 4267 7363 4266 7363 4275 7364 4315 7364 4272 7364 4315 7365 4314 7365 4272 7365 4272 7366 4314 7366 4273 7366 4289 7367 4313 7367 4314 7367 4289 7368 4314 7368 4290 7368 4315 7369 4292 7369 4290 7369 4315 7370 4290 7370 4314 7370 4314 7371 4313 7371 4273 7371 4273 7372 4313 7372 4289 7372 4294 324 4316 324 4293 324 4293 324 4316 324 4317 324 4293 7373 4317 7373 4295 7373 4288 324 4316 324 4294 324 4288 7374 4291 7374 4318 7374 4288 7375 4318 7375 4319 7375 4319 324 4320 324 4288 324 4288 324 4320 324 4316 324 4321 7376 4245 7376 4242 7376 4321 7377 4242 7377 4322 7377 4322 7378 4242 7378 4237 7378 4323 7379 4296 7379 4297 7379 4323 7380 4297 7380 4324 7380 4324 7381 4297 7381 4298 7381 4324 7382 4298 7382 4325 7382 4325 7383 4298 7383 4326 7383 4326 7384 4298 7384 4299 7384 4327 7385 4299 7385 4245 7385 4327 7386 4245 7386 4321 7386 4328 7387 4252 7387 4296 7387 4329 7388 4330 7388 4258 7388 4258 7389 4330 7389 4305 7389 4305 7390 4330 7390 4331 7390 4305 7391 4331 7391 4306 7391 4306 7392 4332 7392 4307 7392 4307 7393 4332 7393 4333 7393 4307 7394 4333 7394 4303 7394 4264 7395 4334 7395 4191 7395 4334 7396 4196 7396 4191 7396 4299 7397 4327 7397 4326 7397 4296 7398 4323 7398 4328 7398 4306 7399 4331 7399 4332 7399 4303 7400 4333 7400 4335 7400 4303 7401 4335 7401 4304 7401 4304 7402 4335 7402 4336 7402 4304 7403 4336 7403 4264 7403 4264 7404 4336 7404 4334 7404 4253 7405 4252 7405 4328 7405 4253 7406 4328 7406 4302 7406 4302 7407 4328 7407 4329 7407 4302 7408 4329 7408 4259 7408 4259 7409 4329 7409 4258 7409 4266 7410 4200 7410 4196 7410 4334 7411 4266 7411 4196 7411 4337 7412 4311 7412 4310 7412 4309 7413 4308 7413 4338 7413 4338 7414 4308 7414 4339 7414 4339 7415 4308 7415 4312 7415 4340 7416 4274 7416 4311 7416 4341 7417 4342 7417 4318 7417 4318 7418 4342 7418 4319 7418 4319 7419 4343 7419 4320 7419 4320 7420 4343 7420 4316 7420 4316 7421 4344 7421 4317 7421 4317 7422 4344 7422 4345 7422 4317 7423 4345 7423 4295 7423 4295 7424 4322 7424 4236 7424 4322 7425 4237 7425 4236 7425 4266 7426 4334 7426 4346 7426 4266 7427 4346 7427 4312 7427 4312 7428 4346 7428 4339 7428 4309 7429 4338 7429 4347 7429 4309 7430 4347 7430 4310 7430 4310 7431 4347 7431 4337 7431 4311 7432 4337 7432 4340 7432 4319 7433 4342 7433 4348 7433 4319 7434 4348 7434 4343 7434 4316 7435 4343 7435 4344 7435 4295 7436 4345 7436 4322 7436 4275 7437 4274 7437 4340 7437 4275 7438 4340 7438 4315 7438 4315 7439 4340 7439 4341 7439 4315 7440 4341 7440 4292 7440 4292 7441 4341 7441 4291 7441 4291 7442 4341 7442 4318 7442 4349 348 4337 348 4350 348 4350 7443 4337 7443 4347 7443 4350 348 4347 348 4351 348 4351 348 4347 348 4338 348 4351 7444 4338 7444 4352 7444 4352 348 4338 348 4339 348 4352 348 4339 348 4353 348 4354 348 4348 348 4355 348 4355 348 4348 348 4342 348 4355 348 4342 348 4356 348 4356 7445 4342 7445 4341 7445 4356 7446 4341 7446 4357 7446 4357 7447 4341 7447 4349 7447 4349 7448 4341 7448 4340 7448 4349 7449 4340 7449 4337 7449 4358 7450 4345 7450 4344 7450 4358 7451 4344 7451 4359 7451 4359 348 4344 348 4343 348 4359 348 4343 348 4354 348 4354 348 4343 348 4348 348 4360 7452 4327 7452 4321 7452 4360 7453 4321 7453 4361 7453 4361 7454 4321 7454 4322 7454 4361 7455 4322 7455 4358 7455 4358 7456 4322 7456 4345 7456 4362 348 4323 348 4363 348 4363 7457 4323 7457 4324 7457 4363 348 4324 348 4325 348 4363 348 4325 348 4364 348 4364 7458 4325 7458 4365 7458 4365 7459 4325 7459 4326 7459 4365 348 4326 348 4360 348 4360 348 4326 348 4327 348 4370 7460 4330 7460 4366 7460 4366 7461 4330 7461 4329 7461 4366 7462 4329 7462 4367 7462 4367 7463 4329 7463 4328 7463 4367 7464 4328 7464 4362 7464 4362 7465 4328 7465 4323 7465 4368 348 4336 348 4335 348 4368 348 4335 348 4369 348 4369 348 4335 348 4333 348 4369 7466 4333 7466 4370 7466 4370 7467 4333 7467 4332 7467 4370 7468 4332 7468 4331 7468 4370 7469 4331 7469 4330 7469 4353 348 4339 348 4346 348 4353 348 4346 348 4371 348 4371 7470 4346 7470 4334 7470 4371 7471 4334 7471 4372 7471 4372 7472 4334 7472 4368 7472 4368 7473 4334 7473 4336 7473 4360 7474 4373 7474 4374 7474 4360 7475 4374 7475 4365 7475 4365 7476 4374 7476 4375 7476 4364 7477 4375 7477 4376 7477 4364 7478 4376 7478 4363 7478 4363 7479 4376 7479 4377 7479 4362 7480 4377 7480 4378 7480 4366 7481 4379 7481 4380 7481 4368 7482 4384 7482 4385 7482 4361 7483 4373 7483 4360 7483 4365 7484 4375 7484 4364 7484 4363 7485 4377 7485 4362 7485 4362 7486 4378 7486 4367 7486 4367 7487 4378 7487 4379 7487 4367 7488 4379 7488 4366 7488 4366 7489 4380 7489 4370 7489 4370 7490 4380 7490 4381 7490 4370 7491 4381 7491 4382 7491 4370 7492 4382 7492 4369 7492 4369 7493 4382 7493 4383 7493 4369 7494 4383 7494 4368 7494 4368 7495 4383 7495 4384 7495 4372 7496 4368 7496 4385 7496 4372 7497 4385 7497 4386 7497 4353 7498 4387 7498 4388 7498 4353 7499 4388 7499 4352 7499 4352 7500 4388 7500 4389 7500 4351 7501 4389 7501 4390 7501 4351 7502 4390 7502 4350 7502 4350 7503 4390 7503 4391 7503 4349 7504 4391 7504 4392 7504 4357 7505 4392 7505 4393 7505 4355 7506 4394 7506 4395 7506 4359 7507 4396 7507 4397 7507 4358 7508 4397 7508 4398 7508 4358 7509 4398 7509 4361 7509 4361 7510 4398 7510 4373 7510 4372 7511 4386 7511 4371 7511 4371 7512 4386 7512 4387 7512 4371 7513 4387 7513 4353 7513 4352 7514 4389 7514 4351 7514 4350 7515 4391 7515 4349 7515 4349 7516 4392 7516 4357 7516 4356 7517 4357 7517 4393 7517 4356 7518 4393 7518 4394 7518 4356 7519 4394 7519 4355 7519 4354 7520 4355 7520 4395 7520 4354 7521 4395 7521 4396 7521 4354 7522 4396 7522 4359 7522 4359 7523 4397 7523 4358 7523 4388 7524 4399 7524 4400 7524 4401 7525 4390 7525 4400 7525 4400 7526 4390 7526 4389 7526 4400 348 4389 348 4388 348 4401 348 4391 348 4390 348 4402 7527 4392 7527 4401 7527 4401 7528 4392 7528 4391 7528 4402 7529 4393 7529 4392 7529 4403 348 4395 348 4402 348 4402 7530 4395 7530 4394 7530 4402 7531 4394 7531 4393 7531 4403 7532 4396 7532 4395 7532 4404 7533 4397 7533 4403 7533 4403 7534 4397 7534 4396 7534 4405 348 4398 348 4404 348 4404 348 4398 348 4397 348 4406 348 4374 348 4405 348 4405 7535 4374 7535 4373 7535 4405 348 4373 348 4398 348 4406 7536 4375 7536 4374 7536 4407 7537 4376 7537 4406 7537 4406 7538 4376 7538 4375 7538 4408 7539 4378 7539 4407 7539 4407 7540 4378 7540 4377 7540 4407 348 4377 348 4376 348 4408 7541 4379 7541 4378 7541 4409 348 4380 348 4408 348 4408 7542 4380 7542 4379 7542 4410 7543 4381 7543 4409 7543 4409 7544 4381 7544 4380 7544 4410 7545 4382 7545 4381 7545 4411 348 4383 348 4410 348 4410 7546 4383 7546 4382 7546 4411 348 4385 348 4384 348 4411 348 4384 348 4383 348 4399 7547 4388 7547 4387 7547 4399 348 4387 348 4386 348 4399 7548 4386 7548 4411 7548 4411 348 4386 348 4385 348 4406 7549 4412 7549 4413 7549 4407 7550 4413 7550 4414 7550 4407 7551 4414 7551 4408 7551 4408 7552 4414 7552 4415 7552 4409 7553 4415 7553 4416 7553 4411 7554 4417 7554 4418 7554 4405 7555 4412 7555 4406 7555 4406 7556 4413 7556 4407 7556 4408 7557 4415 7557 4409 7557 4410 7558 4409 7558 4416 7558 4410 7559 4416 7559 4417 7559 4410 7560 4417 7560 4411 7560 4420 348 4419 348 4421 348 4421 348 4422 348 4420 348 4420 348 4422 348 4418 348 4423 348 4420 348 4412 348 4412 348 4420 348 4418 348 4412 7561 4418 7561 4417 7561 4415 348 4414 348 4417 348 4417 348 4414 348 4413 348 4417 7562 4413 7562 4412 7562 4417 348 4416 348 4415 348 4399 7563 4418 7563 4422 7563 4400 7564 4422 7564 4421 7564 4402 7565 4419 7565 4420 7565 4404 7566 4423 7566 4405 7566 4405 7567 4423 7567 4412 7567 4411 7568 4418 7568 4399 7568 4399 7569 4422 7569 4400 7569 4401 7570 4400 7570 4421 7570 4401 7571 4421 7571 4419 7571 4401 7572 4419 7572 4402 7572 4403 7573 4402 7573 4420 7573 4403 7574 4420 7574 4423 7574 4403 7575 4423 7575 4404 7575 4277 7576 4280 7576 4424 7576 4424 7577 4280 7577 4425 7577 4425 7578 4280 7578 4281 7578 4425 7579 4281 7579 4426 7579 4426 7580 4281 7580 4282 7580 4426 7581 4282 7581 4427 7581 4427 7582 4282 7582 4284 7582 4427 7583 4284 7583 4428 7583 4428 7584 4284 7584 4285 7584 4428 7585 4285 7585 4429 7585 4429 7586 4285 7586 4276 7586 4429 7587 4276 7587 4430 7587 4430 7588 4276 7588 4279 7588 4430 7589 4279 7589 4278 7589 4430 7590 4278 7590 4431 7590 4431 7591 4278 7591 4432 7591 4432 7592 4278 7592 4277 7592 4432 7593 4277 7593 4424 7593 4424 324 4428 324 4429 324 4426 324 4427 324 4424 324 4424 324 4427 324 4428 324 4424 7594 4425 7594 4426 7594 4431 324 4432 324 4424 324 4429 324 4430 324 4424 324 4424 324 4430 324 4431 324 4437 7595 4435 7595 4436 7595 4433 7596 4434 7596 4438 7596 4433 7597 4438 7597 4436 7597 4436 7598 4438 7598 4437 7598 4439 7599 4435 7599 4437 7599 4436 7600 4435 7600 4439 7600 4440 7601 4442 7601 4441 7601 4436 7602 4439 7602 4441 7602 4441 7603 4439 7603 4440 7603 4442 7604 4440 7604 4443 7604 4442 7605 4443 7605 4444 7605 4445 7606 4442 7606 4444 7606 4441 7607 4442 7607 4445 7607 4445 7608 4447 7608 4446 7608 4441 7609 4445 7609 4446 7609 4450 7610 4447 7610 4449 7610 4449 7611 4447 7611 4445 7611 4448 7612 4447 7612 4451 7612 4451 7613 4447 7613 4450 7613 4454 7614 4452 7614 4453 7614 4448 7615 4454 7615 4453 7615 4446 7616 4447 7616 4453 7616 4453 7617 4447 7617 4448 7617 4452 7618 4454 7618 4455 7618 4453 7619 4452 7619 4455 7619 4455 7620 4457 7620 4456 7620 4453 7621 4455 7621 4456 7621 4459 7622 4457 7622 4455 7622 4460 7623 4457 7623 4459 7623 4458 7624 4457 7624 4461 7624 4461 7625 4457 7625 4460 7625 4458 7626 4434 7626 4433 7626 4456 7627 4457 7627 4433 7627 4433 7628 4457 7628 4458 7628 4462 7629 4434 7629 4458 7629 4438 7630 4434 7630 4463 7630 4463 7631 4434 7631 4462 7631 4458 7632 4466 7632 4465 7632 4445 7633 4464 7633 4472 7633 4464 7634 4445 7634 4444 7634 4465 7635 4462 7635 4458 7635 4466 7636 4467 7636 4468 7636 4466 7637 4468 7637 4469 7637 4466 7638 4458 7638 4470 7638 4466 7639 4470 7639 4471 7639 4466 7640 4471 7640 4467 7640 4477 7641 4437 7641 4465 7641 4465 7642 4437 7642 4438 7642 4465 7643 4438 7643 4462 7643 4472 7644 4473 7644 4474 7644 4472 7645 4474 7645 4475 7645 4472 7646 4475 7646 4445 7646 4454 7647 4448 7647 4469 7647 4469 7648 4448 7648 4472 7648 4472 7649 4448 7649 4476 7649 4472 7650 4476 7650 4473 7650 4477 7651 4439 7651 4437 7651 4464 7652 4444 7652 4440 7652 4464 7653 4440 7653 4477 7653 4469 7654 4455 7654 4454 7654 4477 7655 4440 7655 4439 7655 4468 7656 4478 7656 4469 7656 4469 7657 4478 7657 4455 7657 4465 7658 4466 7658 4479 7658 4479 7659 4480 7659 4465 7659 4465 7660 4480 7660 4477 7660 4477 7661 4480 7661 4481 7661 4477 7662 4481 7662 4464 7662 4481 7663 4482 7663 4464 7663 4483 7664 4464 7664 4482 7664 4472 7665 4464 7665 4483 7665 4483 7666 4484 7666 4472 7666 4472 7667 4484 7667 4469 7667 4469 7668 4484 7668 4485 7668 4469 7669 4485 7669 4466 7669 4485 7670 4486 7670 4466 7670 4479 7671 4466 7671 4486 7671 4487 7672 4479 7672 4486 7672 4487 7673 4486 7673 4485 7673 4487 7674 4485 7674 4488 7674 4488 7675 4485 7675 4489 7675 4489 7676 4485 7676 4484 7676 4489 7677 4484 7677 4490 7677 4490 7678 4484 7678 4483 7678 4490 7679 4483 7679 4491 7679 4491 7680 4483 7680 4482 7680 4491 7681 4482 7681 4481 7681 4491 7682 4481 7682 4492 7682 4492 7683 4481 7683 4493 7683 4493 7684 4481 7684 4480 7684 4493 7685 4480 7685 4494 7685 4494 7686 4480 7686 4479 7686 4494 3438 4479 3438 4487 3438 4495 7687 4491 7687 4496 7687 4491 7688 4492 7688 4496 7688 4492 7689 4493 7689 4496 7689 4496 7690 4493 7690 4497 7690 4493 7691 4494 7691 4497 7691 4497 7692 4494 7692 4498 7692 4487 7693 4498 7693 4494 7693 4498 7694 4487 7694 4499 7694 4487 7695 4488 7695 4499 7695 4488 7696 4489 7696 4499 7696 4499 7697 4489 7697 4500 7697 4489 7698 4490 7698 4500 7698 4500 7699 4490 7699 4495 7699 4491 7700 4495 7700 4490 7700 4500 7701 4495 7701 4446 7701 4446 7702 4495 7702 4441 7702 4436 7703 4496 7703 4497 7703 4436 7704 4497 7704 4433 7704 4453 7705 4499 7705 4500 7705 4453 7706 4500 7706 4446 7706 4441 7707 4495 7707 4496 7707 4441 7708 4496 7708 4436 7708 4433 7709 4497 7709 4498 7709 4433 7710 4498 7710 4456 7710 4456 7711 4498 7711 4499 7711 4456 7712 4499 7712 4453 7712 4501 7713 4502 7713 4503 7713 4503 7714 4502 7714 4504 7714 4503 7715 4504 7715 4505 7715 4505 7716 4504 7716 4506 7716 4505 7717 4506 7717 4507 7717 4507 7718 4506 7718 4508 7718 4507 7719 4508 7719 4509 7719 4507 7720 4509 7720 4510 7720 4510 7721 4509 7721 4511 7721 4510 7722 4511 7722 4512 7722 4512 7723 4511 7723 4513 7723 4512 7724 4513 7724 4514 7724 4512 7725 4514 7725 4501 7725 4501 7726 4514 7726 4502 7726 4527 7727 4515 7727 4516 7727 4516 7728 4515 7728 4517 7728 4516 7729 4517 7729 4518 7729 4518 7730 4517 7730 4519 7730 4520 7731 4521 7731 4522 7731 4522 7732 4521 7732 4523 7732 4522 7733 4523 7733 4524 7733 4524 7734 4523 7734 4525 7734 4524 7735 4525 7735 4526 7735 4526 7736 4525 7736 4527 7736 4527 7737 4525 7737 4515 7737 4519 7738 4517 7738 4528 7738 4519 7739 4528 7739 4529 7739 4529 7740 4528 7740 4530 7740 4528 7741 4531 7741 4530 7741 4530 7742 4531 7742 4532 7742 4532 7743 4531 7743 4533 7743 4532 7744 4533 7744 4534 7744 4534 7745 4533 7745 4520 7745 4520 7746 4533 7746 4521 7746 4536 7747 4535 7747 4538 7747 4536 7748 4538 7748 4537 7748 4537 7749 4538 7749 4540 7749 4537 7750 4540 7750 4539 7750 4539 7751 4540 7751 4541 7751 4539 7752 4541 7752 4542 7752 4542 7753 4541 7753 4586 7753 4542 7754 4586 7754 4543 7754 4543 7755 4586 7755 4544 7755 4543 7756 4544 7756 4545 7756 4546 7757 4547 7757 4545 7757 4546 7758 4545 7758 4544 7758 4548 7759 4547 7759 4546 7759 4547 7760 4548 7760 4550 7760 4547 7761 4550 7761 4549 7761 4549 7762 4550 7762 4551 7762 4549 7763 4551 7763 4552 7763 4552 7764 4551 7764 4553 7764 4552 7765 4553 7765 4536 7765 4536 7766 4553 7766 4535 7766 4554 7767 4555 7767 4556 7767 4558 7768 4557 7768 4555 7768 4559 7769 4558 7769 4555 7769 4555 7770 4554 7770 4559 7770 4560 7771 4534 7771 4520 7771 4560 7772 4520 7772 4561 7772 4561 7773 4520 7773 4522 7773 4561 7774 4522 7774 4562 7774 4562 7775 4522 7775 4524 7775 4562 7776 4524 7776 4563 7776 4563 7777 4524 7777 4526 7777 4563 7778 4526 7778 4527 7778 4563 7779 4527 7779 4564 7779 4564 7780 4527 7780 4516 7780 4564 7781 4516 7781 4565 7781 4565 7782 4516 7782 4518 7782 4565 7783 4518 7783 4566 7783 4566 7784 4518 7784 4519 7784 4566 7785 4519 7785 4567 7785 4567 7786 4519 7786 4529 7786 4567 7787 4529 7787 4568 7787 4568 7788 4529 7788 4530 7788 4568 7789 4530 7789 4569 7789 4569 7790 4530 7790 4532 7790 4569 7791 4532 7791 4570 7791 4570 7792 4532 7792 4534 7792 4570 7793 4534 7793 4560 7793 4564 7794 4513 7794 4511 7794 4564 7795 4511 7795 4563 7795 4563 7796 4511 7796 4509 7796 4563 7797 4509 7797 4562 7797 4562 7798 4509 7798 4508 7798 4562 7799 4508 7799 4561 7799 4561 7800 4508 7800 4506 7800 4561 7801 4506 7801 4560 7801 4560 7802 4506 7802 4570 7802 4570 7803 4506 7803 4504 7803 4570 7804 4504 7804 4569 7804 4569 7805 4504 7805 4502 7805 4569 7806 4502 7806 4568 7806 4568 7807 4502 7807 4567 7807 4567 7808 4502 7808 4514 7808 4567 7809 4514 7809 4566 7809 4566 7810 4514 7810 4565 7810 4565 7811 4514 7811 4513 7811 4565 7812 4513 7812 4564 7812 4536 7813 4556 7813 4552 7813 4552 7814 4556 7814 4555 7814 4552 7815 4555 7815 4549 7815 4549 7816 4555 7816 4557 7816 4549 7817 4557 7817 4547 7817 4547 7818 4557 7818 4545 7818 4545 7819 4557 7819 4558 7819 4545 7820 4558 7820 4543 7820 4543 7821 4558 7821 4542 7821 4542 7822 4558 7822 4559 7822 4542 7823 4559 7823 4539 7823 4539 7824 4559 7824 4554 7824 4539 7825 4554 7825 4537 7825 4537 7826 4554 7826 4536 7826 4536 7827 4554 7827 4556 7827 4501 7828 4571 7828 4512 7828 4503 7829 4572 7829 4501 7829 4505 7830 4573 7830 4503 7830 4507 7831 4574 7831 4505 7831 4510 7832 4575 7832 4507 7832 4512 7833 4576 7833 4510 7833 4580 7834 4581 7834 4578 7834 4580 7835 4578 7835 4579 7835 4579 7836 4578 7836 4577 7836 4582 7837 4577 7837 4578 7837 4583 7838 4582 7838 4578 7838 4584 7839 4583 7839 4578 7839 4578 7840 4581 7840 4584 7840 4582 7841 4512 7841 4571 7841 4582 7842 4571 7842 4577 7842 4501 7843 4577 7843 4571 7843 4579 7844 4572 7844 4580 7844 4580 7845 4572 7845 4503 7845 4577 7846 4501 7846 4572 7846 4572 7847 4579 7847 4577 7847 4573 7848 4505 7848 4581 7848 4573 7849 4580 7849 4503 7849 4573 7850 4581 7850 4580 7850 4507 7851 4584 7851 4574 7851 4581 7852 4505 7852 4574 7852 4581 7853 4574 7853 4584 7853 4510 7854 4583 7854 4575 7854 4584 7855 4507 7855 4575 7855 4584 7856 4575 7856 4583 7856 4512 7857 4582 7857 4576 7857 4583 7858 4510 7858 4576 7858 4583 7859 4576 7859 4582 7859 4528 7860 4517 7860 4585 7860 4531 7861 4535 7861 4533 7861 4531 7862 4538 7862 4535 7862 4525 7863 4546 7863 4515 7863 4515 7864 4546 7864 4544 7864 4515 7865 4544 7865 4517 7865 4517 7866 4544 7866 4586 7866 4533 7867 4535 7867 4553 7867 4531 7868 4540 7868 4538 7868 4531 7869 4528 7869 4540 7869 4528 7870 4585 7870 4541 7870 4528 7871 4541 7871 4540 7871 4585 7872 4586 7872 4541 7872 4585 7873 4517 7873 4586 7873 4525 7874 4548 7874 4546 7874 4525 7875 4550 7875 4548 7875 4525 7876 4523 7876 4550 7876 4523 7877 4551 7877 4550 7877 4523 7878 4521 7878 4551 7878 4521 7879 4533 7879 4553 7879 4521 7880 4553 7880 4551 7880 4587 7881 4588 7881 4589 7881 4587 7882 4589 7882 4590 7882 4591 7883 4592 7883 4587 7883 4587 7884 4592 7884 4588 7884 4593 7885 4597 7885 4594 7885 4593 7886 4594 7886 4591 7886 4591 7887 4594 7887 4592 7887 4595 7888 4596 7888 4593 7888 4593 7889 4596 7889 4597 7889 4600 7890 4598 7890 4595 7890 4595 7891 4598 7891 4596 7891 4590 7892 4599 7892 4600 7892 4600 7893 4599 7893 4598 7893 4589 7894 4601 7894 4590 7894 4590 7895 4601 7895 4599 7895 4602 7896 4603 7896 4604 7896 4604 7897 4603 7897 4605 7897 4604 7898 4605 7898 4606 7898 4606 7899 4605 7899 4607 7899 4607 7900 4605 7900 4608 7900 4607 7901 4608 7901 4609 7901 4609 7902 4608 7902 4610 7902 4610 7903 4608 7903 4611 7903 4610 7904 4611 7904 4612 7904 4612 5948 4611 5948 4613 5948 4612 7905 4613 7905 4614 7905 4614 7906 4613 7906 4615 7906 4615 7907 4613 7907 4616 7907 4615 7908 4616 7908 4617 7908 4617 7909 4616 7909 4618 7909 4616 7910 4619 7910 4618 7910 4618 7911 4619 7911 4620 7911 4620 7912 4619 7912 4621 7912 4620 7913 4621 7913 4622 7913 4622 7914 4621 7914 4623 7914 4623 7915 4621 7915 4624 7915 4623 5948 4624 5948 4625 5948 4625 7916 4624 7916 4626 7916 4626 7917 4624 7917 4627 7917 4626 7918 4627 7918 4628 7918 4628 7919 4627 7919 4629 7919 4629 7920 4627 7920 4630 7920 4629 7921 4630 7921 4631 7921 4631 7922 4630 7922 4632 7922 4631 7923 4632 7923 4633 7923 4633 7924 4632 7924 4634 7924 4634 7925 4632 7925 4635 7925 4634 7926 4635 7926 4636 7926 4636 7927 4635 7927 4637 7927 4636 7928 4637 7928 4638 7928 4638 7929 4637 7929 4639 7929 4639 7930 4637 7930 4640 7930 4639 7931 4640 7931 4641 7931 4641 7932 4640 7932 4642 7932 4641 7933 4642 7933 4643 7933 4643 7934 4642 7934 4644 7934 4644 7935 4642 7935 4645 7935 4644 5946 4645 5946 4646 5946 4646 7936 4645 7936 4647 7936 4647 7937 4645 7937 4648 7937 4647 5950 4648 5950 4649 5950 4649 7938 4648 7938 4650 7938 4650 7939 4648 7939 4651 7939 4650 7940 4651 7940 4602 7940 4602 7941 4651 7941 4603 7941 4653 7942 4652 7942 4654 7942 4654 7943 4652 7943 4655 7943 4654 7944 4655 7944 4656 7944 4656 7945 4655 7945 4657 7945 4657 7946 4658 7946 4656 7946 4658 7947 4657 7947 4659 7947 4659 7948 4660 7948 4658 7948 4660 7949 4659 7949 4661 7949 4661 7950 4662 7950 4660 7950 4662 7951 4661 7951 4663 7951 4663 7952 4664 7952 4662 7952 4664 7953 4663 7953 4665 7953 4665 7954 4666 7954 4664 7954 4666 7955 4665 7955 4667 7955 4667 7956 4668 7956 4666 7956 4668 7957 4667 7957 4669 7957 4669 7958 4670 7958 4668 7958 4670 7959 4669 7959 4710 7959 4671 7960 4670 7960 4710 7960 4670 7961 4671 7961 4672 7961 4672 7962 4671 7962 4673 7962 4672 7963 4673 7963 4653 7963 4653 7964 4673 7964 4652 7964 4653 7965 4654 7965 4662 7965 4670 7966 4672 7966 4662 7966 4662 7967 4672 7967 4653 7967 4662 7968 4668 7968 4670 7968 4662 7969 4666 7969 4668 7969 4654 7970 4656 7970 4662 7970 4662 7971 4656 7971 4660 7971 4588 7972 4675 7972 4674 7972 4674 7973 4675 7973 4676 7973 4675 7974 4677 7974 4676 7974 4676 7975 4677 7975 4678 7975 4678 7976 4677 7976 4594 7976 4678 7977 4594 7977 4679 7977 4679 7978 4594 7978 4680 7978 4680 7979 4681 7979 4679 7979 4679 7980 4681 7980 4682 7980 4682 7981 4681 7981 4596 7981 4682 7982 4596 7982 4683 7982 4683 7983 4596 7983 4684 7983 4683 7984 4684 7984 4685 7984 4685 7985 4684 7985 4686 7985 4686 7986 4687 7986 4685 7986 4685 7987 4687 7987 4688 7987 4688 7988 4687 7988 4689 7988 4687 7989 4690 7989 4689 7989 4689 7990 4690 7990 4601 7990 4689 7991 4601 7991 4691 7991 4691 7992 4601 7992 4589 7992 4691 7993 4589 7993 4674 7993 4589 7994 4588 7994 4674 7994 4596 7995 4681 7995 4597 7995 4681 7996 4680 7996 4597 7996 4597 7997 4680 7997 4594 7997 4594 7998 4677 7998 4592 7998 4677 7999 4675 7999 4592 7999 4592 8000 4675 8000 4588 8000 4601 8001 4690 8001 4599 8001 4690 8002 4687 8002 4599 8002 4599 8003 4687 8003 4598 8003 4687 8004 4686 8004 4598 8004 4598 8005 4686 8005 4684 8005 4598 8006 4684 8006 4596 8006 4664 8007 4666 8007 4662 8007 4658 8008 4660 8008 4656 8008 4593 8009 4692 8009 4595 8009 4591 8010 4693 8010 4593 8010 4587 8011 4694 8011 4591 8011 4590 8012 4695 8012 4587 8012 4600 8013 4696 8013 4590 8013 4595 8014 4697 8014 4600 8014 4699 8015 4703 8015 4704 8015 4698 8016 4699 8016 4704 8016 4699 8017 4702 8017 4703 8017 4701 8018 4702 8018 4699 8018 4700 8019 4701 8019 4699 8019 4698 8020 4700 8020 4699 8020 4593 8021 4702 8021 4692 8021 4701 8022 4595 8022 4692 8022 4692 8023 4702 8023 4701 8023 4693 8024 4591 8024 4703 8024 4702 8025 4593 8025 4693 8025 4703 8026 4702 8026 4693 8026 4704 8027 4694 8027 4587 8027 4703 8028 4591 8028 4694 8028 4703 8029 4694 8029 4704 8029 4704 8030 4587 8030 4698 8030 4698 8031 4587 8031 4695 8031 4698 8032 4695 8032 4590 8032 4600 8033 4700 8033 4696 8033 4696 8034 4700 8034 4698 8034 4696 8035 4698 8035 4590 8035 4595 8036 4701 8036 4697 8036 4700 8037 4600 8037 4697 8037 4697 8038 4701 8038 4700 8038 4705 8039 4671 8039 4709 8039 4709 8040 4671 8040 4710 8040 4710 8041 4669 8041 4711 8041 4711 8042 4669 8042 4712 8042 4712 8043 4669 8043 4667 8043 4712 8044 4667 8044 4713 8044 4713 8045 4667 8045 4714 8045 4714 8046 4667 8046 4665 8046 4714 8047 4665 8047 4715 8047 4715 8048 4665 8048 4663 8048 4715 8049 4663 8049 4716 8049 4716 8050 4663 8050 4717 8050 4717 8051 4663 8051 4661 8051 4717 8052 4661 8052 4718 8052 4718 8053 4661 8053 4659 8053 4718 8054 4659 8054 4719 8054 4719 8055 4659 8055 4720 8055 4720 8056 4659 8056 4657 8056 4720 8057 4657 8057 4721 8057 4721 8058 4657 8058 4722 8058 4722 8059 4657 8059 4655 8059 4722 8060 4655 8060 4708 8060 4723 8061 4652 8061 4706 8061 4706 8062 4652 8062 4673 8062 4652 8063 4723 8063 4707 8063 4707 8064 4708 8064 4655 8064 4707 8065 4655 8065 4652 8065 4705 8066 4706 8066 4673 8066 4705 8067 4673 8067 4671 8067 4724 8068 4725 8068 4726 8068 4724 8069 4726 8069 4727 8069 4728 8070 4729 8070 4724 8070 4724 8071 4729 8071 4725 8071 4730 8072 4734 8072 4731 8072 4730 8073 4731 8073 4728 8073 4728 8074 4731 8074 4729 8074 4732 8075 4733 8075 4730 8075 4730 8076 4733 8076 4734 8076 4737 8077 4735 8077 4732 8077 4732 8078 4735 8078 4733 8078 4727 8079 4736 8079 4737 8079 4737 8080 4736 8080 4735 8080 4726 8081 4738 8081 4727 8081 4727 8082 4738 8082 4736 8082 4739 8083 4740 8083 4741 8083 4741 8084 4740 8084 4742 8084 4741 8085 4742 8085 4743 8085 4743 8086 4742 8086 4744 8086 4744 8087 4742 8087 4745 8087 4744 8088 4745 8088 4746 8088 4746 8089 4745 8089 4747 8089 4747 8090 4745 8090 4748 8090 4747 8091 4748 8091 4749 8091 4749 8092 4748 8092 4750 8092 4749 8093 4750 8093 4751 8093 4751 8094 4750 8094 4752 8094 4752 8095 4750 8095 4753 8095 4752 8096 4753 8096 4754 8096 4754 8097 4753 8097 4755 8097 4753 8098 4756 8098 4755 8098 4755 8099 4756 8099 4757 8099 4757 8100 4756 8100 4758 8100 4757 8101 4758 8101 4759 8101 4759 8102 4758 8102 4760 8102 4760 8103 4758 8103 4761 8103 4760 8104 4761 8104 4762 8104 4762 8105 4761 8105 4763 8105 4763 8106 4761 8106 4764 8106 4763 8107 4764 8107 4765 8107 4765 8108 4764 8108 4766 8108 4766 8109 4764 8109 4767 8109 4766 8110 4767 8110 4768 8110 4768 8111 4767 8111 4769 8111 4768 8112 4769 8112 4770 8112 4770 8113 4769 8113 4771 8113 4771 8114 4769 8114 4772 8114 4771 8115 4772 8115 4773 8115 4773 8116 4772 8116 4774 8116 4773 8117 4774 8117 4775 8117 4775 8118 4774 8118 4776 8118 4776 8119 4774 8119 4777 8119 4776 8120 4777 8120 4778 8120 4778 8121 4777 8121 4779 8121 4778 8122 4779 8122 4780 8122 4780 8123 4779 8123 4781 8123 4781 8124 4779 8124 4782 8124 4781 8125 4782 8125 4783 8125 4783 8126 4782 8126 4784 8126 4784 8127 4782 8127 4785 8127 4784 8128 4785 8128 4786 8128 4786 8129 4785 8129 4787 8129 4787 8130 4785 8130 4788 8130 4787 8131 4788 8131 4739 8131 4739 8132 4788 8132 4740 8132 4790 8133 4789 8133 4791 8133 4791 8134 4789 8134 4792 8134 4791 8135 4792 8135 4793 8135 4793 8136 4792 8136 4794 8136 4794 8137 4795 8137 4793 8137 4795 8138 4794 8138 4796 8138 4796 8139 4797 8139 4795 8139 4797 8140 4796 8140 4798 8140 4798 8141 4799 8141 4797 8141 4799 8142 4798 8142 4800 8142 4800 8143 4801 8143 4799 8143 4801 8144 4800 8144 4802 8144 4802 8145 4803 8145 4801 8145 4803 8146 4802 8146 4804 8146 4804 8147 4805 8147 4803 8147 4805 8148 4804 8148 4806 8148 4806 8149 4807 8149 4805 8149 4807 8150 4806 8150 4847 8150 4808 8151 4807 8151 4847 8151 4807 8152 4808 8152 4809 8152 4809 8153 4808 8153 4810 8153 4809 8154 4810 8154 4790 8154 4790 8155 4810 8155 4789 8155 4790 8156 4791 8156 4799 8156 4807 8157 4809 8157 4799 8157 4799 8158 4809 8158 4790 8158 4799 8159 4805 8159 4807 8159 4799 8160 4803 8160 4805 8160 4791 8161 4793 8161 4799 8161 4799 8162 4793 8162 4797 8162 4725 8163 4812 8163 4811 8163 4811 8164 4812 8164 4813 8164 4812 8165 4814 8165 4813 8165 4813 8166 4814 8166 4815 8166 4815 8167 4814 8167 4731 8167 4815 8168 4731 8168 4816 8168 4816 8169 4731 8169 4817 8169 4817 8170 4818 8170 4816 8170 4816 8171 4818 8171 4819 8171 4819 8172 4818 8172 4733 8172 4819 8173 4733 8173 4820 8173 4820 8174 4733 8174 4821 8174 4820 8175 4821 8175 4822 8175 4822 8176 4821 8176 4823 8176 4823 8177 4824 8177 4822 8177 4822 8178 4824 8178 4825 8178 4825 8179 4824 8179 4826 8179 4824 8180 4827 8180 4826 8180 4826 8181 4827 8181 4738 8181 4826 8182 4738 8182 4828 8182 4828 8183 4738 8183 4726 8183 4828 8184 4726 8184 4811 8184 4726 8185 4725 8185 4811 8185 4733 8186 4818 8186 4734 8186 4818 8187 4817 8187 4734 8187 4734 8188 4817 8188 4731 8188 4731 8189 4814 8189 4729 8189 4814 8190 4812 8190 4729 8190 4729 8191 4812 8191 4725 8191 4738 8192 4827 8192 4736 8192 4827 8193 4824 8193 4736 8193 4736 8194 4824 8194 4735 8194 4824 8195 4823 8195 4735 8195 4735 8196 4823 8196 4821 8196 4735 8197 4821 8197 4733 8197 4801 8198 4803 8198 4799 8198 4795 8199 4797 8199 4793 8199 4730 8200 4829 8200 4732 8200 4728 8201 4830 8201 4730 8201 4724 8202 4831 8202 4728 8202 4727 8203 4832 8203 4724 8203 4737 8204 4833 8204 4727 8204 4732 8205 4834 8205 4737 8205 4836 8206 4840 8206 4841 8206 4835 8207 4836 8207 4841 8207 4836 8208 4839 8208 4840 8208 4838 8209 4839 8209 4836 8209 4837 8210 4838 8210 4836 8210 4835 8211 4837 8211 4836 8211 4730 8212 4839 8212 4829 8212 4838 8213 4732 8213 4829 8213 4829 8214 4839 8214 4838 8214 4830 8215 4728 8215 4840 8215 4839 8216 4730 8216 4830 8216 4840 8217 4839 8217 4830 8217 4841 8218 4831 8218 4724 8218 4840 8219 4728 8219 4831 8219 4840 8220 4831 8220 4841 8220 4841 8221 4724 8221 4835 8221 4835 8222 4724 8222 4832 8222 4835 8223 4832 8223 4727 8223 4737 8224 4837 8224 4833 8224 4833 8225 4837 8225 4835 8225 4833 8226 4835 8226 4727 8226 4732 8227 4838 8227 4834 8227 4837 8228 4737 8228 4834 8228 4834 8229 4838 8229 4837 8229 4842 8230 4808 8230 4846 8230 4846 8231 4808 8231 4847 8231 4847 8232 4806 8232 4848 8232 4848 8233 4806 8233 4849 8233 4849 8234 4806 8234 4804 8234 4849 8235 4804 8235 4850 8235 4850 8236 4804 8236 4851 8236 4851 8237 4804 8237 4802 8237 4851 8238 4802 8238 4852 8238 4852 8239 4802 8239 4800 8239 4852 8240 4800 8240 4853 8240 4853 8241 4800 8241 4854 8241 4854 8242 4800 8242 4798 8242 4854 8243 4798 8243 4855 8243 4855 8244 4798 8244 4796 8244 4855 8245 4796 8245 4856 8245 4856 8246 4796 8246 4857 8246 4857 8247 4796 8247 4794 8247 4857 8248 4794 8248 4858 8248 4858 8249 4794 8249 4859 8249 4859 8250 4794 8250 4792 8250 4859 8251 4792 8251 4845 8251 4860 8252 4789 8252 4843 8252 4843 8253 4789 8253 4810 8253 4789 8254 4860 8254 4844 8254 4844 8255 4845 8255 4792 8255 4844 8256 4792 8256 4789 8256 4842 8257 4843 8257 4810 8257 4842 8258 4810 8258 4808 8258 4866 8259 4863 8259 4864 8259 4861 8260 4862 8260 4865 8260 4865 8261 4866 8261 4864 8261 4861 8262 4865 8262 4864 8262 4867 8263 4863 8263 4866 8263 4870 8264 4868 8264 4869 8264 4864 8265 4863 8265 4867 8265 4867 8266 4870 8266 4869 8266 4864 8267 4867 8267 4869 8267 4870 8268 4871 8268 4868 8268 4872 8269 4868 8269 4871 8269 4869 8270 4868 8270 4872 8270 4873 8271 4875 8271 4874 8271 4869 8272 4872 8272 4873 8272 4869 8273 4873 8273 4874 8273 4878 8274 4875 8274 4877 8274 4877 8275 4875 8275 4873 8275 4876 8276 4875 8276 4879 8276 4879 8277 4875 8277 4878 8277 4882 8278 4880 8278 4881 8278 4876 8279 4882 8279 4881 8279 4874 8280 4875 8280 4881 8280 4881 8281 4875 8281 4876 8281 4880 8282 4882 8282 4883 8282 4881 8283 4880 8283 4883 8283 4883 8284 4885 8284 4884 8284 4881 8285 4883 8285 4884 8285 4888 8286 4885 8286 4883 8286 4889 8287 4885 8287 4888 8287 4889 8288 4886 8288 4885 8288 4890 8289 4862 8289 4861 8289 4884 8290 4885 8290 4886 8290 4887 8291 4890 8291 4861 8291 4884 8292 4886 8292 4861 8292 4861 8293 4886 8293 4887 8293 4865 8294 4862 8294 4890 8294 4887 8295 4893 8295 4892 8295 4873 8296 4891 8296 4899 8296 4891 8297 4873 8297 4872 8297 4892 8298 4865 8298 4890 8298 4892 8299 4890 8299 4887 8299 4893 8300 4894 8300 4895 8300 4893 8301 4895 8301 4896 8301 4893 8302 4887 8302 4897 8302 4893 6280 4897 6280 4898 6280 4893 8303 4898 8303 4894 8303 4904 8304 4865 8304 4892 8304 4904 8305 4866 8305 4865 8305 4899 8306 4900 8306 4901 8306 4899 8307 4901 8307 4902 8307 4899 8308 4902 8308 4873 8308 4882 8309 4876 8309 4896 8309 4896 8310 4876 8310 4899 8310 4899 8311 4876 8311 4903 8311 4899 8312 4903 8312 4900 8312 4904 8313 4867 8313 4866 8313 4891 8314 4872 8314 4871 8314 4891 8315 4871 8315 4904 8315 4896 8316 4883 8316 4882 8316 4904 8317 4871 8317 4867 8317 4895 8318 4905 8318 4896 8318 4896 8319 4905 8319 4883 8319 4892 8320 4893 8320 4906 8320 4906 8321 4907 8321 4892 8321 4892 8322 4907 8322 4904 8322 4904 8323 4907 8323 4908 8323 4904 8324 4908 8324 4891 8324 4908 8325 4909 8325 4891 8325 4910 8326 4891 8326 4909 8326 4899 8327 4891 8327 4910 8327 4910 8328 4911 8328 4899 8328 4899 8329 4911 8329 4896 8329 4896 8330 4911 8330 4912 8330 4896 8331 4912 8331 4893 8331 4912 8332 4913 8332 4893 8332 4906 8333 4893 8333 4913 8333 4914 8334 4906 8334 4913 8334 4914 8335 4913 8335 4912 8335 4914 8336 4912 8336 4915 8336 4915 8337 4912 8337 4916 8337 4916 8338 4912 8338 4911 8338 4916 8339 4911 8339 4917 8339 4917 8340 4911 8340 4910 8340 4917 8341 4910 8341 4918 8341 4918 8342 4910 8342 4909 8342 4918 8343 4909 8343 4908 8343 4918 8344 4908 8344 4919 8344 4919 8345 4908 8345 4920 8345 4920 8346 4908 8346 4907 8346 4920 8347 4907 8347 4921 8347 4921 8348 4907 8348 4906 8348 4921 8349 4906 8349 4914 8349 4922 8350 4918 8350 4923 8350 4918 8351 4919 8351 4923 8351 4923 8352 4919 8352 4924 8352 4919 8353 4920 8353 4924 8353 4924 8354 4920 8354 4925 8354 4920 8355 4921 8355 4925 8355 4914 8356 4926 8356 4921 8356 4921 8357 4926 8357 4925 8357 4926 8358 4914 8358 4927 8358 4914 8359 4915 8359 4927 8359 4915 8360 4916 8360 4927 8360 4927 8361 4916 8361 4928 8361 4916 8362 4917 8362 4928 8362 4928 8363 4917 8363 4922 8363 4918 8364 4922 8364 4917 8364 4928 8365 4922 8365 4874 8365 4874 8366 4922 8366 4869 8366 4869 8367 4922 8367 4923 8367 4864 8368 4924 8368 4861 8368 4861 8369 4924 8369 4925 8369 4881 8370 4927 8370 4928 8370 4881 8371 4928 8371 4874 8371 4869 8372 4923 8372 4864 8372 4864 8373 4923 8373 4924 8373 4861 8374 4925 8374 4884 8374 4884 8375 4925 8375 4926 8375 4884 8376 4926 8376 4927 8376 4884 8377 4927 8377 4881 8377 4931 348 4932 348 4933 348 4933 348 4932 348 4934 348 4931 8378 4933 8378 4935 8378 4937 348 4936 348 4938 348 4937 348 4938 348 4935 348 4941 348 4937 348 4942 348 4939 348 4943 348 4940 348 4940 348 4943 348 4932 348 4932 348 4943 348 4944 348 4932 348 4944 348 4934 348 4946 348 4945 348 4947 348 4948 348 4949 348 4950 348 4949 348 4951 348 4950 348 4950 8379 4951 8379 4952 8379 4958 8380 4959 8380 4960 8380 4960 348 4959 348 4961 348 4961 8381 4962 8381 4931 8381 4931 8382 4962 8382 4932 8382 4932 348 4962 348 4963 348 4963 348 4964 348 4932 348 4932 348 4964 348 4960 348 4960 348 4964 348 4958 348 4931 8383 4960 8383 4961 8383 4965 8384 4966 8384 4967 8384 4967 348 4966 348 4968 348 4968 348 4969 348 4967 348 4967 348 4969 348 4931 348 4931 8385 4969 8385 4970 8385 4971 348 4972 348 4965 348 4965 348 4972 348 4966 348 4973 348 4931 348 5057 348 4974 348 4967 348 4975 348 4975 348 4967 348 4931 348 4975 348 4931 348 4973 348 4940 8386 4976 8386 4977 8386 4978 8387 4979 8387 5013 8387 5013 8388 4979 8388 4980 8388 5013 348 4980 348 4940 348 4940 348 4980 348 4981 348 4940 348 4981 348 4976 348 4942 348 4939 348 4941 348 4941 348 4939 348 4940 348 4941 348 4940 348 4982 348 4982 348 4940 348 4977 348 4941 348 4982 348 4983 348 4941 348 4983 348 4984 348 4941 348 4984 348 4957 348 4957 348 4984 348 4985 348 4957 8389 4985 8389 4978 8389 4950 348 4945 348 4948 348 4948 348 4945 348 4986 348 4987 348 4988 348 4952 348 4987 8386 4989 8386 4988 8386 4988 348 4989 348 4990 348 4988 348 4990 348 4995 348 4995 348 4990 348 4991 348 4995 8388 4991 8388 4992 8388 4993 348 4994 348 4995 348 4995 8390 4994 8390 4996 8390 4995 348 4996 348 4997 348 4997 348 4996 348 4998 348 4997 348 4998 348 4999 348 4999 348 5000 348 4997 348 4997 8391 5000 8391 5001 8391 4997 8392 5001 8392 5002 8392 5004 348 5005 348 4946 348 4946 348 5005 348 5006 348 4946 8393 5006 8393 5007 8393 4946 8394 5007 8394 4993 8394 5008 348 5009 348 5010 348 5010 348 5009 348 4930 348 5008 8395 5011 8395 5009 8395 5009 348 5011 348 5012 348 5009 348 5012 348 5013 348 5014 348 5015 348 5016 348 5016 348 5015 348 5013 348 5016 8396 5013 8396 5017 8396 5017 348 5013 348 5012 348 5014 348 5018 348 5015 348 5015 8393 5018 8393 5019 8393 5015 348 5019 348 5020 348 5015 8397 5020 8397 4930 8397 4930 348 5020 348 5021 348 4930 348 5021 348 5022 348 4930 348 5022 348 5010 348 5001 348 5004 348 5002 348 5002 348 5004 348 4946 348 5002 348 4946 348 5023 348 4930 348 4929 348 5015 348 5027 348 5023 348 5028 348 5029 348 5030 348 5031 348 5032 348 5033 348 5040 348 5040 8398 5033 8398 5034 8398 5040 8399 5034 8399 5025 8399 5025 348 5034 348 5026 348 5026 348 5034 348 5035 348 5026 348 5035 348 5023 348 5023 348 5035 348 5028 348 5028 348 5036 348 5027 348 5027 8400 5036 8400 5031 8400 5037 348 5038 348 5009 348 5009 348 5038 348 5039 348 5009 348 5039 348 4930 348 4930 348 5039 348 5040 348 5041 348 5042 348 5043 348 5043 348 5042 348 5030 348 5040 348 5044 348 5030 348 5030 348 5044 348 5043 348 5042 348 5041 348 5045 348 5045 348 5041 348 5037 348 5045 348 5037 348 5009 348 5046 348 4997 348 5047 348 5047 348 4997 348 5002 348 5047 348 5002 348 5048 348 5046 348 5049 348 4997 348 4997 348 5049 348 5050 348 5050 348 5049 348 5051 348 5050 8401 5051 8401 5027 8401 5027 348 5051 348 5052 348 5052 348 5053 348 5027 348 5027 348 5053 348 5023 348 5023 348 5053 348 5048 348 5023 8402 5048 8402 5002 8402 4967 348 4974 348 5054 348 4967 348 5054 348 4988 348 5054 348 5055 348 4988 348 4988 348 5055 348 5056 348 4988 8403 5056 8403 4952 8403 4952 348 5056 348 5057 348 4952 348 5057 348 4950 348 5058 348 4931 348 5059 348 5059 348 4931 348 4935 348 5059 348 4935 348 4938 348 5058 8404 5060 8404 4955 8404 4955 8405 5060 8405 5061 8405 4955 348 5061 348 4936 348 5062 348 5063 348 5085 348 5064 348 5065 348 5066 348 5066 348 5065 348 5085 348 5066 348 5085 348 5063 348 5067 348 5042 348 5065 348 5067 348 5065 348 5064 348 5067 348 5068 348 5042 348 5042 8406 5068 8406 5030 8406 4957 348 4954 348 4941 348 4941 8407 4954 8407 4955 8407 4941 348 4955 348 4937 348 4937 348 4955 348 4936 348 4930 348 5040 348 4929 348 4929 348 5040 348 5025 348 5040 348 5030 348 5032 348 5032 348 5030 348 5029 348 4978 348 5013 348 5015 348 4978 348 5015 348 4957 348 4957 348 5015 348 4956 348 4956 348 5015 348 5024 348 4965 348 4960 348 4931 348 4965 348 4931 348 4971 348 4971 8408 4931 8408 4970 8408 5069 8409 5070 8409 5003 8409 5071 348 5072 348 4956 348 5072 348 5073 348 4956 348 4956 348 5073 348 4947 348 5073 348 5074 348 4947 348 4947 348 5074 348 5075 348 4947 348 5075 348 5003 348 5003 8410 5075 8410 5069 8410 5024 8411 5003 8411 5070 8411 5070 8412 5076 8412 5024 8412 5024 348 5076 348 5077 348 5024 348 5077 348 4956 348 4956 8413 5077 8413 5071 8413 4931 8414 5058 8414 4955 8414 4931 8415 4955 8415 4953 8415 4931 8416 4953 8416 4950 8416 4931 8417 4950 8417 5057 8417 5003 348 4946 348 4947 348 4993 348 4995 348 4946 348 4946 348 4995 348 4945 348 4945 348 4995 348 4992 348 4945 8418 4992 8418 4986 8418 5050 348 5078 348 5079 348 5079 348 5078 348 5080 348 5080 348 5081 348 5079 348 5079 8419 5081 8419 5085 8419 5085 8420 5081 8420 5082 8420 5050 8421 5027 8421 5084 8421 5050 348 5084 348 5078 348 5082 348 5083 348 5085 348 5085 8422 5083 8422 5027 8422 5085 8423 5027 8423 5031 8423 5085 348 5031 348 5030 348 5085 8424 5030 8424 5062 8424 5092 324 5093 324 5094 324 5097 8425 5096 8425 5166 8425 5102 324 5103 324 5104 324 5104 8426 5103 8426 5105 8426 5105 8427 5103 8427 5106 8427 5105 324 5106 324 5107 324 5107 8428 5106 8428 5108 8428 5107 324 5108 324 5109 324 5108 8429 5110 8429 5109 8429 5109 324 5110 324 5111 324 5109 8430 5111 8430 5112 8430 5111 324 5113 324 5112 324 5104 324 5113 324 5102 324 5115 8431 5114 8431 5116 8431 5117 8432 5118 8432 5119 8432 5119 324 5118 324 5120 324 5119 324 5120 324 5121 324 5116 324 5121 324 5120 324 5117 324 5122 324 5118 324 5118 324 5122 324 5123 324 5123 324 5122 324 5124 324 5124 8433 5122 8433 5125 8433 5126 324 5113 324 5127 324 5127 8434 5113 8434 5104 8434 5127 324 5104 324 5128 324 5093 324 5132 324 5094 324 5093 324 5134 324 5132 324 5132 8435 5134 8435 5112 8435 5132 324 5112 324 5113 324 5132 324 5113 324 5135 324 5135 324 5113 324 5137 324 5137 8436 5113 8436 5126 8436 5138 324 5131 324 5139 324 5138 324 5139 324 5140 324 5138 324 5136 324 5131 324 5131 324 5136 324 5130 324 5130 324 5136 324 5135 324 5130 8437 5135 8437 5137 8437 5140 8438 5142 8438 5143 8438 5143 324 5144 324 5145 324 5145 8439 5144 8439 5146 8439 5145 324 5146 324 5118 324 5118 8440 5146 8440 5147 8440 5118 8441 5147 8441 5120 8441 5109 8442 5148 8442 5149 8442 5109 324 5149 324 5087 324 5087 324 5149 324 5150 324 5087 8443 5150 8443 5094 8443 5094 8444 5150 8444 5092 8444 5109 8445 5112 8445 5148 8445 5087 8446 5151 8446 5152 8446 5153 324 5154 324 5096 324 5096 324 5154 324 5095 324 5095 8447 5154 8447 5155 8447 5095 8448 5155 8448 5156 8448 5087 324 5152 324 5157 324 5157 8449 5152 8449 5158 8449 5157 8450 5158 8450 5153 8450 5163 324 5145 324 5164 324 5164 324 5145 324 5162 324 5164 324 5162 324 5161 324 5163 324 5165 324 5099 324 5166 8451 5167 8451 5091 8451 5091 324 5167 324 5168 324 5091 324 5170 324 5171 324 5091 8452 5171 8452 5172 8452 5091 324 5172 324 5173 324 5169 8453 5174 8453 5168 8453 5168 324 5174 324 5175 324 5168 8454 5175 8454 5091 8454 5091 8455 5175 8455 5170 8455 5173 8456 5172 8456 5176 8456 5168 8457 5178 8457 5173 8457 5168 324 5173 324 5169 324 5169 8458 5173 8458 5176 8458 5177 324 5180 324 5179 324 5179 324 5180 324 5181 324 5179 324 5181 324 5168 324 5168 8459 5181 8459 5178 8459 5184 8460 5185 8460 5186 8460 5186 324 5185 324 5182 324 5182 8461 5185 8461 5183 8461 5182 8462 5187 8462 5188 8462 5182 8463 5188 8463 5186 8463 5186 8464 5188 8464 5189 8464 5191 8465 5190 8465 5192 8465 5189 8466 5193 8466 5186 8466 5186 324 5193 324 5191 324 5191 324 5193 324 5194 324 5191 8467 5194 8467 5190 8467 5162 8468 5196 8468 5197 8468 5178 324 5198 324 5173 324 5173 8469 5198 8469 5196 8469 5173 324 5196 324 5162 324 5160 8470 5161 8470 5159 8470 5159 8471 5161 8471 5162 8471 5159 324 5162 324 5195 324 5195 324 5162 324 5197 324 5180 324 5177 324 5159 324 5180 324 5159 324 5195 324 5199 324 5157 324 5153 324 5199 324 5153 324 5200 324 5200 8472 5153 8472 5097 8472 5096 8473 5097 8473 5153 8473 5199 8474 5201 8474 5157 8474 5157 324 5201 324 5186 324 5186 8475 5201 8475 5184 8475 5090 8476 5089 8476 5100 8476 5100 8477 5089 8477 5202 8477 5202 324 5203 324 5166 324 5166 8478 5203 8478 5167 8478 5168 324 5167 324 5179 324 5088 324 5095 324 5087 324 5087 324 5095 324 5156 324 5087 8479 5156 8479 5151 8479 5204 324 5205 324 5206 324 5207 324 5086 324 5208 324 5208 324 5086 324 5206 324 5208 324 5206 324 5205 324 5209 324 5105 324 5086 324 5209 8480 5086 8480 5207 8480 5209 8481 5210 8481 5105 8481 5105 8482 5210 8482 5104 8482 5166 324 5091 324 5191 324 5166 324 5191 324 5182 324 5182 8483 5191 8483 5192 8483 5182 8484 5192 8484 5187 8484 5202 324 5166 324 5100 324 5166 8485 5182 8485 5097 8485 5097 324 5182 324 5183 324 5211 324 5088 324 5133 324 5133 324 5088 324 5094 324 5094 324 5088 324 5087 324 5211 8486 5212 8486 5088 8486 5088 8487 5212 8487 5213 8487 5098 324 5088 324 5213 324 5098 8488 5213 8488 5214 8488 5098 8489 5214 8489 5215 8489 5098 324 5215 324 5141 324 5215 324 5216 324 5141 324 5141 8490 5216 8490 5217 8490 5141 324 5217 324 5133 324 5133 324 5217 324 5211 324 5141 324 5140 324 5098 324 5098 324 5140 324 5099 324 5101 324 5160 324 5159 324 5101 324 5159 324 5090 324 5090 324 5159 324 5177 324 5090 8491 5177 8491 5089 8491 5139 324 5142 324 5140 324 5090 324 5099 324 5101 324 5101 324 5099 324 5165 324 5131 324 5115 324 5116 324 5131 8492 5116 8492 5139 8492 5139 8493 5116 8493 5120 8493 5140 324 5143 324 5145 324 5140 324 5145 324 5099 324 5099 324 5145 324 5163 324 5218 324 5219 324 5115 324 5206 8494 5220 8494 5218 8494 5219 324 5221 324 5115 324 5115 324 5221 324 5124 324 5115 8495 5124 8495 5114 8495 5114 324 5124 324 5125 324 5204 324 5206 324 5104 324 5104 324 5206 324 5128 324 5128 8496 5206 8496 5129 8496 5129 8497 5206 8497 5115 8497 5115 8498 5206 8498 5218 8498 5124 8499 5221 8499 5222 8499 5124 324 5222 324 5225 324 5225 8500 5222 8500 5223 8500 5225 8501 5223 8501 5224 8501 5225 324 5224 324 5206 324 5206 8502 5224 8502 5220 8502 5206 324 5086 324 5225 324 4965 8503 4967 8503 5191 8503 5191 8504 4967 8504 5186 8504 5091 8505 4960 8505 4965 8505 5091 8505 4965 8505 5191 8505 4960 8506 5091 8506 4932 8506 4932 8506 5091 8506 5173 8506 5225 8507 5065 8507 5124 8507 5124 8507 5065 8507 5042 8507 5124 8507 5042 8507 5123 8507 5123 8507 5042 8507 5045 8507 5123 8507 5045 8507 5118 8507 5118 8507 5045 8507 5009 8507 5118 8507 5009 8507 5145 8507 5145 8507 5009 8507 5013 8507 5145 8507 5013 8507 5162 8507 5162 8507 5013 8507 4940 8507 5162 8507 4940 8507 5173 8507 5173 8507 4940 8507 4932 8507 5086 8508 5079 8508 5085 8508 5086 8509 5085 8509 5225 8509 5225 8510 5085 8510 5065 8510 5186 8511 4967 8511 5157 8511 5157 8511 4967 8511 4988 8511 5157 8511 4988 8511 5087 8511 5087 8511 4988 8511 4995 8511 5087 8511 4995 8511 5109 8511 5109 8511 4995 8511 4997 8511 5109 8511 4997 8511 5107 8511 5107 8512 4997 8512 5050 8512 5107 8511 5050 8511 5105 8511 5105 8511 5050 8511 5086 8511 5086 8511 5050 8511 5079 8511 5213 8513 5226 8513 5214 8513 5214 8514 5226 8514 5072 8514 5214 8515 5072 8515 5071 8515 5214 8516 5071 8516 5215 8516 5215 8517 5071 8517 5077 8517 5215 8518 5077 8518 5216 8518 5216 8519 5077 8519 5076 8519 5216 8520 5076 8520 5217 8520 5217 8521 5076 8521 5070 8521 5217 8522 5070 8522 5211 8522 5211 8523 5070 8523 5069 8523 5211 8524 5069 8524 5075 8524 5211 8525 5075 8525 5212 8525 5212 8526 5075 8526 5074 8526 5212 8527 5074 8527 5213 8527 5213 8528 5074 8528 5226 8528 5161 8529 4982 8529 4977 8529 5161 8530 4977 8530 5164 8530 5164 8531 4977 8531 4976 8531 5164 8532 4976 8532 4981 8532 5164 8533 4981 8533 5163 8533 5163 8534 4981 8534 4980 8534 5163 8535 4980 8535 4979 8535 5163 8536 4979 8536 5165 8536 5165 8537 4979 8537 4978 8537 5165 8538 4978 8538 5101 8538 5101 8539 4978 8539 4985 8539 5101 8540 4985 8540 4984 8540 5101 8541 4984 8541 5160 8541 5160 8542 4984 8542 4983 8542 5160 8543 4983 8543 4982 8543 5160 8544 4982 8544 5161 8544 5153 8545 4952 8545 5154 8545 5154 8546 4952 8546 4951 8546 5154 8547 4951 8547 4949 8547 5154 8548 4949 8548 5155 8548 5155 8549 4949 8549 4948 8549 5155 8550 4948 8550 5156 8550 5156 8551 4948 8551 4986 8551 5156 8552 4986 8552 5151 8552 5151 8553 4986 8553 4992 8553 5151 8554 4992 8554 5152 8554 5152 8555 4992 8555 4991 8555 5152 8556 4991 8556 4990 8556 5152 8557 4990 8557 5158 8557 5158 8558 4990 8558 4989 8558 5158 8559 4989 8559 4987 8559 5158 8560 4987 8560 5153 8560 5153 8561 4987 8561 4952 8561 5092 8562 4993 8562 5007 8562 5092 8563 5007 8563 5093 8563 5093 8564 5007 8564 5006 8564 5093 8565 5006 8565 5005 8565 5093 8566 5005 8566 5134 8566 5134 8567 5005 8567 5004 8567 5134 8568 5004 8568 5112 8568 5112 8569 5004 8569 5001 8569 5112 8570 5001 8570 5148 8570 5148 8571 5001 8571 5000 8571 5148 8572 5000 8572 4999 8572 5148 8573 4999 8573 5149 8573 5149 8574 4999 8574 4998 8574 5149 8575 4998 8575 4996 8575 5149 8576 4996 8576 5150 8576 5150 8577 4996 8577 4994 8577 5150 8578 4994 8578 5092 8578 5092 8579 4994 8579 4993 8579 5143 8580 5014 8580 5144 8580 5144 8581 5014 8581 5016 8581 5144 8582 5016 8582 5146 8582 5146 8583 5016 8583 5017 8583 5146 8584 5017 8584 5012 8584 5146 8533 5012 8533 5147 8533 5147 8585 5012 8585 5011 8585 5147 8586 5011 8586 5008 8586 5147 8587 5008 8587 5120 8587 5120 8588 5008 8588 5010 8588 5120 8589 5010 8589 5022 8589 5120 8590 5022 8590 5139 8590 5139 8591 5022 8591 5021 8591 5139 8592 5021 8592 5020 8592 5139 8593 5020 8593 5142 8593 5142 8594 5020 8594 5019 8594 5142 8595 5019 8595 5143 8595 5143 8596 5019 8596 5018 8596 5143 8597 5018 8597 5014 8597 5104 8598 5027 8598 5204 8598 5204 8599 5027 8599 5083 8599 5204 8600 5083 8600 5205 8600 5205 8601 5083 8601 5082 8601 5205 8602 5082 8602 5208 8602 5208 8603 5082 8603 5081 8603 5208 8604 5081 8604 5207 8604 5207 8605 5081 8605 5080 8605 5207 8606 5080 8606 5209 8606 5209 8607 5080 8607 5078 8607 5209 8608 5078 8608 5210 8608 5210 8609 5078 8609 5084 8609 5210 8610 5084 8610 5104 8610 5104 8611 5084 8611 5027 8611 5221 8598 5068 8598 5222 8598 5222 8599 5068 8599 5067 8599 5222 8612 5067 8612 5223 8612 5223 8613 5067 8613 5064 8613 5223 8614 5064 8614 5224 8614 5224 8615 5064 8615 5066 8615 5224 8616 5066 8616 5220 8616 5220 8617 5066 8617 5063 8617 5220 8618 5063 8618 5218 8618 5218 8619 5063 8619 5062 8619 5218 8620 5062 8620 5219 8620 5219 8621 5062 8621 5030 8621 5219 8622 5030 8622 5221 8622 5221 8623 5030 8623 5068 8623 5190 8624 4972 8624 5192 8624 5192 8625 4972 8625 4971 8625 5192 8626 4971 8626 5187 8626 5187 8627 4971 8627 4970 8627 5187 8628 4970 8628 5188 8628 5188 8629 4970 8629 4969 8629 5188 8630 4969 8630 5189 8630 5189 8631 4969 8631 4968 8631 5189 8632 4968 8632 5193 8632 5193 8633 4968 8633 4966 8633 5193 8634 4966 8634 5194 8634 5194 8635 4966 8635 5190 8635 5190 8636 4966 8636 4972 8636 5171 8624 4958 8624 5172 8624 5172 8599 4958 8599 4964 8599 5172 8637 4964 8637 5176 8637 5176 8638 4964 8638 4963 8638 5176 8639 4963 8639 5169 8639 5169 8629 4963 8629 4962 8629 5169 8640 4962 8640 5174 8640 5174 8641 4962 8641 4961 8641 5174 8632 4961 8632 5175 8632 5175 8642 4961 8642 4959 8642 5175 8643 4959 8643 5170 8643 5170 8644 4959 8644 5171 8644 5171 8645 4959 8645 4958 8645 5026 8505 5135 8505 5025 8505 5025 8505 5135 8505 5136 8505 4929 8511 5138 8511 5015 8511 5015 8511 5138 8511 5140 8511 5133 8646 5003 8646 5141 8646 5141 8646 5003 8646 5024 8646 4946 8507 5094 8507 5132 8507 4946 8647 5132 8647 5023 8647 4946 8577 5003 8577 5094 8577 5094 8648 5003 8648 5133 8648 5026 8649 5023 8649 5135 8649 5135 8649 5023 8649 5132 8649 4929 8650 5025 8650 5138 8650 5138 8650 5025 8650 5136 8650 5024 8651 5015 8651 5141 8651 5141 8652 5015 8652 5140 8652 5031 8505 5128 8505 5129 8505 5031 8505 5129 8505 5029 8505 5115 8511 5131 8511 5032 8511 5032 8511 5131 8511 5033 8511 5137 8646 5035 8646 5130 8646 5130 8646 5035 8646 5034 8646 5126 8507 5127 8507 5028 8507 5028 8507 5127 8507 5036 8507 5028 8577 5035 8577 5126 8577 5126 8653 5035 8653 5137 8653 5031 8654 5036 8654 5128 8654 5128 8655 5036 8655 5127 8655 5032 8656 5029 8656 5115 8656 5115 8657 5029 8657 5129 8657 5034 8658 5033 8658 5130 8658 5130 8659 5033 8659 5131 8659 5121 8660 5040 8660 5119 8660 5119 8661 5040 8661 5039 8661 5119 8662 5039 8662 5117 8662 5117 8663 5039 8663 5038 8663 5117 8664 5038 8664 5122 8664 5122 8665 5038 8665 5037 8665 5125 8666 5041 8666 5114 8666 5114 8667 5041 8667 5043 8667 5114 8668 5043 8668 5116 8668 5116 8669 5043 8669 5044 8669 5041 8670 5125 8670 5037 8670 5037 8671 5125 8671 5122 8671 5116 8672 5044 8672 5121 8672 5121 8673 5044 8673 5040 8673 5108 8674 5049 8674 5110 8674 5110 8675 5049 8675 5046 8675 5110 8676 5046 8676 5111 8676 5111 8677 5046 8677 5047 8677 5111 8678 5047 8678 5113 8678 5113 8679 5047 8679 5048 8679 5102 8680 5053 8680 5103 8680 5103 8681 5053 8681 5052 8681 5103 8682 5052 8682 5106 8682 5106 8683 5052 8683 5051 8683 5053 8684 5102 8684 5048 8684 5048 8671 5102 8671 5113 8671 5106 8685 5051 8685 5108 8685 5108 8686 5051 8686 5049 8686 5166 8646 4953 8646 5100 8646 5100 8646 4953 8646 4955 8646 5095 8507 4945 8507 5096 8507 5096 8507 4945 8507 4950 8507 4947 8505 5088 8505 4956 8505 4956 8505 5088 8505 5098 8505 5090 8511 4954 8511 5099 8511 5099 8511 4954 8511 4957 8511 4947 8655 4945 8655 5088 8655 5088 8655 4945 8655 5095 8655 4950 8687 4953 8687 5096 8687 5096 8577 4953 8577 5166 8577 4955 8688 4954 8688 5100 8688 5100 8689 4954 8689 5090 8689 4957 8690 4956 8690 5099 8690 5099 8690 4956 8690 5098 8690 5196 8691 4943 8691 5197 8691 5197 8692 4943 8692 4939 8692 5197 8693 4939 8693 5195 8693 5195 8694 4939 8694 4942 8694 5195 8695 4942 8695 5180 8695 5180 8696 4942 8696 4937 8696 5181 8697 4935 8697 5178 8697 5178 8698 4935 8698 4933 8698 5178 8699 4933 8699 5198 8699 5198 8700 4933 8700 4934 8700 5198 8701 4934 8701 4944 8701 4935 8702 5181 8702 4937 8702 4937 8703 5181 8703 5180 8703 5198 8704 4944 8704 5196 8704 5196 8705 4944 8705 4943 8705 5097 8706 5057 8706 5200 8706 5200 8707 5057 8707 5056 8707 5200 8708 5056 8708 5199 8708 5199 8709 5056 8709 5055 8709 5199 8710 5055 8710 5201 8710 5201 8711 5055 8711 5054 8711 5184 8712 4974 8712 5185 8712 5185 8713 4974 8713 4975 8713 5185 8714 4975 8714 5183 8714 5183 8715 4975 8715 4973 8715 4974 8716 5184 8716 5054 8716 5054 8717 5184 8717 5201 8717 5183 8718 4973 8718 5097 8718 5097 8719 4973 8719 5057 8719 5203 8720 5058 8720 5167 8720 5167 8721 5058 8721 5059 8721 5167 8722 5059 8722 5179 8722 5179 8723 5059 8723 4938 8723 5177 8724 4936 8724 5089 8724 5089 8725 4936 8725 5061 8725 5089 8726 5061 8726 5202 8726 5202 8727 5061 8727 5060 8727 4936 8728 5177 8728 4938 8728 4938 8729 5177 8729 5179 8729 5202 8730 5060 8730 5203 8730 5203 8731 5060 8731 5058 8731 5227 8732 5228 8732 5229 8732 5230 8733 5234 8733 5231 8733 5230 8734 5231 8734 5227 8734 5227 8735 5231 8735 5228 8735 5232 8736 5233 8736 5234 8736 5232 8737 5234 8737 5230 8737 5235 8738 5236 8738 5232 8738 5232 8739 5236 8739 5233 8739 5240 8740 5237 8740 5235 8740 5235 8741 5237 8741 5238 8741 5235 8742 5238 8742 5236 8742 5229 8743 5239 8743 5240 8743 5240 8744 5239 8744 5241 8744 5240 8745 5241 8745 5237 8745 5228 8746 5242 8746 5229 8746 5229 8747 5242 8747 5239 8747 5243 8748 5244 8748 5245 8748 5245 8749 5244 8749 5246 8749 5246 8750 5244 8750 5247 8750 5246 8751 5247 8751 5248 8751 5248 8752 5247 8752 5249 8752 5248 8753 5249 8753 5250 8753 5250 8754 5249 8754 5251 8754 5251 8755 5249 8755 5252 8755 5251 8756 5252 8756 5253 8756 5253 8757 5252 8757 5254 8757 5253 8758 5254 8758 5255 8758 5255 8759 5254 8759 5256 8759 5256 8760 5254 8760 5257 8760 5256 8761 5257 8761 5258 8761 5258 8762 5257 8762 5259 8762 5258 8763 5259 8763 5260 8763 5260 8764 5259 8764 5261 8764 5260 8765 5261 8765 5262 8765 5262 8766 5261 8766 5263 8766 5263 8767 5261 8767 5264 8767 5263 8768 5264 8768 5265 8768 5265 8769 5264 8769 5266 8769 5265 8770 5266 8770 5267 8770 5267 8771 5266 8771 5268 8771 5268 8772 5266 8772 5269 8772 5268 8773 5269 8773 5270 8773 5270 8774 5269 8774 5271 8774 5271 8775 5269 8775 5272 8775 5271 8776 5272 8776 5273 8776 5273 8777 5272 8777 5274 8777 5273 8778 5274 8778 5275 8778 5275 8779 5274 8779 5276 8779 5276 8780 5274 8780 5277 8780 5276 8781 5277 8781 5278 8781 5277 8782 5279 8782 5278 8782 5278 8783 5279 8783 5280 8783 5280 8784 5279 8784 5281 8784 5280 8785 5281 8785 5282 8785 5282 8786 5281 8786 5283 8786 5282 8787 5283 8787 5284 8787 5284 8788 5283 8788 5285 8788 5285 8789 5283 8789 5286 8789 5285 8790 5286 8790 5287 8790 5287 8791 5286 8791 5288 8791 5288 8792 5286 8792 5289 8792 5288 8793 5289 8793 5290 8793 5290 8794 5289 8794 5291 8794 5291 8795 5289 8795 5292 8795 5291 8796 5292 8796 5293 8796 5293 8797 5292 8797 5294 8797 5293 8798 5294 8798 5243 8798 5243 8799 5294 8799 5244 8799 5295 8800 5296 8800 5297 8800 5296 8801 5295 8801 5298 8801 5298 8802 5295 8802 5299 8802 5298 8803 5299 8803 5300 8803 5300 8804 5299 8804 5301 8804 5301 8805 5302 8805 5300 8805 5302 8806 5301 8806 5303 8806 5303 8807 5304 8807 5302 8807 5304 8808 5303 8808 5305 8808 5305 8809 5306 8809 5304 8809 5306 8810 5305 8810 5307 8810 5307 8811 5308 8811 5306 8811 5308 8812 5307 8812 5309 8812 5309 8813 5310 8813 5308 8813 5310 8814 5309 8814 5311 8814 5311 8815 5312 8815 5310 8815 5312 8816 5311 8816 5313 8816 5312 8817 5313 8817 5314 8817 5312 8818 5314 8818 5315 8818 5316 8819 5315 8819 5314 8819 5315 8820 5316 8820 5317 8820 5317 8821 5316 8821 5318 8821 5317 8822 5318 8822 5297 8822 5297 8823 5318 8823 5295 8823 5297 8824 5304 8824 5317 8824 5304 8825 5315 8825 5317 8825 5304 8826 5319 8826 5315 8826 5304 8827 5308 8827 5319 8827 5304 8828 5300 8828 5302 8828 5297 8829 5296 8829 5304 8829 5304 8830 5296 8830 5300 8830 5336 8831 5231 8831 5320 8831 5320 8832 5231 8832 5321 8832 5231 8833 5322 8833 5321 8833 5321 8834 5322 8834 5323 8834 5322 8835 5324 8835 5323 8835 5323 8836 5324 8836 5325 8836 5323 8837 5325 8837 5326 8837 5326 8838 5325 8838 5233 8838 5326 8839 5233 8839 5327 8839 5233 8840 5236 8840 5327 8840 5236 8841 5238 8841 5327 8841 5327 8842 5238 8842 5328 8842 5238 8843 5237 8843 5328 8843 5328 8844 5237 8844 5329 8844 5237 8845 5241 8845 5329 8845 5329 8846 5241 8846 5330 8846 5241 8847 5331 8847 5330 8847 5330 8848 5331 8848 5239 8848 5330 8849 5239 8849 5332 8849 5239 8850 5333 8850 5332 8850 5332 8851 5333 8851 5334 8851 5333 8852 5335 8852 5334 8852 5334 8853 5335 8853 5336 8853 5334 8854 5336 8854 5320 8854 5233 8855 5325 8855 5234 8855 5234 8856 5325 8856 5324 8856 5324 8857 5322 8857 5234 8857 5234 8858 5322 8858 5231 8858 5231 8859 5336 8859 5228 8859 5228 8860 5336 8860 5335 8860 5228 8861 5335 8861 5242 8861 5335 8862 5333 8862 5242 8862 5242 8863 5333 8863 5239 8863 5239 8864 5331 8864 5241 8864 5312 8865 5315 8865 5319 8865 5312 8866 5319 8866 5310 8866 5310 8867 5319 8867 5308 8867 5306 8868 5308 8868 5304 8868 5298 8869 5300 8869 5296 8869 5232 8870 5337 8870 5235 8870 5230 8871 5338 8871 5232 8871 5227 8872 5339 8872 5230 8872 5229 8873 5340 8873 5227 8873 5240 8874 5341 8874 5229 8874 5235 8875 5342 8875 5240 8875 5344 8876 5348 8876 5349 8876 5343 8877 5344 8877 5349 8877 5344 8878 5347 8878 5348 8878 5346 8879 5347 8879 5344 8879 5345 8880 5346 8880 5344 8880 5343 8881 5345 8881 5344 8881 5232 8882 5347 8882 5337 8882 5346 8883 5235 8883 5337 8883 5337 8884 5347 8884 5346 8884 5338 8885 5230 8885 5348 8885 5347 8886 5232 8886 5338 8886 5348 8887 5347 8887 5338 8887 5349 8888 5339 8888 5227 8888 5348 8889 5230 8889 5339 8889 5348 8890 5339 8890 5349 8890 5349 8891 5227 8891 5343 8891 5343 8892 5227 8892 5340 8892 5343 8893 5340 8893 5229 8893 5240 8894 5345 8894 5341 8894 5341 8895 5345 8895 5343 8895 5341 8896 5343 8896 5229 8896 5235 8897 5346 8897 5342 8897 5345 8898 5240 8898 5342 8898 5342 8899 5346 8899 5345 8899 5350 8900 5316 8900 5353 8900 5353 8901 5316 8901 5354 8901 5354 8902 5316 8902 5314 8902 5314 8903 5313 8903 5355 8903 5355 8904 5313 8904 5311 8904 5355 8905 5311 8905 5356 8905 5356 8906 5311 8906 5357 8906 5357 8907 5311 8907 5309 8907 5357 8908 5309 8908 5358 8908 5358 8909 5309 8909 5359 8909 5359 8910 5309 8910 5307 8910 5359 8911 5307 8911 5360 8911 5360 8912 5307 8912 5305 8912 5360 8913 5305 8913 5361 8913 5361 8914 5305 8914 5362 8914 5362 8915 5305 8915 5303 8915 5362 8916 5303 8916 5363 8916 5363 8917 5303 8917 5364 8917 5364 8918 5303 8918 5301 8918 5364 8919 5301 8919 5365 8919 5365 8920 5301 8920 5299 8920 5365 8921 5299 8921 5366 8921 5367 8922 5295 8922 5351 8922 5351 8923 5295 8923 5318 8923 5295 8924 5367 8924 5352 8924 5352 8925 5366 8925 5299 8925 5352 8926 5299 8926 5295 8926 5350 8927 5351 8927 5318 8927 5350 8928 5318 8928 5316 8928 5371 348 5372 348 5373 348 5374 348 5375 348 5373 348 5378 348 5379 348 5530 348 5380 348 5515 348 5381 348 5382 348 5383 348 5384 348 5388 348 5389 348 5390 348 5391 348 5392 348 5393 348 5389 348 5394 348 5390 348 5390 348 5394 348 5395 348 5390 348 5395 348 5396 348 5396 348 5395 348 5397 348 5396 348 5397 348 5392 348 5392 348 5397 348 5393 348 5388 8929 5398 8929 5368 8929 5398 348 5399 348 5368 348 5368 348 5399 348 5400 348 5368 348 5400 348 5401 348 5401 348 5402 348 5403 348 5403 348 5402 348 5404 348 5403 348 5404 348 5405 348 5405 348 5404 348 5406 348 5405 348 5406 348 5407 348 5407 348 5406 348 5408 348 5410 348 5411 348 5412 348 5412 348 5411 348 5413 348 5414 348 5415 348 5416 348 5417 348 5418 348 5410 348 5410 348 5418 348 5419 348 5410 348 5419 348 5420 348 5420 348 5419 348 5421 348 5414 348 5416 348 5422 348 5414 348 5422 348 5423 348 5423 348 5422 348 5417 348 5421 348 5415 348 5420 348 5420 348 5415 348 5414 348 5420 348 5414 348 5424 348 5426 348 5427 348 5428 348 5430 348 5431 348 5432 348 5431 348 5430 348 5433 348 5431 348 5433 348 5434 348 5434 348 5433 348 5435 348 5386 348 5437 348 5436 348 5436 348 5437 348 5438 348 5439 348 5441 348 5387 348 5387 348 5441 348 5438 348 5440 348 5442 348 5439 348 5443 348 5444 348 5442 348 5445 348 5446 348 5443 348 5443 348 5446 348 5475 348 5444 348 5443 348 5475 348 5444 348 5475 348 5447 348 5449 348 5450 348 5451 348 5451 348 5448 348 5447 348 5449 348 5452 348 5453 348 5453 348 5452 348 5454 348 5453 348 5454 348 5383 348 5455 348 5384 348 5456 348 5383 348 5457 348 5458 348 5383 348 5458 348 5384 348 5384 348 5458 348 5456 348 5459 348 5460 348 5461 348 5462 348 5459 348 5463 348 5456 348 5464 348 5455 348 5455 348 5464 348 5463 348 5463 348 5464 348 5462 348 5460 348 5465 348 5461 348 5461 348 5465 348 5383 348 5383 348 5465 348 5457 348 5459 348 5461 348 5463 348 5463 348 5461 348 5466 348 5466 348 5467 348 5468 348 5469 348 5467 348 5470 348 5470 348 5467 348 5466 348 5470 348 5466 348 5471 348 5472 348 5473 348 5474 348 5469 348 5476 348 5467 348 5467 348 5476 348 5477 348 5467 348 5477 348 5475 348 5475 348 5477 348 5474 348 5474 348 5477 348 5472 348 5478 348 5475 348 5479 348 5478 348 5479 348 5480 348 5480 348 5479 348 5481 348 5483 348 5482 348 5743 348 5483 348 5743 348 5484 348 5484 8930 5743 8930 5485 8930 5487 348 5486 348 5484 348 5487 348 5488 348 5489 348 5489 348 5488 348 5490 348 5370 348 5491 348 5492 348 5370 348 5492 348 5490 348 5490 348 5492 348 5493 348 5494 348 5495 348 5493 348 5493 348 5496 348 5494 348 5494 348 5496 348 5497 348 5497 348 5498 348 5499 348 5500 348 5496 348 5515 348 5500 348 5515 348 5380 348 5500 348 5501 348 5496 348 5496 348 5501 348 5502 348 5496 348 5502 348 5497 348 5497 348 5502 348 5498 348 5498 348 5503 348 5499 348 5499 348 5503 348 5504 348 5504 348 5503 348 5505 348 5504 348 5505 348 5381 348 5381 348 5505 348 5506 348 5381 348 5506 348 5380 348 5507 348 5508 348 5509 348 5507 348 5509 348 5510 348 5507 348 5511 348 5508 348 5508 348 5511 348 5512 348 5511 348 5513 348 5512 348 5512 348 5513 348 5514 348 5515 348 5514 348 5516 348 5515 348 5516 348 5517 348 5517 348 5516 348 5509 348 5509 348 5516 348 5510 348 5370 348 5490 348 5518 348 5518 8931 5490 8931 5520 8931 5521 348 5522 348 5520 348 5520 8932 5522 8932 5518 8932 5521 348 5523 348 5524 348 5524 348 5523 348 5525 348 5524 348 5525 348 5526 348 5525 348 5527 348 5526 348 5528 348 5529 348 5530 348 5532 348 5533 348 5531 348 5531 348 5533 348 5528 348 5531 348 5528 348 5530 348 5533 348 5535 348 5528 348 5528 348 5535 348 5536 348 5536 348 5535 348 5537 348 5536 348 5537 348 5376 348 5538 348 5377 348 5539 348 5539 348 5377 348 5376 348 5539 348 5376 348 5537 348 5377 348 5538 348 5540 348 5377 348 5540 348 5531 348 5531 348 5540 348 5532 348 5377 348 5541 348 5376 348 5376 348 5541 348 5542 348 5376 348 5542 348 5543 348 5543 348 5542 348 5544 348 5544 348 5542 348 5545 348 5544 348 5545 348 5546 348 5545 348 5547 348 5546 348 5546 348 5547 348 5548 348 5548 348 5547 348 5549 348 5552 348 5550 348 5669 348 5669 348 5550 348 5551 348 5669 348 5551 348 5548 348 5669 348 5548 348 5549 348 5373 348 5554 348 5552 348 5373 348 5552 348 5374 348 5553 348 5554 348 5555 348 5556 348 5368 348 5558 348 5558 348 5559 348 5560 348 5559 348 5561 348 5560 348 5560 348 5561 348 5562 348 5560 348 5562 348 5563 348 5563 348 5562 348 5403 348 5562 348 5564 348 5403 348 5564 348 5565 348 5403 348 5403 348 5565 348 5566 348 5559 348 5558 348 5567 348 5567 348 5558 348 5368 348 5401 348 5403 348 5368 348 5368 348 5403 348 5566 348 5368 348 5566 348 5567 348 5568 348 5569 348 5393 348 5393 348 5569 348 5407 348 5393 348 5407 348 5408 348 5393 348 5408 348 5391 348 5568 348 5570 348 5569 348 5569 348 5570 348 5409 348 5570 348 5571 348 5409 348 5409 348 5571 348 5389 348 5389 348 5571 348 5394 348 5439 348 5572 348 5573 348 5574 348 5572 348 5575 348 5575 348 5572 348 5576 348 5573 348 5578 348 5439 348 5439 348 5578 348 5440 348 5440 348 5578 348 5579 348 5440 348 5579 348 5577 348 5580 348 5440 348 5577 348 5577 348 5581 348 5580 348 5580 348 5581 348 5575 348 5575 348 5581 348 5574 348 5576 348 5572 348 5439 348 5576 348 5439 348 5582 348 5576 8933 5582 8933 5583 8933 5583 348 5582 348 5525 348 5583 348 5525 348 5584 348 5584 348 5525 348 5585 348 5440 348 5580 348 5586 348 5414 348 5588 348 5589 348 5414 348 5589 348 5425 348 5425 348 5589 348 5427 348 5427 348 5589 348 5428 348 5432 348 5590 348 5591 348 5432 348 5591 348 5592 348 5592 348 5591 348 5593 348 5596 348 5597 348 5387 348 5598 348 5599 348 5600 348 5386 348 5601 348 5437 348 5387 348 5602 348 5598 348 5387 348 5598 348 5600 348 5423 348 5417 348 5410 348 5423 348 5410 348 5387 348 5602 348 5387 348 5597 348 5603 348 5531 348 5530 348 5603 348 5530 348 5379 348 5604 348 5605 348 5527 348 5527 348 5605 348 5378 348 5527 348 5378 348 5534 348 5604 348 5527 348 5373 348 5604 348 5373 348 5606 348 5603 348 5607 348 5531 348 5531 348 5607 348 5608 348 5514 348 5515 348 5512 348 5512 348 5515 348 5609 348 5496 348 5370 348 5610 348 5610 348 5611 348 5496 348 5496 348 5611 348 5612 348 5496 348 5612 348 5613 348 5496 348 5613 348 5515 348 5515 348 5613 348 5614 348 5515 348 5614 348 5609 348 5512 348 5615 348 5508 348 5508 348 5615 348 5616 348 5508 348 5616 348 5617 348 5370 348 5617 348 5618 348 5370 348 5618 348 5619 348 5370 348 5619 348 5610 348 5620 348 5370 348 5496 348 5620 348 5496 348 5621 348 5492 348 5622 348 5493 348 5493 348 5622 348 5623 348 5493 348 5623 348 5624 348 5493 348 5624 348 5496 348 5370 348 5625 348 5617 348 5617 348 5625 348 5626 348 5508 348 5629 348 5627 348 5519 348 5508 348 5627 348 5519 348 5627 348 5518 348 5518 348 5627 348 5628 348 5628 348 5631 348 5518 348 5518 348 5631 348 5370 348 5370 348 5631 348 5632 348 5370 348 5632 348 5625 348 5473 348 5471 348 5474 348 5474 348 5471 348 5633 348 5634 348 5635 348 5383 348 5383 348 5635 348 5636 348 5383 348 5636 348 5461 348 5471 348 5461 348 5637 348 5471 348 5637 348 5633 348 5638 348 5639 348 5640 348 5640 348 5639 348 5641 348 5640 348 5641 348 5642 348 5642 348 5641 348 5643 348 5454 348 5644 348 5383 348 5383 348 5644 348 5639 348 5639 348 5645 348 5641 348 5641 348 5645 348 5646 348 5641 348 5646 348 5647 348 5641 348 5650 348 5643 348 5643 348 5650 348 5651 348 5447 348 5648 348 5451 348 5451 348 5648 348 5652 348 5650 348 5653 348 5475 348 5648 348 5447 348 5654 348 5654 348 5447 348 5475 348 5475 348 5653 348 5655 348 5475 348 5655 348 5654 348 5373 348 5372 348 5608 348 5656 348 5531 348 5657 348 5657 348 5531 348 5608 348 5657 348 5608 348 5658 348 5658 348 5608 348 5372 348 5659 348 5660 348 5661 348 5661 348 5660 348 5662 348 5662 348 5660 348 5377 348 5662 348 5377 348 5663 348 5663 348 5377 348 5664 348 5664 348 5377 348 5665 348 5665 348 5377 348 5531 348 5665 348 5531 348 5666 348 5375 348 5667 348 5373 348 5659 348 5371 348 5660 348 5660 348 5371 348 5373 348 5660 348 5373 348 5668 348 5668 348 5373 348 5667 348 5668 348 5669 348 5660 348 5669 348 5670 348 5552 348 5552 348 5670 348 5671 348 5552 348 5671 348 5374 348 5672 348 5673 348 5660 348 5673 348 5674 348 5660 348 5660 348 5674 348 5377 348 5377 348 5674 348 5541 348 5594 348 5590 348 5432 348 5675 348 5432 348 5676 348 5592 348 5677 348 5432 348 5432 348 5677 348 5678 348 5432 348 5678 348 5676 348 5675 348 5679 348 5386 348 5386 348 5679 348 5680 348 5386 348 5680 348 5600 348 5600 348 5681 348 5387 348 5387 348 5681 348 5682 348 5387 348 5682 348 5423 348 5414 348 5423 348 5683 348 5414 348 5683 348 5592 348 5684 348 5685 348 5386 348 5386 348 5685 348 5675 348 5675 348 5685 348 5429 348 5433 348 5686 348 5435 348 5435 348 5686 348 5386 348 5386 348 5686 348 5684 348 5687 348 5688 348 5689 348 5687 348 5689 348 5690 348 5691 348 5692 348 5440 348 5687 348 5694 348 5688 348 5688 348 5694 348 5691 348 5688 348 5691 348 5695 348 5695 348 5691 348 5440 348 5695 348 5440 348 5586 348 5692 348 5696 348 5440 348 5440 348 5696 348 5442 348 5442 348 5696 348 5697 348 5442 348 5697 348 5693 348 5698 348 5699 348 5720 348 5720 348 5699 348 5700 348 5701 348 5702 348 5695 348 5586 8934 5703 8934 5704 8934 5695 348 5702 348 5700 348 5586 348 5704 348 5695 348 5695 8935 5704 8935 5701 8935 5700 8936 5702 8936 5705 8936 5700 8937 5705 8937 5720 8937 5720 8938 5705 8938 5706 8938 5706 348 5707 348 5720 348 5720 8939 5707 8939 5708 8939 5720 8940 5708 8940 5586 8940 5586 348 5708 348 5703 348 5709 348 5698 348 5520 348 5709 348 5520 348 5443 348 5689 348 5443 348 5442 348 5689 348 5442 348 5693 348 5689 348 5693 348 5690 348 5710 348 5525 348 5711 348 5711 348 5525 348 5712 348 5712 348 5525 348 5523 348 5713 348 5714 348 5523 348 5523 348 5714 348 5712 348 5710 348 5715 348 5525 348 5525 348 5715 348 5716 348 5525 348 5716 348 5585 348 5585 348 5716 348 5713 348 5717 348 5718 348 5521 348 5521 348 5718 348 5719 348 5521 348 5719 348 5720 348 5721 348 5720 348 5722 348 5722 348 5720 348 5719 348 5723 348 5698 348 5720 348 5723 348 5720 348 5724 348 5724 348 5720 348 5721 348 5725 348 5387 348 5410 348 5725 348 5410 348 5412 348 5387 348 5728 348 5439 348 5439 348 5728 348 5582 348 5727 348 5726 348 5729 348 5729 348 5726 348 5582 348 5727 348 5730 348 5726 348 5726 348 5730 348 5412 348 5475 348 5446 348 5731 348 5475 348 5731 348 5479 348 5479 348 5732 348 5733 348 5733 348 5732 348 5734 348 5734 348 5732 348 5735 348 5735 348 5736 348 5443 348 5443 348 5736 348 5445 348 5413 348 5737 348 5726 348 5413 348 5726 348 5412 348 5740 348 5739 348 5525 348 5740 348 5525 348 5582 348 5582 348 5728 348 5729 348 5741 348 5742 348 5743 348 5744 348 5741 348 5482 348 5745 348 5746 348 5481 348 5741 348 5747 348 5742 348 5747 348 5748 348 5742 348 5742 348 5748 348 5749 348 5482 348 5481 348 5746 348 5482 348 5746 348 5744 348 5479 348 5733 348 5481 348 5481 348 5733 348 5742 348 5481 348 5742 348 5749 348 5481 348 5749 348 5745 348 5734 348 5735 348 5443 348 5734 348 5443 348 5750 348 5750 348 5443 348 5520 348 5750 348 5520 348 5488 348 5482 348 5741 348 5743 348 5484 348 5485 348 5752 348 5753 348 5751 348 5754 348 5484 348 5752 348 5755 348 5484 348 5755 348 5487 348 5755 348 5756 348 5487 348 5487 348 5756 348 5754 348 5753 348 5757 348 5751 348 5751 348 5757 348 5485 348 5485 348 5757 348 5758 348 5485 348 5758 348 5752 348 5534 348 5378 348 5530 348 5531 348 5656 348 5666 348 5630 348 5509 348 5508 348 5508 348 5617 348 5629 348 5629 348 5617 348 5626 348 5621 348 5496 348 5624 348 5549 348 5672 348 5660 348 5549 348 5660 348 5669 348 5606 348 5373 348 5608 348 5620 348 5491 348 5370 348 5369 348 5368 348 5556 348 5369 348 5556 348 5739 348 5739 348 5556 348 5557 348 5759 348 5760 348 5557 348 5555 348 5759 348 5557 348 5555 348 5557 348 5553 348 5761 348 5525 348 5739 348 5761 348 5739 348 5762 348 5761 348 5763 348 5525 348 5525 348 5763 348 5555 348 5555 348 5763 348 5764 348 5555 348 5764 348 5759 348 5557 348 5760 348 5765 348 5557 348 5765 348 5739 348 5739 348 5765 348 5762 348 5766 348 5767 348 5488 348 5767 348 5768 348 5490 348 5490 348 5768 348 5769 348 5490 348 5769 348 5520 348 5520 348 5769 348 5770 348 5717 348 5521 348 5520 348 5520 348 5770 348 5771 348 5771 348 5772 348 5520 348 5520 348 5772 348 5488 348 5488 348 5772 348 5766 348 5754 348 5751 348 5487 348 5487 348 5751 348 5488 348 5490 348 5488 348 5767 348 5523 348 5521 348 5720 348 5523 348 5720 348 5713 348 5713 348 5720 348 5585 348 5585 348 5720 348 5587 348 5587 348 5720 348 5586 348 5520 348 5698 348 5717 348 5717 348 5698 348 5723 348 5388 348 5368 348 5738 348 5388 8941 5738 8941 5389 8941 5389 348 5738 348 5737 348 5389 348 5737 348 5413 348 5437 348 5596 348 5438 348 5438 348 5596 348 5387 348 5525 348 5555 348 5527 348 5527 8942 5555 8942 5554 8942 5527 348 5554 348 5373 348 5650 348 5475 348 5474 348 5650 348 5474 348 5651 348 5414 348 5592 348 5588 348 5588 348 5592 348 5593 348 5428 348 5595 348 5426 348 5426 348 5595 348 5594 348 5426 348 5594 348 5432 348 5430 348 5432 348 5675 348 5430 348 5675 348 5429 348 5599 348 5601 348 5600 348 5600 348 5601 348 5386 348 5435 348 5386 348 5385 348 5652 348 5649 348 5451 348 5451 348 5649 348 5641 348 5451 348 5641 348 5647 348 5451 348 5647 348 5449 348 5449 348 5647 348 5452 348 5638 348 5634 348 5639 348 5639 348 5634 348 5383 348 5471 348 5466 348 5461 348 5776 324 5777 324 5778 324 5781 324 5799 324 5782 324 5783 324 5784 324 5785 324 5788 324 5789 324 5790 324 5791 324 5792 324 5793 324 5794 324 5795 324 5796 324 5797 324 5798 324 5799 324 5797 324 5799 324 5800 324 5800 324 5799 324 5801 324 5800 324 5801 324 5802 324 5804 324 5805 324 5799 324 5805 324 5806 324 5799 324 5799 324 5806 324 5807 324 5799 324 5807 324 5801 324 5801 324 5807 324 5808 324 5801 324 5808 324 5803 324 5803 324 5809 324 5801 324 5801 324 5809 324 5810 324 5801 324 5810 324 5811 324 5812 324 5813 324 5814 324 5814 324 5813 324 5815 324 5814 324 5815 324 5816 324 5816 324 5815 324 5811 324 5816 324 5811 324 5817 324 5817 324 5811 324 5810 324 5818 324 5819 324 5820 324 5820 324 5819 324 5821 324 5820 324 5821 324 5822 324 5799 324 5822 324 5813 324 5823 324 5824 324 5825 324 5825 324 5824 324 5826 324 5827 324 5828 324 5829 324 5818 324 5825 324 5826 324 5826 324 5830 324 5818 324 5818 324 5830 324 5831 324 5818 324 5831 324 5828 324 5828 324 5831 324 5832 324 5828 324 5832 324 5829 324 5834 324 5835 324 5836 324 5836 324 5835 324 5837 324 5836 324 5837 324 5838 324 5838 324 5837 324 5839 324 5838 324 5839 324 5840 324 5840 324 5839 324 5841 324 5842 324 5843 324 5844 324 5843 324 5845 324 5844 324 5844 324 5845 324 5846 324 5844 324 5846 324 5840 324 5847 324 5848 324 5849 324 5849 324 5848 324 5850 324 5849 324 5850 324 5851 324 5851 324 5850 324 5840 324 5851 324 5840 324 5852 324 5852 324 5840 324 5846 324 5847 324 5853 324 5848 324 5848 324 5853 324 5854 324 5848 324 5854 324 5855 324 5855 324 5857 324 5848 324 5848 324 5857 324 5858 324 5848 324 5858 324 5859 324 5860 324 5818 324 5861 324 5861 324 5818 324 5862 324 5863 324 5864 324 5862 324 5862 324 5864 324 5861 324 5869 324 5870 324 5868 324 5868 324 5870 324 5865 324 5795 324 5874 324 5875 324 5874 324 5876 324 5875 324 5875 324 5876 324 5877 324 5875 324 5877 324 5773 324 5773 324 5877 324 5878 324 5879 324 5880 324 5881 324 5881 324 5880 324 5882 324 5881 324 5882 324 5796 324 5796 324 5882 324 5883 324 5796 324 5883 324 5794 324 5878 324 5884 324 5773 324 5773 324 5884 324 5885 324 5773 324 5885 324 5879 324 5879 324 5885 324 5886 324 5879 324 5886 324 5880 324 5887 324 5888 324 5889 324 5887 324 5889 324 5890 324 5890 324 5889 324 5891 324 5890 324 5891 324 5892 324 5892 324 5891 324 5893 324 5892 324 5893 324 5894 324 5893 324 5895 324 5894 324 5894 324 5895 324 5896 324 5894 324 5896 324 5897 324 5898 324 5899 324 5900 324 5898 324 5900 324 5901 324 5899 324 5902 324 5900 324 5900 324 5902 324 5903 324 5900 324 5903 324 5887 324 5887 324 5903 324 5904 324 5887 324 5904 324 5888 324 5896 324 5905 324 5897 324 5897 324 5905 324 5906 324 5897 324 5906 324 5901 324 5901 324 5900 324 5897 324 5897 324 5900 324 5907 324 5910 324 5908 324 5909 324 5909 324 5911 324 5910 324 5910 324 5911 324 5912 324 5910 324 5912 324 5914 324 5914 324 5915 324 5916 324 5916 324 5915 324 5917 324 5919 324 5918 324 5920 324 5921 324 5920 324 5922 324 5922 324 5920 324 5923 324 5922 324 5923 324 5924 324 5924 324 5923 324 5925 324 5926 324 5927 324 5928 324 5929 324 5925 324 5789 324 5927 324 5930 324 5928 324 5928 324 5930 324 5931 324 5928 324 5931 324 5789 324 5789 324 5931 324 5932 324 5933 324 5934 324 5791 324 5932 324 5935 324 5789 324 5789 324 5935 324 5936 324 5789 324 5936 324 5929 324 5929 324 5936 324 5937 324 5929 324 5937 324 5938 324 5938 324 5934 324 5929 324 5929 324 5934 324 5933 324 5939 324 5933 324 5940 324 5939 324 5940 324 5941 324 5942 324 5943 324 5941 324 5941 324 5943 324 5944 324 5940 324 5945 324 5946 324 5940 324 5946 324 5941 324 5941 324 5946 324 5947 324 5941 324 5947 324 5942 324 5958 324 5948 324 5940 324 5940 324 5948 324 5949 324 5940 324 5949 324 5945 324 5943 324 5950 324 5944 324 5944 324 5950 324 5951 324 5944 324 5951 324 5952 324 5951 324 5953 324 5952 324 5952 324 5953 324 5954 324 5952 324 5954 324 5958 324 5954 324 5955 324 5958 324 5958 324 5955 324 5956 324 5958 324 5956 324 5957 324 5958 324 5957 324 5948 324 5958 324 5959 324 5960 324 5960 324 5959 324 5961 324 5960 324 5961 324 5962 324 5962 324 5961 324 5963 324 5790 324 5964 324 5788 324 5967 324 5966 324 5964 324 5968 324 5969 324 5970 324 5968 324 5970 324 6241 324 6241 324 5970 324 5971 324 5969 324 5972 324 5970 324 5970 324 5972 324 5973 324 5970 324 5973 324 5974 324 5974 324 5973 324 5975 324 5974 324 5975 324 5976 324 5976 324 5975 324 5977 324 5976 324 5978 324 5979 324 5979 324 5978 324 5980 324 5979 324 5980 324 5981 324 5981 324 5980 324 5982 324 5981 324 5982 324 5983 324 5982 324 5984 324 5983 324 5983 324 5984 324 5985 324 5983 324 5985 324 5784 324 5784 324 5985 324 5986 324 5987 324 5988 324 5989 324 5990 324 5991 324 5784 324 5778 324 5992 324 5993 324 5993 324 5994 324 5995 324 5995 324 5994 324 5996 324 5989 324 5988 324 5778 324 5778 324 5988 324 5997 324 5778 324 5997 324 5992 324 5996 324 5998 324 5995 324 5995 324 5998 324 5999 324 5995 324 5999 324 5784 324 5784 324 5999 324 6000 324 5784 324 6000 324 5990 324 5785 324 5784 324 5989 324 5989 324 5784 324 5991 324 5989 324 5991 324 5987 324 5965 324 6001 324 5778 324 5966 324 6002 324 5965 324 5965 324 6002 324 6003 324 5965 324 6003 324 6001 324 6001 324 6003 324 6004 324 6001 324 6004 324 6005 324 5782 324 6006 324 6007 324 6009 324 6010 324 6011 324 6011 324 6010 324 6012 324 6011 324 6012 324 6013 324 6014 324 6015 324 5782 324 5782 324 6015 324 6016 324 5782 324 6016 324 6008 324 6008 324 6016 324 6017 324 6017 324 6018 324 6008 324 6008 324 6018 324 6019 324 6008 324 6019 324 6009 324 6009 324 6019 324 6020 324 6009 324 6020 324 6010 324 6021 324 6022 324 6014 324 6014 324 6022 324 6023 324 6011 324 6024 324 6025 324 6025 8943 6024 8943 6026 8943 6025 8944 6026 8944 5801 8944 5801 8945 6026 8945 6027 8945 5801 324 6027 324 5802 324 5782 324 6028 324 6029 324 6023 324 6022 324 6030 324 6030 324 6022 324 6031 324 6030 324 6031 324 6013 324 6013 324 6031 324 6032 324 6013 324 6032 324 6011 324 6011 324 6032 324 6033 324 6011 324 6033 324 6024 324 6036 324 6037 324 5917 324 6038 324 5918 324 6039 324 6037 324 6040 324 5917 324 5917 324 6040 324 6041 324 5917 324 6041 324 5918 324 5918 324 6041 324 6042 324 5918 324 6042 324 6039 324 6043 324 6044 324 6045 324 6046 324 5962 324 6047 324 6047 324 5962 324 6048 324 6047 324 6048 324 6049 324 6049 324 6048 324 6050 324 6050 324 6048 324 5789 324 5789 324 6051 324 5790 324 5790 324 6051 324 6052 324 5790 324 6052 324 6053 324 6054 324 6055 324 5923 324 5923 324 6055 324 6056 324 5923 324 6056 324 5789 324 5789 324 6056 324 6057 324 5789 324 6057 324 6051 324 6058 324 6059 324 6060 324 6060 324 6059 324 6061 324 6060 324 6061 324 6062 324 6062 324 6061 324 6063 324 6062 324 6063 324 6064 324 6065 324 6062 324 5923 324 5923 324 6062 324 6064 324 5923 324 6064 324 6054 324 5920 324 6066 324 6067 324 5923 324 6068 324 6069 324 6066 324 5920 324 6070 324 6070 324 5920 324 6071 324 6071 324 5920 324 6072 324 6071 324 6072 324 6073 324 6065 324 5923 324 6069 324 6065 324 6069 324 6074 324 6065 324 6074 324 6072 324 6072 324 6074 324 6075 324 6072 324 6075 324 6073 324 6067 324 6076 324 5920 324 5920 324 6076 324 6077 324 5920 324 6077 324 5923 324 5923 324 6077 324 6078 324 5923 324 6078 324 6068 324 6045 324 5918 324 6043 324 6043 324 5918 324 6080 324 6080 324 5918 324 6038 324 5918 324 6045 324 6081 324 5918 324 6081 324 5920 324 5920 324 6081 324 6072 324 6034 324 6079 324 6045 324 6053 324 6058 324 5790 324 5790 324 6058 324 6060 324 5790 324 6060 324 5868 324 5868 324 6060 324 6082 324 6083 324 6084 324 6085 324 6006 324 6005 324 6004 324 6006 324 6004 324 6086 324 6087 324 6085 324 6084 324 6087 324 6084 324 5966 324 5966 324 6084 324 6088 324 5966 324 6088 324 6002 324 6089 324 6090 324 6091 324 6091 324 6090 324 6092 324 6091 324 6092 324 6093 324 6091 324 6093 324 6085 324 6085 324 6093 324 6094 324 6085 324 6094 324 6083 324 6086 324 6089 324 6006 324 6006 324 6089 324 6091 324 6006 324 6091 324 6007 324 6087 324 5862 324 6095 324 5865 324 6097 324 6098 324 6098 324 6097 324 6099 324 5867 324 6100 324 6101 324 6101 324 6102 324 5867 324 5867 324 6102 324 6103 324 5867 324 6103 324 5865 324 5865 324 6103 324 6104 324 5865 324 6104 324 6097 324 6099 324 6105 324 6098 324 6098 324 6105 324 6106 324 6098 324 6106 324 6107 324 6098 324 6107 324 5867 324 5867 324 6107 324 6108 324 5867 324 6108 324 6109 324 5867 324 6109 324 6100 324 6110 324 6111 324 5862 324 5862 324 6111 324 6112 324 5862 324 6112 324 6113 324 5865 324 5863 324 5866 324 5866 324 5863 324 5862 324 5866 324 5862 324 6114 324 6114 324 5862 324 6113 324 6114 324 6115 324 5866 324 5866 324 6115 324 6116 324 5866 324 6116 324 6117 324 6117 324 6116 324 6118 324 6119 324 6117 324 6120 324 6120 324 6117 324 6121 324 6121 324 6117 324 6118 324 6110 324 5862 324 6122 324 6122 324 5862 324 6119 324 6123 324 5928 324 6124 324 6124 324 5928 324 6125 324 6124 324 6126 324 6123 324 6123 324 6126 324 6127 324 6123 324 6127 324 6128 324 6129 324 6130 324 6048 324 6048 324 6130 324 6131 324 6131 324 6132 324 6048 324 6048 324 6132 324 6133 324 6048 324 6133 324 5789 324 5789 324 6133 324 6134 324 5789 324 6135 324 5928 324 5928 324 6135 324 6136 324 5928 324 6136 324 6125 324 6134 324 6137 324 5789 324 5789 324 6137 324 6138 324 5789 324 6138 324 6139 324 5789 324 6139 324 6135 324 6140 324 6141 324 6142 324 6142 324 6141 324 5962 324 6142 324 5962 324 6143 324 6140 324 6144 324 6141 324 6141 324 6144 324 6145 324 6141 324 6145 324 6146 324 6145 324 6147 324 6146 324 6146 324 6147 324 6148 324 6146 324 6148 324 6149 324 6146 324 6149 324 5958 324 5958 324 6149 324 6150 324 5958 324 6150 324 5959 324 6151 324 6152 324 5928 324 5928 324 6152 324 5793 324 5928 324 5793 324 5926 324 5926 324 5793 324 5792 324 6152 324 6153 324 5793 324 5793 324 6153 324 6154 324 5793 324 6154 324 5940 324 5958 324 5940 324 6155 324 5958 324 6155 324 6156 324 6146 324 6157 324 6141 324 6141 324 6157 324 6158 324 6141 324 6158 324 6123 324 5928 324 6123 324 6159 324 5900 324 6160 324 6161 324 5887 324 5875 324 6163 324 6163 324 6164 324 5887 324 5887 324 6164 324 6165 324 5887 324 6165 324 5900 324 5900 324 6165 324 6166 324 5900 324 6166 324 6167 324 5900 324 6167 324 6160 324 5913 324 6168 324 5773 324 5773 324 6168 324 6169 324 5773 324 6169 324 6170 324 5773 324 6170 324 5875 324 6171 324 6172 324 5913 324 5913 324 6172 324 6173 324 5913 324 6173 324 6161 324 6173 324 6174 324 6161 324 6161 324 6174 324 6175 324 6161 324 6175 324 5900 324 5900 324 6175 324 6176 324 5900 324 6176 324 6177 324 6178 324 5908 324 5900 324 5900 324 5908 324 5907 324 5907 324 5908 324 5910 324 5907 324 5910 324 6179 324 6180 324 6181 324 5869 324 5869 324 6181 324 6182 324 5869 324 6182 324 6183 324 5915 324 5914 324 5869 324 5869 324 5914 324 5913 324 5869 324 5913 324 6180 324 6180 324 5913 324 6184 324 5913 324 6185 324 6186 324 5913 324 6186 324 6184 324 6183 324 6187 324 5872 324 5872 324 6187 324 6188 324 6189 324 6190 324 5773 324 5773 324 6190 324 6191 324 5773 324 6191 324 5913 324 5913 324 6191 324 6192 324 5913 324 6192 324 6185 324 6188 324 6193 324 5872 324 5872 324 6193 324 6194 324 5872 324 6194 324 5773 324 5773 324 6194 324 6195 324 5773 324 6195 324 6189 324 5842 324 5844 324 5856 324 5856 324 5844 324 6196 324 5856 324 6196 324 6197 324 5841 324 6198 324 5840 324 5840 324 6198 324 6199 324 5840 324 6199 324 5844 324 5775 324 6200 324 6199 324 6199 324 6200 324 6201 324 6199 324 6201 324 5844 324 5780 324 6202 324 5818 324 5818 324 6202 324 6203 324 5818 324 6203 324 5825 324 5774 324 5825 324 6204 324 5774 324 6204 324 5775 324 5827 324 6205 324 5774 324 6206 324 5825 324 6207 324 6207 324 5825 324 5774 324 6207 324 5774 324 6208 324 6208 324 5774 324 6205 324 6209 324 6210 324 5780 324 5780 324 6210 324 6211 324 5780 324 6211 324 5857 324 5857 324 6211 324 6212 324 6212 324 6213 324 5857 324 5857 324 6213 324 6214 324 5857 324 6214 324 6215 324 5857 324 6215 324 5861 324 5861 324 6215 324 6216 324 5861 324 6216 324 5860 324 6209 324 5780 324 6217 324 6217 324 5780 324 6218 324 6218 324 5780 324 5818 324 6218 324 5818 324 6219 324 5860 324 6221 324 5818 324 5818 324 6221 324 6222 324 5818 324 6222 324 6223 324 5818 324 6223 324 6220 324 6224 324 6225 324 5774 324 5774 324 6225 324 6226 324 5774 324 6226 324 5833 324 5833 324 6226 324 6227 324 5833 324 6227 324 5834 324 5834 324 6227 324 6228 324 5834 324 6228 324 5835 324 6199 324 6229 324 5775 324 5775 324 6229 324 6230 324 5775 324 6230 324 6231 324 6232 324 5778 324 6233 324 6234 324 6235 324 5784 324 5784 324 6235 324 6236 324 5784 324 6236 324 5995 324 5778 324 5995 324 6237 324 5778 324 6237 324 6233 324 6238 324 6239 324 5978 324 5978 324 6239 324 6234 324 6232 324 6240 324 6241 324 6241 324 6240 324 6242 324 6243 324 6241 324 5978 324 5978 324 6241 324 6242 324 5978 324 6242 324 6244 324 5786 324 5787 324 5978 324 5978 324 5787 324 6245 324 5978 324 6245 324 6243 324 6243 324 6246 324 6241 324 6241 324 6246 324 6247 324 6248 324 6241 324 6249 324 6249 324 6241 324 6250 324 6250 324 6241 324 6251 324 6250 324 6251 324 6252 324 6252 324 6251 324 5965 324 6252 324 5965 324 6253 324 6253 324 5965 324 6254 324 5965 324 6255 324 6254 324 5993 324 5995 324 5778 324 5965 324 5778 324 5777 324 5965 324 5777 324 6256 324 5965 324 6256 324 6255 324 5776 324 5778 324 6257 324 6257 324 5778 324 6232 324 6257 324 6232 324 6258 324 6258 324 6232 324 6259 324 6248 324 6260 324 6241 324 6241 324 6260 324 6261 324 6241 324 6261 324 6232 324 6232 324 6261 324 6262 324 6232 324 6262 324 6259 324 5978 324 6263 324 6264 324 5978 324 6264 324 5980 324 5986 324 6265 324 5784 324 5784 324 6265 324 6266 324 5784 324 6266 324 6234 324 6234 324 6266 324 6267 324 6234 324 6267 324 6268 324 6268 324 6269 324 6234 324 6234 324 6269 324 6270 324 6234 324 6270 324 5978 324 5978 324 6270 324 6271 324 5978 324 6271 324 6263 324 6272 324 6273 324 5967 324 6274 324 6275 324 5964 324 5964 324 6275 324 6276 324 5964 324 6276 324 5967 324 5967 324 6276 324 6277 324 5967 324 6277 324 6272 324 6278 324 6279 324 6280 324 6280 324 6279 324 6281 324 6280 324 6281 324 6282 324 6278 324 6283 324 6279 324 6279 324 6283 324 6284 324 6279 324 6284 324 5964 324 5964 324 6284 324 6285 324 5964 324 6285 324 6274 324 5868 324 6286 324 5790 324 5964 324 5790 324 6279 324 6287 324 6288 324 6289 324 6289 324 6288 324 6290 324 6290 324 6291 324 6289 324 6289 324 6291 324 6292 324 6289 324 6292 324 5867 324 6292 324 6293 324 5867 324 5867 324 6293 324 6294 324 5867 324 6294 324 6295 324 6296 324 6287 324 6297 324 6297 324 6287 324 6289 324 6297 324 6289 324 5967 324 6297 324 5967 324 6281 324 6281 324 5967 324 6273 324 6281 324 6273 324 6282 324 6295 324 6298 324 5867 324 5867 324 6298 324 6299 324 5867 324 6299 324 6098 324 6295 324 6300 324 6298 324 6298 324 6300 324 6301 324 6298 324 6301 324 6297 324 6297 324 6301 324 6302 324 6297 324 6302 324 6296 324 6303 324 6304 324 5967 324 5967 324 6304 324 6305 324 6306 324 6307 324 5966 324 6305 324 6308 324 5967 324 5967 324 6308 324 6309 324 5967 324 6309 324 5966 324 5966 324 6309 324 6310 324 5966 324 6310 324 6306 324 6307 324 6311 324 6312 324 6312 324 6311 324 6313 324 6312 324 6313 324 6314 324 6314 324 6313 324 6315 324 6314 324 6315 324 6316 324 6316 324 6303 324 6314 324 6314 324 6303 324 5967 324 5867 324 6317 324 6289 324 5967 324 6289 324 6314 324 6119 324 5862 324 6117 324 6117 324 5862 324 6318 324 6307 324 6312 324 5966 324 5966 324 6312 324 6319 324 5966 324 6319 324 6087 324 6087 324 6319 324 5862 324 5862 324 6319 324 6320 324 5862 324 6320 324 6318 324 5977 324 5786 324 5976 324 5976 324 5786 324 5978 324 5978 324 6244 324 6238 324 5971 324 6321 324 6241 324 5968 324 6241 324 6247 324 6156 324 6146 324 5958 324 5963 324 6143 324 5962 324 5962 324 6141 324 6123 324 5962 324 6123 324 6048 324 6048 324 6123 324 6128 324 6048 324 6128 324 6129 324 5791 324 5793 324 5933 324 5933 324 5793 324 5940 324 5958 324 6322 324 5952 324 5925 324 5923 324 5789 324 5928 324 6159 324 6151 324 6007 324 5781 324 5782 324 6014 324 5782 324 6029 324 6014 324 6029 324 6021 324 5782 324 5799 324 6028 324 6028 324 5799 324 5798 324 6044 324 6035 324 6045 324 6045 324 6035 324 6034 324 6323 324 6324 324 5820 324 6325 324 6326 324 6327 324 5862 324 6328 324 6329 324 6095 324 6330 324 6331 324 6323 324 5820 324 6332 324 6325 324 5818 324 5820 324 6325 324 5820 324 6326 324 6326 324 5820 324 6324 324 6095 324 5862 324 6329 324 6095 324 6329 324 6330 324 6331 324 6332 324 6095 324 6095 324 6332 324 5820 324 6095 324 5820 324 5822 324 6095 324 5822 324 6096 324 6096 324 5822 324 5799 324 5799 324 5813 324 5804 324 5804 324 5813 324 5812 324 6327 324 6333 324 6325 324 6325 324 6333 324 6334 324 6325 324 6334 324 5862 324 5862 324 6334 324 6335 324 5862 324 6335 324 6328 324 5818 324 6325 324 5862 324 5865 324 5866 324 5867 324 5867 324 5866 324 6117 324 5867 324 6117 324 6317 324 5868 324 5865 324 6098 324 5868 324 6098 324 6286 324 5915 324 6336 324 6337 324 6338 324 6339 324 6079 324 6079 324 6339 324 6340 324 6079 324 6340 324 6341 324 6342 324 6343 324 5868 324 5868 324 6343 324 6344 324 6082 324 6079 324 5868 324 5868 324 6079 324 6341 324 5868 324 6341 324 6342 324 6344 324 6345 324 5868 324 5868 324 6345 324 6346 324 5868 324 6346 324 6347 324 6034 324 6036 324 5917 324 6034 324 5917 324 6079 324 6079 324 5917 324 5915 324 6079 324 5915 324 6338 324 6338 324 5915 324 6337 324 6220 324 6219 324 5818 324 5823 324 5825 324 6206 324 5912 324 6171 324 5914 324 5914 324 6171 324 5913 324 5913 324 6161 324 6162 324 5913 324 6162 324 6168 324 6231 324 6224 324 5775 324 5775 324 6224 324 5774 324 5774 324 6348 324 5827 324 5827 324 6348 324 5828 324 5780 324 5857 324 5855 324 5780 324 5855 324 5856 324 5780 324 5856 324 5779 324 5779 324 5856 324 6197 324 5879 324 5871 324 5773 324 5773 324 5871 324 5872 324 5872 324 5873 324 6183 324 6183 324 5873 324 5869 324 5869 324 5868 324 5915 324 5915 324 5868 324 6347 324 5915 324 6347 324 6336 324 5795 324 5875 324 5796 324 5796 324 5875 324 5887 324 5900 324 6177 324 6178 324 6025 8505 5405 8505 5407 8505 6025 8505 5407 8505 6011 8505 5409 8511 6008 8511 5569 8511 5569 8511 6008 8511 6009 8511 5966 8946 5439 8946 5964 8946 5964 8947 5439 8947 5442 8947 5828 8948 5552 8948 5818 8948 5818 8949 5552 8949 5554 8949 5526 8950 5527 8950 5864 8950 5864 8951 5527 8951 5861 8951 5558 8507 5813 8507 5556 8507 5556 8507 5813 8507 5822 8507 5524 8952 5863 8952 5521 8952 5521 8953 5863 8953 5865 8953 5929 8954 5467 8954 5925 8954 5925 8955 5467 8955 5475 8955 5444 8956 5447 8956 5789 8956 5789 8957 5447 8957 6050 8957 5482 8958 5921 8958 5481 8958 5481 8959 5921 8959 5922 8959 5782 8960 5389 8960 6006 8960 6006 8961 5389 8961 5413 8961 5920 8646 5483 8646 5919 8646 5919 8646 5483 8646 5484 8646 5918 8962 5486 8962 5917 8962 5917 8963 5486 8963 5487 8963 5493 8964 5910 8964 5490 8964 5490 8965 5910 8965 5914 8965 5870 8966 5869 8966 5522 8966 5522 8967 5869 8967 5518 8967 5910 8968 5493 8968 5495 8968 5910 8969 5495 8969 6179 8969 6179 8970 5495 8970 5494 8970 6179 8971 5494 8971 5907 8971 5907 8972 5494 8972 5497 8972 5907 8973 5497 8973 5897 8973 5897 8974 5497 8974 5499 8974 5897 8974 5499 8974 5894 8974 5894 8975 5499 8975 5504 8975 5894 8976 5504 8976 5892 8976 5892 8977 5504 8977 5381 8977 5892 8978 5381 8978 5890 8978 5890 8979 5381 8979 5887 8979 5887 8980 5381 8980 5796 8980 5381 8981 5515 8981 5796 8981 5796 8982 5515 8982 5517 8982 5796 8983 5517 8983 5881 8983 5881 8984 5517 8984 5509 8984 5881 8984 5509 8984 5879 8984 5879 8985 5509 8985 5630 8985 5879 8986 5630 8986 5871 8986 5871 8987 5630 8987 5508 8987 5871 8988 5508 8988 5872 8988 5872 8989 5508 8989 5519 8989 5872 8990 5519 8990 5873 8990 5873 8991 5519 8991 5518 8991 5873 8992 5518 8992 5869 8992 6169 8993 5617 8993 6170 8993 6170 8994 5617 8994 5616 8994 6170 8995 5616 8995 5875 8995 5875 8996 5616 8996 5615 8996 5875 8997 5615 8997 6163 8997 6163 8998 5615 8998 5512 8998 6163 8999 5512 8999 6164 8999 6164 9000 5512 9000 5609 9000 6164 8690 5609 8690 6165 8690 6165 8690 5609 8690 5614 8690 6165 9001 5614 9001 6166 9001 6166 9001 5614 9001 5613 9001 6166 9002 5613 9002 6167 9002 6167 9002 5613 9002 5612 9002 6167 8655 5612 8655 6160 8655 6160 8655 5612 8655 5611 8655 6160 9003 5611 9003 6161 9003 6161 9003 5611 9003 5610 9003 6161 9004 5610 9004 6162 9004 6162 9004 5610 9004 5619 9004 6162 8577 5619 8577 6168 8577 6168 8577 5619 8577 5618 8577 6168 9005 5618 9005 6169 9005 6169 9006 5618 9006 5617 9006 6349 9007 5507 9007 5510 9007 6349 9008 5510 9008 6350 9008 6350 9009 5510 9009 5516 9009 6350 9010 5516 9010 6351 9010 6351 9011 5516 9011 5514 9011 6351 9012 5514 9012 6352 9012 6352 9013 5514 9013 6353 9013 6353 9014 5514 9014 5513 9014 6353 9015 5513 9015 6354 9015 6354 9016 5513 9016 5511 9016 6354 9017 5511 9017 6355 9017 6355 9018 5511 9018 5507 9018 6355 9019 5507 9019 6349 9019 6356 9020 5491 9020 6357 9020 6357 9021 5491 9021 5620 9021 6357 9022 5620 9022 6358 9022 6358 9023 5620 9023 5621 9023 6358 9024 5621 9024 6359 9024 6359 9025 5621 9025 5624 9025 6359 9026 5624 9026 6360 9026 6360 9027 5624 9027 5623 9027 6360 9028 5623 9028 6361 9028 6361 9029 5623 9029 5622 9029 6361 9030 5622 9030 6362 9030 6362 9031 5622 9031 5492 9031 6362 9032 5492 9032 6356 9032 6356 9033 5492 9033 5491 9033 6363 9034 5631 9034 6364 9034 6364 9035 5631 9035 5628 9035 6364 9036 5628 9036 6365 9036 6365 9037 5628 9037 5627 9037 6365 9038 5627 9038 6366 9038 6367 9039 5629 9039 6368 9039 6368 9040 5629 9040 5626 9040 6368 9041 5626 9041 6369 9041 6369 9042 5626 9042 5625 9042 6369 9043 5625 9043 6370 9043 6370 9044 5625 9044 5632 9044 5629 9045 6367 9045 5627 9045 5627 9046 6367 9046 6366 9046 6370 9047 5632 9047 6363 9047 6363 9048 5632 9048 5631 9048 6371 9049 5502 9049 6372 9049 6372 9050 5502 9050 5501 9050 6372 9051 5501 9051 5500 9051 6372 9052 5500 9052 6373 9052 6373 9053 5500 9053 6374 9053 6374 9054 5500 9054 5380 9054 6375 9055 5506 9055 6376 9055 6376 9056 5506 9056 5505 9056 6376 9057 5505 9057 6377 9057 6377 9058 5505 9058 5503 9058 6377 9059 5503 9059 6378 9059 6378 9060 5503 9060 5498 9060 5506 9061 6375 9061 5380 9061 5380 9062 6375 9062 6374 9062 6378 9063 5498 9063 6371 9063 6371 9064 5498 9064 5502 9064 6050 9065 5447 9065 5448 9065 6050 9066 5448 9066 6049 9066 6049 9067 5448 9067 5451 9067 6049 9068 5451 9068 6047 9068 6047 9069 5451 9069 5450 9069 6047 9070 5450 9070 6046 9070 6046 9071 5450 9071 5449 9071 6046 9072 5449 9072 5962 9072 5962 9073 5449 9073 5453 9073 5962 9074 5453 9074 5960 9074 5960 9075 5453 9075 5383 9075 5960 9076 5383 9076 5958 9076 5958 9077 5383 9077 5382 9077 5958 9078 5382 9078 6322 9078 6322 9079 5382 9079 5384 9079 6322 9079 5384 9079 5952 9079 5952 9080 5384 9080 5455 9080 5952 9081 5455 9081 5944 9081 5944 9082 5455 9082 5463 9082 5944 9082 5463 9082 5941 9082 5941 9083 5463 9083 5466 9083 5941 9084 5466 9084 5939 9084 5939 9085 5466 9085 5468 9085 5939 9086 5468 9086 5933 9086 5933 9087 5468 9087 5467 9087 5933 9088 5467 9088 5929 9088 6123 9089 5642 9089 6159 9089 6159 8993 5642 8993 5643 8993 6159 8659 5643 8659 6151 8659 6151 8659 5643 8659 5651 8659 6151 9090 5651 9090 6152 9090 6152 9090 5651 9090 5474 9090 6152 8999 5474 8999 6153 8999 6153 8999 5474 8999 5633 8999 6153 8690 5633 8690 6154 8690 6154 8690 5633 8690 5637 8690 6154 9091 5637 9091 5940 9091 5940 9001 5637 9001 5461 9001 5940 9092 5461 9092 6155 9092 6155 9093 5461 9093 5636 9093 6155 8655 5636 8655 6156 8655 6156 8655 5636 8655 5635 8655 6156 9094 5635 9094 6146 9094 6146 9003 5635 9003 5634 9003 6146 9095 5634 9095 6157 9095 6157 9004 5634 9004 5638 9004 6157 8577 5638 8577 6158 8577 6158 8577 5638 8577 5640 8577 6158 9096 5640 9096 6123 9096 6123 9005 5640 9005 5642 9005 6379 9097 5647 9097 5646 9097 6379 9098 5646 9098 6380 9098 6380 9009 5646 9009 5645 9009 6380 9099 5645 9099 6381 9099 6381 9100 5645 9100 5639 9100 6381 9101 5639 9101 6382 9101 6382 9102 5639 9102 5644 9102 6382 9103 5644 9103 6383 9103 6383 9104 5644 9104 5454 9104 6383 9105 5454 9105 6384 9105 6384 9106 5454 9106 5452 9106 6384 9107 5452 9107 6379 9107 6379 9108 5452 9108 5647 9108 6385 9109 5472 9109 6386 9109 6386 9110 5472 9110 5477 9110 6386 9111 5477 9111 6387 9111 6387 9112 5477 9112 5476 9112 6387 9113 5476 9113 6388 9113 6388 9114 5476 9114 5469 9114 6388 9115 5469 9115 6389 9115 6389 9116 5469 9116 5470 9116 6389 9117 5470 9117 6390 9117 6390 9118 5470 9118 5471 9118 6390 9119 5471 9119 6391 9119 6391 9120 5471 9120 5473 9120 6391 9121 5473 9121 6385 9121 6385 9122 5473 9122 5472 9122 6392 9123 5652 9123 5648 9123 6392 9124 5648 9124 6393 9124 6393 9125 5648 9125 5654 9125 6393 9126 5654 9126 6394 9126 6394 9127 5654 9127 5655 9127 6395 9128 5653 9128 6396 9128 6396 9129 5653 9129 5650 9129 6396 9130 5650 9130 6397 9130 6397 9131 5650 9131 5641 9131 6397 9132 5641 9132 6398 9132 6398 9133 5641 9133 5649 9133 5653 9134 6395 9134 5655 9134 5655 9135 6395 9135 6394 9135 6398 9136 5649 9136 6392 9136 6392 9137 5649 9137 5652 9137 6399 9138 5457 9138 6400 9138 6400 9139 5457 9139 5465 9139 6400 9140 5465 9140 6401 9140 6401 9141 5465 9141 5460 9141 6401 9142 5460 9142 6402 9142 6402 9143 5460 9143 5459 9143 6403 9144 5462 9144 6404 9144 6404 9145 5462 9145 5464 9145 6404 9146 5464 9146 6405 9146 6405 9147 5464 9147 5456 9147 6405 9148 5456 9148 6406 9148 6406 9149 5456 9149 5458 9149 5462 9150 6403 9150 5459 9150 5459 9151 6403 9151 6402 9151 6406 9152 5458 9152 6399 9152 6399 9153 5458 9153 5457 9153 5861 9154 5527 9154 5534 9154 5861 9155 5534 9155 5857 9155 5857 9156 5534 9156 5530 9156 5857 9157 5530 9157 5858 9157 5858 9158 5530 9158 5529 9158 5858 9159 5529 9159 5859 9159 5859 9160 5529 9160 5528 9160 5859 9161 5528 9161 5848 9161 5848 9162 5528 9162 5536 9162 5848 9162 5536 9162 5850 9162 5850 9163 5536 9163 5376 9163 5850 9163 5376 9163 5840 9163 5840 9164 5376 9164 5543 9164 5840 9164 5543 9164 5838 9164 5838 9165 5543 9165 5544 9165 5838 9165 5544 9165 5836 9165 5836 9166 5544 9166 5546 9166 5836 9167 5546 9167 5834 9167 5834 9168 5546 9168 5548 9168 5834 9168 5548 9168 5833 9168 5833 9169 5548 9169 5551 9169 5833 9170 5551 9170 5774 9170 5774 9171 5551 9171 5550 9171 5774 9172 5550 9172 6348 9172 6348 9173 5550 9173 5552 9173 6348 9174 5552 9174 5828 9174 6200 8993 5661 8993 6201 8993 6201 8993 5661 8993 5662 8993 6201 8995 5662 8995 5844 8995 5844 8996 5662 8996 5663 8996 5844 8997 5663 8997 6196 8997 6196 9090 5663 9090 5664 9090 6196 8999 5664 8999 6197 8999 6197 8999 5664 8999 5665 8999 6197 8690 5665 8690 5779 8690 5779 8690 5665 8690 5666 8690 5779 9175 5666 9175 5780 9175 5780 9001 5666 9001 5656 9001 5780 9176 5656 9176 6202 9176 6202 9002 5656 9002 5657 9002 6202 8655 5657 8655 6203 8655 6203 8655 5657 8655 5658 8655 6203 9003 5658 9003 5825 9003 5825 9177 5658 9177 5372 9177 5825 9004 5372 9004 6204 9004 6204 9004 5372 9004 5371 9004 6204 8577 5371 8577 5775 8577 5775 8577 5371 8577 5659 8577 5775 9005 5659 9005 6200 9005 6200 9005 5659 9005 5661 9005 6407 9178 5538 9178 5539 9178 6407 9179 5539 9179 6408 9179 6408 9180 5539 9180 5537 9180 6408 9181 5537 9181 6409 9181 6409 9182 5537 9182 5535 9182 6409 9183 5535 9183 6410 9183 6410 9184 5535 9184 5533 9184 6410 9185 5533 9185 5532 9185 6410 9186 5532 9186 6411 9186 6411 9187 5532 9187 5540 9187 6411 9188 5540 9188 6412 9188 6412 9189 5540 9189 5538 9189 6412 9190 5538 9190 6407 9190 6413 9191 5669 9191 6414 9191 6414 9192 5669 9192 5668 9192 6414 9193 5668 9193 6415 9193 6415 9194 5668 9194 5667 9194 6415 9195 5667 9195 6416 9195 6416 9196 5667 9196 5375 9196 6416 9197 5375 9197 6417 9197 6417 9198 5375 9198 5374 9198 6417 9199 5374 9199 6418 9199 6418 9200 5374 9200 5671 9200 6418 9030 5671 9030 6419 9030 6419 9201 5671 9201 5670 9201 6419 9202 5670 9202 6413 9202 6413 9203 5670 9203 5669 9203 6420 9204 5379 9204 5378 9204 6420 9205 5378 9205 6421 9205 6421 9206 5378 9206 5605 9206 6421 9207 5605 9207 6422 9207 6422 9208 5605 9208 5604 9208 6423 9209 5606 9209 6424 9209 6424 9210 5606 9210 5608 9210 6424 9211 5608 9211 6425 9211 6425 9212 5608 9212 5607 9212 6425 9213 5607 9213 6426 9213 6426 9214 5607 9214 5603 9214 5606 9215 6423 9215 5604 9215 5604 9216 6423 9216 6422 9216 6426 9217 5603 9217 6420 9217 6420 9218 5603 9218 5379 9218 6427 9219 5541 9219 6428 9219 6428 9220 5541 9220 5674 9220 6428 9221 5674 9221 6429 9221 6429 9222 5674 9222 5673 9222 6429 9223 5673 9223 6430 9223 6430 9224 5673 9224 5672 9224 6431 9225 5549 9225 6432 9225 6432 9226 5549 9226 5547 9226 6432 9227 5547 9227 6433 9227 6433 9228 5547 9228 5545 9228 6433 9229 5545 9229 6434 9229 6434 9230 5545 9230 5542 9230 5549 9231 6431 9231 5672 9231 5672 9232 6431 9232 6430 9232 6434 9233 5542 9233 6427 9233 6427 9234 5542 9234 5541 9234 5420 9235 5989 9235 5410 9235 5410 9236 5989 9236 5778 9236 5410 9237 5778 9237 6001 9237 5965 9238 6251 9238 5441 9238 5441 9239 6251 9239 5438 9239 5989 9240 5420 9240 5424 9240 5989 9241 5424 9241 5785 9241 5785 9242 5424 9242 5414 9242 5785 9243 5414 9243 5783 9243 5783 9244 5414 9244 5425 9244 5783 9245 5425 9245 5784 9245 5784 9246 5425 9246 5427 9246 5784 9247 5427 9247 5983 9247 5983 9248 5427 9248 5426 9248 5983 9249 5426 9249 5981 9249 5981 9250 5426 9250 5432 9250 5981 9251 5432 9251 5979 9251 5979 9252 5432 9252 5431 9252 5979 9253 5431 9253 5976 9253 5976 9254 5431 9254 5434 9254 5976 9254 5434 9254 5974 9254 5974 9255 5434 9255 5435 9255 5974 9255 5435 9255 5970 9255 5970 9256 5435 9256 5385 9256 5970 9257 5385 9257 5971 9257 5971 9258 5385 9258 5386 9258 5971 9259 5386 9259 6321 9259 6321 9260 5386 9260 5436 9260 6321 9261 5436 9261 6241 9261 6241 9262 5436 9262 5438 9262 6241 9263 5438 9263 6251 9263 6234 9264 5677 9264 6235 9264 6235 9265 5677 9265 5592 9265 6235 9266 5592 9266 6236 9266 6236 8659 5592 8659 5683 8659 6236 9090 5683 9090 5995 9090 5995 9090 5683 9090 5423 9090 5995 9267 5423 9267 6237 9267 6237 8999 5423 8999 5682 8999 6237 8690 5682 8690 6233 8690 6233 8690 5682 8690 5681 8690 6233 9001 5681 9001 6232 9001 6232 9268 5681 9268 5600 9268 6232 9002 5600 9002 6240 9002 6240 9092 5600 9092 5680 9092 6240 8655 5680 8655 6242 8655 6242 8655 5680 8655 5679 8655 6242 9003 5679 9003 6244 9003 6244 9094 5679 9094 5675 9094 6244 9004 5675 9004 6238 9004 6238 9095 5675 9095 5676 9095 6238 8577 5676 8577 6239 8577 6239 8577 5676 8577 5678 8577 6239 9269 5678 9269 6234 9269 6234 9270 5678 9270 5677 9270 6435 9271 5430 9271 6436 9271 6436 9272 5430 9272 5429 9272 6436 9273 5429 9273 6437 9273 6437 9274 5429 9274 5685 9274 6437 9275 5685 9275 6438 9275 6438 9276 5685 9276 5684 9276 6438 9277 5684 9277 6439 9277 6439 9278 5684 9278 5686 9278 6439 9279 5686 9279 6440 9279 6440 9187 5686 9187 5433 9187 6440 9280 5433 9280 6441 9280 6441 9281 5433 9281 5430 9281 6441 9282 5430 9282 6435 9282 6442 9283 5415 9283 6443 9283 6443 9284 5415 9284 5421 9284 6443 9285 5421 9285 6444 9285 6444 9286 5421 9286 5419 9286 6444 9113 5419 9113 6445 9113 6445 9287 5419 9287 5418 9287 6445 9288 5418 9288 6446 9288 6446 9289 5418 9289 5417 9289 6446 9290 5417 9290 6447 9290 6447 9291 5417 9291 5422 9291 6447 9292 5422 9292 6448 9292 6448 9293 5422 9293 5416 9293 6448 9294 5416 9294 6442 9294 6442 9295 5416 9295 5415 9295 6449 9296 5597 9296 6450 9296 6450 9297 5597 9297 5596 9297 6450 9298 5596 9298 6451 9298 6451 9299 5596 9299 5437 9299 6451 9300 5437 9300 6452 9300 6453 9301 5601 9301 6454 9301 6454 9302 5601 9302 5599 9302 6454 9303 5599 9303 6455 9303 6455 9304 5599 9304 5598 9304 6455 9305 5598 9305 6456 9305 6456 9306 5598 9306 5602 9306 5601 9307 6453 9307 5437 9307 5437 9308 6453 9308 6452 9308 6456 9309 5602 9309 6449 9309 6449 9310 5602 9310 5597 9310 6457 9311 5588 9311 6458 9311 6458 9312 5588 9312 5593 9312 6458 9313 5593 9313 5591 9313 6458 9314 5591 9314 6459 9314 6459 9315 5591 9315 6460 9315 6460 9316 5591 9316 5590 9316 6461 9317 5594 9317 6462 9317 6462 9318 5594 9318 5595 9318 6462 9319 5595 9319 6463 9319 6463 9320 5595 9320 5428 9320 6463 9321 5428 9321 6464 9321 6464 9322 5428 9322 5589 9322 5594 9323 6461 9323 5590 9323 5590 9324 6461 9324 6460 9324 6464 9325 5589 9325 6457 9325 6457 9326 5589 9326 5588 9326 5818 9327 5554 9327 5819 9327 5819 9328 5554 9328 5553 9328 5819 9329 5553 9329 5821 9329 5821 9330 5553 9330 5557 9330 5821 9331 5557 9331 5822 9331 5822 9332 5557 9332 5556 9332 5526 9333 5864 9333 5524 9333 5524 9334 5864 9334 5863 9334 5410 9335 6001 9335 5411 9335 5411 9336 6001 9336 6005 9336 5411 9337 6005 9337 5413 9337 5413 9338 6005 9338 6006 9338 5965 9339 5441 9339 5966 9339 5966 9340 5441 9340 5439 9340 5444 9341 5789 9341 5788 9341 5444 9342 5788 9342 5442 9342 5442 9343 5788 9343 5964 9343 5925 9344 5475 9344 5478 9344 5925 9345 5478 9345 5924 9345 5924 9346 5478 9346 5480 9346 5924 9347 5480 9347 5922 9347 5922 9348 5480 9348 5481 9348 5870 9349 5522 9349 5865 9349 5865 9350 5522 9350 5521 9350 5490 9351 5914 9351 5489 9351 5489 9352 5914 9352 5916 9352 5489 9353 5916 9353 5487 9353 5487 9354 5916 9354 5917 9354 6465 9355 5707 9355 6466 9355 6466 9356 5707 9356 6467 9356 6467 9357 5707 9357 5706 9357 6467 9358 5706 9358 6468 9358 6468 9359 5706 9359 5705 9359 6468 9360 5705 9360 6469 9360 6469 9361 5705 9361 5702 9361 6469 9362 5702 9362 6470 9362 6470 9363 5702 9363 5701 9363 6470 9364 5701 9364 6471 9364 6471 9365 5701 9365 5704 9365 6471 9366 5704 9366 6472 9366 6472 9367 5704 9367 5703 9367 6472 9368 5703 9368 6465 9368 6465 9369 5703 9369 5707 9369 5443 8505 5790 8505 5709 8505 5709 8505 5790 8505 6286 8505 6299 8511 5699 8511 6098 8511 6098 8511 5699 8511 5698 8511 6297 8646 5695 8646 6298 8646 6298 8646 5695 8646 5700 8646 6279 8507 5689 8507 6281 8507 6281 8507 5689 8507 5688 8507 5443 9370 5689 9370 5790 9370 5790 9371 5689 9371 6279 9371 5688 8577 5695 8577 6281 8577 6281 8577 5695 8577 6297 8577 5700 8659 5699 8659 6298 8659 6298 8659 5699 8659 6299 8659 5698 9372 5709 9372 6098 9372 6098 8690 5709 8690 6286 8690 6319 8646 5576 8646 6320 8646 6320 8646 5576 8646 5583 8646 5575 8507 6312 8507 5580 8507 5580 8507 6312 8507 6314 8507 5586 8505 6289 8505 5587 8505 5587 8505 6289 8505 6317 8505 5585 8511 6117 8511 5584 8511 5584 8511 6117 8511 6318 8511 5575 9373 5576 9373 6312 9373 6312 9373 5576 9373 6319 9373 5586 8655 5580 8655 6289 8655 6289 8655 5580 8655 6314 8655 5585 8690 5587 8690 6117 8690 6117 8690 5587 8690 6317 8690 5583 8659 5584 8659 6320 8659 6320 8659 5584 8659 6318 8659 6473 9374 5710 9374 6474 9374 6474 9375 5710 9375 6475 9375 6475 9376 5710 9376 5711 9376 6475 9377 5711 9377 5712 9377 6475 9378 5712 9378 6476 9378 6476 9379 5712 9379 6477 9379 6477 9380 5712 9380 5714 9380 6477 9381 5714 9381 6478 9381 6478 9382 5714 9382 5713 9382 6478 9383 5713 9383 6479 9383 6479 9384 5713 9384 5716 9384 6479 9385 5716 9385 6480 9385 6480 9386 5716 9386 6473 9386 6473 9387 5716 9387 5715 9387 6473 9388 5715 9388 5710 9388 6481 9389 5572 9389 6482 9389 6482 9390 5572 9390 6483 9390 6483 9391 5572 9391 5574 9391 6483 9392 5574 9392 6484 9392 6484 9393 5574 9393 5581 9393 6484 9394 5581 9394 6485 9394 6485 9395 5581 9395 5577 9395 6485 9396 5577 9396 6486 9396 6486 9397 5577 9397 6487 9397 6487 9398 5577 9398 5579 9398 6487 9399 5579 9399 5578 9399 6487 9400 5578 9400 6488 9400 6488 9401 5578 9401 6481 9401 6481 9402 5578 9402 5573 9402 6481 9403 5573 9403 5572 9403 6489 9404 5692 9404 6490 9404 6490 9405 5692 9405 5691 9405 6490 9406 5691 9406 6491 9406 6491 9407 5691 9407 5694 9407 6491 9408 5694 9408 5687 9408 6491 9409 5687 9409 6492 9409 6492 9410 5687 9410 6493 9410 6493 9411 5687 9411 5690 9411 6493 9412 5690 9412 5693 9412 6493 9413 5693 9413 6494 9413 6494 9414 5693 9414 6495 9414 6495 9398 5693 9398 5697 9398 6495 9415 5697 9415 5696 9415 6495 9416 5696 9416 6496 9416 6496 9417 5696 9417 6489 9417 6489 9418 5696 9418 5692 9418 6497 9419 5721 9419 6498 9419 6498 9420 5721 9420 6499 9420 6499 9376 5721 9376 5722 9376 6499 9421 5722 9421 5719 9421 6499 9422 5719 9422 6500 9422 6500 9423 5719 9423 6501 9423 6501 9424 5719 9424 5718 9424 6501 9425 5718 9425 5717 9425 6501 9426 5717 9426 6502 9426 6502 9427 5717 9427 6503 9427 6503 9428 5717 9428 5723 9428 6503 9429 5723 9429 6504 9429 6504 9430 5723 9430 5724 9430 6504 9431 5724 9431 6497 9431 6497 9432 5724 9432 5721 9432 6505 9433 5412 9433 6506 9433 6506 9434 5412 9434 5730 9434 6506 9435 5730 9435 6507 9435 6507 9436 5730 9436 5727 9436 6507 9437 5727 9437 5729 9437 6507 9438 5729 9438 6508 9438 6508 9439 5729 9439 5728 9439 6508 9440 5728 9440 6509 9440 6509 9441 5728 9441 6510 9441 6510 9442 5728 9442 5387 9442 6510 9443 5387 9443 5725 9443 6510 9444 5725 9444 6511 9444 6511 9445 5725 9445 5412 9445 6511 9446 5412 9446 6505 9446 6512 9447 5765 9447 5760 9447 6512 9448 5760 9448 6513 9448 6513 9449 5760 9449 5759 9449 6513 9450 5759 9450 6514 9450 6514 9451 5759 9451 6515 9451 6515 9452 5759 9452 5764 9452 6515 9453 5764 9453 5763 9453 6515 9454 5763 9454 6516 9454 6516 9455 5763 9455 5761 9455 6516 9456 5761 9456 6517 9456 6517 9457 5761 9457 6518 9457 6518 9458 5761 9458 5762 9458 6518 9459 5762 9459 6512 9459 6512 9460 5762 9460 5765 9460 6519 9461 5445 9461 6520 9461 6520 9462 5445 9462 5736 9462 6520 9463 5736 9463 5735 9463 6520 9464 5735 9464 6521 9464 6521 9465 5735 9465 5732 9465 6521 9466 5732 9466 6522 9466 6522 9467 5732 9467 6523 9467 6523 9468 5732 9468 5479 9468 6523 9117 5479 9117 6524 9117 6524 9469 5479 9469 5731 9469 6524 9470 5731 9470 5446 9470 6524 9471 5446 9471 6525 9471 6525 9472 5446 9472 6519 9472 6519 9473 5446 9473 5445 9473 6526 9474 5771 9474 6527 9474 6527 9475 5771 9475 5770 9475 6527 9476 5770 9476 6528 9476 6528 9477 5770 9477 5769 9477 6528 9478 5769 9478 6529 9478 6529 9479 5769 9479 5768 9479 6529 9480 5768 9480 6530 9480 6530 9481 5768 9481 5767 9481 6530 9482 5767 9482 6531 9482 6531 9483 5767 9483 5766 9483 6531 9484 5766 9484 6532 9484 6532 9485 5766 9485 5772 9485 6532 9486 5772 9486 6526 9486 6526 9487 5772 9487 5771 9487 5815 8507 5560 8507 5811 8507 5811 8507 5560 8507 5563 8507 6533 9488 5393 9488 6534 9488 6534 9489 5393 9489 5397 9489 6534 9490 5397 9490 6535 9490 6535 9491 5397 9491 5395 9491 6535 9492 5395 9492 6536 9492 6536 9493 5395 9493 5394 9493 6536 9494 5394 9494 6537 9494 6537 9495 5394 9495 5571 9495 6537 9496 5571 9496 6538 9496 6538 9497 5571 9497 5570 9497 6538 9498 5570 9498 6539 9498 6539 9499 5570 9499 5568 9499 6539 9500 5568 9500 6533 9500 6533 9501 5568 9501 5393 9501 6540 9502 5564 9502 6541 9502 6541 9503 5564 9503 5562 9503 6541 9504 5562 9504 6542 9504 6542 9505 5562 9505 5561 9505 6542 9506 5561 9506 6543 9506 6543 9507 5561 9507 5559 9507 6543 9508 5559 9508 6544 9508 6544 9509 5559 9509 5567 9509 6544 9510 5567 9510 6545 9510 6545 9511 5567 9511 5566 9511 6545 9512 5566 9512 6546 9512 6546 9513 5566 9513 5565 9513 6546 9514 5565 9514 6540 9514 6540 9515 5565 9515 5564 9515 5582 8505 6085 8505 5740 8505 5740 8505 6085 8505 6087 8505 6096 8511 5369 8511 6095 8511 6095 8511 5369 8511 5739 8511 5781 8646 5738 8646 5799 8646 5799 8646 5738 8646 5368 8646 5737 8507 6007 8507 6091 8507 5737 8507 6091 8507 5726 8507 5737 9516 5738 9516 6007 9516 6007 9517 5738 9517 5781 9517 5582 9518 5726 9518 6085 9518 6085 9519 5726 9519 6091 9519 5368 9520 5369 9520 5799 9520 5799 9521 5369 9521 6096 9521 5739 8690 5740 8690 6095 8690 6095 9522 5740 9522 6087 9522 5743 8505 6072 8505 5485 8505 5485 8505 6072 8505 6081 8505 6079 8511 5488 8511 6045 8511 6045 8511 5488 8511 5751 8511 6060 8646 5734 8646 6082 8646 6082 8646 5734 8646 5750 8646 6065 8507 5742 8507 6062 8507 6062 8507 5742 8507 5733 8507 5743 9523 5742 9523 6072 9523 6072 9524 5742 9524 6065 9524 5733 9525 5734 9525 6062 9525 6062 9526 5734 9526 6060 9526 5750 8659 5488 8659 6082 8659 6082 8659 5488 8659 6079 8659 5751 9527 5485 9527 6045 9527 6045 9528 5485 9528 6081 9528 5920 8659 5921 8659 5483 8659 5483 8659 5921 8659 5482 8659 5918 8577 5919 8577 5486 8577 5486 8577 5919 8577 5484 8577 6547 9529 5749 9529 6548 9529 6548 9530 5749 9530 5748 9530 6548 9531 5748 9531 6549 9531 6549 9532 5748 9532 5747 9532 6549 9533 5747 9533 6550 9533 6550 9534 5747 9534 5741 9534 6550 9535 5741 9535 6551 9535 6551 9536 5741 9536 5744 9536 6551 9537 5744 9537 6552 9537 6552 9538 5744 9538 5746 9538 6552 9471 5746 9471 6553 9471 6553 9539 5746 9539 6547 9539 6547 9540 5746 9540 5745 9540 6547 9541 5745 9541 5749 9541 6554 9542 5754 9542 6555 9542 6555 9543 5754 9543 6556 9543 6556 9544 5754 9544 5756 9544 6556 9545 5756 9545 5755 9545 6556 9546 5755 9546 6557 9546 6557 9547 5755 9547 5752 9547 6557 9548 5752 9548 6558 9548 6558 9549 5752 9549 5758 9549 6558 9550 5758 9550 6559 9550 6559 9551 5758 9551 5757 9551 6559 9552 5757 9552 6560 9552 6560 9553 5757 9553 5753 9553 6560 9554 5753 9554 6554 9554 6554 9555 5753 9555 5754 9555 5405 9556 6025 9556 5403 9556 5403 9556 6025 9556 5801 9556 5403 9557 5801 9557 5563 9557 5563 9558 5801 9558 5811 9558 6009 9559 6011 9559 5569 9559 5569 9560 6011 9560 5407 9560 5409 8659 5389 8659 6008 8659 6008 8659 5389 8659 5782 8659 5558 8577 5560 8577 5813 8577 5813 8577 5560 8577 5815 8577 6561 9561 5406 9561 6562 9561 6562 9561 5406 9561 5404 9561 6562 9562 5404 9562 6563 9562 6563 9563 5404 9563 5402 9563 6563 9564 5402 9564 6564 9564 6564 9565 5402 9565 5401 9565 6564 9566 5401 9566 6565 9566 6565 9566 5401 9566 5400 9566 6565 9567 5400 9567 6566 9567 6566 9567 5400 9567 5399 9567 6566 9568 5399 9568 6567 9568 6567 9569 5399 9569 5398 9569 6568 9570 5388 9570 6569 9570 6569 9571 5388 9571 5390 9571 6569 9572 5390 9572 6570 9572 6570 9572 5390 9572 5396 9572 6570 9573 5396 9573 6571 9573 6571 9573 5396 9573 5392 9573 6571 9574 5392 9574 6572 9574 6572 9575 5392 9575 5391 9575 6572 9576 5391 9576 6573 9576 6573 9577 5391 9577 5408 9577 5388 8505 6029 8505 5398 8505 5398 8505 6029 8505 6028 8505 6573 9578 5408 9578 6026 9578 6026 9579 5408 9579 5406 9579 6574 348 6575 348 6576 348 6576 9580 6575 9580 6577 9580 6578 348 6579 348 6574 348 6574 348 6579 348 6580 348 6574 348 6580 348 6575 348 6575 9581 6581 9581 6577 9581 6577 9582 6581 9582 6582 9582 6577 348 6582 348 6583 348 6583 348 6582 348 6584 348 6583 9583 6584 9583 6585 9583 6585 9584 6584 9584 6586 9584 6585 348 6586 348 6587 348 6587 348 6586 348 6588 348 6587 348 6588 348 6589 348 6588 348 6590 348 6589 348 6589 9585 6590 9585 6591 9585 6589 9586 6591 9586 6578 9586 6578 348 6591 348 6579 348 6592 324 6593 324 6594 324 6594 324 6593 324 6595 324 6594 324 6595 324 6596 324 6597 324 6598 324 6599 324 6597 324 6599 324 6592 324 6592 324 6599 324 6593 324 6600 324 6601 324 6602 324 6600 324 6602 324 6603 324 6603 324 6602 324 6604 324 6604 324 6602 324 6605 324 6604 324 6605 324 6606 324 6604 324 6606 324 6607 324 6607 324 6606 324 6597 324 6597 324 6606 324 6598 324 6595 324 6608 324 6596 324 6596 324 6608 324 6609 324 6596 324 6609 324 6600 324 6600 324 6609 324 6601 324 6595 9587 6579 9587 6608 9587 6608 9588 6579 9588 6591 9588 6608 9589 6591 9589 6609 9589 6609 9590 6591 9590 6590 9590 6609 9591 6590 9591 6601 9591 6601 9592 6590 9592 6602 9592 6602 9593 6590 9593 6588 9593 6602 9594 6588 9594 6586 9594 6602 9595 6586 9595 6605 9595 6605 9596 6586 9596 6584 9596 6605 9597 6584 9597 6606 9597 6606 9598 6584 9598 6582 9598 6606 9599 6582 9599 6598 9599 6598 9600 6582 9600 6581 9600 6598 9601 6581 9601 6599 9601 6599 9602 6581 9602 6575 9602 6599 9603 6575 9603 6593 9603 6593 9604 6575 9604 6580 9604 6593 9605 6580 9605 6595 9605 6595 9606 6580 9606 6579 9606 6574 9607 6594 9607 6578 9607 6578 9608 6594 9608 6596 9608 6578 9609 6596 9609 6589 9609 6589 9610 6596 9610 6600 9610 6589 9611 6600 9611 6587 9611 6587 9612 6600 9612 6603 9612 6587 9613 6603 9613 6585 9613 6585 9614 6603 9614 6604 9614 6585 9615 6604 9615 6583 9615 6583 9616 6604 9616 6607 9616 6583 9617 6607 9617 6577 9617 6577 9618 6607 9618 6597 9618 6577 9619 6597 9619 6576 9619 6576 9620 6597 9620 6592 9620 6576 9621 6592 9621 6574 9621 6574 9622 6592 9622 6594 9622 6620 348 6621 348 6697 348 6697 9623 6621 9623 6622 9623 6697 348 6622 348 6623 348 6624 348 6625 348 6626 348 6626 348 6625 348 6627 348 6618 9624 6625 9624 6628 9624 6618 9625 6628 9625 6619 9625 6629 348 6630 348 6625 348 6625 348 6624 348 6628 348 6632 348 6633 348 6634 348 6634 348 6633 348 6625 348 6634 9626 6625 9626 6618 9626 6625 348 6633 348 6635 348 6625 348 6635 348 6629 348 6629 348 6635 348 6631 348 6636 9627 6637 9627 6638 9627 6632 348 6634 348 6639 348 6632 348 6639 348 6640 348 6640 348 6639 348 6641 348 6640 348 6641 348 6637 348 6631 348 6636 348 6629 348 6629 9628 6636 9628 6638 9628 6629 9629 6638 9629 6642 9629 6612 9630 6642 9630 6638 9630 6641 9631 6638 9631 6637 9631 6642 348 6643 348 6644 348 6645 9632 6616 9632 6646 9632 6646 348 6616 348 6647 348 6648 348 6644 348 6649 348 6649 9633 6644 9633 6650 9633 6650 348 6644 348 6651 348 6654 9634 6617 9634 6655 9634 6655 9635 6617 9635 6616 9635 6655 348 6616 348 6656 348 6656 9636 6616 9636 6652 9636 6645 9637 6651 9637 6616 9637 6616 9638 6651 9638 6644 9638 6616 348 6644 348 6653 348 6616 9639 6653 9639 6652 9639 6652 348 6657 348 6656 348 6656 348 6657 348 6658 348 6656 348 6658 348 6643 348 6643 348 6658 348 6659 348 6659 9640 6660 9640 6643 9640 6643 9641 6660 9641 6644 9641 6644 9642 6660 9642 6661 9642 6644 348 6661 348 6653 348 6662 9643 6663 9643 6664 9643 6664 348 6665 348 6666 348 6664 9644 6666 9644 6662 9644 6662 9645 6614 9645 6663 9645 6663 9646 6614 9646 6615 9646 6663 9647 6615 9647 6643 9647 6643 348 6615 348 6656 348 6615 348 6614 348 6667 348 6667 348 6668 348 6615 348 6615 9648 6668 9648 6669 9648 6669 348 6668 348 6670 348 6671 348 6615 348 6672 348 6672 348 6615 348 6669 348 6672 348 6669 348 6673 348 6664 9649 6674 9649 6675 9649 6675 348 6676 348 6664 348 6664 9650 6676 9650 6677 9650 6664 9651 6677 9651 6678 9651 6670 348 6665 348 6669 348 6669 348 6665 348 6664 348 6669 9652 6664 9652 6678 9652 6669 348 6678 348 6679 348 6680 348 6674 348 6664 348 6664 9653 6663 9653 6612 9653 6612 348 6663 348 6681 348 6612 9654 6681 9654 6642 9654 6642 348 6681 348 6643 348 6682 348 6683 348 6684 348 6682 348 6684 348 6685 348 6685 9655 6684 9655 6610 9655 6685 348 6610 348 6611 348 6682 348 6613 348 6683 348 6683 348 6613 348 6638 348 6638 348 6613 348 6612 348 6613 9656 6687 9656 6612 9656 6612 9657 6687 9657 6690 9657 6690 9658 6687 9658 6688 9658 6690 9659 6688 9659 6686 9659 6689 348 6690 348 6691 348 6691 348 6690 348 6611 348 6611 348 6690 348 6686 348 6692 348 6693 348 6691 348 6694 9625 6695 9625 6696 9625 6697 348 6698 348 6699 348 6694 348 6696 348 6610 348 6611 9660 6610 9660 6696 9660 6611 348 6696 348 6691 348 6691 348 6696 348 6700 348 6691 9661 6700 9661 6692 9661 6695 348 6694 348 6701 348 6701 348 6694 348 6702 348 6699 348 6702 348 6697 348 6697 9662 6702 9662 6694 9662 6697 348 6694 348 6618 348 6697 9663 6618 9663 6620 9663 6620 348 6618 348 6619 348 6629 9664 6703 9664 6704 9664 6629 9665 6704 9665 6630 9665 6630 9666 6704 9666 6705 9666 6630 9667 6705 9667 6625 9667 6706 9668 6707 9668 6634 9668 6634 9669 6707 9669 6639 9669 6626 9670 6627 9670 6708 9670 6709 9671 6824 9671 6623 9671 6708 9371 6710 9371 6626 9371 6626 9672 6710 9672 6711 9672 6626 9673 6711 9673 6624 9673 6624 9674 6711 9674 6712 9674 6624 9675 6712 9675 6628 9675 6628 9676 6712 9676 6713 9676 6628 9677 6713 9677 6619 9677 6619 9678 6713 9678 6714 9678 6619 9678 6714 9678 6620 9678 6620 9679 6714 9679 6715 9679 6620 9680 6715 9680 6621 9680 6621 9681 6715 9681 6716 9681 6621 9520 6716 9520 6622 9520 6622 9682 6716 9682 6717 9682 6622 9682 6717 9682 6623 9682 6623 9683 6717 9683 6718 9683 6623 9684 6718 9684 6709 9684 6709 9685 6718 9685 6719 9685 6709 9686 6719 9686 6720 9686 6720 9687 6719 9687 6721 9687 6720 9688 6721 9688 6722 9688 6722 9689 6721 9689 6708 9689 6722 9690 6708 9690 6723 9690 6723 9691 6708 9691 6627 9691 6694 8505 6724 8505 6725 8505 6694 8505 6725 8505 6618 8505 6693 9692 6692 9692 6728 9692 6728 9675 6692 9675 6700 9675 6728 9674 6700 9674 6729 9674 6729 9673 6700 9673 6696 9673 6729 9672 6696 9672 6730 9672 6730 9371 6696 9371 6695 9371 6730 9693 6695 9693 6731 9693 6731 9694 6695 9694 6701 9694 6731 9694 6701 9694 6732 9694 6732 9695 6701 9695 6702 9695 6732 9696 6702 9696 6733 9696 6733 9697 6702 9697 6699 9697 6733 9698 6699 9698 6734 9698 6734 9683 6699 9683 6698 9683 6734 9683 6698 9683 6735 9683 6735 9699 6698 9699 6726 9699 6735 9700 6726 9700 6736 9700 6736 9701 6726 9701 6737 9701 6736 9702 6737 9702 6738 9702 6738 9703 6737 9703 6739 9703 6738 9704 6739 9704 6740 9704 6740 9705 6739 9705 6727 9705 6740 9706 6727 9706 6741 9706 6741 9707 6727 9707 6693 9707 6741 9708 6693 9708 6728 9708 6742 9709 6743 9709 6684 9709 6684 9710 6743 9710 6610 9710 6643 9711 6744 9711 6745 9711 6745 9712 6744 9712 6746 9712 6747 9713 6748 9713 6749 9713 6749 9714 6748 9714 6663 9714 6644 9715 6750 9715 6642 9715 6642 9716 6750 9716 6751 9716 6656 9717 6752 9717 6753 9717 6656 9718 6753 9718 6655 9718 6655 9719 6753 9719 6754 9719 6655 9720 6754 9720 6654 9720 6654 9721 6754 9721 6755 9721 6654 9722 6755 9722 6617 9722 6617 9723 6755 9723 6763 9723 6617 9723 6763 9723 6616 9723 6742 9724 6684 9724 6756 9724 6756 8577 6684 8577 6683 8577 6756 9725 6683 9725 6757 9725 6757 9726 6683 9726 6758 9726 6691 9727 6759 9727 6760 9727 6691 9728 6760 9728 6689 9728 6689 9729 6760 9729 6761 9729 6689 9730 6761 9730 6690 9730 6690 9731 6761 9731 6612 9731 6612 9732 6761 9732 6762 9732 4989 324 6764 324 6765 324 6782 324 6766 324 6767 324 5012 324 5011 324 6705 324 6705 324 5011 324 6769 324 6769 324 6707 324 6705 324 6705 9733 6707 9733 6706 9733 6705 324 6706 324 6725 324 6705 324 6725 324 6723 324 6769 324 5010 324 6707 324 5010 324 5021 324 6707 324 6707 324 5021 324 5020 324 6707 324 5020 324 6768 324 6768 9734 5020 9734 5019 9734 6768 9735 5019 9735 5018 9735 5018 9736 5014 9736 6751 9736 6751 9737 5014 9737 5016 9737 6751 9738 5016 9738 6703 9738 6703 324 5016 324 5017 324 6703 324 5017 324 5012 324 6703 324 5012 324 6704 324 6704 324 5012 324 6705 324 5018 9739 6751 9739 6768 9739 6768 324 6751 324 6762 324 6768 324 6762 324 6761 324 6768 9740 6761 9740 4993 9740 4993 324 6761 324 4994 324 4994 324 6761 324 4996 324 6756 324 5004 324 6742 324 6742 324 5004 324 6770 324 6742 324 6770 324 6743 324 6743 324 6770 324 5001 324 6743 324 5001 324 6724 324 5001 324 6771 324 6724 324 6724 324 6771 324 4999 324 6724 324 4999 324 4998 324 4993 324 5007 324 6768 324 6768 9735 5007 9735 5006 9735 6768 9741 5006 9741 6756 9741 6756 324 5006 324 5005 324 6756 324 5005 324 5004 324 6761 324 6760 324 6759 324 6759 324 6724 324 6761 324 6761 324 6724 324 4998 324 6761 324 4998 324 4996 324 6759 324 6772 324 6773 324 6774 324 6773 324 6775 324 6774 324 6775 324 6726 324 6726 324 6775 324 6776 324 6726 324 6776 324 6737 324 6737 324 6776 324 6777 324 6737 324 6777 324 6739 324 6739 324 6777 324 6727 324 6727 324 6777 324 6778 324 6727 324 6778 324 6779 324 6727 324 6779 324 6759 324 6759 324 6779 324 6772 324 6749 324 6762 324 6746 324 6746 324 6762 324 6751 324 6746 9742 6751 9742 6745 9742 6780 324 6781 324 6782 324 6783 324 6781 324 6784 324 6785 324 6786 324 6787 324 6787 324 6786 324 6783 324 6787 324 6783 324 6788 324 6788 324 6783 324 6784 324 6787 324 6788 324 6789 324 6787 324 6789 324 6790 324 6790 324 6789 324 6767 324 6767 324 6789 324 6791 324 6791 324 6780 324 6767 324 6767 324 6780 324 6782 324 6793 324 6792 324 6794 324 6793 324 6794 324 6764 324 6764 324 6794 324 6795 324 6764 324 6795 324 6765 324 6765 324 6795 324 6796 324 6763 324 6755 324 6797 324 6797 324 6755 324 6754 324 6797 324 6754 324 6798 324 6798 324 6754 324 6753 324 6798 324 6753 324 6752 324 6800 324 6801 324 6802 324 6802 324 6801 324 6803 324 6805 324 6806 324 6751 324 6745 324 6751 324 6806 324 6824 324 6807 324 6808 324 6807 324 6824 324 6809 324 6809 324 6824 324 6709 324 6809 324 6709 324 6810 324 6810 324 6709 324 6720 324 6810 324 6720 324 6722 324 6810 324 6722 324 6811 324 6725 324 6808 324 6812 324 6812 324 6813 324 6725 324 6725 324 6813 324 6723 324 6723 324 6813 324 6811 324 6723 324 6811 324 6722 324 6763 324 6797 324 4976 324 6751 9743 6750 9743 6805 9743 6805 324 6750 324 4980 324 4980 324 6750 324 4981 324 6806 324 4985 324 6745 324 6745 324 4985 324 4984 324 6745 9744 4984 9744 6752 9744 6752 324 4984 324 4983 324 6752 324 4983 324 6798 324 6793 324 4951 324 6792 324 6792 324 4951 324 4949 324 6792 324 4949 324 6749 324 4949 324 4948 324 6749 324 6749 9745 4948 9745 6815 9745 6749 9746 6815 9746 6783 9746 6783 324 6815 324 6816 324 4991 324 4990 324 6783 324 6783 324 6816 324 4991 324 6750 324 6817 324 6763 324 6763 9747 6817 9747 6818 9747 6802 324 6819 324 6820 324 6802 324 6814 324 6763 324 6802 9748 6763 9748 6819 9748 6819 324 6763 324 6818 324 6802 324 6820 324 6821 324 6802 324 6821 324 6800 324 6800 324 6821 324 6822 324 6800 324 6822 324 6823 324 6800 9749 6823 9749 6750 9749 6750 324 6823 324 6817 324 4976 324 4981 324 6763 324 6763 324 4981 324 6750 324 6750 324 6804 324 6800 324 6800 324 6804 324 6799 324 6752 9750 6792 9750 6745 9750 6745 9751 6792 9751 6749 9751 6749 324 6783 324 6762 324 6773 324 6774 324 6759 324 6759 324 6774 324 6724 324 6724 324 6774 324 6824 324 6724 324 6824 324 6725 324 6725 324 6824 324 6808 324 6781 324 6783 324 6782 324 6782 9752 6783 9752 6765 9752 6765 324 6783 324 4990 324 6765 324 4990 324 4989 324 6669 9753 6765 9753 6796 9753 6669 9753 6796 9753 6673 9753 6673 9754 6796 9754 6795 9754 6673 9755 6795 9755 6672 9755 6672 9756 6795 9756 6794 9756 6672 9757 6794 9757 6671 9757 6671 9758 6794 9758 6792 9758 6671 9759 6792 9759 6615 9759 6783 9760 6664 9760 6612 9760 6783 9761 6612 9761 6762 9761 6642 9762 6751 9762 6629 9762 6629 9763 6751 9763 6703 9763 6639 9764 6707 9764 6641 9764 6641 9765 6707 9765 6825 9765 6825 9766 6707 9766 6757 9766 6615 9767 6792 9767 6656 9767 6656 9768 6792 9768 6752 9768 6749 8646 6663 8646 6745 8646 6745 8646 6663 8646 6643 8646 6680 9769 6786 9769 6785 9769 6766 9770 6782 9770 6679 9770 6826 9771 6785 9771 6827 9771 6827 9772 6785 9772 6787 9772 6827 9772 6787 9772 6828 9772 6828 9704 6787 9704 6790 9704 6828 9704 6790 9704 6829 9704 6829 9773 6790 9773 6767 9773 6829 9773 6767 9773 6830 9773 6830 9774 6767 9774 6766 9774 6830 9774 6766 9774 6831 9774 6831 9775 6766 9775 6679 9775 6831 9674 6679 9674 6832 9674 6832 9673 6679 9673 6678 9673 6832 9672 6678 9672 6833 9672 6833 9371 6678 9371 6677 9371 6833 9693 6677 9693 6834 9693 6834 9694 6677 9694 6676 9694 6834 9694 6676 9694 6835 9694 6835 9695 6676 9695 6675 9695 6835 9695 6675 9695 6836 9695 6836 9698 6675 9698 6674 9698 6836 9776 6674 9776 6837 9776 6837 9777 6674 9777 6680 9777 6837 9683 6680 9683 6826 9683 6826 9682 6680 9682 6785 9682 6664 8646 6783 8646 6786 8646 6664 8646 6786 8646 6680 8646 6679 8505 6782 8505 6669 8505 6669 8505 6782 8505 6765 8505 6648 8646 6804 8646 6644 8646 6644 8646 6804 8646 6750 8646 6616 8505 6763 8505 6647 8505 6647 8505 6763 8505 6814 8505 6647 9778 6814 9778 6802 9778 6799 9779 6804 9779 6648 9779 6838 9780 6802 9780 6839 9780 6839 9781 6802 9781 6803 9781 6839 9782 6803 9782 6840 9782 6840 9689 6803 9689 6801 9689 6840 9689 6801 9689 6841 9689 6841 9783 6801 9783 6800 9783 6841 9784 6800 9784 6842 9784 6842 9785 6800 9785 6799 9785 6842 9685 6799 9685 6843 9685 6843 9684 6799 9684 6648 9684 6843 9683 6648 9683 6844 9683 6844 9682 6648 9682 6649 9682 6844 9786 6649 9786 6845 9786 6845 9787 6649 9787 6650 9787 6845 9520 6650 9520 6846 9520 6846 9679 6650 9679 6651 9679 6846 9679 6651 9679 6847 9679 6847 9678 6651 9678 6645 9678 6847 9678 6645 9678 6848 9678 6848 9677 6645 9677 6646 9677 6848 9676 6646 9676 6849 9676 6849 9675 6646 9675 6647 9675 6849 9674 6647 9674 6838 9674 6838 9788 6647 9788 6802 9788 6724 9789 6694 9789 6610 9789 6724 9790 6610 9790 6743 9790 6759 9791 6691 9791 6727 9791 6727 9792 6691 9792 6693 9792 6623 8646 6824 8646 6697 8646 6697 8646 6824 8646 6774 8646 6697 8646 6774 8646 6698 8646 6698 9793 6774 9793 6726 9793 6625 9794 6705 9794 6627 9794 6627 9795 6705 9795 6723 9795 6706 9796 6634 9796 6618 9796 6706 9797 6618 9797 6725 9797 5001 9798 6685 9798 6771 9798 6771 9799 6685 9799 6611 9799 6771 9800 6611 9800 4999 9800 4999 9801 6611 9801 4998 9801 4998 9802 6611 9802 6686 9802 4998 9803 6686 9803 4996 9803 4996 9804 6686 9804 4994 9804 4994 9805 6686 9805 6688 9805 4994 9005 6688 9005 4993 9005 4993 9806 6688 9806 6687 9806 4993 9807 6687 9807 5007 9807 5007 9808 6687 9808 5006 9808 5006 9809 6687 9809 6613 9809 5006 9810 6613 9810 5005 9810 5005 9811 6613 9811 5004 9811 5004 9812 6613 9812 6682 9812 5004 9813 6682 9813 6770 9813 6770 9814 6682 9814 5001 9814 5001 9815 6682 9815 6685 9815 5010 9816 6632 9816 5021 9816 5021 9817 6632 9817 6640 9817 5021 9003 6640 9003 5020 9003 5020 9818 6640 9818 6637 9818 5020 9819 6637 9819 5019 9819 5019 9820 6637 9820 5018 9820 5018 9821 6637 9821 6636 9821 5018 9822 6636 9822 5014 9822 5014 9823 6636 9823 5016 9823 5016 9824 6636 9824 6631 9824 5016 9825 6631 9825 5017 9825 5017 9826 6631 9826 6635 9826 5017 9810 6635 9810 5012 9810 5012 9827 6635 9827 5011 9827 5011 9828 6635 9828 6633 9828 5011 9829 6633 9829 6769 9829 6769 9830 6633 9830 5010 9830 5010 9831 6633 9831 6632 9831 6806 9832 6660 9832 4985 9832 4985 9833 6660 9833 6659 9833 4985 9834 6659 9834 4984 9834 4984 9835 6659 9835 4983 9835 4983 9836 6659 9836 6658 9836 4983 9837 6658 9837 6798 9837 6798 9838 6658 9838 6657 9838 6798 9839 6657 9839 6797 9839 6797 9840 6657 9840 6652 9840 6797 9841 6652 9841 4976 9841 4976 9842 6652 9842 4981 9842 4981 9843 6652 9843 6653 9843 4981 9844 6653 9844 4980 9844 4980 9845 6653 9845 6805 9845 6805 9846 6653 9846 6661 9846 6805 9847 6661 9847 6806 9847 6806 9848 6661 9848 6660 9848 6815 9849 6662 9849 6816 9849 6816 9850 6662 9850 6666 9850 6816 9851 6666 9851 4991 9851 4991 9852 6666 9852 6665 9852 4991 9853 6665 9853 4990 9853 4990 9854 6665 9854 4989 9854 4989 9855 6665 9855 6670 9855 4989 9856 6670 9856 6764 9856 6764 9857 6670 9857 6793 9857 6793 9858 6670 9858 6668 9858 6793 9859 6668 9859 4951 9859 4951 9860 6668 9860 6667 9860 4951 9861 6667 9861 4949 9861 4949 9862 6667 9862 6614 9862 4949 9863 6614 9863 4948 9863 4948 9864 6614 9864 6815 9864 6815 9865 6614 9865 6662 9865 6850 348 6828 348 6851 348 6851 9866 6828 9866 6829 9866 6851 9867 6829 9867 6852 9867 6852 348 6829 348 6830 348 6852 348 6830 348 6831 348 6852 348 6831 348 6853 348 6853 348 6831 348 6832 348 6853 348 6832 348 6854 348 6854 348 6832 348 6833 348 6854 348 6833 348 6834 348 6854 348 6834 348 6855 348 6855 9868 6834 9868 6835 9868 6855 9869 6835 9869 6836 9869 6855 348 6836 348 6856 348 6856 9870 6836 9870 6837 9870 6856 348 6837 348 6826 348 6856 348 6826 348 6850 348 6850 348 6826 348 6827 348 6850 348 6827 348 6828 348 6857 348 6846 348 6858 348 6858 9871 6846 9871 6847 9871 6858 9872 6847 9872 6848 9872 6858 348 6848 348 6859 348 6859 9873 6848 9873 6849 9873 6859 348 6849 348 6838 348 6859 348 6838 348 6860 348 6860 348 6838 348 6839 348 6860 9874 6839 9874 6840 9874 6860 9875 6840 9875 6861 9875 6861 9876 6840 9876 6841 9876 6861 9877 6841 9877 6862 9877 6862 348 6841 348 6842 348 6862 348 6842 348 6843 348 6862 348 6843 348 6863 348 6863 348 6843 348 6844 348 6863 348 6844 348 6845 348 6863 348 6845 348 6857 348 6857 348 6845 348 6846 348 6864 9878 6716 9878 6865 9878 6865 348 6716 348 6715 348 6865 348 6715 348 6714 348 6865 9879 6714 9879 6866 9879 6866 348 6714 348 6713 348 6866 348 6713 348 6712 348 6866 9880 6712 9880 6867 9880 6867 348 6712 348 6711 348 6867 348 6711 348 6710 348 6867 348 6710 348 6868 348 6868 348 6710 348 6708 348 6868 348 6708 348 6869 348 6869 348 6708 348 6721 348 6869 348 6721 348 6719 348 6869 348 6719 348 6870 348 6870 348 6719 348 6718 348 6870 348 6718 348 6717 348 6870 9881 6717 9881 6864 9881 6864 348 6717 348 6716 348 6871 9882 6736 9882 6872 9882 6872 348 6736 348 6738 348 6872 348 6738 348 6740 348 6872 348 6740 348 6873 348 6873 348 6740 348 6741 348 6873 348 6741 348 6728 348 6873 348 6728 348 6874 348 6874 348 6728 348 6729 348 6874 348 6729 348 6730 348 6874 348 6730 348 6875 348 6875 348 6730 348 6731 348 6875 348 6731 348 6876 348 6876 348 6731 348 6732 348 6876 348 6732 348 6733 348 6876 348 6733 348 6877 348 6877 348 6733 348 6734 348 6877 348 6734 348 6735 348 6877 348 6735 348 6871 348 6871 348 6735 348 6736 348 6775 9883 6877 9883 6776 9883 6776 9884 6877 9884 6871 9884 6776 9885 6871 9885 6777 9885 6777 9886 6871 9886 6872 9886 6777 9887 6872 9887 6778 9887 6778 9888 6872 9888 6873 9888 6778 9889 6873 9889 6779 9889 6779 9890 6873 9890 6874 9890 6779 9891 6874 9891 6772 9891 6772 9892 6874 9892 6875 9892 6772 9893 6875 9893 6773 9893 6773 9894 6875 9894 6876 9894 6773 9895 6876 9895 6775 9895 6775 9896 6876 9896 6877 9896 6809 9897 6870 9897 6807 9897 6807 9898 6870 9898 6864 9898 6807 9899 6864 9899 6808 9899 6808 9900 6864 9900 6865 9900 6808 9901 6865 9901 6812 9901 6812 9902 6865 9902 6866 9902 6812 9903 6866 9903 6813 9903 6813 9904 6866 9904 6867 9904 6813 9905 6867 9905 6811 9905 6811 9906 6867 9906 6868 9906 6811 9907 6868 9907 6810 9907 6810 9908 6868 9908 6869 9908 6810 9909 6869 9909 6809 9909 6809 9910 6869 9910 6870 9910 6823 9911 6863 9911 6817 9911 6817 9912 6863 9912 6857 9912 6817 9913 6857 9913 6858 9913 6817 9914 6858 9914 6818 9914 6818 9915 6858 9915 6859 9915 6818 9916 6859 9916 6819 9916 6819 9917 6859 9917 6820 9917 6820 9918 6859 9918 6860 9918 6820 9919 6860 9919 6821 9919 6821 9920 6860 9920 6861 9920 6821 9921 6861 9921 6822 9921 6822 9922 6861 9922 6862 9922 6822 9923 6862 9923 6823 9923 6823 9924 6862 9924 6863 9924 6788 9925 6856 9925 6850 9925 6788 9926 6850 9926 6789 9926 6789 9927 6850 9927 6851 9927 6789 9928 6851 9928 6791 9928 6791 9929 6851 9929 6852 9929 6791 9930 6852 9930 6780 9930 6780 9931 6852 9931 6853 9931 6780 9932 6853 9932 6854 9932 6780 9933 6854 9933 6781 9933 6781 9934 6854 9934 6855 9934 6781 9935 6855 9935 6784 9935 6784 9936 6855 9936 6856 9936 6784 9937 6856 9937 6788 9937 6878 348 6879 348 6880 348 6880 348 6879 348 6881 348 6881 8646 6879 8646 6882 8646 6882 8646 6879 8646 6883 8646 6879 8507 6878 8507 6883 8507 6883 8507 6878 8507 6884 8507 6878 8505 6880 8505 6884 8505 6884 8505 6880 8505 6885 8505 6880 8511 6881 8511 6885 8511 6885 8511 6881 8511 6882 8511 6886 348 6887 348 6888 348 6888 348 6887 348 6889 348 6889 8646 6887 8646 6890 8646 6890 8646 6887 8646 6891 8646 6887 8507 6886 8507 6891 8507 6891 8507 6886 8507 6892 8507 6886 8505 6888 8505 6892 8505 6892 8505 6888 8505 6893 8505 6888 8511 6889 8511 6893 8511 6893 8511 6889 8511 6890 8511 6894 348 6895 348 6896 348 6896 348 6895 348 6897 348 6897 8646 6895 8646 6898 8646 6898 8646 6895 8646 6899 8646 6895 8507 6894 8507 6899 8507 6899 8507 6894 8507 6900 8507 6894 8505 6896 8505 6900 8505 6900 8505 6896 8505 6901 8505 6896 8511 6897 8511 6901 8511 6901 8511 6897 8511 6898 8511 6902 348 6903 348 6904 348 6904 348 6903 348 6905 348 6905 8646 6903 8646 6906 8646 6906 8646 6903 8646 6907 8646 6903 8507 6902 8507 6907 8507 6907 8507 6902 8507 6908 8507 6902 8505 6904 8505 6908 8505 6908 8505 6904 8505 6909 8505 6904 8511 6905 8511 6909 8511 6909 8511 6905 8511 6906 8511 6910 348 6911 348 6912 348 6912 348 6911 348 6913 348 6913 8646 6911 8646 6914 8646 6914 8646 6911 8646 6915 8646 6911 8507 6910 8507 6915 8507 6915 8507 6910 8507 6916 8507 6910 8505 6912 8505 6916 8505 6916 8505 6912 8505 6917 8505 6912 8511 6913 8511 6917 8511 6917 8511 6913 8511 6914 8511 6918 348 6919 348 6920 348 6920 348 6919 348 6921 348 6921 8646 6919 8646 6922 8646 6922 8646 6919 8646 6923 8646 6919 8507 6918 8507 6923 8507 6923 8507 6918 8507 6924 8507 6918 8505 6920 8505 6924 8505 6924 8505 6920 8505 6925 8505 6920 8511 6921 8511 6925 8511 6925 8511 6921 8511 6922 8511 6926 348 6927 348 6928 348 6928 348 6927 348 6929 348 6929 8646 6927 8646 6930 8646 6930 8646 6927 8646 6931 8646 6927 8507 6926 8507 6931 8507 6931 8507 6926 8507 6932 8507 6926 8505 6928 8505 6932 8505 6932 8505 6928 8505 6933 8505 6928 8511 6929 8511 6933 8511 6933 8511 6929 8511 6930 8511 6934 348 6935 348 6936 348 6936 348 6935 348 6937 348 6937 8646 6935 8646 6938 8646 6938 8646 6935 8646 6939 8646 6935 8507 6934 8507 6939 8507 6939 8507 6934 8507 6940 8507 6934 8505 6936 8505 6940 8505 6940 8505 6936 8505 6941 8505 6936 8511 6937 8511 6941 8511 6941 8511 6937 8511 6938 8511 6942 348 6943 348 6944 348 6944 348 6943 348 6945 348 6945 8646 6943 8646 6946 8646 6946 8646 6943 8646 6947 8646 6943 8507 6942 8507 6947 8507 6947 8507 6942 8507 6948 8507 6942 8505 6944 8505 6948 8505 6948 8505 6944 8505 6949 8505 6944 8511 6945 8511 6949 8511 6949 8511 6945 8511 6946 8511 6950 348 6951 348 6952 348 6952 348 6951 348 6953 348 6953 8646 6951 8646 6954 8646 6954 8646 6951 8646 6955 8646 6951 8507 6950 8507 6955 8507 6955 8507 6950 8507 6956 8507 6950 8505 6952 8505 6956 8505 6956 8505 6952 8505 6957 8505 6952 8511 6953 8511 6957 8511 6957 8511 6953 8511 6954 8511 6958 348 6959 348 6960 348 6960 348 6959 348 6961 348 6961 8646 6959 8646 6962 8646 6962 8646 6959 8646 6963 8646 6959 8507 6958 8507 6963 8507 6963 8507 6958 8507 6964 8507 6958 8505 6960 8505 6964 8505 6964 8505 6960 8505 6965 8505 6960 8511 6961 8511 6965 8511 6965 8511 6961 8511 6962 8511 6966 348 6967 348 6968 348 6968 348 6967 348 6969 348 6969 8646 6967 8646 6970 8646 6970 8646 6967 8646 6971 8646 6967 8507 6966 8507 6971 8507 6971 8507 6966 8507 6972 8507 6966 8505 6968 8505 6972 8505 6972 8505 6968 8505 6973 8505 6968 8511 6969 8511 6973 8511 6973 8511 6969 8511 6970 8511 6974 348 6975 348 6976 348 6976 348 6975 348 6977 348 6977 8646 6975 8646 6978 8646 6978 8646 6975 8646 6979 8646 6975 8507 6974 8507 6979 8507 6979 8507 6974 8507 6980 8507 6974 8505 6976 8505 6980 8505 6980 8505 6976 8505 6981 8505 6976 8511 6977 8511 6981 8511 6981 8511 6977 8511 6978 8511 6982 348 6983 348 6984 348 6984 348 6983 348 6985 348 6985 8646 6983 8646 6986 8646 6986 8646 6983 8646 6987 8646 6983 8507 6982 8507 6987 8507 6987 8507 6982 8507 6988 8507 6982 8505 6984 8505 6988 8505 6988 8505 6984 8505 6989 8505 6984 8511 6985 8511 6989 8511 6989 8511 6985 8511 6986 8511 6990 348 6991 348 6992 348 6992 348 6991 348 6993 348 6993 8646 6991 8646 6994 8646 6994 8646 6991 8646 6995 8646 6991 8507 6990 8507 6995 8507 6995 8507 6990 8507 6996 8507 6990 8505 6992 8505 6996 8505 6996 8505 6992 8505 6997 8505 6992 8511 6993 8511 6997 8511 6997 8511 6993 8511 6994 8511 6998 348 6999 348 7000 348 7000 348 6999 348 7001 348 7001 8646 6999 8646 7002 8646 7002 8646 6999 8646 7003 8646 6999 8507 6998 8507 7003 8507 7003 8507 6998 8507 7004 8507 6998 8505 7000 8505 7004 8505 7004 8505 7000 8505 7005 8505 7000 8511 7001 8511 7005 8511 7005 8511 7001 8511 7002 8511 7006 348 7007 348 7008 348 7008 348 7007 348 7009 348 7009 8646 7007 8646 7010 8646 7010 8646 7007 8646 7011 8646 7007 8507 7006 8507 7011 8507 7011 8507 7006 8507 7012 8507 7006 8505 7008 8505 7012 8505 7012 8505 7008 8505 7013 8505 7008 8511 7009 8511 7013 8511 7013 8511 7009 8511 7010 8511 7014 348 7015 348 7016 348 7016 348 7015 348 7017 348 7017 8646 7015 8646 7018 8646 7018 8646 7015 8646 7019 8646 7015 8507 7014 8507 7019 8507 7019 8507 7014 8507 7020 8507 7014 8505 7016 8505 7020 8505 7020 8505 7016 8505 7021 8505 7016 8511 7017 8511 7021 8511 7021 8511 7017 8511 7018 8511 7022 348 7023 348 7024 348 7024 348 7023 348 7025 348 7025 8646 7023 8646 7026 8646 7026 8646 7023 8646 7027 8646 7023 8507 7022 8507 7027 8507 7027 8507 7022 8507 7028 8507 7022 8505 7024 8505 7028 8505 7028 8505 7024 8505 7029 8505 7024 8511 7025 8511 7029 8511 7029 8511 7025 8511 7026 8511 7030 348 7031 348 7032 348 7032 348 7031 348 7033 348 7033 8646 7031 8646 7034 8646 7034 8646 7031 8646 7035 8646 7031 8507 7030 8507 7035 8507 7035 8507 7030 8507 7036 8507 7030 8505 7032 8505 7036 8505 7036 8505 7032 8505 7037 8505 7032 8511 7033 8511 7037 8511 7037 8511 7033 8511 7034 8511 7038 348 7039 348 7040 348 7040 348 7039 348 7041 348 7041 8646 7039 8646 7042 8646 7042 8646 7039 8646 7043 8646 7039 8507 7038 8507 7043 8507 7043 8507 7038 8507 7044 8507 7038 8505 7040 8505 7044 8505 7044 8505 7040 8505 7045 8505 7040 8511 7041 8511 7045 8511 7045 8511 7041 8511 7042 8511 7046 348 7047 348 7048 348 7048 348 7047 348 7049 348 7049 8646 7047 8646 7050 8646 7050 8646 7047 8646 7051 8646 7047 8507 7046 8507 7051 8507 7051 8507 7046 8507 7052 8507 7046 8505 7048 8505 7052 8505 7052 8505 7048 8505 7053 8505 7048 8511 7049 8511 7053 8511 7053 8511 7049 8511 7050 8511 7054 348 7055 348 7056 348 7056 348 7055 348 7057 348 7057 8646 7055 8646 7058 8646 7058 8646 7055 8646 7059 8646 7055 8507 7054 8507 7059 8507 7059 8507 7054 8507 7060 8507 7054 8505 7056 8505 7060 8505 7060 8505 7056 8505 7061 8505 7056 8511 7057 8511 7061 8511 7061 8511 7057 8511 7058 8511 7062 348 7063 348 7064 348 7064 348 7063 348 7065 348 7065 8646 7063 8646 7066 8646 7066 8646 7063 8646 7067 8646 7063 8507 7062 8507 7067 8507 7067 8507 7062 8507 7068 8507 7062 8505 7064 8505 7068 8505 7068 8505 7064 8505 7069 8505 7064 8511 7065 8511 7069 8511 7069 8511 7065 8511 7066 8511 7070 348 7071 348 7072 348 7072 348 7071 348 7073 348 7073 8646 7071 8646 7074 8646 7074 8646 7071 8646 7075 8646 7071 8507 7070 8507 7075 8507 7075 8507 7070 8507 7076 8507 7070 8505 7072 8505 7076 8505 7076 8505 7072 8505 7077 8505 7072 8511 7073 8511 7077 8511 7077 8511 7073 8511 7074 8511 7078 348 7079 348 7080 348 7080 348 7079 348 7081 348 7081 8646 7079 8646 7082 8646 7082 8646 7079 8646 7083 8646 7079 8507 7078 8507 7083 8507 7083 8507 7078 8507 7084 8507 7078 8505 7080 8505 7084 8505 7084 8505 7080 8505 7085 8505 7080 8511 7081 8511 7085 8511 7085 8511 7081 8511 7082 8511 7086 348 7087 348 7088 348 7088 348 7087 348 7089 348 7089 8646 7087 8646 7090 8646 7090 8646 7087 8646 7091 8646 7087 8507 7086 8507 7091 8507 7091 8507 7086 8507 7092 8507 7086 8505 7088 8505 7092 8505 7092 8505 7088 8505 7093 8505 7088 8511 7089 8511 7093 8511 7093 8511 7089 8511 7090 8511 7094 348 7095 348 7096 348 7096 348 7095 348 7097 348 7097 8646 7095 8646 7098 8646 7098 8646 7095 8646 7099 8646 7095 8507 7094 8507 7099 8507 7099 8507 7094 8507 7100 8507 7094 8505 7096 8505 7100 8505 7100 8505 7096 8505 7101 8505 7096 8511 7097 8511 7101 8511 7101 8511 7097 8511 7098 8511 7102 348 7103 348 7104 348 7104 348 7103 348 7105 348 7105 8646 7103 8646 7106 8646 7106 8646 7103 8646 7107 8646 7103 8507 7102 8507 7107 8507 7107 8507 7102 8507 7108 8507 7102 8505 7104 8505 7108 8505 7108 8505 7104 8505 7109 8505 7104 8511 7105 8511 7109 8511 7109 8511 7105 8511 7106 8511 7110 348 7111 348 7112 348 7112 348 7111 348 7113 348 7113 8646 7111 8646 7114 8646 7114 8646 7111 8646 7115 8646 7111 8507 7110 8507 7115 8507 7115 8507 7110 8507 7116 8507 7110 8505 7112 8505 7116 8505 7116 8505 7112 8505 7117 8505 7112 8511 7113 8511 7117 8511 7117 8511 7113 8511 7114 8511 7118 348 7119 348 7120 348 7120 348 7119 348 7121 348 7121 8646 7119 8646 7122 8646 7122 8646 7119 8646 7123 8646 7119 8507 7118 8507 7123 8507 7123 8507 7118 8507 7124 8507 7118 8505 7120 8505 7124 8505 7124 8505 7120 8505 7125 8505 7120 8511 7121 8511 7125 8511 7125 8511 7121 8511 7122 8511 7126 348 7127 348 7128 348 7128 348 7127 348 7129 348 7129 8646 7127 8646 7130 8646 7130 8646 7127 8646 7131 8646 7127 8507 7126 8507 7131 8507 7131 8507 7126 8507 7132 8507 7126 8505 7128 8505 7132 8505 7132 8505 7128 8505 7133 8505 7128 8511 7129 8511 7133 8511 7133 8511 7129 8511 7130 8511 7134 348 7135 348 7136 348 7136 348 7135 348 7137 348 7137 8646 7135 8646 7138 8646 7138 8646 7135 8646 7139 8646 7135 8507 7134 8507 7139 8507 7139 8507 7134 8507 7140 8507 7134 8505 7136 8505 7140 8505 7140 8505 7136 8505 7141 8505 7136 8511 7137 8511 7141 8511 7141 8511 7137 8511 7138 8511 7142 348 7143 348 7144 348 7144 348 7143 348 7145 348 7145 8646 7143 8646 7146 8646 7146 8646 7143 8646 7147 8646 7143 8507 7142 8507 7147 8507 7147 8507 7142 8507 7148 8507 7142 8505 7144 8505 7148 8505 7148 8505 7144 8505 7149 8505 7144 8511 7145 8511 7149 8511 7149 8511 7145 8511 7146 8511 7150 348 7151 348 7152 348 7152 348 7151 348 7153 348 7153 8646 7151 8646 7154 8646 7154 8646 7151 8646 7155 8646 7151 8507 7150 8507 7155 8507 7155 8507 7150 8507 7156 8507 7150 8505 7152 8505 7156 8505 7156 8505 7152 8505 7157 8505 7152 8511 7153 8511 7157 8511 7157 8511 7153 8511 7154 8511 7158 348 7159 348 7160 348 7160 348 7159 348 7161 348 7161 8646 7159 8646 7162 8646 7162 8646 7159 8646 7163 8646 7159 8507 7158 8507 7163 8507 7163 8507 7158 8507 7164 8507 7158 8505 7160 8505 7164 8505 7164 8505 7160 8505 7165 8505 7160 8511 7161 8511 7165 8511 7165 8511 7161 8511 7162 8511 7166 8646 7167 8646 7168 8646 7168 8646 7167 8646 7169 8646 7168 8646 7169 8646 7170 8646 7171 8507 7173 8507 7169 8507 7169 9938 7173 9938 7174 9938 7175 8505 7176 8505 7171 8505 7171 9939 7176 9939 7177 9939 7171 9940 7177 9940 7172 9940 7167 9941 7178 9941 7175 9941 7175 8511 7178 8511 7179 8511 7175 8511 7179 8511 7176 8511 7180 348 7181 348 7182 348 7182 348 7181 348 7183 348 7183 8646 7181 8646 7184 8646 7184 8646 7181 8646 7185 8646 7181 8507 7180 8507 7185 8507 7185 8507 7180 8507 7186 8507 7180 8505 7182 8505 7186 8505 7186 8505 7182 8505 7187 8505 7182 8511 7183 8511 7187 8511 7187 8511 7183 8511 7184 8511 7188 348 7189 348 7190 348 7190 348 7189 348 7191 348 7191 8646 7189 8646 7192 8646 7192 8646 7189 8646 7193 8646 7189 8507 7188 8507 7193 8507 7193 8507 7188 8507 7194 8507 7188 8505 7190 8505 7194 8505 7194 8505 7190 8505 7195 8505 7190 8511 7191 8511 7195 8511 7195 8511 7191 8511 7192 8511 7196 348 7197 348 7198 348 7198 348 7197 348 7199 348 7199 8646 7197 8646 7200 8646 7200 8646 7197 8646 7201 8646 7197 8507 7196 8507 7201 8507 7201 8507 7196 8507 7202 8507 7196 8505 7198 8505 7202 8505 7202 8505 7198 8505 7203 8505 7198 8511 7199 8511 7203 8511 7203 8511 7199 8511 7200 8511 7204 348 7205 348 7206 348 7206 348 7205 348 7207 348 7207 8646 7205 8646 7208 8646 7208 8646 7205 8646 7209 8646 7205 8507 7204 8507 7209 8507 7209 8507 7204 8507 7210 8507 7204 8505 7206 8505 7210 8505 7210 8505 7206 8505 7211 8505 7206 8511 7207 8511 7211 8511 7211 8511 7207 8511 7208 8511 7169 8646 7212 8646 7170 8646 7170 8646 7212 8646 7213 8646 7214 8507 7215 8507 7212 8507 7212 8507 7215 8507 7213 8507 7214 8505 7171 8505 7215 8505 7215 8505 7171 8505 7172 8505 7169 8511 7170 8511 7174 8511 7169 8511 7174 8511 7171 8511 7171 9942 7174 9942 7173 9942 7171 8511 7173 8511 7172 8511 7216 8646 7217 8646 7218 8646 7218 8646 7217 8646 7219 8646 7216 324 7218 324 7220 324 7220 324 7218 324 7221 324 7217 8511 7216 8511 7222 8511 7222 8511 7216 8511 7220 8511 7219 348 7217 348 7223 348 7223 348 7217 348 7222 348 7218 8507 7219 8507 7221 8507 7221 8507 7219 8507 7223 8507 7224 8646 7225 8646 7226 8646 7226 8646 7225 8646 7227 8646 7224 324 7226 324 7228 324 7228 324 7226 324 7229 324 7225 8511 7224 8511 7230 8511 7230 8511 7224 8511 7228 8511 7227 348 7225 348 7231 348 7231 348 7225 348 7230 348 7226 8507 7227 8507 7229 8507 7229 8507 7227 8507 7231 8507 7232 348 7233 348 7234 348 7234 348 7233 348 7235 348 7233 8505 7236 8505 7235 8505 7235 8505 7236 8505 7237 8505 7236 8511 7233 8511 7238 8511 7238 9943 7233 9943 7232 9943 7238 8511 7232 8511 7239 8511 7240 9944 7234 9944 7241 9944 7241 9945 7234 9945 7242 9945 7241 9946 7242 9946 7243 9946 7243 9947 7242 9947 7239 9947 7243 9948 7239 9948 7244 9948 7244 9949 7239 9949 7232 9949 7244 9950 7232 9950 7240 9950 7240 9951 7232 9951 7234 9951 7242 9952 7234 9952 7245 9952 7245 9953 7234 9953 7235 9953 7245 8507 7235 8507 7237 8507 7238 9954 7239 9954 7245 9954 7245 9955 7239 9955 7242 9955 7246 348 7247 348 7248 348 7248 348 7247 348 7249 348 7247 8505 7250 8505 7249 8505 7249 9956 7250 9956 7251 9956 7250 9957 7247 9957 7252 9957 7252 8511 7247 8511 7246 8511 7252 8511 7246 8511 7253 8511 7254 9958 7248 9958 7255 9958 7255 9959 7248 9959 7256 9959 7255 9960 7256 9960 7257 9960 7257 9961 7256 9961 7253 9961 7257 9962 7253 9962 7258 9962 7258 9963 7253 9963 7246 9963 7258 9964 7246 9964 7254 9964 7254 9965 7246 9965 7248 9965 7256 8507 7248 8507 7259 8507 7259 8507 7248 8507 7249 8507 7259 8507 7249 8507 7251 8507 7252 324 7253 324 7259 324 7259 324 7253 324 7256 324 7260 348 7261 348 7262 348 7262 348 7261 348 7263 348 7264 324 7265 324 7266 324 7266 324 7265 324 7267 324 7262 9966 7268 9966 7269 9966 7262 9967 7269 9967 7260 9967 7270 8507 7265 8507 7271 8507 7271 9968 7265 9968 7264 9968 7271 8507 7264 8507 7272 8507 7272 8507 7264 8507 7261 8507 7272 8507 7261 8507 7269 8507 7269 9969 7261 9969 7260 9969 7273 9970 7274 9970 7275 9970 7276 9971 7277 9971 7264 9971 7263 9972 7278 9972 7266 9972 7266 9973 7278 9973 7279 9973 7277 9974 7280 9974 7264 9974 7264 9975 7280 9975 7281 9975 7264 9976 7281 9976 7261 9976 7261 9977 7281 9977 7282 9977 7261 8646 7282 8646 7263 8646 7263 8646 7282 8646 7283 8646 7263 9978 7283 9978 7278 9978 7279 9979 7273 9979 7266 9979 7266 9980 7273 9980 7275 9980 7266 8646 7275 8646 7264 8646 7264 8646 7275 8646 7284 8646 7264 9981 7284 9981 7276 9981 7285 9982 7268 9982 7262 9982 7266 8511 7267 8511 7286 8511 7286 9983 7287 9983 7266 9983 7266 8511 7287 8511 7285 8511 7266 8511 7285 8511 7263 8511 7263 9984 7285 9984 7262 9984 7267 8505 7265 8505 7286 8505 7286 8505 7265 8505 7270 8505 7288 348 7289 348 7290 348 7290 348 7289 348 7291 348 7229 8646 7291 8646 7228 8646 7228 8646 7291 8646 7289 8646 7228 8646 7289 8646 7230 8646 7230 8646 7289 8646 7292 8646 7230 8646 7292 8646 7231 8646 7231 8646 7292 8646 7293 8646 7231 8646 7293 8646 7229 8646 7229 8646 7293 8646 7291 8646 7292 8507 7289 8507 7294 8507 7294 9985 7289 9985 7288 9985 7294 9986 7288 9986 7295 9986 7295 9987 7288 9987 7290 9987 7295 8505 7290 8505 7296 8505 7296 8511 7290 8511 7297 8511 7297 8511 7290 8511 7291 8511 7297 8511 7291 8511 7293 8511 7297 324 7293 324 7294 324 7294 324 7293 324 7292 324 7298 348 7299 348 7300 348 7300 348 7299 348 7301 348 7299 9987 7303 9987 7301 9987 7301 9988 7303 9988 7302 9988 7303 9989 7299 9989 7304 9989 7304 9990 7299 9990 7298 9990 7304 8511 7298 8511 7305 8511 7220 9991 7300 9991 7222 9991 7222 8646 7300 8646 7306 8646 7222 8646 7306 8646 7223 8646 7223 8646 7306 8646 7305 8646 7223 9992 7305 9992 7221 9992 7221 8646 7305 8646 7298 8646 7221 8646 7298 8646 7220 8646 7220 8646 7298 8646 7300 8646 7306 8507 7300 8507 7307 8507 7307 8507 7300 8507 7301 8507 7307 9993 7301 9993 7302 9993 7304 324 7305 324 7307 324 7307 324 7305 324 7306 324 7308 348 7309 348 7310 348 7310 348 7309 348 7311 348 7309 8646 7312 8646 7311 8646 7311 8646 7312 8646 7313 8646 7309 9994 7308 9994 7312 9994 7312 9995 7308 9995 7315 9995 7310 9996 7314 9996 7315 9996 7310 9997 7315 9997 7308 9997 7316 348 7317 348 7318 348 7318 348 7317 348 7319 348 7317 8646 7320 8646 7319 8646 7320 8646 7321 8646 7319 8646 7317 9998 7316 9998 7320 9998 7320 9999 7316 9999 7323 9999 7318 10000 7322 10000 7323 10000 7318 9997 7323 9997 7316 9997 7324 348 7325 348 7326 348 7326 348 7325 348 7327 348 7325 8646 7328 8646 7327 8646 7327 8646 7328 8646 7329 8646 7325 9994 7324 9994 7328 9994 7328 10001 7324 10001 7331 10001 7326 10002 7330 10002 7324 10002 7330 10003 7331 10003 7324 10003 7332 348 7333 348 7334 348 7334 348 7333 348 7335 348 7336 8646 7337 8646 7333 8646 7333 8646 7337 8646 7335 8646 7333 10004 7332 10004 7336 10004 7336 10005 7332 10005 7338 10005 7334 10002 7339 10002 7332 10002 7332 10006 7339 10006 7338 10006 7340 348 7341 348 7342 348 7342 348 7341 348 7343 348 7341 8646 7344 8646 7343 8646 7343 8646 7344 8646 7345 8646 7341 9994 7340 9994 7344 9994 7344 8507 7340 8507 7347 8507 7342 8505 7346 8505 7340 8505 7340 8505 7346 8505 7347 8505 7348 348 7349 348 7350 348 7350 348 7349 348 7351 348 7352 8646 7353 8646 7349 8646 7349 8646 7353 8646 7351 8646 7349 9994 7348 9994 7352 9994 7352 8507 7348 8507 7355 8507 7350 8505 7354 8505 7348 8505 7348 8505 7354 8505 7355 8505 7356 348 7357 348 7358 348 7358 348 7357 348 7359 348 7357 8646 7360 8646 7359 8646 7359 8646 7360 8646 7361 8646 7357 9994 7356 9994 7360 9994 7360 8507 7356 8507 7363 8507 7358 8505 7362 8505 7356 8505 7362 8505 7363 8505 7356 8505 7364 348 7365 348 7366 348 7366 348 7365 348 7367 348 7365 8646 7368 8646 7367 8646 7367 8646 7368 8646 7369 8646 7365 10007 7364 10007 7368 10007 7368 8507 7364 8507 7371 8507 7366 8505 7370 8505 7364 8505 7370 8505 7371 8505 7364 8505 7372 348 7373 348 7374 348 7374 348 7373 348 7375 348 7373 8646 7376 8646 7375 8646 7375 8646 7376 8646 7377 8646 7373 10008 7372 10008 7376 10008 7376 8507 7372 8507 7379 8507 7374 8505 7378 8505 7372 8505 7372 8505 7378 8505 7379 8505 7380 348 7381 348 7382 348 7382 10009 7381 10009 7383 10009 7381 8646 7384 8646 7385 8646 7381 10010 7385 10010 7383 10010 7381 10008 7380 10008 7384 10008 7384 8507 7380 8507 7387 8507 7382 8505 7386 8505 7380 8505 7386 8505 7387 8505 7380 8505 7388 348 7389 348 7390 348 7390 348 7389 348 7391 348 7392 10011 7393 10011 7389 10011 7389 10012 7393 10012 7391 10012 7389 10013 7388 10013 7392 10013 7392 8507 7388 8507 7394 8507 7390 8505 7395 8505 7388 8505 7388 8505 7395 8505 7394 8505 7396 348 7397 348 7398 348 7398 348 7397 348 7399 348 7397 10014 7400 10014 7399 10014 7399 10014 7400 10014 7401 10014 7397 8507 7396 8507 7400 8507 7400 8507 7396 8507 7402 8507 7398 8505 7403 8505 7396 8505 7396 8505 7403 8505 7402 8505 7404 348 7405 348 7406 348 7406 348 7405 348 7407 348 7408 10015 7409 10015 7405 10015 7405 10016 7409 10016 7407 10016 7405 10008 7404 10008 7408 10008 7408 8507 7404 8507 7411 8507 7410 8505 7411 8505 7406 8505 7406 8505 7411 8505 7404 8505 7412 348 7413 348 7414 348 7414 348 7413 348 7415 348 7413 10017 7416 10017 7415 10017 7416 10017 7417 10017 7415 10017 7413 10007 7412 10007 7416 10007 7416 8507 7412 8507 7419 8507 7414 8505 7418 8505 7412 8505 7418 8505 7419 8505 7412 8505 7420 348 7421 348 7422 348 7422 348 7421 348 7423 348 7421 8646 7424 8646 7423 8646 7423 8646 7424 8646 7425 8646 7421 9994 7420 9994 7424 9994 7424 8507 7420 8507 7427 8507 7422 8505 7426 8505 7420 8505 7420 8505 7426 8505 7427 8505 7428 348 7429 348 7430 348 7430 348 7429 348 7431 348 7429 8646 7432 8646 7431 8646 7431 8646 7432 8646 7433 8646 7429 9994 7428 9994 7432 9994 7432 8507 7428 8507 7435 8507 7434 8505 7435 8505 7430 8505 7430 8505 7435 8505 7428 8505 7436 348 7437 348 7438 348 7438 348 7437 348 7439 348 7437 8646 7440 8646 7441 8646 7437 8646 7441 8646 7439 8646 7437 10004 7436 10004 7440 10004 7440 8507 7436 8507 7443 8507 7438 8505 7442 8505 7436 8505 7436 8505 7442 8505 7443 8505 7444 348 7445 348 7446 348 7446 348 7445 348 7447 348 7445 10018 7448 10018 7447 10018 7447 10018 7448 10018 7449 10018 7445 8507 7444 8507 7448 8507 7448 8507 7444 8507 7451 8507 7446 8505 7450 8505 7444 8505 7444 8505 7450 8505 7451 8505 7452 10019 7453 10019 7454 10019 7455 10020 7456 10020 7457 10020 7479 10021 7478 10021 7480 10021 7479 10022 7480 10022 7481 10022 7481 10023 7480 10023 7482 10023 7477 10024 7484 10024 7478 10024 7477 10025 7485 10025 7484 10025 7485 10026 7486 10026 7487 10026 7488 10027 7489 10027 7383 10027 7455 10028 7457 10028 7476 10028 7455 10029 7476 10029 7490 10029 7490 10030 7476 10030 7475 10030 7490 10031 7475 10031 7474 10031 7490 10032 7474 10032 7491 10032 7491 10033 7474 10033 7471 10033 7491 10034 7471 10034 7472 10034 7491 10035 7472 10035 7492 10035 7492 10036 7472 10036 7473 10036 7492 10037 7473 10037 7470 10037 7492 10038 7470 10038 7493 10038 7493 10039 7470 10039 7469 10039 7493 10040 7469 10040 7468 10040 7493 10041 7468 10041 7494 10041 7494 10042 7468 10042 7465 10042 7494 10043 7465 10043 7466 10043 7494 10044 7466 10044 7495 10044 7495 10045 7466 10045 7467 10045 7495 10046 7467 10046 7464 10046 7495 10047 7464 10047 7496 10047 7496 10048 7464 10048 7463 10048 7496 10049 7463 10049 7497 10049 7497 10050 7463 10050 7462 10050 7497 10051 7462 10051 7460 10051 7497 10052 7460 10052 7498 10052 7498 10053 7460 10053 7461 10053 7498 10054 7461 10054 7459 10054 7498 10055 7459 10055 7499 10055 7499 10056 7459 10056 7458 10056 7453 10057 7455 10057 7454 10057 7454 10058 7455 10058 7490 10058 7454 10059 7490 10059 7500 10059 7500 10060 7490 10060 7491 10060 7500 10061 7491 10061 7501 10061 7501 10062 7491 10062 7492 10062 7501 10063 7492 10063 7502 10063 7502 10064 7492 10064 7493 10064 7502 10065 7493 10065 7503 10065 7503 10066 7493 10066 7494 10066 7503 10067 7494 10067 7504 10067 7504 10068 7494 10068 7505 10068 7505 10069 7494 10069 7495 10069 7505 10070 7495 10070 7506 10070 7506 10071 7495 10071 7496 10071 7506 10072 7496 10072 7497 10072 7506 10073 7497 10073 7507 10073 7507 10074 7497 10074 7498 10074 7507 10075 7498 10075 7508 10075 7508 10076 7498 10076 7499 10076 7508 10077 7499 10077 7509 10077 7509 10078 7499 10078 7510 10078 7452 10079 7454 10079 7483 10079 7483 10080 7454 10080 7500 10080 7483 10081 7500 10081 7482 10081 7482 10082 7500 10082 7501 10082 7482 10083 7501 10083 7481 10083 7481 10084 7501 10084 7502 10084 7481 10085 7502 10085 7479 10085 7479 10086 7502 10086 7503 10086 7479 10087 7503 10087 7478 10087 7478 10088 7503 10088 7477 10088 7477 10089 7503 10089 7504 10089 7477 10090 7504 10090 7505 10090 7477 10091 7505 10091 7485 10091 7485 10092 7505 10092 7506 10092 7485 10093 7506 10093 7486 10093 7486 10094 7506 10094 7507 10094 7486 10095 7507 10095 7487 10095 7487 10096 7507 10096 7508 10096 7487 10097 7508 10097 7488 10097 7488 10098 7508 10098 7509 10098 7488 10099 7509 10099 7489 10099 7489 10100 7509 10100 7510 10100 7513 10101 7514 10101 7515 10101 7519 10102 7522 10102 7523 10102 7523 10103 7522 10103 7524 10103 7523 10104 7524 10104 7525 10104 7526 10105 7521 10105 7520 10105 7526 10106 7520 10106 7527 10106 7518 10107 7519 10107 7523 10107 7518 10108 7523 10108 7528 10108 7528 10109 7523 10109 7529 10109 7529 10110 7523 10110 7525 10110 7524 10111 7521 10111 7526 10111 7530 10112 7526 10112 7527 10112 7530 10113 7527 10113 7531 10113 7517 10114 7518 10114 7532 10114 7532 10115 7518 10115 7528 10115 7532 10116 7528 10116 7533 10116 7533 10117 7528 10117 7529 10117 7533 10118 7529 10118 7534 10118 7534 10119 7529 10119 7515 10119 7527 10120 7535 10120 7536 10120 7537 10121 7535 10121 7538 10121 7538 10122 7535 10122 7527 10122 7538 10123 7527 10123 7520 10123 7521 10124 7539 10124 7520 10124 7537 10125 7538 10125 7540 10125 7541 10126 7522 10126 7542 10126 7542 10127 7522 10127 7519 10127 7542 10128 7519 10128 7543 10128 7543 10129 7519 10129 7518 10129 7543 10130 7518 10130 7544 10130 7544 10131 7518 10131 7517 10131 7544 10132 7517 10132 7516 10132 7516 10133 7517 10133 7532 10133 7516 10134 7532 10134 7545 10134 7545 10135 7532 10135 7533 10135 7533 10136 7534 10136 7514 10136 7515 10137 7514 10137 7534 10137 7513 10138 7515 10138 7530 10138 7530 10139 7515 10139 7529 10139 7530 10140 7529 10140 7525 10140 7525 10141 7524 10141 7526 10141 7525 10142 7526 10142 7530 10142 7513 10143 7530 10143 7531 10143 7527 10144 7536 10144 7531 10144 7512 10145 7540 10145 7546 10145 7546 10146 7540 10146 7538 10146 7546 10147 7538 10147 7547 10147 7547 10148 7538 10148 7520 10148 7547 10149 7520 10149 7539 10149 7511 10150 7512 10150 7548 10150 7548 10151 7512 10151 7546 10151 7548 10152 7546 10152 7547 10152 7511 10153 7548 10153 7549 10153 7539 10154 7522 10154 7541 10154 7539 10155 7541 10155 7550 10155 7550 10156 7541 10156 7551 10156 7522 10157 7539 10157 7521 10157 7522 10158 7521 10158 7524 10158 7551 10159 7552 10159 7550 10159 7549 10160 7553 10160 7511 10160 7511 10161 7553 10161 7554 10161 7555 10162 7512 10162 7554 10162 7554 10163 7512 10163 7511 10163 7556 10164 7540 10164 7555 10164 7555 10165 7540 10165 7512 10165 7557 10166 7535 10166 7556 10166 7556 10167 7535 10167 7537 10167 7556 10168 7537 10168 7540 10168 7558 10169 7536 10169 7557 10169 7557 10170 7536 10170 7535 10170 7559 10171 7513 10171 7531 10171 7559 10172 7531 10172 7558 10172 7558 10173 7531 10173 7536 10173 7513 10174 7559 10174 7514 10174 7514 10175 7559 10175 7560 10175 7514 10176 7560 10176 7561 10176 7514 10177 7561 10177 7533 10177 7533 10178 7561 10178 7545 10178 7545 10179 7561 10179 7562 10179 7545 10180 7562 10180 7516 10180 7516 10181 7562 10181 7563 10181 7516 10182 7563 10182 7564 10182 7516 10183 7564 10183 7544 10183 7561 10184 7565 10184 7562 10184 7562 10185 7565 10185 7566 10185 7562 10186 7566 10186 7563 10186 7563 10187 7566 10187 7567 10187 7563 10188 7567 10188 7564 10188 7564 10189 7567 10189 7568 10189 7564 10190 7568 10190 7569 10190 7569 10191 7568 10191 7570 10191 7569 348 7570 348 7571 348 7570 10192 7572 10192 7571 10192 7571 10193 7572 10193 7573 10193 7571 10194 7573 10194 7574 10194 7574 348 7573 348 7575 348 7574 10195 7575 10195 7576 10195 7576 348 7575 348 7577 348 7576 10196 7577 10196 7578 10196 7578 348 7577 348 7579 348 7578 348 7579 348 7580 348 7580 10197 7579 10197 7581 10197 7580 10198 7581 10198 7582 10198 7582 10199 7581 10199 7583 10199 7582 10200 7583 10200 7584 10200 7555 348 7585 348 7556 348 7556 348 7585 348 7586 348 7556 348 7586 348 7557 348 7557 348 7586 348 7587 348 7557 10201 7587 10201 7558 10201 7558 348 7587 348 7588 348 7558 348 7588 348 7559 348 7559 10202 7588 10202 7589 10202 7559 348 7589 348 7560 348 7560 348 7589 348 7590 348 7560 348 7590 348 7561 348 7561 348 7590 348 7591 348 7561 348 7591 348 7565 348 7583 10203 7592 10203 7584 10203 7584 348 7592 348 7593 348 7584 348 7593 348 7594 348 7594 348 7593 348 7595 348 7594 348 7595 348 7596 348 7596 10204 7595 10204 7597 10204 7596 10205 7597 10205 7553 10205 7553 10206 7597 10206 7598 10206 7553 10207 7598 10207 7554 10207 7554 10208 7598 10208 7599 10208 7554 348 7599 348 7555 348 7555 10209 7599 10209 7600 10209 7555 348 7600 348 7585 348 7601 10210 7570 10210 7602 10210 7602 10211 7570 10211 7568 10211 7602 10212 7568 10212 7456 10212 7570 10213 7601 10213 7603 10213 7570 10214 7603 10214 7572 10214 7604 10215 7573 10215 7605 10215 7605 10216 7573 10216 7572 10216 7605 10217 7572 10217 7603 10217 7573 10218 7604 10218 7606 10218 7573 10219 7606 10219 7575 10219 7607 10220 7577 10220 7608 10220 7608 10221 7577 10221 7575 10221 7608 10222 7575 10222 7606 10222 7577 10223 7607 10223 7609 10223 7577 10224 7609 10224 7579 10224 7610 10225 7581 10225 7611 10225 7611 10226 7581 10226 7579 10226 7611 10227 7579 10227 7609 10227 7581 10228 7610 10228 7612 10228 7581 10229 7612 10229 7583 10229 7613 10230 7592 10230 7614 10230 7614 10231 7592 10231 7583 10231 7614 10232 7583 10232 7612 10232 7592 10233 7613 10233 7615 10233 7592 10234 7615 10234 7593 10234 7616 10235 7595 10235 7617 10235 7617 10236 7595 10236 7593 10236 7617 10237 7593 10237 7615 10237 7595 10238 7616 10238 7618 10238 7595 10239 7618 10239 7597 10239 7458 10240 7598 10240 7619 10240 7619 10241 7598 10241 7597 10241 7619 10242 7597 10242 7618 10242 7483 10243 7482 10243 7620 10243 7482 10244 7480 10244 7620 10244 7620 10245 7480 10245 7478 10245 7620 10246 7478 10246 7484 10246 7622 10247 7623 10247 7624 10247 7624 10248 7623 10248 7621 10248 7623 10249 7622 10249 7625 10249 7623 8505 7625 8505 7738 8505 7625 10250 7626 10250 7738 10250 7738 10251 7626 10251 7483 10251 7738 10252 7483 10252 7627 10252 7627 10253 7483 10253 7620 10253 7627 10254 7620 10254 7484 10254 7627 10255 7484 10255 7628 10255 7628 10256 7484 10256 7629 10256 7635 10257 7630 10257 7636 10257 7636 10258 7630 10258 7631 10258 7636 10259 7631 10259 7637 10259 7637 10260 7631 10260 7632 10260 7637 10261 7632 10261 7633 10261 7637 10262 7633 10262 7638 10262 7638 10263 7633 10263 7634 10263 7644 10264 7639 10264 7645 10264 7645 10265 7639 10265 7640 10265 7645 10266 7640 10266 7646 10266 7646 10267 7640 10267 7641 10267 7646 10268 7641 10268 7642 10268 7646 10269 7642 10269 7647 10269 7647 10270 7642 10270 7648 10270 7648 10271 7642 10271 7643 10271 7653 10272 7649 10272 7654 10272 7654 10273 7649 10273 7650 10273 7654 10274 7650 10274 7655 10274 7655 10275 7650 10275 7651 10275 7655 10276 7651 10276 7656 10276 7656 10277 7651 10277 7652 10277 7661 10278 7657 10278 7662 10278 7662 10279 7657 10279 7658 10279 7662 10280 7658 10280 7663 10280 7663 10281 7658 10281 7659 10281 7663 10282 7659 10282 7664 10282 7664 10283 7659 10283 7660 10283 7662 324 7663 324 7270 324 7662 324 7270 324 7661 324 7663 10284 7665 10284 7666 10284 7667 10285 7668 10285 7669 10285 7670 10286 7655 10286 7671 10286 7665 324 7663 324 7671 324 7671 10287 7663 10287 7664 10287 7671 324 7664 324 7672 324 7672 10288 7664 10288 7673 10288 7673 324 7674 324 7672 324 7672 10289 7674 10289 7271 10289 7675 10290 7667 10290 7287 10290 7675 10291 7287 10291 7676 10291 7653 10292 7637 10292 7666 10292 7666 10293 7637 10293 7638 10293 7655 10294 7656 10294 7671 10294 7671 10295 7656 10295 7665 10295 7674 324 7677 324 7271 324 7271 324 7677 324 7270 324 7270 10296 7677 10296 7661 10296 7675 324 7644 324 7667 324 7667 324 7644 324 7668 324 7646 324 7647 324 7286 324 7286 10297 7647 10297 7648 10297 7286 324 7648 324 7287 324 7287 10298 7648 10298 7676 10298 7669 324 7635 324 7667 324 7667 324 7635 324 7670 324 7635 324 7636 324 7670 324 7670 324 7636 324 7637 324 7644 10299 7645 10299 7668 10299 7668 10300 7645 10300 7646 10300 7668 324 7646 324 7678 324 7678 10301 7646 10301 7286 10301 7678 10302 7286 10302 7638 10302 7638 10303 7286 10303 7270 10303 7638 10304 7270 10304 7666 10304 7666 10305 7270 10305 7663 10305 7637 10306 7653 10306 7654 10306 7637 324 7654 324 7670 324 7670 10307 7654 10307 7655 10307 7271 8646 7272 8646 7238 8646 7271 8646 7238 8646 7245 8646 7259 8646 7672 8646 7252 8646 7252 8646 7672 8646 7271 8646 7252 8646 7271 8646 7245 8646 7259 8646 7304 8646 7672 8646 7672 8646 7304 8646 7307 8646 7672 8646 7307 8646 7679 8646 7679 8507 7671 8507 7672 8507 7671 8507 7679 8507 7680 8507 7671 8505 7680 8505 7681 8505 7681 10308 7177 10308 7671 10308 7671 10309 7177 10309 7682 10309 7671 8505 7682 8505 7683 8505 7683 8505 7684 8505 7671 8505 7671 8505 7684 8505 7685 8505 7671 8505 7685 8505 7670 8505 7670 8505 7685 8505 7686 8505 7670 8505 7686 8505 7687 8505 7687 8505 7688 8505 7670 8505 7670 8505 7688 8505 7689 8505 7670 8511 7689 8511 7690 8511 7670 8511 7690 8511 7691 8511 7670 10310 7691 10310 7667 10310 7667 8511 7691 8511 7692 8511 7625 10311 7622 10311 7693 10311 7625 10312 7693 10312 7626 10312 7694 10313 7621 10313 7383 10313 7694 10314 7695 10314 7621 10314 7621 10315 7695 10315 7624 10315 7485 10316 7629 10316 7484 10316 7629 10317 7485 10317 7487 10317 7383 10318 7629 10318 7488 10318 7629 10319 7487 10319 7488 10319 7621 8507 7623 8507 7450 8507 7450 8507 7446 8507 7621 8507 7621 8507 7446 8507 7447 8507 7621 10320 7447 10320 7383 10320 7439 8507 7441 8507 7434 8507 7430 10321 7431 10321 7383 10321 7449 8507 7442 8507 7447 8507 7447 8507 7442 8507 7438 8507 7447 10322 7438 10322 7383 10322 7383 10323 7438 10323 7439 10323 7383 10322 7439 10322 7430 10322 7430 8507 7439 8507 7434 8507 7423 8507 7425 8507 7418 8507 7414 10324 7415 10324 7383 10324 7418 8507 7414 8507 7423 8507 7423 10325 7414 10325 7383 10325 7423 10326 7383 10326 7422 10326 7422 10327 7383 10327 7431 10327 7422 8507 7431 8507 7426 8507 7426 8507 7431 8507 7433 8507 7407 8507 7409 8507 7403 8507 7398 10328 7399 10328 7383 10328 7403 8507 7398 8507 7407 8507 7407 10329 7398 10329 7383 10329 7407 10330 7383 10330 7406 10330 7406 10331 7383 10331 7415 10331 7406 8507 7415 8507 7410 8507 7410 8507 7415 8507 7417 8507 7391 8507 7393 8507 7386 8507 7401 8507 7395 8507 7399 8507 7399 8507 7395 8507 7390 8507 7399 10332 7390 10332 7383 10332 7383 10333 7390 10333 7391 10333 7383 10334 7391 10334 7382 10334 7382 8507 7391 8507 7386 8507 7385 10335 7378 10335 7383 10335 7383 10336 7378 10336 7374 10336 7383 10337 7374 10337 7375 10337 7343 8507 7345 8507 7339 8507 7327 8507 7329 8507 7322 8507 7377 8507 7370 8507 7375 8507 7375 8507 7370 8507 7366 8507 7375 10338 7366 10338 7383 10338 7383 10337 7366 10337 7367 10337 7321 8507 7314 8507 7319 8507 7319 8507 7314 8507 7310 8507 7369 8507 7362 8507 7367 8507 7367 8507 7362 8507 7358 8507 7367 10331 7358 10331 7383 10331 7383 10339 7358 10339 7359 10339 7361 8507 7354 8507 7359 8507 7359 8507 7354 8507 7350 8507 7359 10340 7350 10340 7383 10340 7383 10339 7350 10339 7351 10339 7334 10339 7335 10339 7383 10339 7339 8507 7334 8507 7343 8507 7343 10322 7334 10322 7383 10322 7343 10321 7383 10321 7342 10321 7342 10341 7383 10341 7351 10341 7342 8507 7351 8507 7346 8507 7346 8507 7351 8507 7353 8507 7322 8507 7318 8507 7327 8507 7327 10342 7318 10342 7383 10342 7327 10323 7383 10323 7326 10323 7326 10322 7383 10322 7335 10322 7326 8507 7335 8507 7330 8507 7330 8507 7335 8507 7337 8507 7313 8507 7628 8507 7311 8507 7311 8507 7628 8507 7629 8507 7311 8507 7629 8507 7310 8507 7310 10343 7629 10343 7383 10343 7310 10344 7383 10344 7319 10344 7319 10345 7383 10345 7318 10345 7692 8646 7297 8646 7667 8646 7667 8646 7297 8646 7294 8646 7667 8646 7294 8646 7287 8646 7287 8646 7294 8646 7285 8646 7696 10346 7697 10346 7254 10346 7254 10347 7697 10347 7258 10347 7698 10348 7699 10348 7257 10348 7257 10349 7699 10349 7255 10349 7700 10350 7258 10350 7697 10350 7697 10351 7696 10351 7700 10351 7255 10352 7701 10352 7254 10352 7254 10353 7701 10353 7702 10353 7703 10354 7704 10354 7700 10354 7700 10355 7704 10355 7698 10355 7696 10356 7254 10356 7702 10356 7700 10357 7705 10357 7258 10357 7700 10358 7696 10358 7703 10358 7703 10359 7696 10359 7702 10359 7704 8511 7703 8511 7701 8511 7701 8511 7703 8511 7702 8511 7699 10360 7698 10360 7704 10360 7699 10361 7704 10361 7255 10361 7255 10362 7704 10362 7701 10362 7700 10363 7698 10363 7705 10363 7705 10364 7698 10364 7257 10364 7258 10365 7705 10365 7257 10365 7706 10366 7707 10366 7240 10366 7240 10367 7707 10367 7244 10367 7708 10368 7709 10368 7243 10368 7243 10369 7709 10369 7241 10369 7241 10370 7710 10370 7240 10370 7240 10371 7710 10371 7711 10371 7712 8646 7713 8646 7714 8646 7714 8646 7713 8646 7715 8646 7240 10372 7711 10372 7706 10372 7706 10373 7711 10373 7712 10373 7706 10374 7712 10374 7707 10374 7707 10375 7712 10375 7714 10375 7707 10376 7714 10376 7244 10376 7244 10377 7714 10377 7716 10377 7713 8511 7712 8511 7710 8511 7710 8511 7712 8511 7711 8511 7708 10378 7243 10378 7717 10378 7713 10379 7710 10379 7241 10379 7241 10380 7709 10380 7713 10380 7713 10381 7709 10381 7708 10381 7713 10382 7708 10382 7715 10382 7715 10383 7708 10383 7717 10383 7714 8507 7715 8507 7716 8507 7716 8507 7715 8507 7717 8507 7244 10384 7716 10384 7243 10384 7243 10385 7716 10385 7717 10385 7718 348 7719 348 7275 348 7275 348 7719 348 7284 348 7720 8507 7721 8507 7283 8507 7283 8507 7721 8507 7278 8507 7722 324 7720 324 7282 324 7282 324 7720 324 7283 324 7723 8511 7722 8511 7281 8511 7281 8511 7722 8511 7282 8511 7724 348 7723 348 7725 348 7725 348 7723 348 7281 348 7725 10386 7281 10386 7280 10386 7726 10387 7276 10387 7284 10387 7726 10388 7284 10388 7727 10388 7727 8511 7284 8511 7719 8511 7729 8507 7718 8507 7728 8507 7728 8507 7718 8507 7275 8507 7728 10389 7275 10389 7274 10389 7730 10390 7279 10390 7278 10390 7730 348 7278 348 7731 348 7731 348 7278 348 7721 348 7731 10391 7721 10391 7732 10391 7732 10392 7721 10392 7720 10392 7732 10393 7720 10393 7733 10393 7733 10394 7720 10394 7722 10394 7733 10395 7722 10395 7724 10395 7724 8646 7722 8646 7723 8646 7719 8646 7718 8646 7727 8646 7727 8646 7718 8646 7729 8646 7276 10396 7726 10396 7277 10396 7277 10397 7726 10397 7734 10397 7277 10398 7734 10398 7280 10398 7280 10399 7734 10399 7725 10399 7733 10400 7735 10400 7732 10400 7732 10401 7735 10401 7736 10401 7725 8511 7734 8511 7724 8511 7724 8511 7734 8511 7735 8511 7724 8511 7735 8511 7733 8511 7728 348 7737 348 7729 348 7729 348 7737 348 7736 348 7729 348 7736 348 7727 348 7727 348 7736 348 7735 348 7727 348 7735 348 7726 348 7726 348 7735 348 7734 348 7731 8507 7732 8507 7736 8507 7731 8507 7736 8507 7730 8507 7730 8507 7736 8507 7737 8507 7728 10402 7274 10402 7273 10402 7279 10403 7730 10403 7273 10403 7273 10404 7730 10404 7737 10404 7273 10405 7737 10405 7728 10405 7185 348 7186 348 7214 348 7214 10406 7186 10406 7187 10406 7214 348 7187 348 7171 348 7203 348 7200 348 7169 348 7169 10407 7200 10407 7201 10407 7169 348 7201 348 7212 348 7184 348 7193 348 7187 348 7187 348 7193 348 7194 348 7187 10408 7194 10408 7171 10408 7171 10406 7194 10406 7195 10406 7171 348 7195 348 7192 348 7169 348 7171 348 7203 348 7203 348 7171 348 7192 348 7203 348 7192 348 7202 348 7202 348 7192 348 7211 348 7202 348 7211 348 7201 348 7201 348 7211 348 7208 348 7201 10409 7208 10409 7212 10409 7212 10407 7208 10407 7209 10407 7212 348 7209 348 7210 348 7214 348 7212 348 7185 348 7185 348 7212 348 7210 348 7185 348 7210 348 7184 348 7184 348 7210 348 7211 348 7184 348 7211 348 7193 348 7193 348 7211 348 7192 348 7450 10410 7740 10410 7451 10410 7252 10411 7245 10411 7250 10411 7250 348 7245 348 7237 348 7660 10412 7659 10412 7303 10412 7303 10413 7659 10413 7658 10413 7304 10414 7259 10414 7741 10414 7237 10415 7658 10415 7657 10415 7237 10416 7657 10416 7250 10416 7250 10417 7657 10417 7251 10417 7251 10418 7657 10418 7742 10418 7251 10419 7742 10419 7259 10419 7259 10420 7742 10420 7741 10420 7741 10421 7743 10421 7304 10421 7304 10422 7743 10422 7303 10422 7303 10423 7743 10423 7660 10423 7658 10424 7237 10424 7303 10424 7303 10425 7312 10425 7302 10425 7627 10426 7269 10426 7268 10426 7641 10427 7640 10427 7295 10427 7295 10428 7640 10428 7639 10428 7295 10429 7639 10429 7294 10429 7294 10430 7639 10430 7744 10430 7294 10431 7744 10431 7745 10431 7294 10432 7745 10432 7285 10432 7285 10433 7745 10433 7643 10433 7285 10434 7643 10434 7268 10434 7268 10435 7643 10435 7642 10435 7297 348 7692 348 7296 348 7296 348 7692 348 7691 348 7296 10436 7691 10436 7295 10436 7295 10437 7268 10437 7641 10437 7641 10438 7268 10438 7642 10438 7238 10439 7272 10439 7236 10439 7236 348 7272 348 7269 348 7652 10440 7680 10440 7746 10440 7746 10441 7680 10441 7679 10441 7746 10442 7679 10442 7747 10442 7680 10443 7652 10443 7651 10443 7215 10444 7651 10444 7650 10444 7649 10445 7213 10445 7215 10445 7649 10446 7215 10446 7650 10446 7302 348 7312 348 7315 348 7302 10447 7315 10447 7747 10447 7747 10448 7315 10448 7320 10448 7747 10449 7320 10449 7323 10449 7336 10450 7338 10450 7747 10450 7331 10451 7336 10451 7747 10451 7331 10452 7747 10452 7328 10452 7328 10451 7747 10451 7323 10451 7352 10453 7355 10453 7747 10453 7347 10454 7352 10454 7747 10454 7347 10455 7747 10455 7344 10455 7344 10456 7747 10456 7338 10456 7368 10457 7371 10457 7747 10457 7363 10458 7368 10458 7747 10458 7363 10459 7747 10459 7360 10459 7360 10460 7747 10460 7355 10460 7384 10457 7387 10457 7747 10457 7379 10458 7384 10458 7747 10458 7379 10459 7747 10459 7376 10459 7376 10458 7747 10458 7371 10458 7400 10459 7402 10459 7747 10459 7394 10458 7400 10458 7747 10458 7394 10457 7747 10457 7392 10457 7392 10458 7747 10458 7387 10458 7416 10461 7419 10461 7747 10461 7411 10462 7416 10462 7747 10462 7411 10457 7747 10457 7408 10457 7408 10458 7747 10458 7402 10458 7432 10457 7435 10457 7747 10457 7427 10463 7432 10463 7747 10463 7427 10457 7747 10457 7424 10457 7424 10458 7747 10458 7419 10458 7443 10464 7448 10464 7747 10464 7443 10465 7747 10465 7440 10465 7440 10466 7747 10466 7435 10466 7312 348 7303 348 7237 348 7312 10467 7237 10467 7628 10467 7312 348 7628 348 7313 348 7237 10468 7236 10468 7628 10468 7628 10469 7236 10469 7269 10469 7628 10470 7269 10470 7627 10470 7627 348 7268 348 7295 348 7623 348 7748 348 7749 348 7750 10471 7623 10471 7751 10471 7450 348 7752 348 7753 348 7448 348 7443 348 7442 348 7448 348 7442 348 7449 348 7440 348 7435 348 7441 348 7441 348 7435 348 7434 348 7432 348 7427 348 7426 348 7432 348 7426 348 7433 348 7424 348 7419 348 7418 348 7424 348 7418 348 7425 348 7416 348 7411 348 7417 348 7417 348 7411 348 7410 348 7408 348 7402 348 7403 348 7408 348 7403 348 7409 348 7400 348 7394 348 7395 348 7400 348 7395 348 7401 348 7392 348 7387 348 7393 348 7393 348 7387 348 7386 348 7384 348 7379 348 7385 348 7385 348 7379 348 7378 348 7376 348 7371 348 7370 348 7376 348 7370 348 7377 348 7368 348 7363 348 7362 348 7368 348 7362 348 7369 348 7360 348 7355 348 7354 348 7360 348 7354 348 7361 348 7352 348 7347 348 7353 348 7353 348 7347 348 7346 348 7344 348 7338 348 7339 348 7344 348 7339 348 7345 348 7336 348 7331 348 7337 348 7337 348 7331 348 7330 348 7328 348 7323 348 7329 348 7329 348 7323 348 7322 348 7320 348 7315 348 7321 348 7321 10472 7315 10472 7314 10472 7172 10473 7681 10473 7215 10473 7215 10474 7681 10474 7680 10474 7213 10475 7451 10475 7754 10475 7213 10476 7754 10476 7170 10476 7170 324 7174 324 7754 324 7170 348 7754 348 7168 348 7168 10477 7754 10477 7451 10477 7168 348 7451 348 7166 348 7176 10478 7755 10478 7682 10478 7172 348 7173 348 7681 348 7681 348 7172 348 7177 348 7682 10479 7177 10479 7176 10479 7756 10480 7683 10480 7755 10480 7755 10481 7683 10481 7682 10481 7755 324 7682 324 7757 324 7758 10482 7759 10482 7740 10482 7166 348 7451 348 7759 348 7759 10483 7451 10483 7740 10483 7760 324 7740 324 7759 324 7740 348 7450 348 7753 348 7740 10484 7753 10484 7758 10484 7762 348 7684 348 7756 348 7756 348 7684 348 7683 348 7756 324 7683 324 7763 324 7764 348 7685 348 7762 348 7762 348 7685 348 7684 348 7765 348 7684 348 7762 348 7766 10485 7767 10485 7752 10485 7758 324 7761 324 7753 324 7758 348 7753 348 7767 348 7767 348 7753 348 7752 348 7768 324 7752 324 7767 324 7450 10486 7623 10486 7752 10486 7752 10487 7623 10487 7750 10487 7752 10488 7750 10488 7766 10488 7766 348 7750 348 7769 348 7770 348 7686 348 7764 348 7764 348 7686 348 7685 348 7771 348 7685 348 7764 348 7772 348 7687 348 7770 348 7770 348 7687 348 7686 348 7773 348 7686 348 7770 348 7774 10489 7775 10489 7751 10489 7766 348 7750 348 7775 348 7775 348 7750 348 7751 348 7775 348 7751 348 7776 348 7751 348 7623 348 7749 348 7751 10490 7749 10490 7774 10490 7778 348 7688 348 7772 348 7772 348 7688 348 7687 348 7772 324 7687 324 7779 324 7739 10491 7689 10491 7778 10491 7778 10492 7689 10492 7688 10492 7780 348 7688 348 7778 348 7623 348 7738 348 7748 348 7748 10493 7738 10493 7781 10493 7748 10494 7781 10494 7782 10494 7774 324 7777 324 7749 324 7774 348 7749 348 7782 348 7782 348 7749 348 7748 348 7783 324 7748 324 7782 324 7215 10495 7680 10495 7651 10495 7784 10496 7690 10496 7630 10496 7630 10497 7690 10497 7689 10497 7630 10498 7689 10498 7631 10498 7690 10499 7784 10499 7785 10499 7690 10500 7785 10500 7738 10500 7738 10501 7785 10501 7634 10501 7738 10502 7634 10502 7739 10502 7739 10503 7634 10503 7633 10503 7739 10504 7633 10504 7632 10504 7739 10505 7632 10505 7689 10505 7689 10506 7632 10506 7631 10506 7739 348 7781 348 7738 348 7690 10507 7738 10507 7691 10507 7691 10508 7738 10508 7627 10508 7691 10509 7627 10509 7295 10509 7649 10510 7747 10510 7213 10510 7213 10511 7747 10511 7451 10511 7451 10512 7747 10512 7448 10512 7747 10513 7679 10513 7302 10513 7302 10514 7679 10514 7307 10514 7786 8511 7760 8511 7787 8511 7787 8511 7760 8511 7757 8511 7175 8505 7787 8505 7176 8505 7176 8505 7787 8505 7755 8505 7175 10515 7179 10515 7167 10515 7167 8507 7179 8507 7178 8507 7167 8507 7178 8507 7166 8507 7786 8646 7167 8646 7759 8646 7759 8646 7167 8646 7166 8646 7788 8511 7758 8511 7761 8511 7788 8511 7761 8511 7789 8511 7789 8511 7761 8511 7763 8511 7789 8511 7763 8511 7756 8511 7787 8505 7789 8505 7755 8505 7755 8505 7789 8505 7756 8505 7787 8507 7755 8507 7757 8507 7787 8507 7757 8507 7786 8507 7786 8507 7757 8507 7760 8507 7786 8507 7760 8507 7759 8507 7788 8646 7786 8646 7758 8646 7758 8646 7786 8646 7759 8646 7790 8511 7768 8511 7791 8511 7791 10516 7768 10516 7765 10516 7791 8511 7765 8511 7762 8511 7789 8505 7791 8505 7756 8505 7756 8505 7791 8505 7762 8505 7789 8507 7763 8507 7788 8507 7788 8507 7763 8507 7761 8507 7790 8646 7788 8646 7767 8646 7767 8646 7788 8646 7758 8646 7792 8511 7769 8511 7793 8511 7793 8511 7769 8511 7771 8511 7793 8511 7771 8511 7764 8511 7791 8505 7793 8505 7762 8505 7762 8505 7793 8505 7764 8505 7791 10517 7765 10517 7790 10517 7790 8507 7765 8507 7768 8507 7790 8507 7768 8507 7767 8507 7792 8646 7790 8646 7766 8646 7766 8646 7790 8646 7767 8646 7794 8511 7775 8511 7776 8511 7794 8511 7776 8511 7795 8511 7795 10518 7776 10518 7773 10518 7793 8505 7795 8505 7764 8505 7764 8505 7795 8505 7770 8505 7793 8507 7771 8507 7792 8507 7792 8507 7771 8507 7769 8507 7792 8507 7769 8507 7766 8507 7794 8646 7792 8646 7775 8646 7775 8646 7792 8646 7766 8646 7796 8511 7777 8511 7797 8511 7797 8511 7777 8511 7779 8511 7795 8505 7797 8505 7770 8505 7770 8505 7797 8505 7772 8505 7795 8507 7770 8507 7773 8507 7795 8507 7773 8507 7794 8507 7794 10519 7773 10519 7776 10519 7796 8646 7794 8646 7774 8646 7774 8646 7794 8646 7775 8646 7798 8511 7783 8511 7799 8511 7799 8511 7783 8511 7780 8511 7799 8511 7780 8511 7778 8511 7797 8505 7799 8505 7772 8505 7772 8505 7799 8505 7778 8505 7797 8507 7772 8507 7779 8507 7797 8507 7779 8507 7796 8507 7796 8507 7779 8507 7777 8507 7796 8507 7777 8507 7774 8507 7798 8646 7796 8646 7782 8646 7782 8646 7796 8646 7774 8646 7800 8511 7781 8511 7801 8511 7801 8511 7781 8511 7739 8511 7799 8505 7801 8505 7778 8505 7778 8505 7801 8505 7739 8505 7799 8507 7780 8507 7798 8507 7798 8507 7780 8507 7783 8507 7798 8507 7783 8507 7782 8507 7800 8646 7798 8646 7781 8646 7781 8646 7798 8646 7782 8646 7139 348 7140 348 7171 348 7171 10520 7140 10520 7141 10520 7171 348 7141 348 7175 348 7157 348 7154 348 7167 348 7167 10407 7154 10407 7155 10407 7167 10521 7155 10521 7169 10521 7138 348 7147 348 7141 348 7141 348 7147 348 7148 348 7141 10522 7148 10522 7175 10522 7175 10406 7148 10406 7149 10406 7175 348 7149 348 7146 348 7167 348 7175 348 7157 348 7157 348 7175 348 7146 348 7157 348 7146 348 7156 348 7156 348 7146 348 7165 348 7156 348 7165 348 7155 348 7155 348 7165 348 7162 348 7155 10523 7162 10523 7169 10523 7169 10524 7162 10524 7163 10524 7169 348 7163 348 7164 348 7171 348 7169 348 7139 348 7139 348 7169 348 7164 348 7139 348 7164 348 7138 348 7138 348 7164 348 7165 348 7138 348 7165 348 7147 348 7147 348 7165 348 7146 348 7107 348 7108 348 7175 348 7175 10520 7108 10520 7109 10520 7175 10525 7109 10525 7787 10525 7125 348 7122 348 7786 348 7786 10524 7122 10524 7123 10524 7786 10526 7123 10526 7167 10526 7106 348 7115 348 7109 348 7109 348 7115 348 7116 348 7109 10527 7116 10527 7787 10527 7787 10520 7116 10520 7117 10520 7787 348 7117 348 7114 348 7786 348 7787 348 7125 348 7125 348 7787 348 7114 348 7125 348 7114 348 7124 348 7124 348 7114 348 7133 348 7124 348 7133 348 7123 348 7123 348 7133 348 7130 348 7123 10523 7130 10523 7167 10523 7167 10524 7130 10524 7131 10524 7167 348 7131 348 7132 348 7175 348 7167 348 7107 348 7107 348 7167 348 7132 348 7107 348 7132 348 7106 348 7106 348 7132 348 7133 348 7106 348 7133 348 7115 348 7115 348 7133 348 7114 348 7075 348 7076 348 7787 348 7787 10406 7076 10406 7077 10406 7787 10528 7077 10528 7789 10528 7093 348 7090 348 7788 348 7788 10524 7090 10524 7091 10524 7788 348 7091 348 7786 348 7074 348 7083 348 7077 348 7077 348 7083 348 7084 348 7077 10527 7084 10527 7789 10527 7789 10520 7084 10520 7085 10520 7789 348 7085 348 7082 348 7788 348 7789 348 7093 348 7093 348 7789 348 7082 348 7093 348 7082 348 7092 348 7092 348 7082 348 7101 348 7092 348 7101 348 7091 348 7091 348 7101 348 7098 348 7091 10529 7098 10529 7786 10529 7786 10407 7098 10407 7099 10407 7786 348 7099 348 7100 348 7787 348 7786 348 7075 348 7075 348 7786 348 7100 348 7075 348 7100 348 7074 348 7074 348 7100 348 7101 348 7074 348 7101 348 7083 348 7083 348 7101 348 7082 348 7043 348 7044 348 7789 348 7789 348 7044 348 7045 348 7789 10528 7045 10528 7791 10528 7061 348 7058 348 7790 348 7790 348 7058 348 7059 348 7790 10530 7059 10530 7788 10530 7042 348 7051 348 7045 348 7045 348 7051 348 7052 348 7045 10522 7052 10522 7791 10522 7791 348 7052 348 7053 348 7791 348 7053 348 7050 348 7790 348 7791 348 7061 348 7061 348 7791 348 7050 348 7061 348 7050 348 7060 348 7060 348 7050 348 7069 348 7060 348 7069 348 7059 348 7059 348 7069 348 7066 348 7059 10531 7066 10531 7788 10531 7788 348 7066 348 7067 348 7788 348 7067 348 7068 348 7789 348 7788 348 7043 348 7043 348 7788 348 7068 348 7043 348 7068 348 7042 348 7042 348 7068 348 7069 348 7042 348 7069 348 7051 348 7051 348 7069 348 7050 348 7011 348 7012 348 7791 348 7791 348 7012 348 7013 348 7791 348 7013 348 7793 348 7029 348 7026 348 7792 348 7792 348 7026 348 7027 348 7792 348 7027 348 7790 348 7010 348 7019 348 7013 348 7013 348 7019 348 7020 348 7013 10532 7020 10532 7793 10532 7793 348 7020 348 7021 348 7793 348 7021 348 7018 348 7792 348 7793 348 7029 348 7029 348 7793 348 7018 348 7029 348 7018 348 7028 348 7028 348 7018 348 7037 348 7028 348 7037 348 7027 348 7027 348 7037 348 7034 348 7027 10533 7034 10533 7790 10533 7790 348 7034 348 7035 348 7790 348 7035 348 7036 348 7791 348 7790 348 7011 348 7011 348 7790 348 7036 348 7011 348 7036 348 7010 348 7010 348 7036 348 7037 348 7010 348 7037 348 7019 348 7019 348 7037 348 7018 348 6979 348 6980 348 7793 348 7793 348 6980 348 6981 348 7793 10534 6981 10534 7795 10534 6997 348 6994 348 7794 348 7794 348 6994 348 6995 348 7794 10526 6995 10526 7792 10526 6978 348 6987 348 6981 348 6981 348 6987 348 6988 348 6981 10535 6988 10535 7795 10535 7795 348 6988 348 6989 348 7795 348 6989 348 6986 348 7794 348 7795 348 6997 348 6997 348 7795 348 6986 348 6997 348 6986 348 6996 348 6996 348 6986 348 7005 348 6996 348 7005 348 6995 348 6995 348 7005 348 7002 348 6995 10529 7002 10529 7792 10529 7792 348 7002 348 7003 348 7792 348 7003 348 7004 348 7793 348 7792 348 6979 348 6979 348 7792 348 7004 348 6979 348 7004 348 6978 348 6978 348 7004 348 7005 348 6978 348 7005 348 6987 348 6987 348 7005 348 6986 348 6947 348 6948 348 7795 348 7795 348 6948 348 6949 348 7795 348 6949 348 7797 348 6965 348 6962 348 7796 348 7796 348 6962 348 6963 348 7796 348 6963 348 7794 348 6946 348 6955 348 6949 348 6949 348 6955 348 6956 348 6949 10536 6956 10536 7797 10536 7797 348 6956 348 6957 348 7797 348 6957 348 6954 348 6964 348 6973 348 6963 348 6963 348 6973 348 6970 348 6963 10537 6970 10537 7794 10537 7794 348 6970 348 6971 348 7794 348 6971 348 6972 348 7795 348 7794 348 6947 348 6947 348 7794 348 6972 348 6947 348 6972 348 6946 348 6946 348 6972 348 6973 348 6946 348 6973 348 6955 348 6955 348 6973 348 6964 348 6955 348 6964 348 6954 348 6954 348 6964 348 6965 348 6954 348 6965 348 7797 348 7797 348 6965 348 7796 348 6915 348 6916 348 7797 348 7797 348 6916 348 6917 348 7797 10528 6917 10528 7799 10528 6933 348 6930 348 7798 348 7798 348 6930 348 6931 348 7798 10530 6931 10530 7796 10530 6914 348 6923 348 6917 348 6917 348 6923 348 6924 348 6917 10527 6924 10527 7799 10527 7799 348 6924 348 6925 348 7799 348 6925 348 6922 348 7798 348 7799 348 6933 348 6933 348 7799 348 6922 348 6933 348 6922 348 6932 348 6932 10538 6922 10538 6941 10538 6932 348 6941 348 6931 348 6931 348 6941 348 6938 348 6931 10537 6938 10537 7796 10537 7796 348 6938 348 6939 348 7796 348 6939 348 6940 348 7797 348 7796 348 6915 348 6915 348 7796 348 6940 348 6915 348 6940 348 6914 348 6914 348 6940 348 6941 348 6914 348 6941 348 6923 348 6923 10539 6941 10539 6922 10539 6883 348 6884 348 7799 348 7799 10540 6884 10540 6885 10540 7799 348 6885 348 7801 348 6901 348 6898 348 7800 348 7800 10524 6898 10524 6899 10524 7800 348 6899 348 7798 348 6882 348 6891 348 6885 348 6885 348 6891 348 6892 348 6885 10541 6892 10541 7801 10541 7801 10520 6892 10520 6893 10520 7801 348 6893 348 6890 348 7800 348 7801 348 6901 348 6901 348 7801 348 6890 348 6901 348 6890 348 6900 348 6900 348 6890 348 6909 348 6900 348 6909 348 6899 348 6899 348 6909 348 6906 348 6899 10542 6906 10542 7798 10542 7798 10543 6906 10543 6907 10543 7798 348 6907 348 6908 348 7799 348 7798 348 6883 348 6883 348 7798 348 6908 348 6883 348 6908 348 6882 348 6882 348 6908 348 6909 348 6882 348 6909 348 6891 348 6891 348 6909 348 6890 348 7664 10544 7660 10544 7673 10544 7673 10545 7660 10545 7743 10545 7673 10546 7743 10546 7674 10546 7674 10547 7743 10547 7741 10547 7674 10548 7741 10548 7677 10548 7677 10549 7741 10549 7742 10549 7677 10550 7742 10550 7661 10550 7661 10551 7742 10551 7657 10551 7656 10552 7652 10552 7665 10552 7665 10553 7652 10553 7746 10553 7665 10554 7746 10554 7666 10554 7666 10555 7746 10555 7747 10555 7666 10556 7747 10556 7653 10556 7653 10557 7747 10557 7649 10557 7648 10558 7643 10558 7676 10558 7676 10559 7643 10559 7745 10559 7676 10560 7745 10560 7675 10560 7675 10561 7745 10561 7744 10561 7675 10562 7744 10562 7644 10562 7644 10563 7744 10563 7639 10563 7638 10564 7634 10564 7678 10564 7678 10565 7634 10565 7668 10565 7668 10566 7634 10566 7785 10566 7668 10567 7785 10567 7669 10567 7669 10568 7785 10568 7784 10568 7669 10569 7784 10569 7635 10569 7635 10570 7784 10570 7630 10570 7461 10571 7599 10571 7459 10571 7459 10572 7599 10572 7598 10572 7459 10573 7598 10573 7458 10573 7599 10574 7461 10574 7460 10574 7599 10575 7460 10575 7600 10575 7463 10576 7585 10576 7462 10576 7462 10577 7585 10577 7600 10577 7462 10578 7600 10578 7460 10578 7585 10579 7463 10579 7464 10579 7585 10580 7464 10580 7586 10580 7466 10581 7587 10581 7467 10581 7467 10582 7587 10582 7586 10582 7467 10583 7586 10583 7464 10583 7587 10584 7466 10584 7465 10584 7587 10585 7465 10585 7588 10585 7469 10586 7589 10586 7468 10586 7468 10587 7589 10587 7588 10587 7468 10588 7588 10588 7465 10588 7589 10589 7469 10589 7470 10589 7589 10590 7470 10590 7590 10590 7472 10591 7591 10591 7473 10591 7473 10592 7591 10592 7590 10592 7473 10593 7590 10593 7470 10593 7591 10594 7472 10594 7471 10594 7591 10595 7471 10595 7565 10595 7475 10596 7566 10596 7474 10596 7474 10597 7566 10597 7565 10597 7474 10598 7565 10598 7471 10598 7566 10599 7475 10599 7476 10599 7566 10600 7476 10600 7567 10600 7456 10601 7568 10601 7457 10601 7457 10602 7568 10602 7567 10602 7457 10603 7567 10603 7476 10603 7544 10604 7564 10604 7802 10604 7802 10605 7564 10605 7569 10605 7571 10606 7803 10606 7569 10606 7569 10607 7803 10607 7802 10607 7574 10608 7804 10608 7571 10608 7571 10609 7804 10609 7803 10609 7576 10610 7805 10610 7574 10610 7574 10611 7805 10611 7806 10611 7574 10612 7806 10612 7804 10612 7578 10613 7807 10613 7576 10613 7576 10614 7807 10614 7805 10614 7580 10615 7808 10615 7809 10615 7580 10616 7809 10616 7578 10616 7578 10617 7809 10617 7807 10617 7808 10618 7580 10618 7810 10618 7810 10619 7580 10619 7582 10619 7810 10620 7582 10620 7584 10620 7810 10621 7584 10621 7811 10621 7811 10622 7584 10622 7812 10622 7812 10623 7584 10623 7594 10623 7812 10624 7594 10624 7813 10624 7813 10625 7594 10625 7596 10625 7813 10626 7596 10626 7553 10626 7813 10627 7553 10627 7549 10627 7808 10628 7810 10628 7814 10628 7818 10629 7551 10629 7541 10629 7817 10630 7550 10630 7819 10630 7819 10631 7550 10631 7552 10631 7819 10632 7552 10632 7820 10632 7816 10633 7817 10633 7822 10633 7822 10634 7817 10634 7819 10634 7822 10635 7819 10635 7823 10635 7823 10636 7819 10636 7820 10636 7815 10637 7816 10637 7824 10637 7824 10638 7816 10638 7822 10638 7824 10639 7822 10639 7811 10639 7811 10640 7822 10640 7823 10640 7811 10641 7823 10641 7825 10641 7825 10642 7823 10642 7814 10642 7826 10643 7805 10643 7807 10643 7806 10644 7805 10644 7826 10644 7826 10645 7827 10645 7828 10645 7826 10646 7828 10646 7806 10646 7806 10647 7828 10647 7804 10647 7539 10648 7550 10648 7547 10648 7547 10649 7550 10649 7817 10649 7547 10650 7817 10650 7548 10650 7548 10651 7817 10651 7816 10651 7548 10652 7816 10652 7549 10652 7549 10653 7816 10653 7815 10653 7549 10654 7815 10654 7813 10654 7813 10655 7815 10655 7824 10655 7813 10656 7824 10656 7812 10656 7812 10657 7824 10657 7811 10657 7811 10658 7825 10658 7810 10658 7814 10659 7810 10659 7825 10659 7808 10660 7814 10660 7829 10660 7829 10661 7814 10661 7823 10661 7829 10662 7823 10662 7820 10662 7552 10663 7551 10663 7820 10663 7820 10664 7551 10664 7818 10664 7820 10665 7818 10665 7829 10665 7829 10666 7818 10666 7821 10666 7829 10667 7821 10667 7808 10667 7808 10668 7821 10668 7809 10668 7541 10669 7827 10669 7818 10669 7818 10670 7827 10670 7826 10670 7818 10671 7826 10671 7821 10671 7821 10672 7826 10672 7807 10672 7821 10673 7807 10673 7809 10673 7803 10674 7804 10674 7828 10674 7802 10675 7803 10675 7543 10675 7543 10676 7803 10676 7828 10676 7543 10677 7828 10677 7542 10677 7542 10678 7828 10678 7827 10678 7542 10679 7827 10679 7541 10679 7802 10680 7543 10680 7544 10680 7510 10681 7499 10681 7830 10681 7383 10682 7489 10682 7831 10682 7383 10683 7831 10683 7694 10683 7694 10684 7831 10684 7832 10684 7694 10685 7832 10685 7695 10685 7622 10686 7833 10686 7693 10686 7693 10687 7833 10687 7834 10687 7693 10688 7834 10688 7626 10688 7626 10689 7834 10689 7835 10689 7626 10690 7835 10690 7452 10690 7626 10691 7452 10691 7483 10691 7499 10692 7458 10692 7619 10692 7499 10693 7619 10693 7830 10693 7830 10694 7619 10694 7618 10694 7830 10695 7618 10695 7836 10695 7836 10696 7618 10696 7616 10696 7836 10697 7616 10697 7617 10697 7836 10698 7617 10698 7837 10698 7837 10699 7617 10699 7615 10699 7837 10700 7615 10700 7613 10700 7837 10701 7613 10701 7838 10701 7838 10702 7613 10702 7614 10702 7838 10703 7614 10703 7612 10703 7838 10704 7612 10704 7839 10704 7839 10705 7612 10705 7610 10705 7839 10706 7610 10706 7611 10706 7839 10707 7611 10707 7840 10707 7840 10708 7611 10708 7609 10708 7840 10709 7609 10709 7607 10709 7840 10710 7607 10710 7841 10710 7841 10711 7607 10711 7608 10711 7841 10712 7608 10712 7606 10712 7841 10713 7606 10713 7842 10713 7842 10714 7606 10714 7604 10714 7842 10715 7604 10715 7605 10715 7842 10716 7605 10716 7843 10716 7843 10717 7605 10717 7603 10717 7843 10718 7603 10718 7601 10718 7843 10719 7601 10719 7844 10719 7844 10720 7601 10720 7602 10720 7844 10721 7602 10721 7456 10721 7844 10722 7456 10722 7455 10722 7510 10723 7830 10723 7836 10723 7510 10724 7836 10724 7845 10724 7845 10725 7836 10725 7837 10725 7845 10726 7837 10726 7846 10726 7846 10727 7837 10727 7838 10727 7846 10728 7838 10728 7847 10728 7847 10729 7838 10729 7839 10729 7847 10730 7839 10730 7848 10730 7848 10731 7839 10731 7840 10731 7848 10732 7840 10732 7849 10732 7849 10733 7840 10733 7850 10733 7850 10734 7840 10734 7841 10734 7850 10735 7841 10735 7851 10735 7851 10736 7841 10736 7842 10736 7851 10737 7842 10737 7852 10737 7852 10738 7842 10738 7843 10738 7852 10739 7843 10739 7853 10739 7853 10740 7843 10740 7844 10740 7853 10741 7844 10741 7854 10741 7854 10742 7844 10742 7453 10742 7453 10743 7844 10743 7455 10743 7489 10744 7510 10744 7845 10744 7489 10745 7845 10745 7831 10745 7831 10746 7845 10746 7846 10746 7831 10747 7846 10747 7832 10747 7832 10748 7846 10748 7847 10748 7832 10749 7847 10749 7695 10749 7695 10750 7847 10750 7848 10750 7695 10751 7848 10751 7624 10751 7624 10752 7848 10752 7849 10752 7624 10753 7849 10753 7850 10753 7624 10754 7850 10754 7622 10754 7622 10755 7850 10755 7833 10755 7833 10756 7850 10756 7851 10756 7833 10757 7851 10757 7852 10757 7833 10758 7852 10758 7834 10758 7834 10759 7852 10759 7853 10759 7834 10760 7853 10760 7835 10760 7835 10761 7853 10761 7854 10761 7835 10762 7854 10762 7453 10762 7835 10763 7453 10763 7452 10763 7860 10764 7857 10764 7858 10764 7855 10765 7856 10765 7859 10765 7859 10766 7860 10766 7858 10766 7855 10767 7859 10767 7858 10767 7861 10768 7857 10768 7860 10768 7864 10769 7862 10769 7863 10769 7858 10770 7857 10770 7861 10770 7861 10771 7864 10771 7863 10771 7858 10772 7861 10772 7863 10772 7864 10773 7865 10773 7862 10773 7866 10774 7862 10774 7865 10774 7863 10775 7862 10775 7866 10775 7867 10776 7869 10776 7868 10776 7863 10777 7866 10777 7867 10777 7863 10778 7867 10778 7868 10778 7872 10779 7869 10779 7871 10779 7871 10780 7869 10780 7867 10780 7870 10781 7869 10781 7873 10781 7873 10782 7869 10782 7872 10782 7876 10783 7874 10783 7875 10783 7870 10784 7876 10784 7875 10784 7868 10785 7869 10785 7875 10785 7875 10786 7869 10786 7870 10786 7874 10787 7876 10787 7877 10787 7875 10788 7874 10788 7877 10788 7877 10789 7879 10789 7878 10789 7875 10790 7877 10790 7878 10790 7882 10791 7879 10791 7877 10791 7883 10792 7879 10792 7882 10792 7883 10793 7880 10793 7879 10793 7884 10794 7856 10794 7855 10794 7878 10795 7879 10795 7880 10795 7881 10796 7884 10796 7855 10796 7878 10797 7880 10797 7855 10797 7855 10798 7880 10798 7881 10798 7859 10799 7856 10799 7884 10799 7881 10800 7887 10800 7886 10800 7867 10801 7885 10801 7893 10801 7885 10802 7867 10802 7866 10802 7886 10803 7859 10803 7884 10803 7886 10804 7884 10804 7881 10804 7887 10805 7888 10805 7889 10805 7887 10806 7889 10806 7890 10806 7887 10807 7881 10807 7891 10807 7887 5700 7891 5700 7892 5700 7887 10808 7892 10808 7888 10808 7898 10809 7859 10809 7886 10809 7898 10810 7860 10810 7859 10810 7893 10811 7894 10811 7895 10811 7893 10812 7895 10812 7896 10812 7893 10813 7896 10813 7867 10813 7876 10814 7870 10814 7890 10814 7890 10815 7870 10815 7893 10815 7893 10816 7870 10816 7897 10816 7893 10817 7897 10817 7894 10817 7898 10818 7861 10818 7860 10818 7885 10819 7866 10819 7865 10819 7885 10820 7865 10820 7898 10820 7890 10821 7877 10821 7876 10821 7898 10822 7865 10822 7861 10822 7889 10823 7899 10823 7890 10823 7890 10824 7899 10824 7877 10824 7886 10825 7887 10825 7900 10825 7900 10826 7901 10826 7886 10826 7886 10827 7901 10827 7898 10827 7898 10828 7901 10828 7902 10828 7898 10829 7902 10829 7885 10829 7902 10830 7903 10830 7885 10830 7904 10831 7885 10831 7903 10831 7893 10832 7885 10832 7904 10832 7904 10833 7905 10833 7893 10833 7893 10834 7905 10834 7890 10834 7890 10835 7905 10835 7906 10835 7890 10836 7906 10836 7887 10836 7906 10837 7907 10837 7887 10837 7900 10838 7887 10838 7907 10838 7908 10839 7900 10839 7907 10839 7908 10840 7907 10840 7906 10840 7908 10841 7906 10841 7909 10841 7909 10842 7906 10842 7910 10842 7910 10843 7906 10843 7905 10843 7910 10844 7905 10844 7911 10844 7911 10845 7905 10845 7904 10845 7911 10846 7904 10846 7912 10846 7912 10847 7904 10847 7903 10847 7912 10848 7903 10848 7902 10848 7912 10849 7902 10849 7913 10849 7913 10850 7902 10850 7914 10850 7914 10851 7902 10851 7901 10851 7914 10852 7901 10852 7915 10852 7915 10853 7901 10853 7900 10853 7915 10854 7900 10854 7908 10854 7916 10855 7912 10855 7917 10855 7912 10856 7913 10856 7917 10856 7913 10857 7914 10857 7917 10857 7917 10858 7914 10858 7918 10858 7914 10859 7915 10859 7918 10859 7918 10860 7915 10860 7919 10860 7908 10861 7919 10861 7915 10861 7919 10862 7908 10862 7920 10862 7908 10863 7909 10863 7920 10863 7909 10864 7910 10864 7920 10864 7920 10865 7910 10865 7921 10865 7910 10866 7911 10866 7921 10866 7921 10867 7911 10867 7916 10867 7912 10868 7916 10868 7911 10868 7921 10869 7916 10869 7868 10869 7868 10870 7916 10870 7863 10870 7858 10871 7917 10871 7918 10871 7858 10872 7918 10872 7855 10872 7875 10873 7920 10873 7921 10873 7875 10874 7921 10874 7868 10874 7863 10875 7916 10875 7917 10875 7863 10876 7917 10876 7858 10876 7855 10877 7918 10877 7919 10877 7855 10878 7919 10878 7878 10878 7878 10879 7919 10879 7920 10879 7878 10880 7920 10880 7875 10880 7922 10881 7923 10881 7924 10881 7922 10882 7924 10882 7925 10882 7926 10883 7927 10883 7922 10883 7922 10884 7927 10884 7923 10884 7928 10885 7929 10885 7926 10885 7926 10886 7929 10886 7927 10886 7930 10887 7931 10887 7928 10887 7928 10888 7931 10888 7932 10888 7928 10889 7932 10889 7929 10889 7935 10890 7933 10890 7930 10890 7930 10891 7933 10891 7931 10891 7925 10892 7934 10892 7935 10892 7935 10893 7934 10893 7933 10893 7925 10894 7924 10894 7936 10894 7925 10895 7936 10895 7934 10895 7937 10896 7967 10896 7965 10896 7937 10897 7965 10897 7938 10897 7938 10898 7965 10898 7963 10898 7938 10899 7963 10899 7939 10899 7939 10900 7963 10900 7940 10900 7940 10901 7963 10901 7961 10901 7961 10902 7959 10902 7940 10902 7940 10903 7959 10903 7941 10903 7941 10904 7959 10904 7957 10904 7941 10905 7957 10905 7955 10905 7941 10906 7955 10906 7942 10906 7942 10907 7955 10907 7954 10907 7942 10908 7954 10908 7943 10908 7943 10909 7954 10909 7953 10909 7943 10910 7953 10910 7944 10910 7953 10911 7951 10911 7944 10911 7944 10912 7951 10912 7945 10912 7944 10913 7945 10913 7946 10913 7946 10914 7945 10914 7947 10914 7946 10915 7947 10915 7948 10915 7948 10916 7947 10916 7937 10916 7937 10917 7947 10917 7967 10917 7949 10918 7993 10918 7945 10918 7949 10919 7945 10919 7950 10919 7950 10920 7945 10920 7951 10920 7950 10921 7951 10921 7952 10921 7952 10922 7951 10922 7953 10922 7952 10923 7953 10923 7954 10923 7955 10924 7956 10924 7952 10924 7955 10925 7952 10925 7954 10925 7957 10926 7958 10926 7956 10926 7957 10927 7956 10927 7955 10927 7958 10928 7957 10928 7959 10928 7959 10929 7960 10929 7958 10929 7960 10930 7959 10930 7961 10930 7961 10931 7962 10931 7960 10931 7962 10932 7961 10932 7963 10932 7963 10933 7964 10933 7962 10933 7964 10934 7963 10934 7965 10934 7965 10935 7966 10935 7964 10935 7966 10936 7965 10936 7967 10936 7966 10937 7967 10937 7947 10937 7966 10938 7947 10938 7968 10938 7968 10939 7947 10939 7949 10939 7949 10940 7947 10940 7993 10940 7949 10941 7969 10941 7968 10941 7966 10942 7968 10942 7969 10942 7969 10943 7970 10943 7966 10943 7960 10944 7970 10944 7969 10944 7969 10945 7958 10945 7960 10945 7949 10946 7950 10946 7969 10946 7946 10947 7971 10947 7944 10947 7944 10948 7971 10948 7972 10948 7944 10949 7972 10949 7943 10949 7972 10950 7929 10950 7943 10950 7929 10951 7973 10951 7943 10951 7943 10952 7973 10952 7942 10952 7973 10953 7932 10953 7942 10953 7942 10954 7932 10954 7941 10954 7932 10955 7974 10955 7941 10955 7941 10956 7974 10956 7975 10956 7941 10957 7975 10957 7940 10957 7940 10958 7975 10958 7976 10958 7940 10959 7976 10959 7939 10959 7976 10960 7977 10960 7939 10960 7939 10961 7977 10961 7938 10961 7938 10962 7977 10962 7978 10962 7938 10963 7978 10963 7937 10963 7937 10964 7978 10964 7924 10964 7937 10965 7924 10965 7948 10965 7948 10966 7924 10966 7979 10966 7948 10967 7979 10967 7946 10967 7946 10968 7979 10968 7971 10968 7931 10969 7975 10969 7974 10969 7931 10970 7974 10970 7932 10970 7932 10971 7973 10971 7929 10971 7929 10972 7972 10972 7927 10972 7927 10973 7972 10973 7971 10973 7927 10974 7971 10974 7923 10974 7923 10975 7971 10975 7979 10975 7923 10976 7979 10976 7924 10976 7924 10977 7978 10977 7936 10977 7936 10978 7978 10978 7977 10978 7936 10979 7977 10979 7934 10979 7934 10980 7977 10980 7933 10980 7977 10981 7976 10981 7933 10981 7933 10982 7976 10982 7975 10982 7933 10983 7975 10983 7931 10983 7966 10984 7970 10984 7964 10984 7964 10985 7970 10985 7962 10985 7962 10986 7970 10986 7960 10986 7956 10987 7958 10987 7969 10987 7956 10988 7969 10988 7952 10988 7952 10989 7969 10989 7950 10989 7928 10990 7980 10990 7930 10990 7926 10991 7981 10991 7928 10991 7922 10992 7982 10992 7926 10992 7925 10993 7983 10993 7922 10993 7935 10994 7984 10994 7925 10994 7930 10995 7985 10995 7935 10995 7987 10996 7991 10996 7992 10996 7986 10997 7987 10997 7992 10997 7987 10998 7990 10998 7991 10998 7989 10999 7990 10999 7987 10999 7988 11000 7989 11000 7987 11000 7986 11001 7988 11001 7987 11001 7928 11002 7990 11002 7980 11002 7989 11003 7930 11003 7980 11003 7980 11004 7990 11004 7989 11004 7981 11005 7926 11005 7991 11005 7990 11006 7928 11006 7981 11006 7991 11007 7990 11007 7981 11007 7992 11008 7982 11008 7922 11008 7991 11009 7926 11009 7982 11009 7991 11010 7982 11010 7992 11010 7992 11011 7922 11011 7986 11011 7986 11012 7922 11012 7983 11012 7986 11013 7983 11013 7925 11013 7935 11014 7988 11014 7984 11014 7984 11015 7988 11015 7986 11015 7984 11016 7986 11016 7925 11016 7930 11017 7989 11017 7985 11017 7988 11018 7935 11018 7985 11018 7985 11019 7989 11019 7988 11019 7945 11020 7993 11020 7947 11020 7995 8507 7994 8507 7996 8507 7997 11021 7999 11021 7998 11021 8000 11022 8002 11022 8001 11022 8005 11023 8003 11023 8004 11023 8006 11024 7996 11024 7994 11024 8006 11025 7994 11025 8007 11025 8007 11026 7994 11026 7995 11026 8007 11027 7995 11027 8008 11027 8008 11028 7995 11028 8006 11028 8006 11029 7995 11029 7996 11029 8009 11030 7999 11030 8010 11030 8010 11031 7999 11031 7997 11031 8010 11032 7997 11032 8011 11032 8011 11033 7997 11033 7998 11033 8011 11034 7998 11034 8009 11034 8009 11035 7998 11035 7999 11035 8001 11036 8055 11036 8054 11036 8002 11037 8012 11037 8001 11037 8001 11038 8012 11038 8055 11038 8002 11039 8013 11039 8012 11039 8000 11040 8013 11040 8002 11040 8000 11041 8014 11041 8013 11041 8000 11042 8015 11042 8014 11042 8001 11043 8054 11043 8015 11043 8001 11044 8015 11044 8000 11044 8005 11045 8016 11045 8057 11045 8004 11046 8016 11046 8005 11046 8004 11047 8017 11047 8016 11047 8004 11048 8018 11048 8017 11048 8003 11049 8018 11049 8004 11049 8003 11050 8019 11050 8018 11050 8005 11051 8019 11051 8003 11051 8057 11052 8056 11052 8005 11052 8005 11053 8056 11053 8019 11053 8020 8507 8021 8507 8022 8507 8022 8507 8021 8507 8023 8507 8007 8507 8024 8507 8006 8507 8006 11054 8024 11054 8025 11054 8024 8507 8010 8507 8026 8507 8026 11055 8010 11055 8011 11055 8009 8507 8010 8507 8024 8507 8009 11056 8027 11056 8011 11056 8011 11057 8027 11057 8026 11057 8027 11058 8009 11058 8008 11058 8027 11059 8008 11059 8006 11059 8027 11060 8006 11060 8025 11060 8009 11061 8007 11061 8008 11061 8024 11062 8007 11062 8009 11062 8028 8507 8029 8507 8030 8507 8030 8507 8029 8507 8031 8507 8032 11063 8026 11063 8027 11063 8033 8507 8032 8507 8034 8507 8034 11064 8032 11064 8027 11064 8036 348 8037 348 8038 348 8024 348 8039 348 8040 348 8041 348 8042 348 8043 348 8025 348 8024 348 8035 348 8035 348 8024 348 8040 348 8035 348 8040 348 8043 348 8043 348 8040 348 8036 348 8043 348 8036 348 8041 348 8041 348 8036 348 8038 348 8020 324 8022 324 8044 324 8044 324 8022 324 8045 324 8028 324 8030 324 8046 324 8046 324 8030 324 8047 324 8033 324 8034 324 8048 324 8048 324 8034 324 8049 324 8022 8505 8023 8505 8045 8505 8045 8505 8023 8505 8050 8505 8023 348 8021 348 8050 348 8050 348 8021 348 8051 348 8031 348 8029 348 8052 348 8052 348 8029 348 8053 348 8029 8646 8028 8646 8053 8646 8053 8646 8028 8646 8046 8646 8060 11065 8058 11065 8061 11065 8059 11066 8061 11066 8058 11066 8059 11067 8058 11067 8062 11067 8062 11068 8058 11068 8063 11068 8064 11069 8065 11069 8063 11069 8063 11070 8065 11070 8062 11070 8066 11071 8067 11071 8068 11071 8068 11072 8067 11072 8069 11072 8070 11073 8071 11073 8072 11073 8072 11074 8071 11074 8073 11074 8043 8511 8042 8511 8074 8511 8074 8511 8042 8511 8075 8511 8040 8507 8039 8507 8076 8507 8076 8507 8039 8507 8077 8507 8025 11075 8035 11075 8078 11075 8078 8507 8035 8507 8079 8507 8044 8505 8049 8505 8020 8505 8020 8505 8049 8505 8034 8505 8078 11076 8075 11076 8025 11076 8025 11077 8075 11077 8042 11077 8025 11078 8042 11078 8027 11078 8034 11079 8027 11079 8020 11079 8020 8505 8027 8505 8021 8505 8021 8505 8027 8505 8042 8505 8021 8505 8042 8505 8051 8505 8051 8505 8042 8505 8041 8505 8035 8646 8043 8646 8079 8646 8079 8646 8043 8646 8074 8646 8036 8505 8040 8505 8080 8505 8080 8505 8040 8505 8076 8505 8031 8646 8077 8646 8030 8646 8030 11080 8077 11080 8039 11080 8081 8646 8077 8646 8037 8646 8037 11081 8077 11081 8031 11081 8037 8646 8031 8646 8038 8646 8038 8646 8031 8646 8052 8646 8048 8646 8047 8646 8033 8646 8033 8646 8047 8646 8030 8646 8032 8646 8033 8646 8026 8646 8026 8646 8033 8646 8030 8646 8026 8646 8030 8646 8024 8646 8024 8646 8030 8646 8039 8646 8037 8511 8036 8511 8081 8511 8081 8511 8036 8511 8080 8511 8082 11082 8083 11082 8038 11082 8038 11083 8083 11083 8041 11083 8046 8507 8084 8507 8053 8507 8053 8507 8084 8507 8082 8507 8053 11084 8082 11084 8052 11084 8052 8507 8082 8507 8038 8507 8049 11085 8085 11085 8048 11085 8048 8507 8085 8507 8084 8507 8048 8507 8084 8507 8047 8507 8047 11086 8084 11086 8046 11086 8051 8507 8041 8507 8050 8507 8050 8507 8041 8507 8083 8507 8050 8507 8083 8507 8045 8507 8045 8507 8083 8507 8085 8507 8045 8507 8085 8507 8044 8507 8044 8507 8085 8507 8049 8507 8072 8505 8073 8505 8086 8505 8086 8505 8073 8505 8087 8505 8089 8505 8090 8505 8067 8505 8067 8505 8090 8505 8091 8505 8067 11087 8091 11087 8069 11087 8069 8505 8091 8505 8092 8505 8093 8511 8070 8511 8086 8511 8086 8511 8070 8511 8072 8511 8068 8646 8094 8646 8066 8646 8066 8646 8094 8646 8095 8646 8071 8511 8096 8511 8073 8511 8073 8511 8096 8511 8089 8511 8073 8511 8089 8511 8066 8511 8066 8511 8089 8511 8067 8511 8018 11088 8019 11088 8095 11088 8066 11089 8056 11089 8073 11089 8095 11090 8019 11090 8066 11090 8013 11091 8014 11091 8018 11091 8012 11092 8013 11092 8087 11092 8018 11093 8095 11093 8087 11093 8018 11094 8014 11094 8017 11094 8073 11095 8056 11095 8057 11095 8019 11096 8056 11096 8066 11096 8018 11097 8087 11097 8013 11097 8014 11098 8016 11098 8017 11098 8014 11099 8057 11099 8016 11099 8057 11100 8014 11100 8015 11100 8057 11101 8054 11101 8073 11101 8073 11102 8054 11102 8055 11102 8057 11103 8015 11103 8054 11103 8073 11104 8055 11104 8087 11104 8087 11105 8055 11105 8012 11105 8097 8505 8082 8505 8098 8505 8098 8505 8082 8505 8084 8505 8062 11106 8065 11106 8088 11106 8062 11107 8088 11107 8059 11107 8060 11108 8097 11108 8058 11108 8058 11109 8097 11109 8098 11109 8058 11110 8098 11110 8063 11110 8059 11111 8088 11111 8091 11111 8059 11112 8091 11112 8061 11112 8061 11113 8091 11113 8090 11113 8068 11114 8069 11114 8094 11114 8094 11115 8069 11115 8092 11115 8070 8646 8093 8646 8071 8646 8071 11116 8093 11116 8099 11116 8071 8646 8099 8646 8096 8646 8096 8646 8099 8646 8100 8646 8105 8646 8085 8646 8106 8646 8106 8646 8085 8646 8083 8646 8061 11117 8090 11117 8089 11117 8096 11118 8100 11118 8107 11118 8078 324 8079 324 8089 324 8083 11119 8082 11119 8060 11119 8060 11120 8082 11120 8097 11120 8106 11121 8083 11121 8108 11121 8108 11122 8083 11122 8080 11122 8080 324 8083 324 8081 324 8081 11123 8083 11123 8060 11123 8081 11124 8060 11124 8077 11124 8089 324 8096 324 8078 324 8078 11125 8096 11125 8107 11125 8078 11126 8107 11126 8075 11126 8075 11127 8107 11127 8108 11127 8075 11128 8108 11128 8074 11128 8074 11129 8108 11129 8080 11129 8074 324 8080 324 8079 324 8079 324 8080 324 8076 324 8079 324 8076 324 8089 324 8089 324 8076 324 8077 324 8089 11130 8077 11130 8061 11130 8061 11131 8077 11131 8060 11131 8084 11132 8085 11132 8109 11132 8109 11133 8085 11133 8105 11133 8101 348 8099 348 8087 348 8087 348 8099 348 8093 348 8087 348 8093 348 8086 348 8104 11134 8103 11134 8109 11134 8109 11135 8103 11135 8101 11135 8098 11136 8084 11136 8063 11136 8063 11137 8084 11137 8109 11137 8063 11138 8109 11138 8088 11138 8063 11139 8088 11139 8064 11139 8064 11140 8088 11140 8065 11140 8094 11141 8092 11141 8095 11141 8095 348 8092 348 8091 348 8095 11142 8091 11142 8088 11142 8087 348 8095 348 8101 348 8101 348 8095 348 8088 348 8101 11143 8088 11143 8109 11143 8103 11144 8104 11144 8110 11144 8110 11145 8104 11145 8109 11145 8110 11146 8102 11146 8101 11146 8110 11147 8101 11147 8103 11147 8107 11148 8100 11148 8102 11148 8102 11149 8100 11149 8099 11149 8102 11150 8099 11150 8101 11150 8111 11151 8109 11151 8105 11151 8111 11152 8105 11152 8108 11152 8108 8511 8105 8511 8106 8511 8110 11153 8109 11153 8102 11153 8102 11154 8109 11154 8111 11154 8102 11155 8111 11155 8107 11155 8107 11156 8111 11156 8108 11156 8113 11157 8112 11157 8114 11157 8115 8646 8117 8646 8116 8646 8119 8646 8118 8646 8120 8646 8120 8646 8121 8646 8119 8646 8123 11158 8124 11158 8122 11158 8123 8646 8125 8646 8124 8646 8127 11159 8128 11159 8126 11159 8130 11160 8129 11160 8131 11160 8132 8646 8134 8646 8133 8646 8136 11161 8135 11161 8137 11161 8138 11162 8139 11162 8140 11162 8140 11163 8139 11163 8141 11163 8142 11164 8143 11164 8144 11164 8144 11165 8143 11165 8145 11165 8112 11166 8189 11166 8146 11166 8112 11167 8146 11167 8114 11167 8114 11168 8146 11168 8147 11168 8114 11169 8147 11169 8148 11169 8114 11170 8148 11170 8113 11170 8113 11171 8148 11171 8188 11171 8113 11172 8188 11172 8112 11172 8112 11173 8188 11173 8189 11173 8116 11174 8191 11174 8115 11174 8115 11175 8191 11175 8149 11175 8115 11176 8149 11176 8150 11176 8115 11177 8150 11177 8117 11177 8117 11178 8150 11178 8151 11178 8117 11179 8151 11179 8116 11179 8116 11180 8151 11180 8190 11180 8116 11181 8190 11181 8191 11181 8118 11182 8193 11182 8152 11182 8118 11183 8152 11183 8120 11183 8120 11184 8152 11184 8153 11184 8120 11185 8153 11185 8121 11185 8121 11186 8153 11186 8154 11186 8121 11187 8154 11187 8119 11187 8119 11188 8154 11188 8192 11188 8119 11189 8192 11189 8118 11189 8118 11190 8192 11190 8193 11190 8124 11191 8195 11191 8122 11191 8122 11192 8195 11192 8155 11192 8122 11193 8155 11193 8123 11193 8123 11194 8155 11194 8156 11194 8123 11195 8156 11195 8157 11195 8123 11196 8157 11196 8125 11196 8125 11197 8157 11197 8124 11197 8124 11198 8157 11198 8194 11198 8124 11199 8194 11199 8195 11199 8126 11200 8197 11200 8158 11200 8126 11201 8158 11201 8127 11201 8127 11202 8158 11202 8159 11202 8127 11203 8159 11203 8160 11203 8127 11204 8160 11204 8128 11204 8128 11205 8160 11205 8196 11205 8128 11206 8196 11206 8126 11206 8126 11207 8196 11207 8197 11207 8130 11208 8201 11208 8129 11208 8129 11209 8201 11209 8161 11209 8129 11210 8161 11210 8162 11210 8129 11211 8162 11211 8131 11211 8131 11212 8162 11212 8163 11212 8131 11213 8163 11213 8130 11213 8130 11214 8163 11214 8200 11214 8130 11215 8200 11215 8201 11215 8133 11216 8203 11216 8132 11216 8132 11217 8203 11217 8164 11217 8132 11218 8164 11218 8165 11218 8132 11219 8165 11219 8134 11219 8134 11220 8165 11220 8166 11220 8134 11221 8166 11221 8133 11221 8133 11222 8166 11222 8202 11222 8133 11223 8202 11223 8203 11223 8136 11224 8206 11224 8135 11224 8135 11225 8206 11225 8167 11225 8135 11226 8167 11226 8137 11226 8137 11227 8167 11227 8168 11227 8137 11228 8168 11228 8169 11228 8137 11229 8169 11229 8136 11229 8136 11230 8169 11230 8205 11230 8136 11231 8205 11231 8206 11231 8140 11232 8172 11232 8173 11232 8140 11233 8173 11233 8138 11233 8144 11234 8174 11234 8175 11234 8144 11235 8175 11235 8142 11235 8176 11236 8172 11236 8177 11236 8170 11237 8177 11237 8172 11237 8170 11238 8172 11238 8141 11238 8141 11239 8172 11239 8140 11239 8144 11240 8145 11240 8174 11240 8174 11241 8145 11241 8171 11241 8174 11242 8171 11242 8179 11242 8179 11243 8171 11243 8178 11243 8180 8646 8181 8646 8182 8646 8182 8646 8181 8646 8183 8646 8184 11244 8185 11244 8186 11244 8186 11245 8185 11245 8187 11245 8198 11246 8180 11246 8199 11246 8199 11247 8180 11247 8182 11247 8198 11248 8204 11248 8180 11248 8180 11248 8204 11248 8181 11248 8207 8646 8208 8646 8186 8646 8186 8646 8208 8646 8184 8646 8208 11249 8209 11249 8184 11249 8184 11248 8209 11248 8185 11248 8210 11250 8211 11250 8175 11250 8175 324 8211 324 8212 324 8175 11251 8212 11251 8141 11251 8141 11252 8212 11252 8213 11252 8207 11253 8186 11253 8187 11253 8139 11254 8138 11254 8141 11254 8141 11255 8138 11255 8173 11255 8207 324 8187 324 8214 324 8214 11256 8187 11256 8173 11256 8173 11257 8187 11257 8216 11257 8143 11258 8142 11258 8145 11258 8145 11259 8142 11259 8175 11259 8145 11260 8175 11260 8173 11260 8173 11261 8175 11261 8141 11261 8216 11262 8145 11262 8173 11262 8182 324 8183 324 8199 324 8199 324 8183 324 8215 324 8199 11263 8215 11263 8145 11263 8199 11264 8145 11264 8216 11264 8217 8511 8218 8511 8219 8511 8219 8511 8218 8511 8220 8511 8221 8507 8222 8507 8223 8507 8223 8507 8222 8507 8224 8507 8170 11265 8141 11265 8213 11265 8170 11266 8213 11266 8177 11266 8177 11267 8213 11267 8225 11267 8179 11268 8226 11268 8174 11268 8174 11269 8226 11269 8210 11269 8174 11270 8210 11270 8175 11270 8176 11271 8227 11271 8172 11271 8172 11272 8227 11272 8214 11272 8172 11273 8214 11273 8173 11273 8226 8507 8228 8507 8210 8507 8210 8507 8228 8507 8211 8507 8171 11274 8145 11274 8215 11274 8171 11275 8215 11275 8178 11275 8178 8505 8215 8505 8229 8505 8213 8511 8212 8511 8225 8511 8225 8511 8212 8511 8230 8511 8231 11276 8229 11276 8204 11276 8204 8507 8229 8507 8215 8507 8204 11277 8215 11277 8181 11277 8181 8507 8215 8507 8183 8507 8209 8646 8232 8646 8185 8646 8185 8646 8232 8646 8233 8646 8185 8646 8233 8646 8187 8646 8231 11278 8204 11278 8198 11278 8153 11279 8151 11279 8150 11279 8153 11280 8150 11280 8199 11280 8150 11281 8149 11281 8199 11281 8198 11282 8149 11282 8191 11282 8191 11283 8190 11283 8231 11283 8199 11284 8149 11284 8198 11284 8198 11285 8191 11285 8231 11285 8231 11286 8190 11286 8153 11286 8153 11287 8190 11287 8151 11287 8216 8646 8187 8646 8234 8646 8216 8646 8234 8646 8235 8646 8216 8646 8235 8646 8236 8646 8216 8646 8237 8646 8238 8646 8216 11288 8238 11288 8199 11288 8199 11289 8238 11289 8153 11289 8231 11290 8193 11290 8239 11290 8238 11291 8154 11291 8153 11291 8231 11292 8152 11292 8193 11292 8193 11293 8192 11293 8239 11293 8153 11294 8152 11294 8231 11294 8239 11295 8192 11295 8238 11295 8238 11296 8192 11296 8154 11296 8237 11297 8148 11297 8147 11297 8237 11298 8147 11298 8238 11298 8147 11299 8146 11299 8238 11299 8239 11300 8146 11300 8189 11300 8189 11301 8188 11301 8239 11301 8238 11302 8146 11302 8239 11302 8239 11303 8188 11303 8237 11303 8237 11304 8188 11304 8148 11304 8216 11305 8157 11305 8156 11305 8216 11306 8156 11306 8237 11306 8156 11307 8155 11307 8237 11307 8239 11308 8155 11308 8195 11308 8195 11309 8194 11309 8239 11309 8237 11310 8155 11310 8239 11310 8239 11311 8194 11311 8216 11311 8216 11312 8194 11312 8157 11312 8239 11313 8201 11313 8240 11313 8236 11314 8163 11314 8162 11314 8236 11315 8162 11315 8216 11315 8162 11316 8161 11316 8216 11316 8239 11317 8161 11317 8201 11317 8201 11318 8200 11318 8240 11318 8216 11319 8161 11319 8239 11319 8240 11320 8200 11320 8236 11320 8236 11321 8200 11321 8163 11321 8235 11322 8166 11322 8165 11322 8235 11323 8165 11323 8236 11323 8165 11324 8164 11324 8236 11324 8240 11325 8164 11325 8203 11325 8203 11326 8202 11326 8240 11326 8236 11327 8164 11327 8240 11327 8240 11328 8202 11328 8235 11328 8235 11329 8202 11329 8166 11329 8240 11330 8206 11330 8233 11330 8234 11331 8169 11331 8168 11331 8234 11332 8168 11332 8235 11332 8168 11333 8167 11333 8235 11333 8240 11334 8167 11334 8206 11334 8206 11335 8205 11335 8233 11335 8235 11336 8167 11336 8240 11336 8233 11337 8205 11337 8234 11337 8234 11338 8205 11338 8169 11338 8187 11339 8160 11339 8159 11339 8187 11340 8159 11340 8234 11340 8159 11341 8158 11341 8234 11341 8233 11342 8158 11342 8197 11342 8197 11343 8196 11343 8233 11343 8234 11344 8158 11344 8233 11344 8233 11345 8196 11345 8187 11345 8187 11346 8196 11346 8160 11346 8208 8511 8207 8511 8209 8511 8209 8511 8207 8511 8214 8511 8209 8511 8214 8511 8232 8511 8232 8511 8214 8511 8227 8511 8242 11347 8243 11347 8241 11347 8244 8505 8245 8505 8246 8505 8248 11348 8247 11348 8249 11348 8251 11349 8250 11349 8252 11349 8254 8505 8253 8505 8255 8505 8257 11350 8258 11350 8256 11350 8259 8507 8260 8507 8261 8507 8261 11351 8260 11351 8262 11351 8263 8511 8264 8511 8265 8511 8265 8511 8264 8511 8266 8511 8267 8646 8259 8646 8261 8646 8218 348 8268 348 8220 348 8220 348 8268 348 8269 348 8270 324 8217 324 8271 324 8271 324 8217 324 8219 324 8218 8505 8217 8505 8268 8505 8268 8505 8217 8505 8270 8505 8260 11352 8272 11352 8262 11352 8262 8505 8272 8505 8273 8505 8274 8505 8275 8505 8221 8505 8221 8505 8275 8505 8222 8505 8276 8505 8277 8505 8278 8505 8278 11353 8277 11353 8279 11353 8228 8505 8219 8505 8211 8505 8211 8505 8219 8505 8220 8505 8280 8505 8212 8505 8281 8505 8281 8505 8212 8505 8211 8505 8281 8505 8211 8505 8269 8505 8269 8505 8211 8505 8220 8505 8224 8505 8230 8505 8223 8505 8223 8505 8230 8505 8212 8505 8223 8505 8212 8505 8282 8505 8282 8505 8212 8505 8280 8505 8271 8505 8219 8505 8283 8505 8283 8505 8219 8505 8228 8505 8283 8505 8228 8505 8284 8505 8284 8505 8228 8505 8230 8505 8284 8505 8230 8505 8285 8505 8285 8505 8230 8505 8224 8505 8222 324 8275 324 8224 324 8224 324 8275 324 8285 324 8274 348 8221 348 8282 348 8282 348 8221 348 8223 348 8229 11354 8231 11354 8178 11354 8286 11355 8176 11355 8287 11355 8287 11356 8176 11356 8177 11356 8287 11357 8177 11357 8266 11357 8228 11358 8226 11358 8179 11358 8179 11359 8178 11359 8273 11359 8273 11360 8178 11360 8231 11360 8273 348 8231 348 8262 348 8262 348 8231 348 8239 348 8262 348 8239 348 8261 348 8273 11361 8267 11361 8179 11361 8179 11362 8267 11362 8261 11362 8179 11363 8261 11363 8228 11363 8228 11364 8261 11364 8266 11364 8228 11365 8266 11365 8230 11365 8230 11366 8266 11366 8177 11366 8230 11367 8177 11367 8225 11367 8232 348 8227 348 8233 348 8233 11368 8227 11368 8176 11368 8233 11369 8176 11369 8286 11369 8233 11370 8286 11370 8240 11370 8240 11371 8286 11371 8265 11371 8240 348 8265 348 8266 348 8240 348 8266 348 8239 348 8239 348 8266 348 8261 348 8264 8646 8288 8646 8266 8646 8266 8646 8288 8646 8287 8646 8289 11372 8263 11372 8286 11372 8286 8505 8263 8505 8265 8505 8276 348 8278 348 8281 348 8281 348 8278 348 8280 348 8291 11373 8292 11373 8290 11373 8293 11374 8243 11374 8294 11374 8294 11375 8243 11375 8242 11375 8294 11376 8242 11376 8295 11376 8295 11377 8242 11377 8241 11377 8295 11378 8241 11378 8243 11378 8295 11379 8243 11379 8293 11379 8296 11380 8245 11380 8297 11380 8297 11381 8245 11381 8244 11381 8297 11382 8244 11382 8298 11382 8298 11383 8244 11383 8246 11383 8298 11384 8246 11384 8296 11384 8296 11385 8246 11385 8245 11385 8277 11386 8299 11386 8279 11386 8300 11387 8248 11387 8249 11387 8300 11388 8249 11388 8301 11388 8301 11389 8249 11389 8247 11389 8301 11390 8247 11390 8302 11390 8302 11391 8247 11391 8248 11391 8302 11392 8248 11392 8300 11392 8303 11393 8251 11393 8252 11393 8303 11394 8252 11394 8304 11394 8304 11395 8252 11395 8250 11395 8304 11396 8250 11396 8305 11396 8305 11397 8250 11397 8251 11397 8305 11398 8251 11398 8303 11398 8306 11399 8254 11399 8255 11399 8306 11400 8255 11400 8307 11400 8307 11401 8255 11401 8253 11401 8307 11402 8253 11402 8308 11402 8308 11403 8253 11403 8254 11403 8308 11404 8254 11404 8306 11404 8309 11405 8257 11405 8310 11405 8310 11406 8257 11406 8256 11406 8310 11407 8256 11407 8311 11407 8311 11408 8256 11408 8258 11408 8311 11409 8258 11409 8312 11409 8312 11410 8258 11410 8257 11410 8312 11411 8257 11411 8309 11411 8313 11412 8272 11412 8260 11412 8284 324 8288 324 8264 324 8284 324 8264 324 8283 324 8283 324 8264 324 8259 324 8283 11413 8259 11413 8267 11413 8314 11414 8264 11414 8315 11414 8315 324 8264 324 8263 324 8315 11415 8263 11415 8289 11415 8260 11416 8259 11416 8317 11416 8314 11417 8316 11417 8264 11417 8264 11418 8316 11418 8317 11418 8264 11419 8317 11419 8259 11419 8270 8511 8271 8511 8283 8511 8281 8511 8269 8511 8276 8511 8276 8511 8269 8511 8268 8511 8283 11420 8267 11420 8270 11420 8270 11421 8267 11421 8273 11421 8270 8511 8273 8511 8268 8511 8268 8511 8273 8511 8272 8511 8268 11422 8272 11422 8313 11422 8277 11423 8276 11423 8299 11423 8299 11424 8276 11424 8268 11424 8299 11425 8268 11425 8313 11425 8274 8507 8282 8507 8280 8507 8280 8507 8278 8507 8274 8507 8274 8507 8278 8507 8279 8507 8284 8507 8285 8507 8288 8507 8288 8507 8285 8507 8275 8507 8274 11426 8279 11426 8289 11426 8274 8507 8289 8507 8275 8507 8275 11427 8289 11427 8286 11427 8275 8507 8286 8507 8288 8507 8288 8507 8286 8507 8287 8507 8318 11428 8292 11428 8319 11428 8319 11429 8292 11429 8291 11429 8319 11430 8291 11430 8320 11430 8320 11431 8291 11431 8290 11431 8320 11432 8290 11432 8292 11432 8320 11433 8292 11433 8318 11433 8313 11434 8323 11434 8299 11434 8299 11435 8323 11435 8321 11435 8322 11436 8260 11436 8304 11436 8322 11437 8323 11437 8260 11437 8260 11438 8323 11438 8313 11438 8299 11439 8321 11439 8304 11439 8304 8505 8321 8505 8322 8505 8305 11440 8303 11440 8317 11440 8317 11441 8303 11441 8260 11441 8260 11442 8303 11442 8304 11442 8318 11443 8324 11443 8320 11443 8320 11444 8324 11444 8305 11444 8324 11445 8318 11445 8317 11445 8320 8505 8305 8505 8319 8505 8319 11446 8305 11446 8317 11446 8318 11447 8319 11447 8317 11447 8307 11448 8324 11448 8317 11448 8325 11449 8308 11449 8306 11449 8307 11450 8308 11450 8324 11450 8324 11451 8308 11451 8325 11451 8317 11452 8306 11452 8307 11452 8325 11453 8297 11453 8298 11453 8306 11454 8317 11454 8325 11454 8325 11455 8317 11455 8297 11455 8325 11456 8298 11456 8311 11456 8311 8505 8298 8505 8296 8505 8316 11457 8296 11457 8317 11457 8317 11458 8296 11458 8297 11458 8296 11459 8316 11459 8311 11459 8311 11460 8316 11460 8310 11460 8309 11461 8310 11461 8314 11461 8314 11462 8310 11462 8316 11462 8309 11463 8314 11463 8312 11463 8312 11464 8314 11464 8301 11464 8312 8505 8301 8505 8302 8505 8315 11465 8300 11465 8314 11465 8314 11466 8300 11466 8301 11466 8293 11467 8294 11467 8289 11467 8300 11468 8315 11468 8302 11468 8302 11469 8315 11469 8294 11469 8302 8505 8294 8505 8295 8505 8289 11470 8294 11470 8315 11470 8302 11471 8295 11471 8279 11471 8279 11472 8295 11472 8293 11472 8293 11473 8289 11473 8279 11473 8299 11474 8304 11474 8305 11474 8299 11475 8305 11475 8324 11475 8299 11476 8324 11476 8325 11476 8299 11477 8325 11477 8279 11477 8279 11478 8325 11478 8311 11478 8279 11479 8311 11479 8312 11479 8279 11480 8312 11480 8302 11480 8328 11481 8326 11481 8327 11481 8322 11482 8328 11482 8327 11482 8322 11483 8327 11483 8323 11483 8323 11484 8327 11484 8321 11484 8321 11485 8327 11485 8326 11485 8321 11486 8326 11486 8322 11486 8322 11487 8326 11487 8328 11487 8329 348 8330 348 8331 348 8331 348 8330 348 8332 348 8333 324 8334 324 8335 324 8335 324 8334 324 8336 324 8332 8646 8336 8646 8331 8646 8331 8646 8336 8646 8334 8646 8331 8511 8334 8511 8329 8511 8329 8511 8334 8511 8333 8511 8329 8505 8333 8505 8330 8505 8330 8505 8333 8505 8335 8505 8330 8507 8335 8507 8332 8507 8332 8507 8335 8507 8336 8507 8337 348 8338 348 8339 348 8339 348 8338 348 8340 348 8341 324 8342 324 8343 324 8343 324 8342 324 8344 324 8340 8646 8344 8646 8339 8646 8339 8646 8344 8646 8342 8646 8339 8511 8342 8511 8337 8511 8337 8511 8342 8511 8341 8511 8337 11488 8341 11488 8338 11488 8338 8505 8341 8505 8343 8505 8338 8507 8343 8507 8340 8507 8340 8507 8343 8507 8344 8507 8345 348 8346 348 8347 348 8347 348 8346 348 8348 348 8349 324 8350 324 8351 324 8351 11489 8350 11489 8352 11489 8348 11490 8352 11490 8347 11490 8347 11491 8352 11491 8350 11491 8347 8505 8350 8505 8345 8505 8345 8505 8350 8505 8349 8505 8345 8507 8349 8507 8346 8507 8346 8507 8349 8507 8351 8507 8346 8646 8351 8646 8348 8646 8348 8646 8351 8646 8352 8646 8353 348 8354 348 8355 348 8355 348 8354 348 8356 348 8357 324 8358 324 8359 324 8359 324 8358 324 8360 324 8356 8511 8360 8511 8355 8511 8355 8511 8360 8511 8358 8511 8355 8505 8358 8505 8353 8505 8353 8505 8358 8505 8357 8505 8353 8507 8357 8507 8354 8507 8354 8507 8357 8507 8359 8507 8354 8646 8359 8646 8356 8646 8356 8646 8359 8646 8360 8646 8363 11492 8364 11492 8365 11492 8369 11493 8367 11493 8370 11493 8370 11494 8367 11494 8368 11494 8373 11495 8371 11495 8374 11495 8374 11496 8371 11496 8372 11496 8377 11497 8375 11497 8378 11497 8378 11496 8375 11496 8376 11496 8379 11498 8361 11498 8380 11498 8381 11499 8382 11499 8383 11499 8367 11500 8385 11500 8368 11500 8368 11501 8385 11501 8370 11501 8384 11502 8387 11502 8383 11502 8375 11500 8388 11500 8376 11500 8376 11503 8388 11503 8378 11503 8371 11504 8389 11504 8372 11504 8372 11505 8389 11505 8374 11505 8366 11506 8390 11506 8365 11506 8391 348 8392 348 8393 348 8393 348 8392 348 8394 348 8395 8505 8391 8505 8396 8505 8396 8505 8391 8505 8393 8505 8397 11507 8395 11507 8398 11507 8398 348 8395 348 8396 348 8399 348 8400 348 8401 348 8401 348 8400 348 8402 348 8403 348 8404 348 8405 348 8405 348 8404 348 8406 348 8400 8505 8403 8505 8402 8505 8402 8505 8403 8505 8405 8505 8409 8646 8410 8646 8411 8646 8410 11508 8412 11508 8413 11508 8386 11509 8380 11509 8361 11509 8386 11510 8361 11510 8362 11510 8390 11511 8366 11511 8363 11511 8363 11512 8366 11512 8364 11512 8386 11513 8362 11513 8379 11513 8379 11514 8362 11514 8361 11514 8412 8646 8414 8646 8413 8646 8413 11515 8414 11515 8415 11515 8385 8507 8367 8507 8369 8507 8365 11516 8364 11516 8366 11516 8387 11517 8384 11517 8381 11517 8381 11518 8384 11518 8382 11518 8389 11519 8371 11519 8373 11519 8416 8646 8417 8646 8407 8646 8388 8507 8375 8507 8377 8507 8383 11520 8382 11520 8384 11520 8400 8511 8399 8511 8403 8511 8403 8511 8399 8511 8418 8511 8403 8511 8418 8511 8404 8511 8404 8511 8418 8511 8419 8511 8397 8507 8420 8507 8395 8507 8395 8507 8420 8507 8421 8507 8395 8507 8421 8507 8391 8507 8391 8507 8421 8507 8392 8507 8421 8505 8418 8505 8389 8505 8389 8505 8418 8505 8399 8505 8389 11521 8399 11521 8374 11521 8374 11522 8399 11522 8401 11522 8374 11523 8401 11523 8422 11523 8386 11524 8421 11524 8389 11524 8386 11525 8389 11525 8373 11525 8378 11526 8388 11526 8421 11526 8387 11527 8381 11527 8378 11527 8387 11528 8378 11528 8421 11528 8387 11529 8421 11529 8383 11529 8383 11530 8421 11530 8386 11530 8383 11531 8386 11531 8379 11531 8363 11532 8423 11532 8390 11532 8390 8505 8423 8505 8394 8505 8390 11533 8394 11533 8365 11533 8365 11534 8394 11534 8392 11534 8365 11535 8392 11535 8421 11535 8385 11536 8369 11536 8365 11536 8385 11537 8365 11537 8421 11537 8385 11538 8421 11538 8370 11538 8370 11539 8421 11539 8388 11539 8370 11540 8388 11540 8377 11540 8420 11541 8397 11541 8424 11541 8424 11542 8397 11542 8398 11542 8404 11543 8419 11543 8406 11543 8406 11544 8419 11544 8425 11544 8394 8507 8423 8507 8393 8507 8393 11545 8423 11545 8414 11545 8393 8507 8414 8507 8396 8507 8396 8507 8414 8507 8412 8507 8412 11546 8410 11546 8409 11546 8428 8507 8429 8507 8409 8507 8409 8507 8429 8507 8424 8507 8409 8507 8424 8507 8412 8507 8412 11547 8424 11547 8398 11547 8412 11548 8398 11548 8396 11548 8428 11549 8409 11549 8431 11549 8431 11550 8409 11550 8411 11550 8425 11551 8432 11551 8433 11551 8422 11552 8401 11552 8417 11552 8417 11553 8401 11553 8402 11553 8417 11554 8402 11554 8407 11554 8407 11555 8402 11555 8405 11555 8426 11556 8408 11556 8407 11556 8433 11557 8426 11557 8425 11557 8425 11558 8426 11558 8407 11558 8425 11559 8407 11559 8406 11559 8406 11560 8407 11560 8405 11560 8416 11561 8407 11561 8408 11561 8427 11562 8416 11562 8408 11562 8427 11563 8408 11563 8434 11563 8434 11564 8408 11564 8426 11564 8431 11565 8411 11565 8430 11565 8430 11566 8411 11566 8410 11566 8410 11567 8413 11567 8430 11567 8430 11568 8413 11568 8415 11568 8435 11569 8436 11569 8431 11569 8431 11570 8436 11570 8437 11570 8438 11571 8439 11571 8440 11571 8440 11572 8439 11572 8434 11572 8380 11573 8386 11573 8373 11573 8423 11574 8363 11574 8414 11574 8427 11575 8430 11575 8416 11575 8416 11576 8430 11576 8373 11576 8416 11577 8373 11577 8374 11577 8416 11578 8374 11578 8417 11578 8417 11579 8374 11579 8422 11579 8363 11580 8365 11580 8414 11580 8414 11581 8365 11581 8369 11581 8414 11582 8369 11582 8415 11582 8369 11583 8370 11583 8415 11583 8415 11584 8370 11584 8377 11584 8415 11585 8377 11585 8430 11585 8430 11586 8377 11586 8378 11586 8378 11587 8381 11587 8430 11587 8430 11588 8381 11588 8383 11588 8383 11589 8379 11589 8430 11589 8430 11590 8379 11590 8380 11590 8430 11591 8380 11591 8373 11591 8432 348 8425 348 8429 348 8429 11592 8425 11592 8419 11592 8424 348 8429 348 8420 348 8420 348 8429 348 8419 348 8420 348 8419 348 8421 348 8421 348 8419 348 8418 348 8434 11593 8426 11593 8433 11593 8436 324 8441 324 8437 324 8436 8646 8435 8646 8441 8646 8442 11594 8435 11594 8431 11594 8439 11595 8443 11595 8434 11595 8434 11596 8443 11596 8444 11596 8439 8646 8438 8646 8443 8646 8440 11597 8434 11597 8433 11597 8440 8646 8433 8646 8432 8646 8434 8646 8444 8646 8445 8646 8434 11598 8445 11598 8427 11598 8446 8646 8442 8646 8431 8646 8447 8646 8440 8646 8432 8646 8447 11599 8432 11599 8448 11599 8448 11600 8432 11600 8429 11600 8427 11601 8445 11601 8430 11601 8430 11602 8445 11602 8446 11602 8430 11603 8446 11603 8431 11603 8428 11604 8431 11604 8437 11604 8428 11605 8437 11605 8429 11605 8429 8646 8437 8646 8448 8646 8449 11606 8450 11606 8461 11606 8461 11607 8450 11607 8462 11607 8463 11608 8449 11608 8461 11608 8464 11609 8455 11609 8465 11609 8467 11610 8454 11610 8468 11610 8468 11611 8454 11611 8453 11611 8435 11612 8442 11612 8446 11612 8448 11613 8437 11613 8469 11613 8469 11614 8437 11614 8441 11614 8469 11615 8441 11615 8470 11615 8470 11616 8441 11616 8435 11616 8470 11617 8435 11617 8446 11617 8448 324 8469 324 8472 324 8471 324 8447 324 8473 324 8472 324 8474 324 8448 324 8448 11618 8474 11618 8475 11618 8448 11619 8475 11619 8447 11619 8447 11620 8475 11620 8476 11620 8447 11621 8476 11621 8473 11621 8462 11622 8450 11622 8463 11622 8463 11611 8450 11611 8449 11611 8455 11623 8456 11623 8465 11623 8465 11624 8456 11624 8466 11624 8468 11625 8453 11625 8477 11625 8451 11623 8452 11623 8478 11623 8478 11626 8452 11626 8459 11626 8479 11627 8451 11627 8478 11627 8440 11628 8447 11628 8438 11628 8438 11629 8447 11629 8471 11629 8438 11630 8471 11630 8443 11630 8445 8507 8444 8507 8480 8507 8480 11631 8444 11631 8443 11631 8480 11632 8443 11632 8471 11632 8457 11606 8458 11606 8481 11606 8481 11633 8458 11633 8460 11633 8482 11634 8457 11634 8481 11634 8470 11635 8446 11635 8480 11635 8445 11636 8480 11636 8446 11636 8459 11637 8452 11637 8479 11637 8479 11638 8452 11638 8451 11638 8453 11639 8454 11639 8477 11639 8477 11640 8454 11640 8467 11640 8466 11641 8456 11641 8464 11641 8464 11638 8456 11638 8455 11638 8460 11642 8458 11642 8482 11642 8482 11643 8458 11643 8457 11643 8484 11644 8483 11644 8486 11644 8486 11638 8483 11638 8485 11638 8459 8646 8470 8646 8460 8646 8459 8646 8460 8646 8478 8646 8478 11645 8460 11645 8472 11645 8478 8646 8472 8646 8479 8646 8479 8646 8472 8646 8469 8646 8479 11646 8469 11646 8459 11646 8459 11647 8469 11647 8470 11647 8460 11648 8467 11648 8481 11648 8481 11649 8467 11649 8474 11649 8481 11650 8474 11650 8482 11650 8482 11651 8474 11651 8472 11651 8482 11652 8472 11652 8460 11652 8467 11653 8466 11653 8477 11653 8477 11654 8466 11654 8475 11654 8477 8646 8475 8646 8468 8646 8468 8646 8475 8646 8474 8646 8468 11655 8474 11655 8467 11655 8466 11656 8484 11656 8465 11656 8465 11657 8484 11657 8476 11657 8465 8646 8476 8646 8464 8646 8464 8646 8476 8646 8475 8646 8464 11655 8475 11655 8466 11655 8484 11653 8462 11653 8487 11653 8487 11649 8462 11649 8473 11649 8487 8646 8473 8646 8486 8646 8486 8646 8473 8646 8476 8646 8486 11655 8476 11655 8484 11655 8471 11658 8473 11658 8463 11658 8463 11659 8473 11659 8462 11659 8463 11660 8461 11660 8471 11660 8471 11661 8461 11661 8462 11661 8471 11662 8462 11662 8480 11662 8460 11663 8470 11663 8467 11663 8467 11664 8470 11664 8480 11664 8467 8646 8480 8646 8466 8646 8466 8646 8480 8646 8484 8646 8484 8646 8480 8646 8462 8646 8485 11623 8483 11623 8487 11623 8487 11665 8483 11665 8484 11665 8486 11666 8485 11666 8487 11666 8488 348 8489 348 8490 348 8490 348 8489 348 8491 348 8492 324 8493 324 8494 324 8494 324 8493 324 8495 324 8491 8511 8495 8511 8490 8511 8490 8511 8495 8511 8493 8511 8490 8505 8493 8505 8488 8505 8488 8505 8493 8505 8492 8505 8488 8507 8492 8507 8489 8507 8489 8507 8492 8507 8494 8507 8489 8646 8494 8646 8491 8646 8491 8646 8494 8646 8495 8646 8496 348 8497 348 8498 348 8498 348 8497 348 8499 348 8500 324 8501 324 8502 324 8502 324 8501 324 8503 324 8499 8646 8503 8646 8498 8646 8498 8646 8503 8646 8501 8646 8498 11667 8501 11667 8496 11667 8496 11668 8501 11668 8500 11668 8496 8505 8500 8505 8497 8505 8497 8505 8500 8505 8502 8505 8497 8507 8502 8507 8499 8507 8499 8507 8502 8507 8503 8507 8504 348 8505 348 8506 348 8506 348 8505 348 8507 348 8508 324 8509 324 8510 324 8510 324 8509 324 8511 324 8507 8507 8511 8507 8506 8507 8506 8507 8511 8507 8509 8507 8506 8646 8509 8646 8504 8646 8504 8646 8509 8646 8508 8646 8504 8511 8508 8511 8505 8511 8505 8511 8508 8511 8510 8511 8505 8505 8510 8505 8507 8505 8507 8505 8510 8505 8511 8505 8512 348 8513 348 8514 348 8514 348 8513 348 8515 348 8516 324 8517 324 8518 324 8518 324 8517 324 8519 324 8515 8646 8519 8646 8514 8646 8514 8646 8519 8646 8517 8646 8514 8511 8517 8511 8512 8511 8512 8511 8517 8511 8516 8511 8512 11669 8516 11669 8513 11669 8513 11670 8516 11670 8518 11670 8513 8507 8518 8507 8515 8507 8515 8507 8518 8507 8519 8507 8520 348 8521 348 8522 348 8522 11671 8521 11671 8523 11671 8524 324 8525 324 8526 324 8526 11672 8525 11672 8527 11672 8523 8646 8527 8646 8522 8646 8522 8646 8527 8646 8525 8646 8522 8511 8525 8511 8520 8511 8520 8511 8525 8511 8524 8511 8520 8505 8524 8505 8521 8505 8521 8505 8524 8505 8526 8505 8521 11673 8526 11673 8523 11673 8523 11674 8526 11674 8527 11674 8528 348 8529 348 8530 348 8530 348 8529 348 8531 348 8532 324 8533 324 8534 324 8534 324 8533 324 8535 324 8531 8646 8535 8646 8530 8646 8530 8646 8535 8646 8533 8646 8530 8511 8533 8511 8528 8511 8528 8511 8533 8511 8532 8511 8528 8505 8532 8505 8529 8505 8529 8505 8532 8505 8534 8505 8529 8507 8534 8507 8531 8507 8531 8507 8534 8507 8535 8507 8536 348 8537 348 8538 348 8538 348 8537 348 8539 348 8540 324 8541 324 8542 324 8542 324 8541 324 8543 324 8539 8646 8543 8646 8538 8646 8538 8646 8543 8646 8541 8646 8538 8511 8541 8511 8536 8511 8536 8511 8541 8511 8540 8511 8536 8505 8540 8505 8537 8505 8537 8505 8540 8505 8542 8505 8537 8507 8542 8507 8539 8507 8539 8507 8542 8507 8543 8507 8544 348 8545 348 8546 348 8546 11675 8545 11675 8547 11675 8548 324 8549 324 8550 324 8550 324 8549 324 8551 324 8547 8646 8551 8646 8546 8646 8546 8646 8551 8646 8549 8646 8546 8511 8549 8511 8544 8511 8544 8511 8549 8511 8548 8511 8544 8505 8548 8505 8545 8505 8545 8505 8548 8505 8550 8505 8545 11676 8550 11676 8547 11676 8547 11677 8550 11677 8551 11677 8552 348 8553 348 8554 348 8554 348 8553 348 8555 348 8556 324 8557 324 8558 324 8558 324 8557 324 8559 324 8555 8646 8559 8646 8554 8646 8554 8646 8559 8646 8557 8646 8554 8511 8557 8511 8552 8511 8552 8511 8557 8511 8556 8511 8552 8505 8556 8505 8553 8505 8553 8505 8556 8505 8558 8505 8553 8507 8558 8507 8555 8507 8555 8507 8558 8507 8559 8507 8560 348 8561 348 8562 348 8562 348 8561 348 8563 348 8564 324 8565 324 8566 324 8566 324 8565 324 8567 324 8563 8511 8567 8511 8562 8511 8562 8511 8567 8511 8565 8511 8562 8505 8565 8505 8560 8505 8560 8505 8565 8505 8564 8505 8560 8507 8564 8507 8561 8507 8561 8507 8564 8507 8566 8507 8561 8646 8566 8646 8563 8646 8563 8646 8566 8646 8567 8646 8568 348 8569 348 8570 348 8570 348 8569 348 8571 348 8572 324 8573 324 8574 324 8574 11678 8573 11678 8575 11678 8571 11679 8575 11679 8570 11679 8570 11679 8575 11679 8573 11679 8570 11680 8573 11680 8568 11680 8568 11681 8573 11681 8572 11681 8568 8507 8572 8507 8569 8507 8569 8507 8572 8507 8574 8507 8569 11682 8574 11682 8571 11682 8571 8646 8574 8646 8575 8646 8576 348 8577 348 8578 348 8578 348 8577 348 8579 348 8580 324 8581 324 8582 324 8582 324 8581 324 8583 324 8579 8646 8583 8646 8578 8646 8578 8646 8583 8646 8581 8646 8578 8511 8581 8511 8576 8511 8576 8511 8581 8511 8580 8511 8576 8505 8580 8505 8577 8505 8577 8505 8580 8505 8582 8505 8577 8507 8582 8507 8579 8507 8579 8507 8582 8507 8583 8507 8584 11683 8585 11683 8586 11683 8586 348 8585 348 8587 348 8588 324 8589 324 8590 324 8590 324 8589 324 8591 324 8587 8507 8585 8507 8591 8507 8591 8507 8585 8507 8590 8507 8585 8505 8584 8505 8590 8505 8590 8505 8584 8505 8588 8505 8584 11684 8586 11684 8588 11684 8588 11685 8586 11685 8589 11685 8586 8646 8587 8646 8589 8646 8589 8646 8587 8646 8591 8646 8592 348 8593 348 8594 348 8594 11686 8593 11686 8595 11686 8596 324 8597 324 8598 324 8598 324 8597 324 8599 324 8595 8646 8599 8646 8594 8646 8594 8646 8599 8646 8597 8646 8594 8511 8597 8511 8592 8511 8592 8511 8597 8511 8596 8511 8592 8505 8596 8505 8593 8505 8593 8505 8596 8505 8598 8505 8593 11687 8598 11687 8595 11687 8595 11688 8598 11688 8599 11688 8600 348 8601 348 8602 348 8602 348 8601 348 8603 348 8604 324 8605 324 8606 324 8606 11689 8605 11689 8607 11689 8603 11690 8607 11690 8602 11690 8602 11691 8607 11691 8605 11691 8602 8505 8605 8505 8600 8505 8600 8505 8605 8505 8604 8505 8600 11692 8604 11692 8601 11692 8601 11693 8604 11693 8606 11693 8601 8646 8606 8646 8603 8646 8603 8646 8606 8646 8607 8646 8608 348 8609 348 8610 348 8610 348 8609 348 8611 348 8612 324 8613 324 8614 324 8614 324 8613 324 8615 324 8611 8646 8615 8646 8610 8646 8610 8646 8615 8646 8613 8646 8610 8511 8613 8511 8608 8511 8608 8511 8613 8511 8612 8511 8608 8505 8612 8505 8609 8505 8609 8505 8612 8505 8614 8505 8609 8507 8614 8507 8611 8507 8611 8507 8614 8507 8615 8507 8616 348 8617 348 8618 348 8618 348 8617 348 8619 348 8620 324 8621 324 8622 324 8622 324 8621 324 8623 324 8619 8646 8623 8646 8618 8646 8618 8646 8623 8646 8621 8646 8618 8511 8621 8511 8616 8511 8616 8511 8621 8511 8620 8511 8616 8505 8620 8505 8617 8505 8617 8505 8620 8505 8622 8505 8617 8507 8622 8507 8619 8507 8619 8507 8622 8507 8623 8507 8624 348 8625 348 8626 348 8626 348 8625 348 8627 348 8628 324 8629 324 8630 324 8630 324 8629 324 8631 324 8627 8646 8631 8646 8626 8646 8626 8646 8631 8646 8629 8646 8626 8511 8629 8511 8624 8511 8624 8511 8629 8511 8628 8511 8624 8505 8628 8505 8625 8505 8625 8505 8628 8505 8630 8505 8625 8507 8630 8507 8627 8507 8627 8507 8630 8507 8631 8507 8632 348 8633 348 8634 348 8634 348 8633 348 8635 348 8636 324 8637 324 8638 324 8638 324 8637 324 8639 324 8635 8511 8639 8511 8634 8511 8634 8511 8639 8511 8637 8511 8634 8505 8637 8505 8632 8505 8632 8505 8637 8505 8636 8505 8632 8507 8636 8507 8633 8507 8633 8507 8636 8507 8638 8507 8633 8646 8638 8646 8635 8646 8635 8646 8638 8646 8639 8646 8640 348 8641 348 8642 348 8642 348 8641 348 8643 348 8644 324 8645 324 8646 324 8646 324 8645 324 8647 324 8643 8511 8647 8511 8642 8511 8642 8511 8647 8511 8645 8511 8642 8505 8645 8505 8640 8505 8640 8505 8645 8505 8644 8505 8640 8507 8644 8507 8641 8507 8641 8507 8644 8507 8646 8507 8641 8646 8646 8646 8643 8646 8643 11682 8646 11682 8647 11682 8648 348 8649 348 8650 348 8650 348 8649 348 8651 348 8652 324 8653 324 8654 324 8654 324 8653 324 8655 324 8651 8511 8655 8511 8650 8511 8650 8511 8655 8511 8653 8511 8650 8505 8653 8505 8648 8505 8648 8505 8653 8505 8652 8505 8648 8507 8652 8507 8649 8507 8649 8507 8652 8507 8654 8507 8649 8646 8654 8646 8651 8646 8651 8646 8654 8646 8655 8646 8656 348 8657 348 8658 348 8658 11694 8657 11694 8659 11694 8660 11695 8661 11695 8662 11695 8662 324 8661 324 8663 324 8659 8646 8663 8646 8658 8646 8658 8646 8663 8646 8661 8646 8658 11696 8661 11696 8656 11696 8656 11696 8661 11696 8660 11696 8656 8505 8660 8505 8657 8505 8657 8505 8660 8505 8662 8505 8657 11697 8662 11697 8659 11697 8659 11697 8662 11697 8663 11697 8664 348 8665 348 8666 348 8666 348 8665 348 8667 348 8668 324 8669 324 8670 324 8670 324 8669 324 8671 324 8667 8646 8671 8646 8666 8646 8666 8646 8671 8646 8669 8646 8666 8511 8669 8511 8664 8511 8664 8511 8669 8511 8668 8511 8664 8505 8668 8505 8665 8505 8665 8505 8668 8505 8670 8505 8665 8507 8670 8507 8667 8507 8667 8507 8670 8507 8671 8507 8672 348 8673 348 8674 348 8674 348 8673 348 8675 348 8676 324 8677 324 8678 324 8678 324 8677 324 8679 324 8675 8646 8679 8646 8674 8646 8674 8646 8679 8646 8677 8646 8674 8511 8677 8511 8672 8511 8672 8511 8677 8511 8676 8511 8672 8505 8676 8505 8673 8505 8673 11698 8676 11698 8678 11698 8673 8507 8678 8507 8675 8507 8675 8507 8678 8507 8679 8507 8680 348 8681 348 8682 348 8682 348 8681 348 8683 348 8684 324 8685 324 8686 324 8686 324 8685 324 8687 324 8683 8646 8687 8646 8682 8646 8682 8646 8687 8646 8685 8646 8682 8511 8685 8511 8680 8511 8680 8511 8685 8511 8684 8511 8680 8505 8684 8505 8681 8505 8681 8505 8684 8505 8686 8505 8681 8507 8686 8507 8683 8507 8683 8507 8686 8507 8687 8507 8688 348 8689 348 8690 348 8690 348 8689 348 8691 348 8692 324 8693 324 8694 324 8694 324 8693 324 8695 324 8691 8646 8695 8646 8690 8646 8690 8646 8695 8646 8693 8646 8690 8511 8693 8511 8688 8511 8688 8511 8693 8511 8692 8511 8688 8505 8692 8505 8689 8505 8689 8505 8692 8505 8694 8505 8689 8507 8694 8507 8691 8507 8691 8507 8694 8507 8695 8507 8696 348 8697 348 8698 348 8698 348 8697 348 8699 348 8700 324 8701 324 8702 324 8702 324 8701 324 8703 324 8699 8646 8703 8646 8698 8646 8698 8646 8703 8646 8701 8646 8698 8511 8701 8511 8696 8511 8696 8511 8701 8511 8700 8511 8696 8505 8700 8505 8697 8505 8697 8505 8700 8505 8702 8505 8697 8507 8702 8507 8699 8507 8699 8507 8702 8507 8703 8507 8704 348 8705 348 8706 348 8706 348 8705 348 8707 348 8708 324 8709 324 8710 324 8710 324 8709 324 8711 324 8707 8646 8711 8646 8706 8646 8706 8646 8711 8646 8709 8646 8706 8511 8709 8511 8704 8511 8704 8511 8709 8511 8708 8511 8704 8505 8708 8505 8705 8505 8705 11670 8708 11670 8710 11670 8705 8507 8710 8507 8707 8507 8707 8507 8710 8507 8711 8507 8712 348 8713 348 8714 348 8714 348 8713 348 8715 348 8716 324 8717 324 8718 324 8718 324 8717 324 8719 324 8715 8511 8719 8511 8714 8511 8714 8511 8719 8511 8717 8511 8714 8505 8717 8505 8712 8505 8712 8505 8717 8505 8716 8505 8712 8507 8716 8507 8713 8507 8713 8507 8716 8507 8718 8507 8713 8646 8718 8646 8715 8646 8715 8646 8718 8646 8719 8646 8720 348 8721 348 8722 348 8722 348 8721 348 8723 348 8724 324 8725 324 8726 324 8726 324 8725 324 8727 324 8723 8511 8727 8511 8722 8511 8722 8511 8727 8511 8725 8511 8722 8505 8725 8505 8720 8505 8720 8505 8725 8505 8724 8505 8720 8507 8724 8507 8721 8507 8721 8507 8724 8507 8726 8507 8721 8646 8726 8646 8723 8646 8723 8646 8726 8646 8727 8646 8728 348 8729 348 8730 348 8730 348 8729 348 8731 348 8732 324 8733 324 8734 324 8734 324 8733 324 8735 324 8731 8511 8735 8511 8730 8511 8730 8511 8735 8511 8733 8511 8730 8505 8733 8505 8728 8505 8728 8505 8733 8505 8732 8505 8728 8507 8732 8507 8729 8507 8729 8507 8732 8507 8734 8507 8729 8646 8734 8646 8731 8646 8731 8646 8734 8646 8735 8646 8736 348 8737 348 8738 348 8738 11699 8737 11699 8739 11699 8740 324 8741 324 8742 324 8742 11700 8741 11700 8743 11700 8739 11701 8743 11701 8738 11701 8738 11702 8743 11702 8741 11702 8738 8505 8741 8505 8736 8505 8736 8505 8741 8505 8740 8505 8736 8507 8740 8507 8737 8507 8737 8507 8740 8507 8742 8507 8737 8646 8742 8646 8739 8646 8739 8646 8742 8646 8743 8646 8744 348 8745 348 8746 348 8746 348 8745 348 8747 348 8748 324 8749 324 8750 324 8750 324 8749 324 8751 324 8747 8511 8751 8511 8746 8511 8746 8511 8751 8511 8749 8511 8746 8505 8749 8505 8744 8505 8744 8505 8749 8505 8748 8505 8744 8507 8748 8507 8745 8507 8745 8507 8748 8507 8750 8507 8745 8646 8750 8646 8747 8646 8747 8646 8750 8646 8751 8646 8752 348 8753 348 8754 348 8754 348 8753 348 8755 348 8756 324 8757 324 8758 324 8758 324 8757 324 8759 324 8755 8646 8759 8646 8754 8646 8754 8646 8759 8646 8757 8646 8754 8511 8757 8511 8752 8511 8752 8511 8757 8511 8756 8511 8752 8505 8756 8505 8753 8505 8753 8505 8756 8505 8758 8505 8753 8507 8758 8507 8755 8507 8755 8507 8758 8507 8759 8507 8760 348 8761 348 8762 348 8762 348 8761 348 8763 348 8764 324 8765 324 8766 324 8766 324 8765 324 8767 324 8763 8646 8767 8646 8762 8646 8762 8646 8767 8646 8765 8646 8762 8511 8765 8511 8760 8511 8760 8511 8765 8511 8764 8511 8760 8505 8764 8505 8761 8505 8761 8505 8764 8505 8766 8505 8761 8507 8766 8507 8763 8507 8763 8507 8766 8507 8767 8507 8768 348 8769 348 8770 348 8770 348 8769 348 8771 348 8772 324 8773 324 8774 324 8774 324 8773 324 8775 324 8771 8646 8775 8646 8770 8646 8770 11703 8775 11703 8773 11703 8770 8511 8773 8511 8768 8511 8768 8511 8773 8511 8772 8511 8768 8505 8772 8505 8769 8505 8769 8505 8772 8505 8774 8505 8769 8507 8774 8507 8771 8507 8771 8507 8774 8507 8775 8507 8776 348 8777 348 8778 348 8778 348 8777 348 8779 348 8780 324 8781 324 8782 324 8782 324 8781 324 8783 324 8779 8646 8783 8646 8778 8646 8778 8646 8783 8646 8781 8646 8778 8511 8781 8511 8776 8511 8776 8511 8781 8511 8780 8511 8776 8505 8780 8505 8777 8505 8777 8505 8780 8505 8782 8505 8777 8507 8782 8507 8779 8507 8779 8507 8782 8507 8783 8507 8784 348 8785 348 8786 348 8786 348 8785 348 8787 348 8788 324 8789 324 8790 324 8790 324 8789 324 8791 324 8787 8511 8791 8511 8786 8511 8786 8511 8791 8511 8789 8511 8786 11704 8789 11704 8784 11704 8784 8505 8789 8505 8788 8505 8784 8507 8788 8507 8785 8507 8785 8507 8788 8507 8790 8507 8785 8646 8790 8646 8787 8646 8787 8646 8790 8646 8791 8646 8792 11705 8793 11705 8794 11705 8797 348 8798 348 8850 348 8802 348 8803 348 8804 348 8807 348 8808 348 8809 348 8810 348 8811 348 8794 348 8817 11706 8796 11706 8795 11706 8820 11707 8821 11707 8822 11707 8823 11708 8824 11708 8825 11708 8834 11709 8835 11709 8836 11709 8836 348 8835 348 8837 348 8838 348 8834 348 8836 348 8838 348 8836 348 8839 348 8826 348 8840 348 8842 348 8828 348 8845 348 8846 348 8846 348 8845 348 8847 348 8848 348 8849 348 8847 348 8847 348 8849 348 8846 348 8827 348 8851 348 8872 348 8854 348 8855 348 8856 348 8858 348 8859 348 8857 348 8855 348 8858 348 8856 348 8856 11710 8858 11710 8857 11710 8859 11711 8855 11711 8860 11711 8854 348 8860 348 8855 348 8857 348 8861 348 8856 348 8865 348 8866 348 8860 348 8864 11712 8867 11712 8868 11712 8860 11713 8866 11713 8867 11713 8867 11714 8864 11714 8857 11714 8867 348 8857 348 8860 348 8860 348 8857 348 8859 348 8864 11715 8868 11715 8869 11715 8864 348 8869 348 8863 348 8866 348 8865 348 8869 348 8871 348 8870 348 8852 348 8849 348 8848 348 8827 348 8827 348 8848 348 8871 348 8827 11716 8871 11716 8852 11716 8827 348 8852 348 8831 348 8831 348 8852 348 8874 348 8831 348 8874 348 8830 348 8830 348 8874 348 8875 348 8876 348 8852 348 8870 348 8876 348 8870 348 8875 348 8821 11717 8825 11717 8878 11717 8820 11718 8822 11718 8879 11718 8880 11719 8834 11719 8881 11719 8882 11720 8881 11720 8883 11720 8882 11721 8883 11721 8884 11721 8821 11722 8820 11722 8885 11722 8885 11723 8820 11723 8886 11723 8885 11724 8886 11724 8887 11724 8822 11725 8834 11725 8879 11725 8879 11726 8834 11726 8880 11726 8879 11727 8880 11727 8887 11727 8887 11728 8880 11728 8884 11728 8887 11729 8884 11729 8885 11729 8885 11730 8884 11730 8883 11730 8888 11731 8818 11731 8883 11731 8888 11732 8883 11732 8889 11732 8890 348 8891 348 8892 348 8892 348 8891 348 8893 348 8892 348 8893 348 8894 348 8894 348 8893 348 8895 348 8795 11733 8896 11733 8817 11733 8890 348 8897 348 8891 348 8891 11734 8897 11734 8896 11734 8891 11735 8896 11735 8898 11735 8902 11736 8901 11736 8903 11736 8818 11737 8904 11737 8905 11737 8905 11738 8904 11738 8816 11738 8907 11739 8906 11739 8908 11739 8910 11740 8899 11740 8905 11740 8911 348 8906 348 8912 348 8899 348 8910 348 8900 348 8900 11741 8910 11741 8913 11741 8900 11742 8913 11742 8909 11742 8909 11743 8913 11743 8914 11743 8914 11744 8913 11744 8912 11744 8914 348 8912 348 8915 348 8900 348 8916 348 8899 348 8899 348 8916 348 8903 348 8903 348 8916 348 8902 348 8900 11745 8917 11745 8902 11745 8918 11746 8902 11746 8917 11746 8920 348 8919 348 8921 348 8902 11747 8918 11747 8922 11747 8920 11748 8922 11748 8919 11748 8919 348 8923 348 8921 348 8917 11749 8923 11749 8918 11749 8900 348 8909 348 8917 348 8909 348 8924 348 8917 348 8924 348 8915 348 8925 348 8925 11750 8928 11750 8926 11750 8923 11751 8917 11751 8921 11751 8917 11752 8929 11752 8921 11752 8921 11753 8929 11753 8930 11753 8930 348 8929 348 8927 348 8927 11754 8929 11754 8928 11754 9181 11755 8931 11755 8932 11755 8912 11756 8933 11756 8934 11756 8912 348 8934 348 8915 348 8933 348 8912 348 8906 348 8933 348 8906 348 8932 348 9181 11757 8938 11757 8935 11757 9181 11758 8935 11758 8931 11758 8931 348 8935 348 8934 348 8934 348 8935 348 8936 348 8934 348 8936 348 8915 348 8915 11759 8936 11759 8937 11759 8915 348 8937 348 8925 348 8925 348 8937 348 8938 348 8925 11760 8938 11760 9181 11760 8925 348 9181 348 8939 348 8940 11761 8941 11761 9181 11761 9181 11762 8941 11762 8939 11762 8928 11763 8925 11763 8942 11763 8928 348 8942 348 8927 348 8927 348 8942 348 8940 348 8940 11764 8942 11764 8941 11764 8943 11765 8815 11765 8944 11765 8944 11766 8815 11766 8921 11766 8814 348 8815 348 8945 348 8927 348 8947 348 8930 348 8946 11767 8950 11767 8927 11767 8927 11768 8950 11768 8948 11768 8927 11769 8948 11769 8947 11769 8945 348 8815 348 8943 348 8945 11770 8943 11770 8949 11770 8949 11771 8943 11771 8950 11771 8949 11772 8950 11772 8946 11772 8944 11773 8921 11773 8951 11773 8944 11774 8951 11774 8948 11774 8948 11775 8951 11775 8947 11775 8952 348 8953 348 8921 348 8954 348 8952 348 8921 348 8954 11776 8921 11776 8955 11776 8955 11777 8921 11777 8815 11777 8956 348 8957 348 8958 348 8957 348 8956 348 8920 348 8957 348 8920 348 8959 348 8952 11778 8954 11778 8957 11778 8957 348 8954 348 8958 348 8921 11779 8960 11779 8920 11779 8920 11780 8960 11780 8961 11780 8920 348 8961 348 8962 348 8920 348 8962 348 8959 348 8960 11781 8921 11781 8963 11781 8963 348 8921 348 8953 348 8963 348 8953 348 8962 348 8962 348 8953 348 8959 348 8965 348 8964 348 8966 348 8966 11782 8964 11782 8815 11782 8956 348 8967 348 8965 348 8967 11783 8956 11783 8815 11783 8815 11784 8956 11784 8955 11784 8968 11785 8940 11785 8969 11785 8968 11786 8969 11786 8970 11786 8972 348 8973 348 8940 348 8971 11787 8946 11787 8974 11787 8971 348 8974 348 8968 348 8968 348 8974 348 8975 348 8968 348 8975 348 8940 348 8940 11788 8975 11788 8976 11788 8977 11789 8978 11789 8927 11789 8974 11790 8946 11790 8927 11790 8974 348 8927 348 8979 348 8979 11791 8927 11791 8978 11791 8940 348 8973 348 8927 348 8927 11792 8973 11792 8977 11792 8972 348 8940 348 8976 348 8972 11793 8976 11793 8978 11793 8978 11794 8976 11794 8979 11794 8799 348 8980 348 8969 348 8969 11795 8980 11795 8981 11795 8946 11796 8982 11796 8799 11796 8799 348 8982 348 8980 348 8969 11797 8981 11797 8983 11797 8969 11798 8983 11798 8970 11798 8971 348 8984 348 8946 348 8946 11799 8984 11799 8982 11799 8982 348 8984 348 8983 348 8983 11800 8984 11800 8970 11800 8988 11801 8966 11801 8815 11801 8986 348 8985 348 8966 348 8986 348 8966 348 8988 348 8799 11802 8985 11802 8946 11802 8946 11803 8985 11803 8987 11803 8946 11804 8987 11804 8814 11804 8814 348 8987 348 8988 348 8814 11805 8988 11805 8815 11805 8965 11806 8966 11806 8989 11806 8965 348 8989 348 8990 348 8993 348 8966 348 8985 348 8994 11807 8990 11807 8995 11807 8994 348 8995 348 8991 348 8991 348 8995 348 8996 348 8991 348 8996 348 8992 348 8997 11808 8998 11808 8999 11808 8997 11809 8999 11809 9000 11809 8998 348 8997 348 9001 348 8998 11810 9001 11810 9002 11810 9003 348 9007 348 9004 348 9004 348 9007 348 9000 348 9004 11811 9000 11811 8999 11811 9002 11812 9003 11812 9005 11812 9005 11813 9003 11813 9006 11813 9001 11814 9007 11814 9002 11814 9002 11815 9007 11815 9003 11815 9005 11816 9010 11816 8804 11816 9005 11817 9006 11817 9010 11817 9010 11818 9006 11818 9011 11818 9011 11819 9006 11819 9009 11819 9011 348 9009 348 9008 348 9008 11820 9009 11820 8999 11820 8999 11821 9012 11821 9013 11821 9014 348 8998 348 9015 348 9015 348 8998 348 9016 348 9017 11822 9020 11822 9016 11822 9016 11823 9020 11823 9015 11823 9017 11824 9018 11824 9020 11824 8998 11825 9014 11825 8999 11825 8999 11826 9014 11826 9019 11826 8999 11827 9019 11827 9012 11827 9012 348 9019 348 9018 348 9018 348 9019 348 9020 348 9021 348 9022 348 9008 348 8813 11828 8812 11828 9017 11828 9017 11829 8812 11829 9023 11829 9008 11830 8999 11830 9021 11830 9008 348 9022 348 8813 348 8813 11831 9022 11831 8812 11831 8999 11832 9013 11832 9021 11832 9021 11833 9013 11833 9023 11833 9023 11834 9013 11834 9024 11834 9023 11835 9024 11835 9017 11835 9025 348 9026 348 9027 348 9028 11836 9029 11836 9030 11836 9030 348 9029 348 9027 348 9030 348 9027 348 9026 348 9032 348 9031 348 9028 348 9028 11837 9031 11837 9029 11837 9026 348 9025 348 9032 348 9029 11838 9033 11838 8794 11838 8794 11839 9033 11839 8810 11839 9188 11840 9034 11840 9035 11840 9188 11841 9035 11841 9036 11841 9188 11842 9036 11842 9037 11842 9036 348 9039 348 9037 348 9037 11843 9039 11843 9038 11843 9038 348 9039 348 8811 348 8811 348 9039 348 9034 348 9040 11844 9038 11844 9029 11844 9029 348 9038 348 9033 348 9029 11845 9031 11845 9040 11845 9042 11846 9041 11846 9037 11846 9042 11847 9037 11847 9038 11847 9042 348 9038 348 9040 348 9037 11848 9044 11848 9043 11848 9042 348 8809 348 9041 348 9041 11849 8809 11849 9044 11849 9047 348 9046 348 9031 348 9031 348 9046 348 8807 348 8809 348 9031 348 8807 348 9044 11850 9048 11850 9049 11850 9044 348 9049 348 9050 348 9050 348 9049 348 9051 348 9044 348 8809 348 9048 348 9048 11851 8809 11851 8808 11851 9050 11852 9051 11852 9052 11852 9045 348 9052 348 8808 348 8808 348 9052 348 9048 348 9053 11844 9045 11844 9047 11844 9047 348 9045 348 9046 348 9055 348 9054 348 9047 348 9047 348 9054 348 9053 348 9050 11853 9056 11853 9057 11853 9050 11854 9057 11854 9058 11854 9058 11855 9057 11855 9059 11855 9058 11856 9059 11856 9060 11856 9060 348 9059 348 9061 348 9045 11857 9056 11857 9050 11857 9045 348 9050 348 9052 348 9045 348 9053 348 9062 348 9045 11858 9062 11858 9056 11858 9056 348 9062 348 9061 348 9061 348 9062 348 9060 348 8805 348 9063 348 9064 348 9064 11859 9063 11859 9065 11859 9064 348 9065 348 9066 348 9068 348 9067 348 9069 348 9068 348 9069 348 9065 348 9065 11860 9069 11860 9066 11860 9071 348 9070 348 9067 348 9072 348 9073 348 9074 348 9055 348 9060 348 9054 348 9074 348 9073 348 9055 348 9058 348 9060 348 9077 348 9055 348 9079 348 9060 348 9060 348 9079 348 9077 348 9077 348 9079 348 9075 348 9075 348 9079 348 9072 348 9075 348 9072 348 9076 348 9071 11861 8806 11861 9070 11861 9074 348 9076 348 9072 348 9071 11862 9080 11862 8806 11862 8806 11863 9080 11863 9074 11863 9074 11864 9080 11864 9076 11864 9078 11865 9081 11865 9082 11865 9085 348 9083 348 9084 348 9084 11866 9083 11866 9071 11866 9078 348 9075 348 9076 348 9078 11867 9076 11867 9081 11867 9078 11868 9082 11868 9085 11868 9078 11869 9085 11869 9084 11869 9076 348 9086 348 9081 348 9081 11870 9086 11870 9083 11870 9083 11871 9086 11871 9071 11871 9087 11872 9088 11872 9089 11872 9090 348 9002 348 9091 348 9092 11873 9005 11873 9093 11873 9091 348 9002 348 9005 348 9091 348 9005 348 9095 348 9095 348 9005 348 9092 348 9002 11874 9090 11874 9087 11874 9087 11875 9090 11875 9094 11875 9087 11876 9094 11876 9088 11876 9088 348 9094 348 9092 348 9092 348 9094 348 9095 348 8804 348 8803 348 9005 348 9087 11877 9096 11877 9097 11877 9097 11878 9096 11878 9098 11878 9097 348 9098 348 8804 348 8804 11879 9098 11879 8802 11879 9087 11880 9089 11880 9096 11880 9096 11881 9089 11881 8803 11881 8803 11882 9089 11882 9099 11882 8803 348 9099 348 9005 348 9005 11883 9099 11883 9093 11883 9100 11884 9002 11884 9101 11884 9101 11885 9002 11885 9087 11885 9002 11886 9100 11886 9102 11886 9102 11887 9100 11887 9103 11887 9102 11888 9104 11888 9119 11888 9119 11889 9104 11889 9111 11889 9102 11890 9103 11890 9105 11890 9102 11891 9105 11891 9104 11891 9104 348 9105 348 9106 348 9106 11892 9105 11892 9101 11892 9106 11893 9101 11893 9087 11893 9119 11894 9107 11894 9108 11894 9119 11895 9108 11895 9097 11895 9097 11896 9108 11896 9110 11896 9097 11897 9110 11897 9087 11897 9087 11898 9110 11898 9109 11898 9109 11899 9110 11899 9111 11899 9111 11900 9110 11900 9107 11900 9111 11901 9107 11901 9119 11901 8860 348 9116 348 9112 348 9112 11902 9116 11902 9113 11902 9112 11903 9113 11903 9114 11903 9114 348 9115 348 8854 348 8854 11904 9115 11904 9116 11904 8854 348 9116 348 8860 348 9120 11905 9119 11905 9121 11905 9120 348 9121 348 8865 348 8865 348 9121 348 9117 348 9122 348 9102 348 9119 348 9122 11906 9119 11906 9123 11906 9122 348 9124 348 9102 348 9102 348 9124 348 9125 348 9125 348 9124 348 9126 348 9126 11907 9127 11907 9125 11907 9125 348 9127 348 9120 348 9120 11908 9127 11908 9128 11908 9120 348 9128 348 9129 348 9120 11909 9129 11909 9119 11909 9119 348 9129 348 9123 348 9016 348 9130 348 9131 348 9016 11910 9131 11910 9017 11910 9017 11911 9131 11911 9132 11911 9130 348 9016 348 9133 348 9130 11912 9133 11912 9134 11912 8800 348 9136 348 8801 348 8801 348 9136 348 9133 348 9133 11913 9136 11913 9137 11913 9133 11914 9137 11914 9135 11914 9133 348 9135 348 9134 348 9141 348 9138 348 9143 348 9139 348 8801 348 9140 348 8801 348 9139 348 8969 348 8801 348 8969 348 8800 348 8799 348 9142 348 8991 348 8991 11915 9142 11915 9143 11915 9140 348 8801 348 8991 348 9140 348 8991 348 9143 348 9140 348 9143 348 9138 348 8969 348 9139 348 9144 348 9141 348 8799 348 8969 348 9141 348 8969 348 9144 348 9141 11916 9144 11916 9138 11916 8992 11917 8993 11917 8991 11917 8991 11918 8993 11918 8985 11918 8991 348 8985 348 8799 348 9148 11919 9145 11919 9146 11919 9146 348 9145 348 9097 348 9147 348 9119 348 9097 348 9147 348 9097 348 9145 348 9119 11920 9147 11920 9148 11920 9097 11921 9151 11921 9150 11921 9097 11922 9150 11922 9146 11922 9149 11923 9151 11923 8804 11923 8804 11924 9151 11924 9097 11924 9149 348 8804 348 9146 348 9155 348 9152 348 9153 348 9153 11925 9152 11925 9008 11925 9154 11926 8804 11926 9008 11926 9154 11927 9008 11927 9152 11927 8804 11928 9154 11928 9155 11928 8804 348 9155 348 9146 348 9008 348 9157 348 9153 348 9153 11929 9157 11929 9158 11929 9156 348 9159 348 8813 348 8813 11930 9159 11930 9008 11930 9008 348 9159 348 9157 348 9156 348 8813 348 9153 348 8863 348 8869 348 8865 348 8863 11931 8865 11931 9117 11931 8863 11932 9117 11932 9118 11932 8862 11933 8863 11933 9118 11933 8926 11934 8917 11934 8924 11934 8926 348 8924 348 8925 348 9160 348 8861 348 8857 348 9160 348 8857 348 8862 348 9160 11935 8862 11935 9118 11935 9160 348 9118 348 9119 348 8905 11936 8816 11936 8906 11936 8905 11937 8906 11937 8911 11937 8905 11938 8911 11938 8910 11938 8932 348 8906 348 9162 348 8932 348 9162 348 9163 348 8932 348 9163 348 8907 348 9163 11939 9164 11939 8907 11939 9162 348 8906 348 9165 348 9165 348 8906 348 8907 348 8905 11940 8901 11940 9166 11940 8905 348 9166 348 9167 348 8905 11941 9167 11941 8818 11941 8818 11942 9167 11942 9168 11942 8901 348 9169 348 9166 348 9170 11943 9112 11943 9114 11943 9170 348 9171 348 9112 348 9171 348 9172 348 9112 348 9112 11944 9172 11944 9173 11944 9173 11945 9172 11945 9174 11945 9173 11946 9174 11946 9114 11946 9114 348 9174 348 9170 348 9173 11947 9176 11947 9177 11947 9178 11948 9112 11948 9173 11948 9178 348 9173 348 9177 348 9112 348 9178 348 8845 348 9178 348 9179 348 8845 348 8845 11949 9179 11949 9176 11949 9176 348 9173 348 8833 348 8854 348 9161 348 9114 348 9114 348 9161 348 9173 348 9173 348 9161 348 8832 348 9173 348 8832 348 8833 348 9175 348 9161 348 9160 348 9146 11950 9119 11950 9148 11950 8843 348 9160 348 9181 348 9181 348 9160 348 9119 348 9181 11951 9119 11951 9146 11951 9181 11952 9146 11952 9153 11952 9153 348 9158 348 9156 348 8847 348 8845 348 8870 348 8870 348 8845 348 8875 348 8875 348 8845 348 8833 348 8833 348 8845 348 9176 348 9180 348 9175 348 9160 348 9146 348 9150 348 9149 348 8853 11953 9175 11953 8841 11953 8853 11954 8841 11954 9182 11954 8853 348 9182 348 8851 348 8851 348 9182 348 9183 348 8851 11955 9183 11955 8872 11955 8872 11956 9183 11956 8826 11956 8826 11957 9183 11957 9184 11957 9153 11958 9146 11958 9155 11958 8842 348 9175 348 9188 348 8841 348 8840 348 9184 348 9184 348 8840 348 8826 348 9161 348 8861 348 9160 348 8969 348 9134 348 9135 348 8969 11959 9135 11959 8800 11959 8883 11960 8881 11960 8889 11960 8889 11961 8881 11961 8834 11961 8889 11962 8834 11962 8819 11962 8819 11963 8834 11963 8907 11963 8819 11964 8907 11964 8818 11964 8818 11965 8907 11965 8908 11965 8907 11966 9164 11966 9165 11966 9043 348 8826 348 8842 348 9043 11967 8842 11967 9188 11967 8830 348 8832 348 8831 348 8831 348 8832 348 9161 348 8831 348 9161 348 8853 348 8853 11968 9161 11968 9175 11968 9175 11969 9180 11969 9188 11969 9180 11970 8844 11970 9188 11970 8828 348 8850 348 8829 348 8849 348 8827 348 8850 348 8828 11971 8829 11971 8845 11971 8845 348 8829 348 9084 348 8850 348 8798 348 8829 348 8872 348 8873 348 8827 348 8827 348 8873 348 9058 348 8827 11972 9058 11972 8850 11972 8850 348 9058 348 8797 348 9132 11973 9134 11973 9017 11973 9017 11974 9134 11974 8969 11974 9017 11975 8969 11975 8813 11975 8813 11976 8969 11976 8940 11976 8813 348 8940 348 9153 348 9153 11977 8940 11977 9181 11977 9181 348 8932 348 8907 348 9181 348 8907 348 8843 348 8843 348 8907 348 8844 348 8844 11978 8907 11978 8839 11978 8844 11979 8839 11979 8836 11979 8844 348 8836 348 9188 348 9188 11980 8836 11980 8837 11980 8878 348 9186 348 8837 348 8837 348 9186 348 9188 348 9186 348 9187 348 9188 348 9188 11981 9187 11981 9185 11981 9188 11982 9037 11982 9043 11982 8873 11983 9043 11983 9044 11983 8873 348 9044 348 9050 348 8873 11984 9050 11984 9058 11984 9067 348 9068 348 9071 348 9071 11985 9068 11985 9084 11985 9084 348 9068 348 8845 348 8811 348 9034 348 8794 348 8794 11986 9034 11986 9188 11986 9078 11987 9084 11987 8797 11987 9078 348 8797 348 9058 348 8878 11988 8837 11988 8822 11988 8878 11989 8822 11989 8821 11989 9189 11990 8821 11990 8885 11990 9189 11991 8885 11991 9190 11991 9190 11992 8885 11992 8823 11992 9190 11993 8823 11993 8825 11993 8878 11994 8825 11994 8824 11994 8878 11995 8824 11995 8877 11995 8878 11996 8877 11996 8795 11996 8878 11997 8795 11997 8796 11997 8823 11998 8885 11998 8883 11998 8818 11999 8908 11999 8904 11999 8795 12000 8823 12000 8883 12000 9169 12001 8818 12001 9168 12001 8896 12002 8795 12002 8898 12002 8898 12003 8795 12003 8883 12003 8898 348 8883 348 9191 348 9191 12004 8883 12004 8818 12004 9191 12005 8818 12005 9169 12005 9191 12006 9169 12006 8901 12006 9191 12007 8901 12007 8902 12007 9191 12008 8902 12008 8922 12008 9191 12009 8922 12009 8920 12009 9191 12010 8920 12010 8956 12010 9191 348 8956 348 8994 348 8994 348 8956 348 8965 348 8994 348 8965 348 8990 348 8796 348 8895 348 8878 348 9074 12011 9192 12011 9193 12011 8806 12012 9194 12012 9063 12012 8806 348 9063 348 8805 348 9063 348 9194 348 9196 348 9063 12013 9196 12013 9195 12013 9195 348 9196 348 9192 348 9074 12014 9193 12014 8806 12014 8806 12015 9193 12015 9194 12015 9074 348 9197 348 9195 348 9074 12016 9195 12016 9192 12016 9195 12017 9197 12017 9198 12017 9195 12018 9198 12018 9199 12018 9199 12019 9198 12019 9200 12019 9199 12020 9200 12020 9055 12020 9055 12021 9200 12021 9074 12021 9047 12022 9201 12022 9202 12022 9047 348 9202 348 9055 348 9203 348 9199 348 9055 348 9203 348 9055 348 9202 348 9203 12023 9204 12023 9199 12023 9199 348 9204 348 9047 348 9047 12024 9204 12024 9201 12024 9031 348 9205 348 9047 348 9032 348 9025 348 9031 348 9031 12025 9025 12025 9206 12025 9031 12026 9206 12026 9205 12026 9207 348 9199 348 9047 348 9199 12027 9207 12027 9025 12027 9025 12028 9207 12028 9206 12028 8794 12029 8793 12029 9029 12029 9208 12030 9027 12030 9029 12030 8792 12031 8893 12031 9208 12031 9208 348 8893 348 9027 348 8895 12032 8893 12032 8878 12032 8878 348 8893 348 9185 348 9185 348 8893 348 9188 348 9188 348 8893 348 8794 348 8794 12033 8893 12033 8792 12033 9210 324 9211 324 9212 324 9214 12034 9215 12034 9216 12034 9219 12035 9220 12035 9221 12035 9220 324 9222 324 9221 324 9221 324 9222 324 9223 324 9221 12036 9223 12036 9224 12036 9224 324 9223 324 9225 324 9224 12037 9225 12037 9475 12037 9219 324 9226 324 9227 324 9219 12038 9227 12038 9220 12038 9228 324 9459 324 9229 324 9459 12039 9228 12039 9230 12039 9230 12040 9228 12040 9231 12040 9230 324 9231 324 9219 324 9219 12041 9231 12041 9232 12041 9229 324 9459 324 9232 324 9233 12042 9234 12042 9235 12042 9233 12043 9235 12043 9241 12043 9241 12044 9235 12044 9236 12044 9241 324 9236 324 9230 324 9236 324 9237 324 9230 324 9230 324 9237 324 9459 324 9459 324 9237 324 9233 324 9233 12045 9237 12045 9234 12045 9238 12046 9239 12046 9240 12046 9238 12047 9240 12047 9241 12047 9241 12048 9240 12048 9242 12048 9242 324 9243 324 9241 324 9241 324 9243 324 9233 324 9233 324 9243 324 9238 324 9238 12049 9243 12049 9239 12049 9212 12050 9244 12050 9245 12050 9246 12051 9244 12051 9247 12051 9248 324 9249 324 9213 324 9250 324 9251 324 9247 324 9247 324 9251 324 9252 324 9249 12052 9251 12052 9213 12052 9213 12053 9251 12053 9250 12053 9213 12054 9250 12054 9212 12054 9253 324 9255 324 9256 324 9244 324 9246 324 9245 324 9256 324 9255 324 9246 324 9212 324 9245 324 9209 324 9252 12055 9246 12055 9247 12055 9259 324 9260 324 9252 324 9252 12056 9260 12056 9246 12056 9261 324 9248 324 9258 324 9261 324 9258 324 9257 324 9259 12057 9252 12057 9262 12057 9259 12058 9262 12058 9261 12058 9261 12059 9262 12059 9263 12059 9261 12060 9263 12060 9248 12060 9263 12061 9264 12061 9248 12061 9248 324 9264 324 9265 324 9248 12062 9265 12062 9249 12062 9253 12063 9256 12063 9254 12063 9256 324 9267 324 9254 324 9254 324 9269 324 9209 324 9254 12064 9209 12064 9253 12064 9253 324 9209 324 9245 324 9269 324 9266 324 9209 324 9270 324 9271 324 9267 324 9273 12065 9272 12065 9274 12065 9273 12066 9274 12066 9270 12066 9267 12067 9271 12067 9268 12067 9267 324 9268 324 9266 324 9272 324 9275 324 9266 324 9266 12068 9268 12068 9272 12068 9277 324 9278 324 9270 324 9270 12069 9278 12069 9273 12069 9279 324 9276 324 9280 324 9276 324 9281 324 9277 324 9277 324 9281 324 9282 324 9282 12070 9281 12070 9283 12070 9273 12071 9275 12071 9272 12071 9275 324 9273 324 9282 324 9279 324 9280 324 9283 324 9283 12072 9280 12072 9275 12072 9283 12073 9275 12073 9282 12073 9284 324 9285 324 9286 324 9287 12074 9288 12074 9289 12074 9285 324 9284 324 9291 324 9289 324 9290 324 9287 324 9287 324 9290 324 9291 324 9291 324 9290 324 9285 324 9284 12075 9286 12075 9288 12075 9288 324 9286 324 9289 324 9296 324 9295 324 9297 324 9297 12076 9295 12076 9298 12076 9297 12077 9298 12077 9294 12077 9294 12078 9298 12078 9299 12078 9296 324 9284 324 9295 324 9287 324 9301 324 9218 324 9218 324 9301 324 9300 324 9301 12079 9287 12079 9302 12079 9302 324 9287 324 9291 324 9302 324 9291 324 9303 324 9284 324 9292 324 9291 324 9291 324 9304 324 9303 324 9303 324 9304 324 9305 324 9306 324 9218 324 9217 324 9306 324 9217 324 9307 324 9307 12080 9217 12080 9305 12080 9291 12081 9292 12081 9308 12081 9308 12082 9292 12082 9294 12082 9308 12083 9294 12083 9293 12083 9308 324 9293 324 9216 324 9216 324 9293 324 9309 324 9309 12084 9310 12084 9311 12084 9312 324 9313 324 9311 324 9314 324 9311 324 9315 324 9315 12085 9311 12085 9310 12085 9315 12086 9310 12086 9316 12086 9312 324 9311 324 9314 324 9312 12087 9314 12087 9317 12087 9317 12088 9314 12088 9332 12088 9295 12089 9320 12089 9321 12089 9321 324 9320 324 9325 324 9299 12090 9293 12090 9294 12090 9320 324 9322 324 9323 324 9324 324 9325 324 9319 324 9320 324 9323 324 9326 324 9320 12091 9326 12091 9325 12091 9318 12092 9319 12092 9322 12092 9322 324 9320 324 9313 324 9322 12093 9313 12093 9318 12093 9319 12094 9325 12094 9326 12094 9328 12095 9327 12095 9321 12095 9321 324 9327 324 9330 324 9321 324 9330 324 9295 324 9295 12096 9330 12096 9298 12096 9316 12097 9310 12097 9331 12097 9316 12098 9331 12098 9299 12098 9299 12099 9331 12099 9293 12099 9329 12100 9328 12100 9332 12100 9332 12101 9328 12101 9324 12101 9332 12102 9324 12102 9317 12102 9319 324 9318 324 9324 324 9324 12103 9318 12103 9317 12103 9328 12104 9329 12104 9327 12104 9327 324 9329 324 9299 324 9299 12105 9329 12105 9316 12105 9307 324 9305 324 9304 324 9307 324 9304 324 9333 324 9333 12106 9304 12106 9216 12106 9333 12107 9216 12107 9215 12107 9333 12108 9215 12108 9334 12108 9218 12109 9306 12109 9335 12109 9335 324 9306 324 9334 324 9216 324 9309 324 9311 324 9216 12110 9311 12110 9336 12110 9337 324 9335 324 9338 324 9337 324 9338 324 9336 324 9336 12111 9338 12111 9216 12111 9216 12112 9338 12112 9214 12112 9339 324 9340 324 9336 324 9339 324 9336 324 9311 324 9340 324 9339 324 9341 324 9340 324 9341 324 9342 324 9334 12113 9215 12113 9335 12113 9335 324 9337 324 9342 324 9342 324 9341 324 9345 324 9342 324 9345 324 9335 324 9335 324 9345 324 9344 324 9344 324 9345 324 9343 324 9320 12114 9350 12114 9313 12114 9313 12115 9350 12115 9346 12115 9347 324 9349 324 9348 324 9348 324 9349 324 9350 324 9351 324 9313 324 9346 324 9351 324 9346 324 9352 324 9352 324 9346 324 9347 324 9348 324 9354 324 9353 324 9353 324 9354 324 9355 324 9356 324 9357 324 9363 324 9363 324 9357 324 9348 324 9355 12116 9354 12116 9358 12116 9358 324 9354 324 9356 324 9363 12117 9359 12117 9360 12117 9360 324 9359 324 9361 324 9509 12118 9362 12118 9363 12118 9361 12119 9359 12119 9364 12119 9361 12120 9364 12120 9365 12120 9313 324 9351 324 9311 324 9351 324 9366 324 9311 324 9311 324 9366 324 9367 324 9367 324 9366 324 9368 324 9352 12121 9347 12121 9348 12121 9352 324 9348 324 9353 324 9353 324 9368 324 9366 324 9509 12122 9369 12122 9370 12122 9509 12123 9370 12123 9371 12123 9371 324 9370 324 9372 324 9373 324 9376 324 9374 324 9375 324 9369 324 9374 324 9372 324 9370 324 9376 324 9376 324 9370 324 9377 324 9376 324 9377 324 9374 324 9374 12124 9377 12124 9375 12124 9353 324 9355 324 9368 324 9358 12125 9356 12125 9363 12125 9358 324 9363 324 9360 324 9360 324 9378 324 9368 324 9343 324 9311 324 9344 324 9344 324 9311 324 9379 324 9368 324 9380 324 9367 324 9311 324 9367 324 9379 324 9368 12126 9381 12126 9382 12126 9344 12127 9380 12127 9368 12127 9344 324 9368 324 9382 324 9344 324 9382 324 9383 324 9381 324 9368 324 9378 324 9381 12128 9378 12128 9384 12128 9360 324 9361 324 9378 324 9364 324 9362 324 9365 324 9365 324 9362 324 9509 324 9365 324 9509 324 9371 324 9371 324 9372 324 9385 324 9385 324 9373 324 9374 324 9378 324 9386 324 9387 324 9384 12129 9378 12129 9387 12129 9384 324 9387 324 9388 324 9389 324 9390 324 9388 324 9386 324 9378 324 9371 324 9386 12130 9371 12130 9389 12130 9385 324 9391 324 9371 324 9371 324 9391 324 9392 324 9390 324 9389 324 9371 324 9390 324 9371 324 9392 324 9393 324 9374 324 9390 324 9391 12131 9385 12131 9374 12131 9391 324 9374 324 9393 324 9396 324 9397 324 9394 324 9394 324 9397 324 9395 324 9394 12132 9395 12132 9399 12132 9400 12133 9374 12133 9280 12133 9401 324 9280 324 9399 324 9401 12134 9399 12134 9402 12134 9402 324 9399 324 9395 324 9246 324 9403 324 9404 324 9406 324 9405 324 9258 324 9258 12135 9405 12135 9403 12135 9260 324 9257 324 9246 324 9246 12136 9257 12136 9258 12136 9246 12137 9258 12137 9403 12137 9246 324 9404 324 9256 324 9411 324 9408 324 9267 324 9267 324 9408 324 9410 324 9410 12138 9408 12138 9406 12138 9406 12139 9408 12139 9409 12139 9256 324 9405 324 9406 324 9256 12140 9406 12140 9407 12140 9407 12141 9406 12141 9409 12141 9407 324 9411 324 9256 324 9256 324 9411 324 9267 324 9270 324 9267 324 9412 324 9413 324 9414 324 9270 324 9413 324 9270 324 9412 324 9415 324 9410 324 9414 324 9415 324 9414 324 9413 324 9410 12142 9415 12142 9416 12142 9410 324 9416 324 9267 324 9267 12143 9416 12143 9412 12143 9277 324 9270 324 9276 324 9276 324 9270 324 9422 324 9276 324 9422 324 9420 324 9418 324 9419 324 9420 324 9420 12144 9419 12144 9276 12144 9421 12145 9414 12145 9419 12145 9421 324 9419 324 9418 324 9417 324 9422 324 9270 324 9414 324 9423 324 9424 324 9414 12146 9424 12146 9270 12146 9270 12147 9424 12147 9417 12147 9422 12148 9417 12148 9425 12148 9422 12149 9425 12149 9421 12149 9421 12150 9425 12150 9414 12150 9414 324 9425 324 9423 324 9429 324 9426 324 9213 324 9213 12151 9426 12151 9238 12151 9238 12152 9426 12152 9427 12152 9238 324 9427 324 9428 324 9238 12153 9428 12153 9212 12153 9212 324 9428 324 9429 324 9212 324 9429 324 9213 324 9212 12154 9211 12154 9238 12154 9238 324 9430 324 9209 324 9209 12155 9430 12155 9431 12155 9209 324 9431 324 9212 324 9212 12156 9431 12156 9210 12156 9211 324 9430 324 9238 324 9238 12157 9209 12157 9432 12157 9266 12158 9433 12158 9209 12158 9435 12159 9434 12159 9433 12159 9433 324 9266 324 9435 324 9435 324 9266 324 9438 324 9238 324 9435 324 9436 324 9238 12160 9436 12160 9437 12160 9238 12161 9437 12161 9275 12161 9275 324 9437 324 9438 324 9275 12162 9438 12162 9266 12162 9439 12163 9440 12163 9509 12163 9509 12164 9440 12164 9280 12164 9238 12165 9441 12165 9442 12165 9445 324 9275 324 9443 324 9443 12166 9275 12166 9280 12166 9443 12167 9280 12167 9440 12167 9275 12168 9444 12168 9238 12168 9238 12169 9444 12169 9441 12169 9445 12170 9442 12170 9446 12170 9445 324 9446 324 9275 324 9275 12171 9446 12171 9444 12171 9419 12172 9399 12172 9280 12172 9374 12173 9400 12173 9398 12173 9241 12174 9447 12174 9448 12174 9241 12175 9448 12175 9238 12175 9450 324 9451 324 9454 324 9238 12176 9448 12176 9451 12176 9238 12177 9451 12177 9449 12177 9449 324 9451 324 9450 324 9452 324 9213 324 9449 324 9449 324 9213 324 9238 324 9213 12178 9452 12178 9453 12178 9447 324 9241 324 9454 324 9454 324 9241 324 9213 324 9454 324 9213 324 9453 324 9454 324 9453 324 9450 324 9456 12179 9455 12179 9457 12179 9456 12180 9457 12180 9458 12180 9456 12181 9458 12181 9459 12181 9460 324 9459 324 9509 324 9280 12182 9276 12182 9419 12182 9458 12183 9461 12183 9459 12183 9459 12184 9461 12184 9455 12184 9462 324 9463 324 9459 324 9459 12185 9463 12185 9456 12185 9464 324 9465 324 9456 324 9462 12186 9460 12186 9465 12186 9462 324 9465 324 9464 324 9460 324 9462 324 9459 324 9467 12187 9466 12187 9468 12187 9467 12188 9468 12188 9469 12188 9467 12189 9469 12189 9460 12189 9348 324 9460 324 9509 324 9469 12190 9470 12190 9460 12190 9460 324 9470 324 9465 324 9465 324 9470 324 9466 324 9471 12191 9472 12191 9460 12191 9460 12192 9472 12192 9467 12192 9473 12193 9295 12193 9467 12193 9471 12194 9295 12194 9473 12194 9471 324 9460 324 9348 324 9219 324 9232 324 9459 324 9219 324 9459 324 9226 324 9476 12195 9477 12195 9456 12195 9456 12196 9477 12196 9455 12196 9477 12197 9478 12197 9455 12197 9455 324 9478 324 9475 324 9475 12198 9478 12198 9474 12198 9479 324 9476 324 9480 324 9480 324 9476 324 9456 324 9481 12199 9482 12199 9479 12199 9479 12200 9482 12200 9476 12200 9482 12201 9481 12201 9465 12201 9456 324 9465 324 9480 324 9467 12202 9484 12202 9486 12202 9467 12203 9486 12203 9465 12203 9467 12204 9465 12204 9466 12204 9486 12205 9487 12205 9465 12205 9465 12206 9487 12206 9482 12206 9482 12207 9487 12207 9483 12207 9484 12208 9488 12208 9491 12208 9488 12209 9484 12209 9467 12209 9489 324 9490 324 9491 324 9491 324 9490 324 9484 324 9490 12210 9489 12210 9295 12210 9295 12211 9489 12211 9492 12211 9295 12212 9492 12212 9467 12212 9467 324 9492 324 9488 324 9475 12213 9493 12213 9494 12213 9494 12214 9493 12214 9495 12214 9494 12215 9495 12215 9476 12215 9476 12216 9495 12216 9496 12216 9476 12217 9496 12217 9475 12217 9476 324 9475 324 9474 324 9496 12218 9497 12218 9475 12218 9475 12219 9497 12219 9493 12219 9498 12220 9494 12220 9499 12220 9499 12221 9494 12221 9476 12221 9500 12222 9501 12222 9498 12222 9498 12223 9501 12223 9494 12223 9501 12224 9500 12224 9502 12224 9501 12225 9502 12225 9482 12225 9482 12226 9502 12226 9476 12226 9476 12227 9502 12227 9499 12227 9484 12228 9503 12228 9504 12228 9484 12229 9504 12229 9482 12229 9484 12230 9482 12230 9485 12230 9485 12231 9482 12231 9483 12231 9505 12232 9503 12232 9506 12232 9506 12233 9503 12233 9484 12233 9507 12234 9490 12234 9503 12234 9507 12235 9503 12235 9505 12235 9490 12236 9507 12236 9508 12236 9490 12237 9508 12237 9484 12237 9484 12238 9508 12238 9506 12238 9509 12239 9374 12239 9369 12239 9398 324 9397 324 9396 324 9398 12240 9396 12240 9374 12240 9374 12241 9396 12241 9510 12241 9374 12242 9510 12242 9390 12242 9390 324 9510 324 9388 324 9388 324 9510 324 9384 324 9384 12243 9510 12243 9383 12243 9383 324 9510 324 9344 324 9344 12244 9510 12244 9335 12244 9335 324 9510 324 9218 324 9217 324 9218 324 9300 324 9233 12245 9238 12245 9459 12245 9226 324 9459 324 9475 324 9432 324 9434 324 9238 324 9238 12246 9434 12246 9435 12246 9445 324 9439 324 9442 324 9442 324 9439 324 9238 324 9238 324 9439 324 9509 324 9238 12247 9509 12247 9459 12247 9475 12248 9459 12248 9455 12248 9224 324 9511 324 9512 324 9512 12249 9511 12249 9513 12249 9512 324 9513 324 9494 324 9494 12250 9513 12250 9514 12250 9494 12251 9514 12251 9475 12251 9475 12252 9514 12252 9515 12252 9475 324 9515 324 9224 324 9224 12253 9515 12253 9511 12253 9516 12254 9512 12254 9494 12254 9516 324 9494 324 9517 324 9512 324 9516 324 9518 324 9512 12255 9518 12255 9501 12255 9518 12256 9519 12256 9501 12256 9501 12257 9519 12257 9494 12257 9494 12258 9519 12258 9517 12258 9512 12259 9520 12259 9521 12259 9521 12260 9520 12260 9522 12260 9521 12261 9522 12261 9503 12261 9503 12262 9522 12262 9523 12262 9503 12263 9523 12263 9524 12263 9503 12264 9524 12264 9501 12264 9501 12265 9524 12265 9512 12265 9512 12266 9524 12266 9520 12266 9525 12267 9526 12267 9503 12267 9503 12268 9528 12268 9521 12268 9521 12269 9528 12269 9527 12269 9529 324 9530 324 9526 324 9526 324 9530 324 9521 324 9527 324 9531 324 9521 324 9521 12270 9531 12270 9526 12270 9503 12271 9490 12271 9525 12271 9531 324 9532 324 9526 324 9526 12272 9532 12272 9503 12272 9503 12273 9532 12273 9528 12273 9530 324 9529 324 9533 324 9530 12274 9533 12274 9490 12274 9530 324 9537 324 9534 324 9295 12275 9534 12275 9535 12275 9535 324 9536 324 9490 324 9295 12276 9535 12276 9490 12276 9490 12277 9536 12277 9537 12277 9490 324 9537 324 9530 324 9534 324 9295 324 9530 324 9530 12278 9295 12278 9538 12278 9530 12279 9538 12279 9539 12279 9530 12280 9539 12280 9288 12280 9284 324 9540 324 9295 324 9288 324 9539 324 9284 324 9284 12281 9539 12281 9540 12281 9509 324 9280 324 9374 324 9509 12282 9363 12282 9348 12282 9471 324 9348 324 9350 324 9471 12283 9350 12283 9320 12283 9471 324 9320 324 9295 324 8897 12284 9397 12284 8896 12284 8896 12285 9397 12285 9398 12285 8896 12286 9398 12286 8817 12286 8817 12287 9398 12287 8796 12287 8796 12288 9398 12288 9400 12288 8796 12289 9400 12289 8895 12289 8895 12290 9400 12290 9280 12290 8895 12291 9280 12291 8894 12291 8894 12292 9280 12292 9401 12292 8894 12293 9401 12293 8892 12293 8892 12294 9401 12294 9402 12294 8892 12295 9402 12295 8890 12295 8890 12296 9402 12296 9395 12296 8890 12297 9395 12297 8897 12297 8897 12298 9395 12298 9397 12298 9169 12299 9390 12299 9166 12299 9166 12300 9390 12300 9392 12300 9166 12301 9392 12301 9167 12301 9167 12302 9392 12302 9391 12302 9167 12303 9391 12303 9168 12303 9168 12304 9391 12304 9393 12304 9168 12305 9393 12305 9169 12305 9169 12306 9393 12306 9390 12306 8901 12307 9388 12307 8903 12307 8903 12300 9388 12300 9387 12300 8903 12308 9387 12308 8899 12308 8899 12309 9387 12309 9386 12309 8899 12310 9386 12310 8905 12310 8905 12311 9386 12311 8901 12311 8901 12312 9386 12312 9389 12312 8901 12313 9389 12313 9388 12313 8904 12314 9385 12314 8816 12314 8816 12315 9385 12315 8906 12315 8906 12316 9385 12316 9372 12316 8906 12317 9372 12317 9376 12317 8906 12318 9376 12318 8908 12318 8908 12319 9376 12319 9373 12319 8908 12320 9373 12320 8904 12320 8904 12321 9373 12321 9385 12321 8910 12322 9378 12322 8913 12322 8913 12323 9378 12323 8912 12323 8912 12324 9378 12324 9361 12324 8912 12325 9361 12325 8911 12325 8911 12326 9361 12326 9365 12326 8911 12327 9365 12327 9371 12327 8911 12328 9371 12328 8910 12328 8910 12329 9371 12329 9378 12329 8962 12330 9345 12330 9341 12330 8962 12331 9341 12331 8963 12331 8963 12332 9341 12332 9339 12332 8963 12333 9339 12333 8960 12333 8960 12334 9339 12334 9311 12334 8960 12335 9311 12335 8961 12335 8961 12336 9311 12336 9343 12336 8961 12337 9343 12337 8962 12337 8962 12338 9343 12338 9345 12338 8957 12339 9342 12339 8952 12339 8952 12340 9342 12340 9337 12340 8952 12341 9337 12341 9336 12341 8952 12342 9336 12342 8953 12342 8953 12343 9336 12343 9340 12343 8953 12344 9340 12344 8959 12344 8959 12345 9340 12345 8957 12345 8957 12346 9340 12346 9342 12346 8902 12347 9383 12347 9382 12347 8902 12348 9382 12348 8900 12348 8900 12349 9382 12349 9381 12349 8900 12350 9381 12350 8916 12350 8916 12351 9381 12351 9384 12351 8916 12352 9384 12352 8902 12352 8902 12353 9384 12353 9383 12353 8922 12354 9344 12354 8919 12354 8919 12355 9344 12355 9379 12355 8919 12356 9379 12356 8923 12356 8923 12357 9379 12357 9367 12357 8923 12358 9367 12358 8918 12358 8918 12359 9367 12359 9380 12359 8918 12360 9380 12360 9344 12360 8918 12361 9344 12361 8922 12361 8909 12362 9368 12362 8924 12362 8924 12363 9368 12363 8915 12363 8915 12364 9368 12364 9355 12364 8915 12365 9355 12365 8914 12365 8914 12366 9355 12366 9358 12366 8914 12367 9358 12367 9360 12367 8914 12368 9360 12368 8909 12368 8909 12369 9360 12369 9368 12369 9162 12370 9370 12370 9163 12370 9163 12371 9370 12371 9369 12371 9163 12372 9369 12372 9164 12372 9164 12373 9369 12373 9375 12373 9164 12374 9375 12374 9377 12374 9164 12375 9377 12375 9165 12375 9165 12376 9377 12376 9162 12376 9162 12377 9377 12377 9370 12377 8917 12378 9366 12378 8929 12378 8929 12379 9366 12379 9351 12379 8929 12380 9351 12380 8928 12380 8928 12381 9351 12381 9352 12381 8928 12382 9352 12382 8926 12382 8926 12383 9352 12383 9353 12383 8926 12384 9353 12384 8917 12384 8917 12385 9353 12385 9366 12385 8934 12386 9364 12386 9359 12386 8934 12387 9359 12387 8931 12387 8931 12388 9359 12388 9363 12388 8931 12389 9363 12389 8932 12389 8932 12390 9363 12390 9362 12390 8932 12391 9362 12391 8933 12391 8933 12392 9362 12392 9364 12392 8933 12393 9364 12393 8934 12393 8937 12394 9354 12394 8938 12394 8938 12395 9354 12395 9348 12395 8938 12396 9348 12396 8935 12396 8935 12397 9348 12397 9357 12397 8935 12398 9357 12398 9356 12398 8935 12399 9356 12399 8936 12399 8936 12400 9356 12400 8937 12400 8937 12401 9356 12401 9354 12401 8942 12402 9346 12402 9350 12402 8942 12403 9350 12403 8941 12403 8941 12404 9350 12404 8939 12404 8939 12405 9350 12405 9349 12405 8939 12406 9349 12406 9347 12406 8939 12407 9347 12407 8925 12407 8925 12408 9347 12408 8942 12408 8942 12409 9347 12409 9346 12409 9312 12410 9317 12410 8951 12410 8951 12411 9317 12411 8947 12411 8947 12412 9317 12412 9318 12412 8947 12413 9318 12413 8930 12413 8930 12414 9318 12414 9313 12414 8930 12415 9313 12415 8921 12415 8921 12416 9313 12416 9312 12416 8921 12417 9312 12417 8951 12417 8978 12418 9319 12418 8972 12418 8972 12419 9319 12419 9326 12419 8972 12420 9326 12420 8973 12420 8973 12421 9326 12421 9323 12421 8973 12422 9323 12422 9322 12422 8973 12423 9322 12423 8977 12423 8977 12424 9322 12424 8978 12424 8978 12425 9322 12425 9319 12425 8974 12426 9328 12426 8975 12426 8975 12427 9328 12427 9321 12427 8975 12428 9321 12428 8976 12428 8976 12429 9321 12429 9325 12429 8976 12430 9325 12430 8979 12430 8979 12431 9325 12431 9324 12431 8979 12432 9324 12432 8974 12432 8974 12433 9324 12433 9328 12433 9214 12434 8955 12434 9215 12434 9215 12435 8955 12435 8956 12435 9215 12436 8956 12436 9335 12436 9335 12437 8956 12437 8958 12437 9335 12438 8958 12438 9338 12438 9338 12439 8958 12439 8954 12439 9338 12440 8954 12440 9214 12440 9214 12441 8954 12441 8955 12441 8950 12442 9316 12442 9329 12442 8950 12443 9329 12443 8948 12443 8948 12444 9329 12444 9332 12444 8948 12445 9332 12445 8944 12445 8944 12446 9332 12446 9314 12446 8944 12447 9314 12447 9315 12447 8944 12448 9315 12448 8943 12448 8943 12449 9315 12449 8950 12449 8950 12450 9315 12450 9316 12450 8965 12451 9306 12451 8964 12451 8964 12452 9306 12452 9307 12452 8964 12453 9307 12453 8815 12453 8815 12454 9307 12454 9333 12454 8815 12455 9333 12455 9334 12455 8815 12456 9334 12456 8967 12456 8967 12457 9334 12457 8965 12457 8965 12458 9334 12458 9306 12458 9298 12459 8970 12459 9299 12459 9299 12460 8970 12460 8984 12460 9299 12461 8984 12461 8971 12461 9299 12462 8971 12462 9327 12462 9327 12463 8971 12463 8968 12463 9327 12464 8968 12464 9330 12464 9330 12465 8968 12465 9298 12465 9298 12466 8968 12466 8970 12466 8949 12467 9331 12467 9310 12467 8949 12468 9310 12468 8945 12468 8945 12469 9310 12469 9309 12469 8945 12470 9309 12470 8814 12470 8814 12471 9309 12471 9293 12471 8814 12472 9293 12472 8946 12472 8946 12473 9293 12473 9331 12473 8946 12474 9331 12474 8949 12474 8988 12475 9304 12475 8986 12475 8986 12476 9304 12476 8985 12476 8985 12477 9304 12477 9291 12477 8985 12478 9291 12478 8987 12478 8987 12479 9291 12479 9308 12479 8987 12480 9308 12480 8988 12480 8988 12481 9308 12481 9216 12481 8988 12482 9216 12482 9304 12482 8990 12483 9217 12483 8995 12483 8995 12484 9217 12484 9300 12484 8995 12485 9300 12485 8996 12485 8996 12486 9300 12486 9301 12486 8996 12487 9301 12487 8992 12487 8992 12488 9301 12488 9302 12488 8992 12489 9302 12489 8993 12489 8993 12490 9302 12490 9303 12490 8993 12491 9303 12491 8966 12491 8966 12492 9303 12492 9305 12492 8966 12493 9305 12493 8989 12493 8989 12494 9305 12494 8990 12494 8990 12495 9305 12495 9217 12495 8982 12496 9292 12496 8980 12496 8980 12497 9292 12497 9284 12497 8980 12498 9284 12498 8981 12498 8981 12499 9284 12499 9296 12499 8981 12500 9296 12500 8983 12500 8983 12501 9296 12501 9297 12501 8983 12502 9297 12502 9294 12502 8983 12503 9294 12503 8982 12503 8982 12504 9294 12504 9292 12504 8799 12505 9285 12505 9142 12505 9142 12506 9285 12506 9290 12506 9142 12507 9290 12507 9143 12507 9143 12508 9290 12508 9289 12508 9143 12509 9289 12509 9141 12509 9141 12510 9289 12510 9286 12510 9141 12511 9286 12511 9285 12511 9141 12512 9285 12512 8799 12512 8812 12513 9489 12513 9023 12513 9023 12514 9489 12514 9491 12514 9023 12515 9491 12515 9021 12515 9021 12516 9491 12516 9488 12516 9021 12517 9488 12517 9022 12517 9022 12518 9488 12518 9492 12518 9022 12519 9492 12519 8812 12519 8812 12520 9492 12520 9489 12520 9156 12521 9471 12521 9473 12521 9156 12522 9473 12522 9159 12522 9159 12523 9473 12523 9467 12523 9159 12524 9467 12524 9157 12524 9157 12525 9467 12525 9472 12525 9157 12526 9472 12526 9158 12526 9158 12527 9472 12527 9471 12527 9158 12528 9471 12528 9156 12528 9134 12529 9533 12529 9130 12529 9130 12530 9533 12530 9529 12530 9130 12531 9529 12531 9131 12531 9131 12532 9529 12532 9526 12532 9131 12533 9526 12533 9132 12533 9132 12534 9526 12534 9525 12534 9132 12535 9525 12535 9490 12535 9132 12536 9490 12536 9134 12536 9134 12537 9490 12537 9533 12537 9482 12538 9006 12538 9501 12538 9501 12539 9006 12539 9003 12539 9501 12540 9003 12540 9004 12540 9501 12541 9004 12541 9503 12541 9004 12542 8999 12542 9503 12542 9503 12543 8999 12543 9504 12543 9504 12544 8999 12544 9009 12544 9504 12545 9009 12545 9482 12545 9482 12546 9009 12546 9006 12546 9506 12547 9013 12547 9505 12547 9505 12548 9013 12548 9012 12548 9505 12549 9012 12549 9507 12549 9507 12550 9012 12550 9018 12550 9507 12551 9018 12551 9508 12551 9018 12552 9017 12552 9508 12552 9508 12553 9017 12553 9024 12553 9508 12554 9024 12554 9506 12554 9506 12555 9024 12555 9013 12555 8800 12556 9534 12556 9136 12556 9136 12557 9534 12557 9137 12557 9137 12558 9534 12558 9537 12558 9137 12559 9537 12559 9135 12559 9135 12560 9537 12560 9536 12560 9135 12561 9536 12561 9535 12561 9135 12562 9535 12562 8800 12562 8800 12563 9535 12563 9534 12563 9138 12564 9540 12564 9140 12564 9140 12565 9540 12565 9539 12565 9140 12566 9539 12566 9139 12566 9139 12567 9539 12567 9538 12567 9139 12568 9538 12568 9144 12568 9144 12569 9538 12569 9295 12569 9144 12570 9295 12570 9138 12570 9138 12571 9295 12571 9540 12571 8997 12572 9522 12572 9001 12572 9001 12573 9522 12573 9520 12573 9001 12574 9520 12574 9007 12574 9007 12575 9520 12575 9524 12575 9007 12576 9524 12576 9000 12576 9000 12577 9524 12577 9523 12577 9000 12578 9523 12578 8997 12578 8997 12579 9523 12579 9522 12579 9015 12580 9531 12580 9014 12580 9014 12581 9531 12581 9527 12581 9014 12582 9527 12582 9528 12582 9014 12583 9528 12583 9019 12583 9019 12584 9528 12584 9020 12584 9020 12585 9528 12585 9532 12585 9020 12586 9532 12586 9015 12586 9015 12587 9532 12587 9531 12587 8793 12588 9420 12588 9029 12588 9029 12589 9420 12589 9422 12589 9029 12590 9422 12590 9208 12590 9208 12591 9422 12591 9421 12591 9208 12592 9421 12592 8792 12592 8792 12593 9421 12593 9418 12593 8792 12594 9418 12594 8793 12594 8793 12595 9418 12595 9420 12595 9028 12596 9425 12596 9417 12596 9028 12597 9417 12597 9032 12597 9032 12598 9417 12598 9424 12598 9032 12599 9424 12599 9026 12599 9026 12600 9424 12600 9423 12600 9026 12601 9423 12601 9030 12601 9030 12602 9423 12602 9425 12602 9030 12603 9425 12603 9028 12603 8810 12604 9279 12604 8811 12604 8811 12605 9279 12605 9283 12605 8811 12606 9283 12606 9038 12606 9038 12607 9283 12607 9033 12607 9033 12608 9283 12608 9281 12608 9033 12609 9281 12609 9276 12609 9033 12610 9276 12610 8810 12610 8810 12611 9276 12611 9279 12611 9205 12612 9413 12612 9412 12612 9205 12613 9412 12613 9047 12613 9047 12598 9412 12598 9416 12598 9047 12614 9416 12614 9207 12614 9207 12615 9416 12615 9415 12615 9207 12616 9415 12616 9206 12616 9206 12617 9415 12617 9413 12617 9206 12618 9413 12618 9205 12618 9040 12619 9282 12619 9042 12619 9042 12620 9282 12620 9273 12620 9042 12621 9273 12621 8809 12621 8809 12622 9273 12622 9031 12622 9031 12623 9273 12623 9278 12623 9031 12624 9278 12624 9277 12624 9031 12625 9277 12625 9040 12625 9040 12626 9277 12626 9282 12626 9037 12627 9446 12627 9442 12627 9037 12628 9442 12628 9044 12628 9044 12629 9442 12629 9441 12629 9044 12630 9441 12630 9444 12630 9044 12631 9444 12631 9041 12631 9041 12632 9444 12632 9446 12632 9041 12633 9446 12633 9037 12633 9034 12634 9440 12634 9035 12634 9035 12635 9440 12635 9036 12635 9036 12636 9440 12636 9439 12636 9036 12637 9439 12637 9039 12637 9039 12638 9439 12638 9445 12638 9039 12639 9445 12639 9443 12639 9039 12640 9443 12640 9034 12640 9034 12641 9443 12641 9440 12641 8807 12642 9274 12642 8808 12642 8808 12643 9274 12643 9272 12643 8808 12644 9272 12644 9045 12644 9045 12645 9272 12645 9268 12645 9045 12646 9268 12646 9046 12646 9046 12647 9268 12647 9271 12647 9046 12648 9271 12648 9270 12648 9046 12649 9270 12649 8807 12649 8807 12650 9270 12650 9274 12650 9048 12651 9437 12651 9049 12651 9049 12652 9437 12652 9436 12652 9049 12653 9436 12653 9435 12653 9049 12654 9435 12654 9051 12654 9051 12655 9435 12655 9438 12655 9051 12656 9438 12656 9052 12656 9052 12657 9438 12657 9048 12657 9048 12658 9438 12658 9437 12658 9201 12659 9408 12659 9411 12659 9201 12660 9411 12660 9202 12660 9202 12661 9411 12661 9203 12661 9203 12662 9411 12662 9407 12662 9203 12663 9407 12663 9409 12663 9203 12664 9409 12664 9204 12664 9204 12665 9409 12665 9408 12665 9204 12666 9408 12666 9201 12666 9200 12667 9405 12667 9256 12667 9200 12668 9256 12668 9074 12668 9074 12669 9256 12669 9404 12669 9074 12670 9404 12670 9197 12670 9197 12671 9404 12671 9403 12671 9197 12672 9403 12672 9198 12672 9198 12673 9403 12673 9405 12673 9198 12674 9405 12674 9200 12674 9053 12675 9266 12675 9062 12675 9062 12676 9266 12676 9269 12676 9062 12677 9269 12677 9060 12677 9060 12678 9269 12678 9254 12678 9060 12679 9254 12679 9054 12679 9054 12680 9254 12680 9267 12680 9054 12681 9267 12681 9053 12681 9053 12682 9267 12682 9266 12682 9192 12683 9257 12683 9193 12683 9193 12684 9257 12684 9260 12684 9193 12685 9260 12685 9194 12685 9194 12686 9260 12686 9259 12686 9194 12687 9259 12687 9261 12687 9194 12688 9261 12688 9196 12688 9196 12689 9261 12689 9192 12689 9192 12690 9261 12690 9257 12690 8806 12691 9252 12691 9070 12691 9070 12692 9252 12692 9251 12692 9070 12693 9251 12693 9067 12693 9067 12694 9251 12694 9249 12694 9067 12695 9249 12695 9069 12695 9069 12696 9249 12696 9265 12696 9069 12697 9265 12697 9066 12697 9066 12698 9265 12698 9264 12698 9066 12699 9264 12699 9064 12699 9064 12700 9264 12700 9263 12700 9064 12701 9263 12701 8805 12701 8805 12702 9263 12702 9262 12702 8805 12703 9262 12703 8806 12703 8806 12704 9262 12704 9252 12704 9079 12705 9253 12705 9245 12705 9079 12706 9245 12706 9072 12706 9072 12707 9245 12707 9073 12707 9073 12708 9245 12708 9246 12708 9073 12709 9246 12709 9055 12709 9055 12710 9246 12710 9255 12710 9055 12711 9255 12711 9079 12711 9079 12712 9255 12712 9253 12712 9058 12713 9430 12713 9078 12713 9078 12714 9430 12714 9211 12714 9078 12715 9211 12715 9075 12715 9075 12716 9211 12716 9210 12716 9075 12717 9210 12717 9077 12717 9077 12718 9210 12718 9431 12718 9077 12719 9431 12719 9058 12719 9058 12720 9431 12720 9430 12720 9076 12721 9244 12721 9086 12721 9086 12722 9244 12722 9212 12722 9086 12723 9212 12723 9071 12723 9071 12724 9212 12724 9250 12724 9071 12725 9250 12725 9080 12725 9080 12726 9250 12726 9247 12726 9080 12727 9247 12727 9076 12727 9076 12728 9247 12728 9244 12728 9081 12729 9428 12729 9082 12729 9082 12730 9428 12730 9427 12730 9082 12731 9427 12731 9085 12731 9085 12732 9427 12732 9426 12732 9085 12733 9426 12733 9083 12733 9083 12734 9426 12734 9429 12734 9083 12735 9429 12735 9081 12735 9081 12736 9429 12736 9428 12736 9152 12737 9469 12737 9468 12737 9152 12738 9468 12738 9154 12738 9154 12739 9468 12739 9466 12739 9154 12740 9466 12740 9155 12740 9155 12741 9466 12741 9470 12741 9155 12742 9470 12742 9469 12742 9155 12743 9469 12743 9152 12743 9149 12521 9462 12521 9464 12521 9149 12744 9464 12744 9151 12744 9151 12745 9464 12745 9456 12745 9151 12740 9456 12740 9150 12740 9150 12741 9456 12741 9463 12741 9150 12746 9463 12746 9462 12746 9150 12747 9462 12747 9149 12747 9008 12748 9484 12748 9485 12748 9008 12749 9485 12749 9011 12749 9011 12750 9485 12750 9010 12750 9010 12751 9485 12751 9483 12751 9010 12752 9483 12752 9487 12752 9010 12753 9487 12753 8804 12753 8804 12518 9487 12518 9486 12518 8804 12754 9486 12754 9008 12754 9008 12755 9486 12755 9484 12755 9145 12756 9458 12756 9457 12756 9145 12757 9457 12757 9147 12757 9147 12758 9457 12758 9455 12758 9147 12759 9455 12759 9461 12759 9147 12760 9461 12760 9148 12760 9148 12761 9461 12761 9458 12761 9148 12762 9458 12762 9145 12762 8803 12763 9481 12763 9479 12763 8803 12764 9479 12764 9096 12764 9096 12765 9479 12765 9098 12765 9098 12766 9479 12766 9480 12766 9098 12767 9480 12767 9465 12767 9098 12768 9465 12768 8802 12768 8802 12769 9465 12769 8803 12769 8803 12770 9465 12770 9481 12770 9499 12771 9089 12771 9498 12771 9498 12772 9089 12772 9088 12772 9498 12773 9088 12773 9092 12773 9498 12774 9092 12774 9500 12774 9500 12775 9092 12775 9502 12775 9092 12776 9093 12776 9502 12776 9502 12777 9093 12777 9099 12777 9502 12778 9099 12778 9499 12778 9499 12779 9099 12779 9089 12779 9091 12780 9518 12780 9090 12780 9090 12781 9518 12781 9516 12781 9090 12782 9516 12782 9094 12782 9094 12783 9516 12783 9517 12783 9094 12784 9517 12784 9095 12784 9095 12785 9517 12785 9519 12785 9095 12786 9519 12786 9091 12786 9091 12787 9519 12787 9518 12787 9497 12788 9111 12788 9493 12788 9493 12789 9111 12789 9104 12789 9493 12790 9104 12790 9106 12790 9493 12791 9106 12791 9495 12791 9106 12792 9087 12792 9495 12792 9495 12793 9087 12793 9496 12793 9496 12794 9087 12794 9109 12794 9496 12795 9109 12795 9497 12795 9497 12796 9109 12796 9111 12796 9101 12797 9513 12797 9100 12797 9100 12798 9513 12798 9511 12798 9100 12799 9511 12799 9103 12799 9103 12800 9511 12800 9515 12800 9103 12801 9515 12801 9105 12801 9105 12802 9515 12802 9514 12802 9105 12803 9514 12803 9101 12803 9101 12804 9514 12804 9513 12804 9056 12805 9433 12805 9057 12805 9057 12806 9433 12806 9434 12806 9057 12807 9434 12807 9059 12807 9059 12808 9434 12808 9432 12808 9059 12809 9432 12809 9209 12809 9059 12810 9209 12810 9061 12810 9061 12811 9209 12811 9433 12811 9061 12812 9433 12812 9056 12812 9176 12813 9449 12813 9177 12813 9177 12814 9449 12814 9450 12814 9177 12815 9450 12815 9178 12815 9178 12816 9450 12816 9453 12816 9178 12817 9453 12817 9179 12817 9179 12818 9453 12818 9452 12818 9179 12819 9452 12819 9176 12819 9176 12820 9452 12820 9449 12820 9174 12821 9448 12821 9170 12821 9170 12822 9448 12822 9447 12822 9170 12823 9447 12823 9171 12823 9171 12824 9447 12824 9454 12824 9171 12825 9454 12825 9172 12825 9172 12826 9454 12826 9451 12826 9172 12827 9451 12827 9174 12827 9174 12828 9451 12828 9448 12828 9114 12829 9239 12829 9115 12829 9115 12830 9239 12830 9243 12830 9115 12831 9243 12831 9116 12831 9116 12832 9243 12832 9242 12832 9116 12833 9242 12833 9113 12833 9113 12834 9242 12834 9240 12834 9113 12835 9240 12835 9114 12835 9114 12836 9240 12836 9239 12836 8858 12837 9234 12837 9237 12837 8858 12838 9237 12838 8859 12838 8859 12839 9237 12839 9236 12839 8859 12840 9236 12840 8855 12840 8855 12841 9236 12841 9235 12841 8855 12842 9235 12842 8858 12842 8858 12843 9235 12843 9234 12843 9110 12844 9477 12844 9476 12844 9110 12845 9476 12845 9474 12845 9110 12846 9474 12846 9107 12846 9107 12847 9474 12847 9478 12847 9107 12848 9478 12848 9108 12848 9108 12849 9478 12849 9477 12849 9108 12850 9477 12850 9110 12850 8868 12851 9229 12851 8869 12851 8869 12852 9229 12852 9232 12852 8869 12853 9232 12853 8866 12853 8866 12854 9232 12854 9231 12854 8866 12855 9231 12855 8867 12855 8867 12856 9231 12856 9228 12856 8867 12857 9228 12857 8868 12857 8868 12858 9228 12858 9229 12858 9122 12859 9225 12859 9124 12859 9124 12860 9225 12860 9223 12860 9124 12861 9223 12861 9126 12861 9126 12862 9223 12862 9222 12862 9126 12863 9222 12863 9127 12863 9127 12864 9222 12864 9220 12864 9127 12865 9220 12865 9128 12865 9128 12866 9220 12866 9227 12866 9128 12867 9227 12867 9129 12867 9129 12868 9227 12868 9226 12868 9129 12869 9226 12869 9123 12869 9123 12870 9226 12870 9475 12870 9123 12871 9475 12871 9122 12871 9122 12872 9475 12872 9225 12872 8795 12873 8877 12873 9541 12873 8795 12874 9541 12874 9542 12874 8823 12875 9544 12875 9543 12875 8824 8505 8823 8505 9543 8505 9190 12876 8825 12876 9545 12876 8821 8505 9189 8505 9546 8505 8886 8646 8820 8646 9547 8646 8879 8505 8887 8505 9548 8505 8884 12877 8880 12877 9549 12877 8884 8646 9549 8646 9550 8646 8881 12878 8882 12878 9551 12878 8888 8646 8889 8646 9552 8646 8819 8505 8818 8505 9553 8505 9560 12879 9561 12879 9562 12879 9562 12880 9561 12880 9563 12880 9564 12881 9565 12881 9841 12881 9841 12882 9565 12882 9566 12882 9568 12883 9569 12883 9567 12883 9570 12884 9571 12884 9574 12884 9574 12885 9571 12885 9572 12885 9575 12886 9573 12886 9574 12886 9574 12887 9572 12887 9575 12887 9576 12888 9570 12888 9573 12888 9573 12889 9570 12889 9574 12889 9571 8646 9570 8646 9577 8646 9577 12890 9570 12890 9576 12890 9584 12891 9578 12891 9581 12891 9581 12892 9578 12892 9579 12892 9580 8505 9581 8505 9582 8505 9581 8505 9579 8505 9582 8505 9583 12893 9584 12893 9580 12893 9580 12894 9584 12894 9581 12894 9583 8646 9578 8646 9584 8646 9585 12895 9586 12895 9587 12895 9587 12896 9586 12896 9588 12896 9587 8505 9588 8505 9589 8505 9590 12897 9585 12897 9589 12897 9589 12898 9585 12898 9587 12898 9586 8646 9585 8646 9590 8646 9592 12899 9591 12899 9569 12899 9594 12900 9593 12900 9592 12900 9592 12901 9593 12901 9591 12901 9595 8511 9596 8511 9597 8511 9597 12902 9596 12902 9598 12902 9597 12903 9598 12903 9599 12903 9601 12904 9785 12904 9602 12904 9602 12905 9785 12905 9603 12905 9598 12906 9600 12906 9602 12906 9603 12907 9598 12907 9602 12907 9606 12908 9607 12908 9608 12908 9606 12909 9608 12909 9609 12909 9612 12910 9613 12910 9614 12910 9614 12911 9613 12911 9615 12911 9616 12912 9617 12912 9615 12912 9615 12913 9617 12913 9614 12913 9610 12914 9617 12914 9611 12914 9620 12915 9618 12915 9621 12915 9621 12916 9618 12916 9619 12916 9611 12917 9623 12917 9622 12917 9622 12918 9620 12918 9611 12918 9675 12919 9677 12919 9624 12919 9626 12920 9627 12920 9625 12920 9625 12921 9627 12921 9675 12921 9625 12922 9675 12922 9624 12922 9630 12923 9631 12923 9628 12923 9628 12924 9631 12924 9629 12924 9633 12925 9632 12925 9630 12925 9630 12926 9632 12926 9631 12926 9634 12927 9635 12927 9633 12927 9633 12928 9635 12928 9632 12928 9636 12929 9637 12929 9634 12929 9634 12930 9637 12930 9635 12930 9638 12931 9639 12931 9636 12931 9636 12932 9639 12932 9637 12932 9640 12933 9641 12933 9642 12933 9642 12934 9641 12934 9643 12934 9644 12935 9645 12935 9646 12935 9646 12936 9645 12936 9647 12936 9649 12937 9648 12937 9644 12937 9644 12938 9648 12938 9645 12938 9650 12939 9651 12939 9649 12939 9649 12940 9651 12940 9648 12940 9642 12941 9643 12941 9650 12941 9650 12942 9643 12942 9651 12942 9766 12943 9652 12943 9653 12943 9646 12944 9647 12944 9654 12944 9654 12945 9647 12945 9655 12945 9654 12946 9655 12946 9652 12946 9652 12947 9655 12947 9653 12947 9659 12948 9653 12948 9655 12948 9659 12949 9655 12949 9656 12949 9653 12950 9659 12950 9660 12950 9658 12951 9657 12951 9767 12951 9767 12952 9657 12952 9661 12952 9673 12953 9660 12953 9664 12953 9664 12954 9660 12954 9659 12954 9662 12955 9663 12955 9674 12955 9674 12956 9663 12956 9670 12956 9669 12957 9663 12957 9666 12957 9666 12958 9663 12958 9665 12958 9771 12959 9670 12959 9663 12959 9771 12960 9663 12960 9669 12960 9671 12961 9672 12961 9668 12961 9668 12962 9672 12962 9667 12962 9662 12963 9675 12963 9676 12963 9675 12964 9662 12964 9677 12964 9677 12965 9662 12965 9674 12965 9678 12966 9679 12966 9626 12966 9626 12967 9679 12967 9627 12967 9639 12968 9638 12968 9666 12968 9666 12969 9638 12969 9676 12969 9666 12970 9676 12970 9669 12970 9669 12971 9676 12971 9675 12971 9669 12972 9675 12972 9770 12972 9680 12973 9627 12973 9672 12973 9628 12974 9629 12974 9679 12974 9679 12975 9629 12975 9667 12975 9679 12976 9667 12976 9627 12976 9627 12977 9667 12977 9672 12977 8823 12978 8795 12978 9544 12978 9544 12979 8795 12979 9542 12979 8877 12980 8824 12980 9541 12980 9541 12981 8824 12981 9543 12981 9189 12982 9190 12982 9682 12982 8825 12983 8821 12983 9545 12983 9545 12984 8821 12984 9546 12984 8887 12985 8886 12985 9684 12985 8820 12986 8879 12986 9547 12986 9547 12987 8879 12987 9548 12987 8882 12988 8884 12988 9550 12988 8882 12989 9550 12989 9686 12989 8880 12990 8881 12990 9549 12990 9549 12991 8881 12991 9551 12991 8818 12992 8888 12992 9687 12992 8889 12993 8819 12993 9552 12993 9552 12994 8819 12994 9553 12994 9688 324 9689 324 9690 324 9690 12995 9689 12995 9691 12995 9692 12996 9693 12996 9694 12996 9694 12997 9693 12997 9695 12997 9695 12998 9696 12998 9694 12998 9694 12999 9696 12999 9698 12999 9688 8646 9690 8646 9696 8646 9696 13000 9690 13000 9698 13000 9699 13001 9700 13001 9701 13001 9701 13002 9700 13002 9702 13002 9703 13003 9692 13003 9698 13003 9694 13004 9698 13004 9692 13004 9701 13005 9704 13005 9691 13005 9701 13006 9691 13006 9699 13006 9693 13007 9692 13007 9697 13007 9697 13008 9692 13008 9703 13008 9697 13009 9703 13009 9705 13009 9705 13010 9703 13010 9706 13010 9707 13011 9705 13011 9706 13011 9708 13012 9705 13012 9707 13012 9709 13013 9710 13013 9708 13013 9711 13014 9712 13014 9716 13014 9716 13015 9712 13015 9713 13015 9715 13016 9714 13016 9719 13016 9713 13017 9718 13017 9716 13017 9712 13018 9720 13018 9718 13018 9713 13019 9712 13019 9718 13019 9715 13020 9719 13020 9722 13020 9722 13021 9719 13021 9721 13021 9720 13022 9712 13022 9711 13022 9714 13023 9717 13023 9719 13023 9719 13024 9717 13024 9721 13024 9721 13025 9717 13025 9723 13025 9724 13026 9725 13026 9723 13026 9728 13027 9727 13027 9704 13027 9704 13028 9727 13028 9726 13028 9727 13029 9728 13029 9730 13029 9730 13030 9728 13030 9729 13030 9731 8505 9732 8505 9733 8505 9733 8505 9732 8505 9734 8505 9735 13031 9736 13031 9733 13031 9735 13032 9733 13032 9734 13032 9737 8511 9738 8511 9739 8511 9739 8511 9738 8511 9740 8511 9736 8511 9741 8511 9733 8511 9733 8511 9741 8511 9731 8511 9742 13033 9737 13033 9709 13033 9709 13034 9737 13034 9739 13034 9737 13035 9742 13035 9738 13035 9703 13036 9743 13036 9706 13036 9706 13037 9743 13037 9744 13037 9706 13038 9744 13038 9745 13038 9746 13039 9747 13039 9744 13039 9744 13040 9747 13040 9745 13040 9742 13041 9747 13041 9738 13041 9738 13042 9747 13042 9746 13042 9738 13043 9746 13043 9740 13043 9729 13044 9732 13044 9730 13044 9730 13045 9732 13045 9731 13045 9730 13046 9731 13046 9723 13046 9723 13047 9731 13047 9741 13047 9746 13048 9721 13048 9740 13048 9740 13049 9721 13049 9748 13049 9748 13050 9721 13050 9749 13050 9748 13051 9749 13051 9750 13051 9750 13052 9749 13052 9724 13052 9750 13053 9724 13053 9741 13053 9741 13054 9724 13054 9723 13054 9700 13055 9699 13055 9751 13055 9751 13056 9699 13056 9691 13056 9689 8505 9751 8505 9691 8505 9693 13057 9697 13057 9696 13057 9696 13058 9695 13058 9693 13058 9751 13059 9752 13059 9700 13059 9700 13060 9752 13060 9702 13060 9752 13061 9704 13061 9702 13061 9702 13062 9704 13062 9701 13062 9704 13063 9752 13063 9753 13063 9704 13064 9753 13064 9754 13064 9753 13065 9755 13065 9754 13065 9735 13066 9755 13066 9756 13066 9691 13067 9757 13067 9690 13067 9690 8511 9757 8511 9698 8511 9541 13068 9543 13068 9757 13068 9757 13069 9543 13069 9545 13069 9757 13070 9545 13070 9546 13070 9546 8511 9547 8511 9757 8511 9757 13071 9547 13071 9548 13071 9757 8511 9548 8511 9698 8511 9698 13072 9548 13072 9549 13072 9698 13073 9549 13073 9551 13073 9551 8511 9552 8511 9698 8511 9698 8511 9552 8511 9553 8511 9745 8511 9747 8511 9707 8511 9709 13074 9708 13074 9742 13074 9742 13075 9708 13075 9707 13075 9747 8511 9742 8511 9707 8511 9706 13076 9745 13076 9707 13076 9755 13077 9735 13077 9754 13077 9754 13078 9735 13078 9734 13078 9754 8511 9734 8511 9732 8511 9754 8511 9732 8511 9729 8511 9729 8511 9728 8511 9754 8511 9754 8511 9728 8511 9704 8511 9623 13079 9610 13079 9698 13079 9758 13080 9623 13080 9698 13080 9190 13081 9544 13081 9682 13081 8886 13082 9681 13082 9684 13082 9550 13083 9683 13083 9686 13083 8888 13084 9685 13084 9687 13084 9541 13085 9757 13085 9542 13085 9542 13086 9757 13086 9759 13086 9544 13087 9190 13087 9543 13087 9543 13088 9190 13088 9545 13088 9681 13089 8886 13089 9189 13089 9189 13090 8886 13090 9546 13090 9546 13091 8886 13091 9547 13091 9683 13092 9550 13092 8887 13092 8887 13093 9550 13093 9548 13093 9548 13094 9550 13094 9549 13094 9685 13095 8888 13095 8882 13095 8882 13096 8888 13096 9551 13096 9551 13097 8888 13097 9552 13097 9760 13098 9758 13098 8818 13098 8818 13099 9758 13099 9698 13099 8818 13100 9698 13100 9553 13100 9684 13101 9681 13101 9759 13101 9759 13102 9623 13102 9760 13102 9760 13103 9623 13103 9758 13103 9683 13104 8887 13104 9684 13104 9685 13105 9759 13105 9687 13105 9687 13106 9759 13106 9760 13106 9687 13107 9760 13107 8818 13107 9544 13108 9542 13108 9759 13108 9544 13109 9759 13109 9682 13109 9682 13110 9759 13110 9681 13110 9682 13111 9681 13111 9189 13111 9683 13112 9684 13112 9759 13112 9683 13113 9759 13113 9686 13113 9686 13114 9759 13114 9685 13114 9686 13111 9685 13111 8882 13111 9663 13115 9662 13115 9665 13115 9759 13116 9656 13116 9622 13116 9759 13117 9622 13117 9623 13117 9662 13118 9623 13118 9665 13118 9656 13119 9759 13119 9664 13119 9656 13120 9664 13120 9659 13120 9664 13121 9654 13121 9652 13121 9764 13122 9673 13122 9664 13122 9764 13123 9664 13123 9652 13123 9762 13124 9763 13124 9761 13124 9761 13125 9763 13125 9640 13125 9641 13126 9640 13126 9657 13126 9657 13127 9640 13127 9661 13127 9661 13128 9640 13128 9763 13128 9653 13129 9660 13129 9765 13129 9765 13130 9766 13130 9653 13130 9766 13131 9765 13131 9609 13131 9767 13132 9661 13132 9608 13132 9608 13133 9661 13133 9768 13133 9608 13134 9768 13134 9766 13134 9608 13135 9766 13135 9609 13135 9766 13136 9769 13136 9652 13136 9764 13137 9652 13137 9604 13137 9763 13138 9762 13138 9605 13138 9652 13139 9769 13139 9604 13139 9604 13140 9769 13140 9605 13140 9605 13141 9769 13141 9763 13141 9763 13142 9768 13142 9661 13142 9680 13143 9770 13143 9627 13143 9627 13144 9770 13144 9675 13144 9766 13145 9768 13145 9769 13145 9769 13146 9768 13146 9763 13146 9671 13147 9680 13147 9672 13147 9770 13148 9771 13148 9669 13148 9771 13149 9770 13149 9772 13149 9680 13150 9671 13150 9773 13150 9772 13151 9770 13151 9773 13151 9773 13152 9770 13152 9680 13152 9772 13153 9773 13153 9774 13153 9772 13154 9774 13154 9775 13154 9782 13155 9778 13155 9783 13155 9783 13156 9778 13156 9779 13156 9782 13157 9781 13157 9780 13157 9778 13158 9782 13158 9780 13158 9777 13159 9783 13159 9776 13159 9783 13160 9779 13160 9776 13160 9601 13161 9602 13161 9784 13161 9784 13162 9602 13162 9600 13162 9784 8511 9600 8511 9604 8511 9604 8511 9600 8511 9606 8511 9604 8511 9606 8511 9609 8511 9604 13163 9609 13163 9764 13163 9764 13164 9609 13164 9765 13164 9764 13165 9765 13165 9660 13165 9764 13166 9660 13166 9673 13166 9674 13167 9670 13167 9677 13167 9677 13168 9670 13168 9771 13168 9677 13169 9771 13169 9624 13169 9624 13170 9771 13170 9772 13170 9624 13171 9772 13171 9775 13171 9624 8511 9775 8511 9777 8511 9777 8511 9775 8511 9781 8511 9777 13172 9781 13172 9783 13172 9783 13173 9781 13173 9782 13173 9599 13174 9601 13174 9784 13174 9785 13175 9601 13175 9599 13175 9779 13176 9778 13176 9776 13176 9776 13177 9778 13177 9780 13177 9599 13178 9598 13178 9785 13178 9785 13179 9598 13179 9603 13179 9786 13180 9776 13180 9780 13180 9776 13181 9786 13181 9787 13181 9787 8511 9786 8511 9788 8511 9709 13182 9739 13182 9740 13182 9709 13183 9740 13183 9710 13183 9710 13184 9740 13184 9748 13184 9710 13185 9748 13185 9789 13185 9787 13186 9788 13186 9748 13186 9748 13187 9788 13187 9789 13187 9705 13188 9688 13188 9697 13188 9697 13189 9688 13189 9696 13189 9752 13190 9751 13190 9753 13190 9753 13191 9751 13191 9689 13191 9710 13192 9689 13192 9708 13192 9708 13193 9689 13193 9688 13193 9708 13194 9688 13194 9705 13194 9789 13195 9790 13195 9710 13195 9710 13196 9790 13196 9756 13196 9710 8511 9756 8511 9689 8511 9689 13197 9756 13197 9755 13197 9689 13198 9755 13198 9753 13198 9756 13199 9750 13199 9735 13199 9735 13200 9750 13200 9741 13200 9735 13201 9741 13201 9736 13201 9596 8646 9595 8646 9790 8646 9790 13202 9595 13202 9750 13202 9756 8646 9790 8646 9750 8646 9791 13203 9810 13203 9792 13203 9797 13204 9796 13204 9793 13204 9794 13205 9795 13205 9796 13205 9794 13206 9796 13206 9797 13206 9798 13207 9799 13207 9794 13207 9794 13208 9799 13208 9795 13208 9800 8507 9801 8507 9798 8507 9798 8507 9801 8507 9799 8507 9802 13209 9803 13209 9800 13209 9800 13210 9803 13210 9801 13210 9804 13211 9805 13211 9802 13211 9802 13212 9805 13212 9803 13212 9806 13213 9791 13213 9804 13213 9804 13214 9791 13214 9805 13214 9797 13215 9793 13215 9807 13215 9806 13216 9807 13216 9791 13216 9791 13217 9807 13217 9793 13217 9793 13218 9809 13218 9808 13218 9791 13219 9793 13219 9808 13219 9810 13220 9791 13220 9808 13220 9809 13221 9792 13221 9808 13221 9808 13222 9792 13222 9810 13222 9815 13223 9814 13223 9811 13223 9811 13224 9814 13224 9826 13224 9812 13225 9813 13225 9814 13225 9812 13226 9814 13226 9815 13226 9816 13227 9817 13227 9812 13227 9812 13228 9817 13228 9813 13228 9818 8507 9819 8507 9816 8507 9816 8507 9819 8507 9817 8507 9820 13229 9821 13229 9818 13229 9818 13230 9821 13230 9819 13230 9822 13231 9823 13231 9820 13231 9820 13232 9823 13232 9821 13232 9824 13233 9825 13233 9822 13233 9822 13234 9825 13234 9823 13234 9825 13235 9826 13235 9827 13235 9828 13236 9825 13236 9827 13236 9826 13237 9829 13237 9827 13237 9792 13238 9774 13238 9607 13238 9801 13239 9720 13239 9799 13239 9799 13240 9720 13240 9711 13240 9803 13241 9805 13241 9814 13241 9792 13242 9607 13242 9805 13242 9600 13243 9598 13243 9606 13243 9792 13244 9809 13244 9774 13244 9801 13245 9803 13245 9720 13245 9720 13246 9803 13246 9718 13246 9718 13247 9803 13247 9817 13247 9805 13248 9791 13248 9792 13248 9795 13249 9799 13249 9775 13249 9830 13250 9829 13250 9607 13250 9607 13251 9829 13251 9805 13251 9805 348 9829 348 9814 348 9814 13252 9829 13252 9826 13252 9780 13253 9781 13253 9775 13253 9780 13254 9775 13254 9786 13254 9786 13255 9775 13255 9799 13255 9786 348 9799 348 9788 348 9788 13256 9799 13256 9711 13256 9788 13257 9711 13257 9789 13257 9790 13258 9716 13258 9596 13258 9716 13259 9718 13259 9596 13259 9596 13260 9718 13260 9817 13260 9596 13261 9817 13261 9598 13261 9598 13262 9817 13262 9819 13262 9598 13263 9819 13263 9606 13263 9606 13264 9819 13264 9821 13264 9606 13265 9821 13265 9823 13265 9606 13266 9823 13266 9607 13266 9774 13267 9796 13267 9775 13267 9775 13268 9796 13268 9795 13268 9803 348 9814 348 9813 348 9803 13269 9813 13269 9817 13269 9789 13270 9711 13270 9790 13270 9790 13271 9711 13271 9716 13271 9774 13272 9809 13272 9796 13272 9796 13273 9809 13273 9793 13273 9830 13274 9607 13274 9825 13274 9825 13275 9607 13275 9823 13275 9829 13276 9830 13276 9827 13276 9827 13277 9830 13277 9828 13277 9825 13278 9828 13278 9830 13278 9826 13279 9825 13279 9811 13279 9811 13280 9825 13280 9824 13280 9811 13281 9824 13281 9605 13281 9599 13282 9784 13282 9604 13282 9599 13283 9604 13283 9597 13283 9800 13284 9798 13284 9776 13284 9777 13285 9776 13285 9624 13285 9750 13286 9725 13286 9748 13286 9748 13287 9725 13287 9831 13287 9748 13288 9831 13288 9787 13288 9597 324 9818 324 9595 324 9595 324 9818 324 9816 324 9605 13289 9824 13289 9822 13289 9597 13290 9604 13290 9818 13290 9818 13291 9604 13291 9820 13291 9804 13292 9811 13292 9806 13292 9605 13293 9822 13293 9604 13293 9604 13294 9822 13294 9820 13294 9798 13295 9794 13295 9624 13295 9798 13296 9624 13296 9776 13296 9624 13297 9794 13297 9625 13297 9625 13298 9794 13298 9797 13298 9811 13299 9605 13299 9806 13299 9806 13300 9605 13300 9625 13300 9806 13301 9625 13301 9807 13301 9807 13302 9625 13302 9797 13302 9750 13303 9595 13303 9725 13303 9725 324 9595 324 9816 324 9725 13304 9816 13304 9723 13304 9723 13305 9816 13305 9812 13305 9723 13306 9802 13306 9721 13306 9776 13307 9787 13307 9800 13307 9800 13308 9787 13308 9831 13308 9800 324 9831 324 9802 324 9802 13309 9831 13309 9721 13309 9723 13310 9812 13310 9802 13310 9802 324 9812 324 9804 324 9804 324 9812 324 9815 324 9804 13311 9815 13311 9811 13311 9749 8511 9831 8511 9724 8511 9724 8511 9831 8511 9725 8511 9831 13312 9749 13312 9721 13312 9834 13313 9832 13313 9722 13313 9722 13314 9832 13314 9593 13314 9715 13315 9722 13315 9717 13315 9717 13316 9722 13316 9593 13316 9717 13317 9593 13317 9594 13317 9717 13318 9714 13318 9715 13318 9832 13319 9833 13319 9593 13319 9837 13320 9835 13320 9834 13320 9834 13321 9835 13321 9832 13321 9832 13322 9835 13322 9833 13322 9565 13323 9835 13323 9837 13323 9591 13324 9567 13324 9569 13324 9572 13325 9838 13325 9575 13325 9575 13326 9838 13326 9839 13326 9579 13327 9571 13327 9582 13327 9582 13328 9571 13328 9577 13328 9588 13329 9578 13329 9589 13329 9589 13330 9578 13330 9583 13330 9566 13331 9586 13331 9840 13331 9840 13332 9586 13332 9590 13332 9835 13333 9565 13333 9836 13333 9841 13334 9566 13334 9840 13334 9836 13335 9564 13335 9840 13335 9840 13336 9564 13336 9841 13336 9565 13337 9564 13337 9836 13337 9575 13338 9839 13338 9842 13338 9575 13339 9842 13339 9573 13339 9582 13340 9577 13340 9576 13340 9582 13341 9576 13341 9580 13341 9835 13342 9836 13342 9833 13342 9833 13343 9836 13343 9840 13343 9840 13344 9590 13344 9833 13344 9833 13345 9590 13345 9589 13345 9589 13346 9583 13346 9833 13346 9833 13347 9583 13347 9580 13347 9833 13348 9580 13348 9576 13348 9567 13349 9591 13349 9593 13349 9567 13350 9593 13350 9842 13350 9842 13351 9593 13351 9833 13351 9842 13352 9833 13352 9573 13352 9573 13353 9833 13353 9576 13353 9842 13354 9843 13354 9567 13354 9567 13355 9843 13355 9568 13355 9838 8646 9843 8646 9839 8646 9839 13356 9843 13356 9842 13356 9843 12884 9838 12884 9568 12884 9568 13357 9838 13357 9569 13357 9730 13358 9723 13358 9594 13358 9594 13359 9723 13359 9717 13359 9569 13360 9838 13360 9621 13360 9621 13361 9838 13361 9572 13361 9621 13362 9572 13362 9571 13362 9621 13363 9571 13363 9620 13363 9620 13364 9571 13364 9579 13364 9579 13365 9578 13365 9620 13365 9620 13366 9578 13366 9588 13366 9588 13367 9586 13367 9620 13367 9620 13368 9586 13368 9566 13368 9726 13369 9592 13369 9621 13369 9621 13370 9592 13370 9569 13370 9566 13371 9565 13371 9620 13371 9620 13372 9565 13372 9610 13372 9620 13373 9610 13373 9611 13373 9592 13374 9730 13374 9594 13374 9726 8507 9727 8507 9592 8507 9592 13375 9727 13375 9730 13375 9610 13376 9565 13376 9743 13376 9743 13377 9565 13377 9837 13377 9837 8507 9834 8507 9746 8507 9722 13378 9721 13378 9834 13378 9834 13379 9721 13379 9746 13379 9746 8507 9744 8507 9837 8507 9837 13380 9744 13380 9743 13380 9698 13381 9610 13381 9743 13381 9698 13382 9743 13382 9703 13382 9704 13383 9726 13383 9691 13383 9691 13384 9726 13384 9621 13384 9691 13385 9621 13385 9757 13385 9759 13386 9757 13386 9621 13386 9662 13387 9676 13387 9638 13387 9845 13388 9628 13388 9678 13388 9678 13389 9628 13389 9679 13389 9844 13390 9614 13390 9636 13390 9845 13391 9846 13391 9636 13391 9614 348 9844 348 9612 348 9636 13392 9630 13392 9845 13392 9845 13393 9630 13393 9628 13393 9638 13394 9610 13394 9623 13394 9638 13395 9623 13395 9662 13395 9846 348 9844 348 9636 348 9610 13396 9638 13396 9617 13396 9617 13397 9638 13397 9614 13397 9614 13398 9638 13398 9636 13398 9634 13399 9633 13399 9636 13399 9636 13400 9633 13400 9630 13400 9759 13401 9621 13401 9664 13401 9664 13402 9621 13402 9646 13402 9664 13403 9646 13403 9654 13403 9761 13404 9560 13404 9848 13404 9646 13405 9621 13405 9619 13405 9849 13406 9640 13406 9642 13406 9849 348 9642 348 9847 348 9847 13407 9642 13407 9619 13407 9642 13408 9644 13408 9619 13408 9619 13409 9644 13409 9646 13409 9848 13410 9560 13410 9562 13410 9761 13411 9640 13411 9560 13411 9560 13412 9640 13412 9849 13412 9619 13413 9850 13413 9847 13413 9650 348 9649 348 9642 348 9642 13414 9649 13414 9644 13414 9851 13415 9846 13415 9852 13415 9852 13416 9846 13416 9845 13416 9846 13417 9851 13417 9844 13417 9844 13418 9851 13418 9853 13418 9558 13419 9613 13419 9612 13419 9844 13420 9853 13420 9854 13420 9854 13421 9558 13421 9844 13421 9844 13422 9558 13422 9612 13422 9620 13423 9622 13423 9656 13423 9559 13424 9557 13424 9643 13424 9658 13425 9861 13425 9858 13425 9858 13426 9861 13426 9860 13426 9856 13427 9855 13427 9643 13427 9643 13428 9855 13428 9559 13428 9655 13429 9647 13429 9656 13429 9656 13430 9647 13430 9556 13430 9862 13431 9618 13431 9556 13431 9556 13432 9618 13432 9620 13432 9556 13433 9620 13433 9656 13433 9643 13434 9641 13434 9856 13434 9856 13435 9641 13435 9858 13435 9858 13436 9641 13436 9658 13436 9658 13437 9641 13437 9657 13437 9557 13438 9645 13438 9643 13438 9643 324 9645 324 9651 324 9556 13439 9647 13439 9557 13439 9557 13440 9647 13440 9645 13440 9648 324 9651 324 9645 324 9617 13441 9616 13441 9611 13441 9611 13442 9616 13442 9555 13442 9859 13443 9852 13443 9668 13443 9859 13444 9668 13444 9857 13444 9857 13445 9668 13445 9554 13445 9857 13446 9554 13446 9854 13446 9854 13447 9554 13447 9558 13447 9637 13448 9631 13448 9635 13448 9668 13449 9667 13449 9629 13449 9631 324 9637 324 9629 324 9629 13450 9637 13450 9554 13450 9554 13451 9637 13451 9555 13451 9668 13452 9629 13452 9554 13452 9611 13453 9666 13453 9665 13453 9611 13454 9665 13454 9623 13454 9555 13455 9637 13455 9639 13455 9555 13456 9639 13456 9611 13456 9611 13457 9639 13457 9666 13457 9632 324 9635 324 9631 324 9863 13458 9850 13458 9862 13458 9862 13459 9850 13459 9619 13459 9862 13460 9619 13460 9618 13460 9850 13461 9863 13461 9847 13461 9847 13462 9863 13462 9864 13462 9847 13463 9864 13463 9849 13463 9560 13464 9849 13464 9559 13464 9559 13465 9849 13465 9864 13465 9561 13466 9560 13466 9855 13466 9855 13467 9560 13467 9559 13467 9554 13468 9555 13468 9616 13468 9616 13469 9615 13469 9554 13469 9554 13470 9615 13470 9558 13470 9558 13471 9615 13471 9613 13471 9852 13472 9859 13472 9851 13472 9851 13473 9859 13473 9857 13473 9853 13474 9851 13474 9854 13474 9854 13475 9851 13475 9857 13475 9855 13476 9856 13476 9561 13476 9561 13477 9856 13477 9858 13477 9563 13478 9561 13478 9860 13478 9860 13479 9561 13479 9858 13479 9557 13480 9559 13480 9556 13480 9556 13481 9559 13481 9864 13481 9864 13482 9863 13482 9862 13482 9864 13483 9862 13483 9556 13483 9860 13484 9861 13484 9848 13484 9860 13485 9848 13485 9563 13485 9563 13486 9848 13486 9562 13486 9848 8507 9861 8507 9761 8507 9761 8507 9861 8507 9658 8507 9761 13487 9658 13487 9762 13487 9762 13488 9658 13488 9767 13488 9762 13489 9767 13489 9605 13489 9605 13490 9767 13490 9608 13490 9605 8507 9608 8507 9607 8507 9605 13491 9607 13491 9625 13491 9625 13492 9607 13492 9774 13492 9625 8507 9774 8507 9773 8507 9625 13493 9773 13493 9626 13493 9626 13494 9773 13494 9671 13494 9626 13495 9671 13495 9678 13495 9678 13496 9671 13496 9668 13496 9678 13497 9668 13497 9845 13497 9845 13498 9668 13498 9852 13498 9865 348 9866 348 9867 348 9867 348 9866 348 9868 348 9868 8511 8876 8511 9867 8511 9867 13499 8876 13499 8875 13499 8874 8505 9865 8505 9867 8505 8874 13500 9867 13500 8875 13500 9865 13501 8874 13501 9866 13501 9866 8507 8874 8507 8852 8507 8876 13502 9868 13502 8852 13502 8852 13503 9868 13503 9866 13503 9869 348 9870 348 9871 348 9871 348 9870 348 9872 348 9872 13504 9084 13504 9871 13504 9871 8511 9084 8511 8829 8511 9871 8505 8829 8505 9869 8505 9869 8505 8829 8505 8798 8505 9869 8507 8798 8507 9870 8507 9870 8507 8798 8507 8797 8507 9870 13505 8797 13505 9872 13505 9872 13506 8797 13506 9084 13506 9873 348 9874 348 9875 348 9875 348 9874 348 9876 348 9876 13507 9184 13507 9875 13507 9875 13507 9184 13507 9183 13507 9182 8511 9873 8511 9183 8511 9183 8511 9873 8511 9875 8511 9873 8505 9182 8505 9874 8505 9874 8505 9182 8505 8841 8505 9184 8507 9876 8507 9874 8507 9184 13508 9874 13508 8841 13508 9877 348 9878 348 9879 348 9879 348 9878 348 9880 348 8873 8646 9879 8646 9043 8646 9043 8646 9879 8646 9880 8646 9877 8511 9879 8511 8873 8511 8873 13509 8872 13509 9877 13509 8826 13510 9878 13510 9877 13510 8826 13510 9877 13510 8872 13510 9043 8507 9880 8507 8826 8507 8826 8507 9880 8507 9878 8507 9881 348 9882 348 9883 348 9883 348 9882 348 9884 348 8848 8507 9883 8507 8871 8507 8871 8507 9883 8507 9884 8507 9883 13511 8848 13511 9881 13511 9881 8646 8848 8646 8847 8646 8870 13512 9882 13512 9881 13512 8870 8511 9881 8511 8847 8511 8871 8505 9884 8505 8870 8505 8870 8505 9884 8505 9882 8505 9885 348 9886 348 9887 348 9887 348 9886 348 9888 348 8864 8646 9887 8646 9888 8646 8864 8646 9888 8646 8857 8646 8863 8511 9885 8511 9887 8511 8863 8511 9887 8511 8864 8511 8862 8505 9886 8505 8863 8505 8863 8505 9886 8505 9885 8505 8857 8507 9888 8507 9886 8507 8857 8507 9886 8507 8862 8507 9889 348 9890 348 9891 348 9891 348 9890 348 9892 348 8854 8646 9891 8646 9892 8646 8854 8646 9892 8646 9161 8646 9891 8511 8854 8511 9889 8511 9889 8511 8854 8511 8856 8511 8861 13513 9890 13513 8856 13513 8856 13513 9890 13513 9889 13513 9161 8507 9892 8507 8861 8507 8861 8507 9892 8507 9890 8507 9893 348 9894 348 9895 348 9895 348 9894 348 9896 348 8853 8505 9895 8505 8831 8505 8831 8505 9895 8505 9896 8505 9895 8507 8853 8507 8851 8507 9895 13514 8851 13514 9893 13514 9893 13515 8851 13515 9894 13515 9894 13515 8851 13515 8827 13515 9894 8511 8827 8511 9896 8511 9896 8511 8827 8511 8831 8511 9897 348 9898 348 9899 348 9899 348 9898 348 9900 348 8850 8507 9899 8507 9900 8507 8850 8507 9900 8507 8849 8507 9899 8646 8850 8646 9897 8646 9897 8646 8850 8646 8828 8646 8846 13512 9898 13512 9897 13512 8846 8511 9897 8511 8828 8511 8849 8505 9900 8505 8846 8505 8846 8505 9900 8505 9898 8505 9901 348 9902 348 9903 348 9903 348 9902 348 9904 348 9904 13507 8844 13507 9903 13507 9903 13507 8844 13507 9180 13507 9160 8511 9901 8511 9180 8511 9180 8511 9901 8511 9903 8511 9901 8505 9160 8505 9902 8505 9902 8505 9160 8505 8843 8505 9904 8507 9902 8507 8843 8507 8843 13516 8844 13516 9904 13516 9905 348 9906 348 9907 348 9907 348 9906 348 9908 348 9908 13517 8842 13517 9907 13517 9907 13518 8842 13518 8840 13518 8841 13519 9905 13519 8840 13519 8840 13520 9905 13520 9907 13520 9905 8505 8841 8505 9906 8505 9906 8505 8841 8505 9175 8505 8842 13521 9908 13521 9906 13521 8842 8507 9906 8507 9175 8507 9909 348 9910 348 9911 348 9911 348 9910 348 9912 348 8839 8511 9911 8511 9912 8511 8839 8511 9912 8511 8838 8511 9911 8505 8839 8505 9909 8505 9909 8505 8839 8505 8907 8505 8834 13522 9910 13522 8907 13522 8907 8507 9910 8507 9909 8507 9910 13523 8834 13523 9912 13523 9912 13524 8834 13524 8838 13524 9913 348 9914 348 9915 348 9915 348 9914 348 9916 348 8835 8511 9915 8511 9916 8511 8835 13525 9916 13525 8837 13525 9915 8505 8835 8505 9913 8505 9913 13526 8835 13526 8834 13526 8822 8507 9914 8507 8834 8507 8834 13527 9914 13527 9913 13527 9914 13528 8822 13528 9916 13528 9916 13528 8822 13528 8837 13528 9917 348 9918 348 9919 348 9919 348 9918 348 9920 348 9920 8511 8875 8511 9919 8511 9919 8511 8875 8511 8833 8511 8832 8505 9917 8505 9919 8505 8832 8505 9919 8505 8833 8505 9917 13529 8832 13529 9918 13529 9918 8507 8832 8507 8830 8507 8875 13530 9920 13530 8830 13530 8830 13531 9920 13531 9918 13531 9921 13532 9922 13532 9923 13532 9923 13533 9922 13533 9924 13533 9924 13534 9922 13534 8878 13534 8878 13535 9922 13535 9186 13535 9922 13536 9921 13536 9186 13536 9186 13537 9921 13537 9187 13537 9921 8659 9923 8659 9187 8659 9187 9772 9923 9772 9185 9772 9923 13538 9924 13538 9185 13538 9185 13539 9924 13539 8878 13539 9925 348 9926 348 9927 348 9927 348 9926 348 9928 348 9121 8511 9927 8511 9117 8511 9117 8511 9927 8511 9928 8511 9927 8505 9121 8505 9925 8505 9925 8505 9121 8505 9119 8505 9925 8507 9119 8507 9926 8507 9926 8507 9119 8507 9118 8507 9926 8646 9118 8646 9928 8646 9928 8646 9118 8646 9117 8646 8898 13540 9510 13540 9396 13540 9394 13541 8891 13541 9396 13541 9396 13542 8891 13542 8898 13542 8898 13543 9191 13543 9510 13543 9510 13544 9191 13544 9218 13544 9218 8507 9191 8507 8994 8507 9218 8505 8994 8505 9287 8505 9287 8505 8994 8505 8991 8505 8801 8505 9530 8505 9288 8505 8801 8505 9288 8505 8991 8505 8991 8505 9288 8505 9287 8505 8801 8505 9133 8505 9530 8505 9530 8505 9133 8505 9016 8505 9530 8505 9016 8505 9521 8505 9521 8505 9016 8505 8998 8505 9521 8505 8998 8505 9512 8505 9512 8505 8998 8505 9002 8505 9512 8505 9002 8505 9224 8505 9224 8505 9002 8505 9102 8505 9125 13545 9221 13545 9102 13545 9102 13546 9221 13546 9224 13546 9221 13547 9125 13547 9219 13547 9219 13548 9125 13548 9120 13548 9219 13549 9120 13549 8865 13549 9219 8511 8865 8511 9230 8511 9230 8511 8865 8511 8860 8511 9230 8511 8860 8511 9241 8511 9241 8511 8860 8511 9112 8511 9241 8511 9112 8511 8845 8511 9241 13550 8845 13550 9213 13550 9065 8511 9248 8511 9068 8511 9068 8511 9248 8511 9213 8511 9068 8511 9213 8511 8845 8511 9025 8646 9414 8646 9199 8646 9199 8646 9414 8646 9410 8646 9199 8646 9410 8646 9406 8646 9199 8646 9406 8646 9195 8646 9195 8646 9406 8646 9258 8646 9195 8646 9258 8646 9063 8646 9063 13551 9258 13551 9248 13551 9063 8646 9248 8646 9065 8646 9414 8646 9025 8646 9027 8646 9414 8646 9027 8646 9419 8646 9419 13552 9027 13552 8893 13552 8891 8646 9394 8646 8893 8646 8893 8646 9394 8646 9399 8646 8893 13553 9399 13553 9419 13553 9929 13554 9942 13554 9930 13554 9929 13555 9930 13555 9931 13555 9931 13556 9930 13556 9932 13556 9931 13557 9932 13557 9933 13557 9933 13558 9932 13558 9934 13558 9933 13559 9934 13559 9935 13559 9934 13560 9936 13560 9935 13560 9935 13561 9936 13561 9937 13561 9937 13562 9936 13562 9938 13562 9937 13563 9938 13563 9939 13563 9937 13564 9939 13564 9940 13564 9940 13565 9939 13565 9941 13565 9940 13566 9941 13566 9929 13566 9929 13567 9941 13567 9942 13567 9943 13568 9944 13568 9945 13568 9945 13569 9944 13569 9946 13569 9945 13570 9946 13570 9947 13570 9948 13571 9949 13571 9950 13571 9950 13572 9949 13572 9951 13572 9951 13573 9949 13573 9952 13573 9951 13574 9952 13574 9953 13574 9953 13575 9952 13575 9954 13575 9953 13576 9954 13576 9955 13576 9955 13577 9954 13577 9943 13577 9943 13578 9954 13578 9944 13578 9947 13579 9946 13579 9956 13579 9947 13580 9956 13580 9957 13580 9957 13581 9956 13581 9958 13581 9958 13582 9956 13582 9959 13582 9958 13583 9959 13583 9960 13583 9960 13584 9959 13584 9948 13584 9948 13585 9959 13585 9949 13585 9962 13586 9961 13586 9964 13586 9962 13587 9964 13587 9963 13587 9963 13588 9964 13588 9965 13588 9963 13589 9965 13589 9966 13589 9966 13590 9965 13590 9967 13590 9966 13591 9967 13591 9968 13591 9968 13592 9967 13592 10013 13592 9968 13593 10013 13593 9969 13593 9969 13594 10013 13594 9970 13594 9969 13595 9970 13595 9971 13595 9970 13596 10010 13596 9971 13596 9972 13597 9973 13597 9971 13597 9972 13598 9971 13598 10010 13598 9974 13599 9973 13599 9972 13599 9973 13600 9974 13600 9975 13600 10015 13601 9975 13601 9974 13601 9975 13602 10015 13602 9976 13602 9975 13603 9976 13603 9977 13603 9977 13604 9976 13604 10014 13604 9977 13605 10014 13605 9962 13605 9962 13606 10014 13606 9961 13606 9978 13607 9979 13607 9980 13607 9981 13608 9978 13608 9980 13608 9983 13609 9982 13609 9980 13609 9980 13610 9979 13610 9983 13610 9984 13611 9960 13611 9948 13611 9984 13612 9948 13612 9985 13612 9985 13613 9948 13613 9950 13613 9985 13614 9950 13614 9986 13614 9986 13615 9950 13615 9951 13615 9986 13616 9951 13616 9987 13616 9987 13617 9951 13617 9953 13617 9987 13618 9953 13618 9988 13618 9988 13619 9953 13619 9955 13619 9988 13620 9955 13620 9989 13620 9989 13621 9955 13621 9943 13621 9989 13622 9943 13622 9990 13622 9990 13623 9943 13623 9991 13623 9991 13624 9943 13624 9945 13624 9991 13625 9945 13625 9992 13625 9992 13626 9945 13626 9947 13626 9992 13627 9947 13627 9993 13627 9993 13628 9947 13628 9957 13628 9993 13629 9957 13629 9994 13629 9994 13630 9957 13630 9958 13630 9994 13631 9958 13631 9995 13631 9995 13632 9958 13632 9960 13632 9995 13633 9960 13633 9984 13633 9990 13634 9939 13634 9989 13634 9989 13635 9939 13635 9938 13635 9989 13636 9938 13636 9988 13636 9988 13637 9938 13637 9936 13637 9988 13638 9936 13638 9987 13638 9987 13639 9936 13639 9986 13639 9986 13640 9936 13640 9934 13640 9986 13641 9934 13641 9985 13641 9985 13642 9934 13642 9984 13642 9984 13643 9934 13643 9932 13643 9984 13644 9932 13644 9995 13644 9995 13645 9932 13645 9994 13645 9994 13646 9932 13646 9930 13646 9994 13647 9930 13647 9993 13647 9993 13648 9930 13648 9942 13648 9993 13649 9942 13649 9992 13649 9992 13650 9942 13650 9941 13650 9992 13651 9941 13651 9991 13651 9991 13652 9941 13652 9939 13652 9991 13653 9939 13653 9990 13653 9962 13654 9978 13654 9977 13654 9977 13655 9978 13655 9981 13655 9977 13656 9981 13656 9975 13656 9975 13657 9981 13657 9980 13657 9975 13658 9980 13658 9973 13658 9973 13659 9980 13659 9971 13659 9971 13660 9980 13660 9982 13660 9971 13661 9982 13661 9969 13661 9969 13662 9982 13662 9968 13662 9968 13663 9982 13663 9983 13663 9968 13664 9983 13664 9966 13664 9966 13665 9983 13665 9979 13665 9966 13666 9979 13666 9963 13666 9963 13667 9979 13667 9962 13667 9962 13668 9979 13668 9978 13668 9929 13669 9996 13669 9940 13669 9931 13670 9997 13670 9929 13670 9933 13671 9998 13671 9931 13671 9935 13672 9999 13672 9933 13672 9937 13673 10000 13673 9935 13673 9940 13674 10001 13674 9937 13674 10005 13675 10006 13675 10003 13675 10005 13676 10003 13676 10004 13676 10004 13677 10003 13677 10002 13677 10007 13678 10002 13678 10003 13678 10008 13679 10007 13679 10003 13679 10009 13680 10008 13680 10003 13680 10003 13681 10006 13681 10009 13681 10007 13682 9940 13682 9996 13682 10007 13683 9996 13683 10002 13683 9929 13684 10002 13684 9996 13684 10004 13685 9997 13685 10005 13685 10005 13686 9997 13686 9931 13686 10002 13687 9929 13687 9997 13687 9997 13688 10004 13688 10002 13688 9998 13689 9933 13689 10006 13689 9998 13690 10005 13690 9931 13690 9998 13691 10006 13691 10005 13691 9935 13692 10009 13692 9999 13692 10006 13693 9933 13693 9999 13693 10006 13694 9999 13694 10009 13694 9937 13695 10008 13695 10000 13695 10009 13696 9935 13696 10000 13696 10009 13697 10000 13697 10008 13697 9940 13698 10007 13698 10001 13698 10008 13699 9937 13699 10001 13699 10008 13700 10001 13700 10007 13700 9956 13701 9946 13701 9967 13701 9944 13702 9954 13702 10010 13702 9944 13703 10010 13703 10011 13703 9944 13704 10011 13704 9946 13704 9956 13705 10012 13705 9959 13705 9959 13706 10012 13706 9949 13706 9946 13707 10011 13707 10013 13707 9956 13708 9964 13708 10012 13708 9954 13709 9972 13709 10010 13709 10010 13710 9970 13710 10011 13710 10011 13711 9970 13711 10013 13711 10012 13712 9964 13712 9961 13712 10012 13713 9961 13713 10014 13713 9956 13714 9965 13714 9964 13714 9956 13715 9967 13715 9965 13715 9946 13716 10013 13716 9967 13716 9954 13717 9974 13717 9972 13717 9954 13718 9952 13718 9974 13718 9952 13719 10015 13719 9974 13719 9952 13720 9949 13720 10015 13720 10015 13721 9949 13721 9976 13721 9949 13722 10014 13722 9976 13722 9949 13723 10012 13723 10014 13723 10037 13724 10016 13724 10017 13724 10017 13725 10016 13725 10018 13725 10017 13726 10018 13726 10019 13726 10019 13727 10018 13727 10020 13727 10019 13728 10020 13728 10021 13728 10019 13729 10021 13729 10022 13729 10022 13730 10021 13730 10023 13730 10022 13731 10023 13731 10024 13731 10024 13732 10023 13732 10025 13732 10024 13733 10025 13733 10026 13733 10026 13734 10025 13734 10027 13734 10026 13735 10027 13735 10028 13735 10028 13736 10027 13736 10029 13736 10028 13737 10029 13737 10030 13737 10030 13738 10029 13738 10031 13738 10030 13739 10031 13739 10032 13739 10032 13740 10031 13740 10033 13740 10032 13741 10033 13741 10034 13741 10034 13742 10033 13742 10035 13742 10034 13743 10035 13743 10036 13743 10036 13744 10035 13744 10037 13744 10037 13745 10035 13745 10016 13745 10038 324 10029 324 10027 324 10038 324 10027 324 10039 324 10040 13746 10016 13746 10041 13746 10040 13747 10018 13747 10016 13747 10041 324 10016 324 10035 324 10041 324 10035 324 10042 324 10043 324 10029 324 10038 324 10043 324 10031 324 10029 324 10044 13748 10021 13748 10020 13748 10044 324 10020 324 10040 324 10040 324 10020 324 10018 324 10042 324 10035 324 10033 324 10042 324 10033 324 10043 324 10043 13749 10033 13749 10031 13749 10039 324 10027 324 10025 324 10039 13750 10025 13750 10045 13750 10025 324 10023 324 10045 324 10045 324 10023 324 10044 324 10044 13751 10023 13751 10021 13751 10041 13752 10046 13752 10040 13752 10040 13753 10046 13753 10047 13753 10040 13754 10047 13754 10044 13754 10044 13755 10047 13755 10045 13755 10045 13756 10047 13756 10048 13756 10045 13757 10048 13757 10039 13757 10039 13758 10048 13758 10049 13758 10039 13759 10049 13759 10038 13759 10038 13760 10049 13760 10050 13760 10038 13761 10050 13761 10043 13761 10043 13762 10050 13762 10051 13762 10043 13763 10051 13763 10042 13763 10042 13764 10051 13764 10052 13764 10042 13765 10052 13765 10041 13765 10041 13766 10052 13766 10053 13766 10041 13767 10053 13767 10046 13767 10053 348 10037 348 10046 348 10052 348 10036 348 10053 348 10053 348 10036 348 10037 348 10049 13768 10030 13768 10050 13768 10051 13769 10032 13769 10034 13769 10051 348 10034 348 10052 348 10052 13770 10034 13770 10036 13770 10050 348 10030 348 10051 348 10051 348 10030 348 10032 348 10048 348 10026 348 10049 348 10049 13771 10026 13771 10028 13771 10049 348 10028 348 10030 348 10048 13772 10024 13772 10026 13772 10046 13773 10019 13773 10047 13773 10019 348 10022 348 10047 348 10047 348 10022 348 10048 348 10048 13774 10022 13774 10024 13774 10037 13775 10017 13775 10046 13775 10046 13776 10017 13776 10019 13776 10057 13777 10058 13777 10056 13777 10054 13778 10055 13778 10059 13778 10054 13779 10059 13779 10056 13779 10056 13780 10059 13780 10057 13780 10061 13781 10058 13781 10057 13781 10062 13782 10058 13782 10061 13782 10062 13783 10060 13783 10058 13783 10056 13784 10058 13784 10060 13784 10060 13785 10064 13785 10063 13785 10056 13786 10060 13786 10063 13786 10064 13787 10060 13787 10065 13787 10064 13788 10065 13788 10066 13788 10067 13789 10064 13789 10066 13789 10063 13790 10064 13790 10067 13790 10072 13791 10069 13791 10068 13791 10063 13792 10067 13792 10072 13792 10063 13793 10072 13793 10068 13793 10073 13794 10069 13794 10072 13794 10074 13795 10069 13795 10073 13795 10074 13796 10070 13796 10069 13796 10068 13797 10069 13797 10070 13797 10071 13798 10076 13798 10075 13798 10068 13799 10070 13799 10075 13799 10075 13800 10070 13800 10071 13800 10076 13801 10078 13801 10079 13801 10077 13802 10076 13802 10080 13802 10080 13803 10076 13803 10079 13803 10078 13804 10076 13804 10071 13804 10077 13805 10082 13805 10081 13805 10075 13806 10076 13806 10077 13806 10075 13807 10077 13807 10081 13807 10085 13808 10082 13808 10077 13808 10086 13809 10082 13809 10085 13809 10087 13810 10082 13810 10086 13810 10083 13811 10082 13811 10087 13811 10088 13812 10055 13812 10054 13812 10084 13813 10088 13813 10054 13813 10081 13814 10082 13814 10083 13814 10081 13815 10083 13815 10054 13815 10054 13816 10083 13816 10084 13816 10089 13817 10055 13817 10088 13817 10059 13818 10055 13818 10090 13818 10090 13819 10055 13819 10089 13819 10091 13820 10101 13820 10093 13820 10093 13821 10089 13821 10088 13821 10093 13822 10088 13822 10091 13822 10094 13823 10057 13823 10093 13823 10093 13824 10057 13824 10059 13824 10093 13825 10059 13825 10089 13825 10094 13826 10095 13826 10057 13826 10096 13827 10071 13827 10097 13827 10096 13828 10097 13828 10092 13828 10098 13829 10062 13829 10094 13829 10094 13830 10062 13830 10095 13830 10097 13831 10074 13831 10092 13831 10092 13832 10074 13832 10099 13832 10092 13833 10099 13833 10072 13833 10096 13834 10100 13834 10071 13834 10098 13835 10060 13835 10062 13835 10101 13836 10086 13836 10102 13836 10101 13837 10102 13837 10103 13837 10091 13838 10084 13838 10101 13838 10101 13839 10084 13839 10083 13839 10101 13840 10083 13840 10104 13840 10101 13841 10104 13841 10086 13841 10098 13842 10066 13842 10060 13842 10092 13843 10072 13843 10067 13843 10092 13844 10067 13844 10098 13844 10098 13845 10067 13845 10066 13845 10103 13846 10105 13846 10096 13846 10096 13847 10105 13847 10079 13847 10096 13848 10079 13848 10106 13848 10096 13849 10106 13849 10100 13849 10102 13850 10077 13850 10103 13850 10103 13851 10077 13851 10105 13851 10093 13852 10101 13852 10107 13852 10107 13853 10108 13853 10093 13853 10093 13854 10108 13854 10094 13854 10094 13855 10108 13855 10109 13855 10094 13856 10109 13856 10098 13856 10109 13857 10110 13857 10098 13857 10098 13858 10110 13858 10092 13858 10111 13859 10092 13859 10110 13859 10092 13860 10111 13860 10096 13860 10111 13861 10112 13861 10096 13861 10112 13862 10113 13862 10096 13862 10096 13863 10113 13863 10103 13863 10113 13864 10114 13864 10103 13864 10103 13865 10114 13865 10101 13865 10107 13866 10101 13866 10114 13866 10115 13867 10107 13867 10114 13867 10115 13868 10114 13868 10116 13868 10116 13869 10114 13869 10113 13869 10116 13870 10113 13870 10117 13870 10117 13871 10113 13871 10112 13871 10117 13872 10112 13872 10118 13872 10118 13873 10112 13873 10111 13873 10118 13874 10111 13874 10119 13874 10119 13875 10111 13875 10110 13875 10119 13876 10110 13876 10109 13876 10119 13877 10109 13877 10120 13877 10120 13878 10109 13878 10121 13878 10121 13879 10109 13879 10108 13879 10121 13880 10108 13880 10122 13880 10122 13881 10108 13881 10107 13881 10122 13882 10107 13882 10115 13882 10123 13883 10119 13883 10124 13883 10119 13884 10120 13884 10124 13884 10120 13885 10121 13885 10124 13885 10124 13886 10121 13886 10125 13886 10121 13887 10122 13887 10125 13887 10125 13888 10122 13888 10126 13888 10115 13889 10126 13889 10122 13889 10126 13890 10115 13890 10127 13890 10115 13891 10116 13891 10127 13891 10127 13892 10116 13892 10128 13892 10116 13893 10117 13893 10128 13893 10128 13894 10117 13894 10129 13894 10117 13895 10118 13895 10129 13895 10119 13896 10123 13896 10118 13896 10118 13897 10123 13897 10129 13897 10126 13898 10127 13898 10081 13898 10063 13899 10123 13899 10124 13899 10063 13900 10124 13900 10056 13900 10056 13901 10124 13901 10125 13901 10056 13902 10125 13902 10054 13902 10081 13903 10127 13903 10075 13903 10075 13904 10127 13904 10128 13904 10075 13905 10128 13905 10068 13905 10068 13906 10128 13906 10129 13906 10054 13907 10125 13907 10126 13907 10054 13908 10126 13908 10081 13908 10068 13909 10129 13909 10063 13909 10063 13910 10129 13910 10123 13910 10130 13911 10131 13911 10132 13911 10130 13912 10132 13912 10133 13912 10134 13913 10135 13913 10130 13913 10130 13914 10135 13914 10131 13914 10136 13915 10140 13915 10137 13915 10136 13916 10137 13916 10134 13916 10134 13917 10137 13917 10135 13917 10138 13918 10139 13918 10136 13918 10136 13919 10139 13919 10140 13919 10143 13920 10141 13920 10138 13920 10138 13921 10141 13921 10139 13921 10133 13922 10142 13922 10143 13922 10143 13923 10142 13923 10141 13923 10132 13924 10144 13924 10133 13924 10133 13925 10144 13925 10142 13925 10145 13926 10146 13926 10147 13926 10147 13927 10146 13927 10148 13927 10147 13928 10148 13928 10149 13928 10149 13929 10148 13929 10150 13929 10150 13930 10148 13930 10151 13930 10150 13931 10151 13931 10152 13931 10152 13932 10151 13932 10153 13932 10153 13933 10151 13933 10154 13933 10153 13934 10154 13934 10155 13934 10155 8785 10154 8785 10156 8785 10155 13935 10156 13935 10157 13935 10157 13936 10156 13936 10158 13936 10158 13937 10156 13937 10159 13937 10158 13938 10159 13938 10160 13938 10160 13939 10159 13939 10161 13939 10159 13940 10162 13940 10161 13940 10161 13941 10162 13941 10163 13941 10163 13942 10162 13942 10164 13942 10163 3519 10164 3519 10165 3519 10165 13943 10164 13943 10166 13943 10166 13944 10164 13944 10167 13944 10166 8785 10167 8785 10168 8785 10168 13945 10167 13945 10169 13945 10169 13946 10167 13946 10170 13946 10169 13947 10170 13947 10171 13947 10171 13948 10170 13948 10172 13948 10172 13949 10170 13949 10173 13949 10172 13950 10173 13950 10174 13950 10174 13951 10173 13951 10175 13951 10174 13952 10175 13952 10176 13952 10176 13953 10175 13953 10177 13953 10177 13954 10175 13954 10178 13954 10177 13955 10178 13955 10179 13955 10179 13956 10178 13956 10180 13956 10179 13957 10180 13957 10181 13957 10181 13958 10180 13958 10182 13958 10182 13959 10180 13959 10183 13959 10182 13960 10183 13960 10184 13960 10184 13961 10183 13961 10185 13961 10184 13962 10185 13962 10186 13962 10186 13963 10185 13963 10187 13963 10187 13964 10185 13964 10188 13964 10187 8783 10188 8783 10189 8783 10189 13965 10188 13965 10190 13965 10190 13966 10188 13966 10191 13966 10190 8787 10191 8787 10192 8787 10192 13967 10191 13967 10193 13967 10193 13968 10191 13968 10194 13968 10193 13969 10194 13969 10145 13969 10145 13970 10194 13970 10146 13970 10196 13971 10195 13971 10197 13971 10197 13972 10195 13972 10198 13972 10197 13973 10198 13973 10199 13973 10199 13974 10198 13974 10200 13974 10200 13975 10201 13975 10199 13975 10201 13976 10200 13976 10202 13976 10202 13977 10203 13977 10201 13977 10203 13978 10202 13978 10204 13978 10204 13979 10205 13979 10203 13979 10205 13980 10204 13980 10206 13980 10206 13981 10207 13981 10205 13981 10207 13982 10206 13982 10208 13982 10208 13983 10209 13983 10207 13983 10209 13984 10208 13984 10210 13984 10210 13985 10211 13985 10209 13985 10211 13986 10210 13986 10212 13986 10212 13987 10213 13987 10211 13987 10213 13988 10212 13988 10253 13988 10214 13989 10213 13989 10253 13989 10213 13990 10214 13990 10215 13990 10215 13991 10214 13991 10216 13991 10215 13992 10216 13992 10196 13992 10196 13993 10216 13993 10195 13993 10196 13994 10197 13994 10205 13994 10213 13995 10215 13995 10205 13995 10205 13996 10215 13996 10196 13996 10205 13997 10211 13997 10213 13997 10205 13998 10209 13998 10211 13998 10197 13999 10199 13999 10205 13999 10205 14000 10199 14000 10203 14000 10131 14001 10218 14001 10217 14001 10217 14002 10218 14002 10219 14002 10218 14003 10220 14003 10219 14003 10219 14004 10220 14004 10221 14004 10221 14005 10220 14005 10137 14005 10221 14006 10137 14006 10222 14006 10222 14007 10137 14007 10223 14007 10223 14008 10224 14008 10222 14008 10222 14009 10224 14009 10225 14009 10225 14010 10224 14010 10139 14010 10225 14011 10139 14011 10226 14011 10226 14012 10139 14012 10227 14012 10226 14013 10227 14013 10228 14013 10228 14014 10227 14014 10229 14014 10229 14015 10230 14015 10228 14015 10228 14016 10230 14016 10231 14016 10231 14017 10230 14017 10232 14017 10230 14018 10233 14018 10232 14018 10232 14019 10233 14019 10144 14019 10232 14020 10144 14020 10234 14020 10234 14021 10144 14021 10132 14021 10234 14022 10132 14022 10217 14022 10132 14023 10131 14023 10217 14023 10139 14024 10224 14024 10140 14024 10224 14025 10223 14025 10140 14025 10140 14026 10223 14026 10137 14026 10137 14027 10220 14027 10135 14027 10220 14028 10218 14028 10135 14028 10135 14029 10218 14029 10131 14029 10144 14030 10233 14030 10142 14030 10233 14031 10230 14031 10142 14031 10142 14032 10230 14032 10141 14032 10230 14033 10229 14033 10141 14033 10141 14034 10229 14034 10227 14034 10141 14035 10227 14035 10139 14035 10207 14036 10209 14036 10205 14036 10201 14037 10203 14037 10199 14037 10136 14038 10235 14038 10138 14038 10134 14039 10236 14039 10136 14039 10130 14040 10237 14040 10134 14040 10133 14041 10238 14041 10130 14041 10143 14042 10239 14042 10133 14042 10138 14043 10240 14043 10143 14043 10242 14044 10246 14044 10247 14044 10241 14045 10242 14045 10247 14045 10242 14046 10245 14046 10246 14046 10244 14047 10245 14047 10242 14047 10243 14048 10244 14048 10242 14048 10241 14049 10243 14049 10242 14049 10136 14050 10245 14050 10235 14050 10244 14051 10138 14051 10235 14051 10235 14052 10245 14052 10244 14052 10236 14053 10134 14053 10246 14053 10245 14054 10136 14054 10236 14054 10246 14055 10245 14055 10236 14055 10247 14056 10237 14056 10130 14056 10246 14057 10134 14057 10237 14057 10246 14058 10237 14058 10247 14058 10247 14059 10130 14059 10241 14059 10241 14060 10130 14060 10238 14060 10241 14061 10238 14061 10133 14061 10143 14062 10243 14062 10239 14062 10239 14063 10243 14063 10241 14063 10239 14064 10241 14064 10133 14064 10138 14065 10244 14065 10240 14065 10243 14066 10143 14066 10240 14066 10240 14067 10244 14067 10243 14067 10248 14068 10214 14068 10252 14068 10252 14069 10214 14069 10253 14069 10253 14070 10212 14070 10254 14070 10254 14071 10212 14071 10255 14071 10255 14072 10212 14072 10210 14072 10255 14073 10210 14073 10256 14073 10256 14074 10210 14074 10257 14074 10257 14075 10210 14075 10208 14075 10257 14076 10208 14076 10258 14076 10258 14077 10208 14077 10206 14077 10258 14078 10206 14078 10259 14078 10259 14079 10206 14079 10260 14079 10260 14080 10206 14080 10204 14080 10260 14081 10204 14081 10261 14081 10261 14082 10204 14082 10202 14082 10261 14083 10202 14083 10262 14083 10262 14084 10202 14084 10263 14084 10263 14085 10202 14085 10200 14085 10263 14086 10200 14086 10264 14086 10264 14087 10200 14087 10265 14087 10265 14088 10200 14088 10198 14088 10265 14089 10198 14089 10251 14089 10266 14090 10195 14090 10249 14090 10249 14091 10195 14091 10216 14091 10195 14092 10266 14092 10250 14092 10250 14093 10251 14093 10198 14093 10250 14094 10198 14094 10195 14094 10248 14095 10249 14095 10216 14095 10248 14096 10216 14096 10214 14096 10277 14097 10267 14097 10268 14097 10268 14098 10267 14098 10269 14098 10268 14099 10269 14099 10270 14099 10270 14100 10269 14100 10271 14100 10270 14101 10271 14101 10272 14101 10272 14102 10271 14102 10273 14102 10272 14103 10273 14103 10274 14103 10275 14104 10280 14104 10276 14104 10275 14105 10276 14105 10277 14105 10277 14106 10276 14106 10267 14106 10272 14107 10274 14107 10278 14107 10278 14108 10274 14108 10279 14108 10278 14109 10279 14109 10275 14109 10275 14110 10279 14110 10280 14110 10281 14111 10288 14111 10282 14111 10282 14112 10288 14112 10283 14112 10282 14113 10283 14113 10284 14113 10285 14114 10286 14114 10287 14114 10287 14115 10286 14115 10288 14115 10287 14116 10288 14116 10281 14116 10283 14117 10289 14117 10284 14117 10284 14118 10289 14118 10290 14118 10290 14119 10289 14119 10291 14119 10291 14120 10289 14120 10292 14120 10291 14121 10292 14121 10293 14121 10293 14122 10292 14122 10294 14122 10293 14123 10294 14123 10295 14123 10295 14124 10294 14124 10296 14124 10296 14125 10294 14125 10297 14125 10296 14126 10297 14126 10298 14126 10298 14127 10297 14127 10299 14127 10298 14128 10299 14128 10300 14128 10300 14129 10299 14129 10285 14129 10285 14130 10299 14130 10286 14130 10302 14131 10301 14131 10304 14131 10302 14132 10304 14132 10303 14132 10303 14133 10304 14133 10305 14133 10303 14134 10305 14134 10306 14134 10306 14135 10305 14135 10307 14135 10306 14136 10307 14136 10352 14136 10306 14137 10352 14137 10308 14137 10309 14138 10308 14138 10352 14138 10308 14139 10309 14139 10311 14139 10308 14140 10311 14140 10310 14140 10310 14141 10311 14141 10312 14141 10310 14142 10312 14142 10313 14142 10313 14143 10312 14143 10314 14143 10313 14144 10314 14144 10315 14144 10316 14145 10315 14145 10314 14145 10315 14146 10316 14146 10318 14146 10315 14147 10318 14147 10317 14147 10317 14148 10318 14148 10319 14148 10317 14149 10319 14149 10320 14149 10320 14150 10319 14150 10353 14150 10320 14151 10353 14151 10302 14151 10302 14152 10353 14152 10301 14152 10322 14153 10321 14153 10323 14153 10322 14154 10325 14154 10324 14154 10326 14155 10325 14155 10322 14155 10323 14156 10326 14156 10322 14156 10327 14157 10300 14157 10285 14157 10327 14158 10285 14158 10328 14158 10328 14159 10285 14159 10287 14159 10328 14160 10287 14160 10329 14160 10329 14161 10287 14161 10281 14161 10329 14162 10281 14162 10330 14162 10330 14163 10281 14163 10282 14163 10330 14164 10282 14164 10331 14164 10331 14165 10282 14165 10284 14165 10331 14166 10284 14166 10332 14166 10332 14167 10284 14167 10333 14167 10333 14168 10284 14168 10290 14168 10333 14169 10290 14169 10334 14169 10334 14170 10290 14170 10291 14170 10334 14171 10291 14171 10293 14171 10334 14172 10293 14172 10335 14172 10335 14173 10293 14173 10336 14173 10336 14174 10293 14174 10295 14174 10336 14175 10295 14175 10337 14175 10337 14176 10295 14176 10296 14176 10337 14177 10296 14177 10298 14177 10337 14178 10298 14178 10338 14178 10338 14179 10298 14179 10300 14179 10338 14180 10300 14180 10327 14180 10333 14181 10276 14181 10332 14181 10332 14182 10276 14182 10280 14182 10332 14183 10280 14183 10331 14183 10331 14184 10280 14184 10330 14184 10330 14185 10280 14185 10279 14185 10330 14186 10279 14186 10329 14186 10329 14187 10279 14187 10328 14187 10328 14188 10279 14188 10274 14188 10328 14189 10274 14189 10327 14189 10327 14190 10274 14190 10273 14190 10327 14191 10273 14191 10338 14191 10338 14192 10273 14192 10271 14192 10338 14193 10271 14193 10337 14193 10337 14194 10271 14194 10269 14194 10337 14195 10269 14195 10336 14195 10336 14196 10269 14196 10335 14196 10335 14197 10269 14197 10267 14197 10335 14198 10267 14198 10334 14198 10334 14199 10267 14199 10276 14199 10334 14200 10276 14200 10333 14200 10302 14201 10321 14201 10320 14201 10320 14202 10321 14202 10317 14202 10317 14203 10321 14203 10322 14203 10317 14204 10322 14204 10315 14204 10315 14205 10322 14205 10324 14205 10315 14206 10324 14206 10313 14206 10313 14207 10324 14207 10325 14207 10313 14208 10325 14208 10310 14208 10310 14209 10325 14209 10308 14209 10308 14210 10325 14210 10326 14210 10308 14211 10326 14211 10306 14211 10306 14212 10326 14212 10323 14212 10306 14213 10323 14213 10303 14213 10303 14214 10323 14214 10302 14214 10302 14215 10323 14215 10321 14215 10268 14216 10339 14216 10277 14216 10270 14217 10340 14217 10268 14217 10272 14218 10341 14218 10270 14218 10278 14219 10342 14219 10272 14219 10275 14220 10343 14220 10278 14220 10277 14221 10344 14221 10275 14221 10346 14222 10347 14222 10348 14222 10349 14223 10345 14223 10346 14223 10350 14224 10349 14224 10346 14224 10348 14225 10350 14225 10346 14225 10346 14226 10351 14226 10347 14226 10345 14227 10351 14227 10346 14227 10268 14228 10350 14228 10339 14228 10348 14229 10277 14229 10339 14229 10348 14230 10339 14230 10350 14230 10270 14231 10349 14231 10340 14231 10350 14232 10268 14232 10340 14232 10350 14233 10340 14233 10349 14233 10272 14234 10345 14234 10341 14234 10349 14235 10270 14235 10341 14235 10349 14236 10341 14236 10345 14236 10278 14237 10351 14237 10342 14237 10345 14238 10272 14238 10342 14238 10345 14239 10342 14239 10351 14239 10275 14240 10347 14240 10343 14240 10351 14241 10278 14241 10343 14241 10351 14242 10343 14242 10347 14242 10277 14243 10348 14243 10344 14243 10347 14244 10275 14244 10344 14244 10347 14245 10344 14245 10348 14245 10294 14246 10292 14246 10352 14246 10297 14247 10304 14247 10299 14247 10292 14248 10311 14248 10309 14248 10292 14249 10309 14249 10352 14249 10288 14250 10318 14250 10316 14250 10288 14251 10316 14251 10283 14251 10283 14252 10316 14252 10314 14252 10299 14253 10304 14253 10301 14253 10299 14254 10301 14254 10353 14254 10297 14255 10305 14255 10304 14255 10297 14256 10294 14256 10307 14256 10297 14257 10307 14257 10305 14257 10294 14258 10352 14258 10307 14258 10292 14259 10289 14259 10311 14259 10289 14260 10312 14260 10311 14260 10289 14261 10283 14261 10312 14261 10283 14262 10314 14262 10312 14262 10288 14263 10286 14263 10318 14263 10286 14264 10319 14264 10318 14264 10286 14265 10353 14265 10319 14265 10286 14266 10299 14266 10353 14266 10363 14267 10354 14267 10355 14267 10355 14268 10354 14268 10356 14268 10355 14269 10356 14269 10357 14269 10355 14270 10357 14270 10358 14270 10358 14271 10357 14271 10359 14271 10358 14272 10359 14272 10360 14272 10361 14273 10366 14273 10362 14273 10361 14274 10362 14274 10363 14274 10363 14275 10362 14275 10354 14275 10364 14276 10368 14276 10365 14276 10364 14277 10365 14277 10361 14277 10361 14278 10365 14278 10366 14278 10359 14279 10367 14279 10360 14279 10360 14280 10367 14280 10368 14280 10360 14281 10368 14281 10364 14281 10369 14282 10385 14282 10370 14282 10370 14283 10385 14283 10371 14283 10370 14284 10371 14284 10372 14284 10370 14285 10372 14285 10373 14285 10374 14286 10389 14286 10375 14286 10375 14287 10389 14287 10376 14287 10375 14288 10376 14288 10377 14288 10378 14289 10379 14289 10380 14289 10380 14290 10379 14290 10381 14290 10380 14291 10381 14291 10382 14291 10376 14292 10383 14292 10377 14292 10377 14293 10383 14293 10384 14293 10384 14294 10383 14294 10385 14294 10384 14295 10385 14295 10369 14295 10373 14296 10372 14296 10386 14296 10386 14297 10372 14297 10387 14297 10386 14298 10387 14298 10388 14298 10388 14299 10387 14299 10378 14299 10378 14300 10387 14300 10379 14300 10382 14301 10381 14301 10389 14301 10382 14302 10389 14302 10374 14302 10391 14303 10390 14303 10393 14303 10391 14304 10393 14304 10392 14304 10392 14305 10393 14305 10441 14305 10392 14306 10441 14306 10394 14306 10395 14307 10394 14307 10441 14307 10394 14308 10395 14308 10397 14308 10394 14309 10397 14309 10396 14309 10396 14310 10397 14310 10399 14310 10399 14311 10397 14311 10443 14311 10399 14312 10443 14312 10398 14312 10399 14313 10398 14313 10400 14313 10401 14314 10400 14314 10398 14314 10400 14315 10401 14315 10402 14315 10400 14316 10402 14316 10403 14316 10403 14317 10402 14317 10442 14317 10403 14318 10442 14318 10404 14318 10405 14319 10404 14319 10442 14319 10404 14320 10405 14320 10407 14320 10404 14321 10407 14321 10406 14321 10406 14322 10407 14322 10408 14322 10406 14323 10408 14323 10391 14323 10391 14324 10408 14324 10390 14324 10410 14325 10413 14325 10409 14325 10409 14326 10411 14326 10410 14326 10409 14327 10413 14327 10412 14327 10382 14328 10414 14328 10380 14328 10380 14329 10414 14329 10415 14329 10380 14330 10415 14330 10378 14330 10378 14331 10415 14331 10416 14331 10378 14332 10416 14332 10417 14332 10378 14333 10417 14333 10388 14333 10388 14334 10417 14334 10386 14334 10386 14335 10417 14335 10418 14335 10386 14336 10418 14336 10419 14336 10386 14337 10419 14337 10373 14337 10373 14338 10419 14338 10420 14338 10373 14339 10420 14339 10370 14339 10370 14340 10420 14340 10421 14340 10370 14341 10421 14341 10369 14341 10369 14342 10421 14342 10422 14342 10369 14343 10422 14343 10384 14343 10384 14344 10422 14344 10423 14344 10384 14345 10423 14345 10377 14345 10377 14346 10423 14346 10424 14346 10377 14347 10424 14347 10425 14347 10377 14348 10425 14348 10375 14348 10375 14349 10425 14349 10374 14349 10374 14350 10425 14350 10426 14350 10374 14351 10426 14351 10382 14351 10382 14352 10426 14352 10414 14352 10362 14353 10420 14353 10354 14353 10420 14354 10419 14354 10354 14354 10419 14355 10418 14355 10354 14355 10354 14356 10418 14356 10356 14356 10418 14357 10417 14357 10356 14357 10356 14358 10417 14358 10357 14358 10417 14359 10416 14359 10357 14359 10357 14360 10416 14360 10359 14360 10416 14361 10415 14361 10359 14361 10359 14362 10415 14362 10414 14362 10359 14363 10414 14363 10367 14363 10414 14364 10426 14364 10367 14364 10367 14365 10426 14365 10368 14365 10426 14366 10425 14366 10368 14366 10368 14367 10425 14367 10424 14367 10368 14368 10424 14368 10365 14368 10424 14369 10423 14369 10365 14369 10365 14370 10423 14370 10366 14370 10423 14371 10422 14371 10366 14371 10366 14372 10422 14372 10421 14372 10366 14373 10421 14373 10362 14373 10421 14374 10420 14374 10362 14374 10391 14375 10410 14375 10406 14375 10406 14376 10410 14376 10404 14376 10404 14377 10410 14377 10411 14377 10404 14378 10411 14378 10403 14378 10403 14379 10411 14379 10409 14379 10403 14380 10409 14380 10400 14380 10400 14381 10409 14381 10399 14381 10399 14382 10409 14382 10412 14382 10399 14383 10412 14383 10396 14383 10396 14384 10412 14384 10394 14384 10394 14385 10412 14385 10413 14385 10394 14386 10413 14386 10392 14386 10392 14387 10413 14387 10391 14387 10391 14388 10413 14388 10410 14388 10355 14389 10427 14389 10363 14389 10358 14390 10428 14390 10355 14390 10360 14391 10429 14391 10358 14391 10364 14392 10430 14392 10360 14392 10361 14393 10431 14393 10364 14393 10363 14394 10432 14394 10361 14394 10436 14395 10434 14395 10435 14395 10434 14396 10437 14396 10433 14396 10438 14397 10437 14397 10434 14397 10438 14398 10434 14398 10436 14398 10439 14399 10435 14399 10434 14399 10439 14400 10434 14400 10433 14400 10436 14401 10363 14401 10427 14401 10436 14402 10427 14402 10438 14402 10438 14403 10427 14403 10355 14403 10358 14404 10437 14404 10428 14404 10428 14405 10437 14405 10438 14405 10428 14406 10438 14406 10355 14406 10360 14407 10433 14407 10429 14407 10437 14408 10358 14408 10429 14408 10433 14409 10437 14409 10429 14409 10433 14410 10360 14410 10430 14410 10433 14411 10430 14411 10439 14411 10439 14412 10430 14412 10364 14412 10361 14413 10435 14413 10431 14413 10431 14414 10435 14414 10439 14414 10431 14415 10439 14415 10364 14415 10363 14416 10436 14416 10432 14416 10435 14417 10361 14417 10432 14417 10436 14418 10435 14418 10432 14418 10381 14419 10440 14419 10389 14419 10387 14420 10395 14420 10379 14420 10379 14421 10395 14421 10441 14421 10376 14422 10405 14422 10383 14422 10383 14423 10405 14423 10442 14423 10389 14424 10440 14424 10408 14424 10387 14425 10397 14425 10395 14425 10376 14426 10407 14426 10405 14426 10440 14427 10393 14427 10390 14427 10440 14428 10390 14428 10408 14428 10381 14429 10379 14429 10440 14429 10440 14430 10379 14430 10441 14430 10440 14431 10441 14431 10393 14431 10387 14432 10372 14432 10397 14432 10372 14433 10443 14433 10397 14433 10372 14434 10398 14434 10443 14434 10372 14435 10371 14435 10398 14435 10371 14436 10401 14436 10398 14436 10371 14437 10385 14437 10401 14437 10385 14438 10402 14438 10401 14438 10385 14439 10383 14439 10442 14439 10385 14440 10442 14440 10402 14440 10376 14441 10389 14441 10407 14441 10389 14442 10408 14442 10407 14442 10444 14443 10445 14443 10446 14443 10446 14444 10445 14444 10447 14444 10446 14445 10447 14445 10448 14445 10448 14446 10447 14446 10449 14446 10448 14447 10449 14447 10450 14447 10450 14448 10449 14448 10451 14448 10450 14449 10451 14449 10452 14449 10452 14450 10451 14450 10453 14450 10453 14451 10451 14451 10454 14451 10453 14452 10454 14452 10455 14452 10453 14453 10455 14453 10456 14453 10456 14454 10455 14454 10457 14454 10456 14455 10457 14455 10458 14455 10458 14456 10457 14456 10459 14456 10458 14457 10459 14457 10460 14457 10458 14458 10460 14458 10461 14458 10461 14459 10460 14459 10462 14459 10461 14460 10462 14460 10444 14460 10444 14461 10462 14461 10445 14461 10459 14462 10457 14462 10455 14462 10455 14463 10460 14463 10459 14463 10455 8505 10462 8505 10460 8505 10447 8505 10445 8505 10455 8505 10455 8505 10445 8505 10462 8505 10455 14464 10449 14464 10447 14464 10455 14465 10451 14465 10449 14465 10450 8646 10452 8646 10463 8646 10463 8646 10452 8646 10453 8646 10463 14466 10448 14466 10450 14466 10444 8646 10446 8646 10463 8646 10463 8646 10446 8646 10448 8646 10463 8646 10461 8646 10444 8646 10463 8646 10458 8646 10461 8646 10463 8646 10456 8646 10458 8646 10464 5147 10465 5147 10466 5147 10466 14467 10465 14467 10467 14467 10468 14468 10464 14468 10469 14468 10469 5149 10464 5149 10466 5149 10470 5143 10468 5143 10471 5143 10471 5143 10468 5143 10469 5143 10465 14469 10470 14469 10467 14469 10467 5146 10470 5146 10471 5146 10468 324 10470 324 10464 324 10464 324 10470 324 10465 324 10471 348 10469 348 10467 348 10467 348 10469 348 10466 348 10472 8505 10473 8505 10474 8505 10474 8505 10473 8505 10475 8505 10476 8505 10477 8505 10478 8505 10478 8505 10477 8505 10479 8505 10480 348 10481 348 10482 348 10483 14470 10484 14470 10485 14470 10486 348 10487 348 10488 348 10489 14471 10481 14471 10490 14471 10489 14472 10490 14472 10491 14472 10492 348 10493 348 10494 348 10494 348 10493 348 10495 348 10494 348 10495 348 10483 348 10494 348 10483 348 10485 348 10473 14473 10496 14473 10475 14473 10475 348 10496 348 10497 348 10497 348 10496 348 10498 348 10497 348 10498 348 10487 348 10489 348 10491 348 10499 348 10489 14474 10499 14474 10478 14474 10478 348 10499 348 10476 348 10476 348 10499 348 10500 348 10492 348 10501 348 10493 348 10493 14475 10501 14475 10502 14475 10502 14476 10503 14476 10493 14476 10493 348 10503 348 10473 348 10473 348 10503 348 10504 348 10473 14477 10504 14477 10496 14477 10486 348 10488 348 10502 348 10486 348 10502 348 10505 348 10505 348 10502 348 10501 348 10483 14478 10482 14478 10484 14478 10484 14479 10482 14479 10481 14479 10484 14480 10481 14480 10489 14480 10484 348 10489 348 10486 348 10486 14481 10489 14481 10497 14481 10486 348 10497 348 10487 348 10506 14482 10507 14482 10476 14482 10476 348 10507 348 10508 348 10507 348 10509 348 10508 348 10508 14483 10509 14483 10510 14483 10508 14484 10510 14484 10511 14484 10511 348 10510 348 10482 348 10482 348 10510 348 10512 348 10482 348 10512 348 10480 348 10500 348 10513 348 10476 348 10476 14485 10513 14485 10506 14485 10513 348 10514 348 10506 348 10506 14486 10514 14486 10515 14486 10506 348 10515 348 10481 348 10481 348 10515 348 10490 348 10516 324 10517 324 10518 324 10519 324 10520 324 10521 324 10522 324 10472 324 10523 324 10523 324 10472 324 10474 324 10523 324 10474 324 10524 324 10523 324 10524 324 10525 324 10526 324 10477 324 10519 324 10521 324 10520 324 10529 324 10521 324 10529 324 10530 324 10531 324 10532 324 10533 324 10533 324 10532 324 10534 324 10534 324 10532 324 10535 324 10534 324 10535 324 10536 324 10521 324 10537 324 10519 324 10519 324 10537 324 10538 324 10526 324 10539 324 10477 324 10477 324 10539 324 10540 324 10477 324 10540 324 10479 324 10479 324 10540 324 10527 324 10527 324 10540 324 10541 324 10527 324 10541 324 10528 324 10522 324 10542 324 10472 324 10472 324 10542 324 10531 324 10531 324 10542 324 10543 324 10531 324 10543 324 10518 324 10517 324 10544 324 10518 324 10518 324 10544 324 10531 324 10531 324 10544 324 10545 324 10531 324 10545 324 10532 324 10546 324 10547 324 10538 324 10538 324 10547 324 10548 324 10538 324 10548 324 10519 324 10519 324 10548 324 10526 324 10546 324 10549 324 10547 324 10547 324 10549 324 10550 324 10547 324 10550 324 10551 324 10534 324 10552 324 10529 324 10529 14487 10552 14487 10530 14487 10516 324 10518 324 10553 324 10516 14488 10553 14488 10527 14488 10527 14489 10553 14489 10554 14489 10527 324 10554 324 10524 324 10524 14490 10554 14490 10525 14490 10528 14491 10551 14491 10527 14491 10527 14492 10551 14492 10550 14492 10527 324 10550 324 10516 324 10516 14493 10550 14493 10552 14493 10516 324 10552 324 10555 324 10555 324 10552 324 10534 324 10555 324 10534 324 10536 324 10495 8646 10493 8646 10533 8646 10533 8646 10493 8646 10531 8646 10520 8646 10519 8646 10511 8646 10511 8646 10519 8646 10508 8646 10476 8511 10508 8511 10477 8511 10477 8511 10508 8511 10519 8511 10493 8507 10473 8507 10531 8507 10531 8507 10473 8507 10472 8507 10523 14494 10496 14494 10522 14494 10522 14495 10496 14495 10542 14495 10542 14496 10496 14496 10504 14496 10542 14497 10504 14497 10503 14497 10542 14498 10503 14498 10543 14498 10543 14499 10503 14499 10518 14499 10518 14500 10503 14500 10502 14500 10518 14501 10502 14501 10553 14501 10553 14502 10502 14502 10488 14502 10553 14503 10488 14503 10554 14503 10554 14504 10488 14504 10487 14504 10554 14505 10487 14505 10525 14505 10525 14506 10487 14506 10523 14506 10523 14507 10487 14507 10498 14507 10523 14508 10498 14508 10496 14508 10540 14509 10499 14509 10541 14509 10541 14510 10499 14510 10528 14510 10528 14511 10499 14511 10491 14511 10528 14512 10491 14512 10551 14512 10551 14513 10491 14513 10490 14513 10551 14514 10490 14514 10547 14514 10547 14515 10490 14515 10515 14515 10547 14516 10515 14516 10548 14516 10548 14517 10515 14517 10526 14517 10526 14518 10515 14518 10514 14518 10526 14519 10514 14519 10513 14519 10526 14520 10513 14520 10539 14520 10539 14506 10513 14506 10540 14506 10540 14521 10513 14521 10500 14521 10540 14522 10500 14522 10499 14522 10549 14523 10506 14523 10550 14523 10550 14524 10506 14524 10481 14524 10550 14525 10481 14525 10552 14525 10552 14526 10481 14526 10480 14526 10552 14527 10480 14527 10530 14527 10530 14528 10480 14528 10521 14528 10521 14529 10480 14529 10512 14529 10521 14530 10512 14530 10510 14530 10521 14531 10510 14531 10537 14531 10537 14532 10510 14532 10538 14532 10538 14518 10510 14518 10509 14518 10538 14533 10509 14533 10507 14533 10538 14534 10507 14534 10546 14534 10546 14535 10507 14535 10549 14535 10549 14536 10507 14536 10506 14536 10516 14537 10486 14537 10517 14537 10517 14538 10486 14538 10544 14538 10544 14496 10486 14496 10505 14496 10544 14539 10505 14539 10501 14539 10544 14540 10501 14540 10545 14540 10545 14528 10501 14528 10532 14528 10532 14541 10501 14541 10492 14541 10532 14542 10492 14542 10494 14542 10532 14543 10494 14543 10535 14543 10535 14544 10494 14544 10536 14544 10536 14545 10494 14545 10485 14545 10536 14546 10485 14546 10555 14546 10555 14547 10485 14547 10484 14547 10555 14548 10484 14548 10516 14548 10516 14549 10484 14549 10486 14549 10495 14550 10533 14550 10483 14550 10483 14550 10533 14550 10534 14550 10483 8646 10534 8646 10482 8646 10482 8646 10534 8646 10529 8646 10482 14551 10529 14551 10511 14551 10511 14551 10529 14551 10520 14551 10475 14552 10497 14552 10474 14552 10474 14552 10497 14552 10524 14552 10489 14553 10478 14553 10527 14553 10527 14553 10478 14553 10479 14553 10497 8505 10489 8505 10524 8505 10524 8505 10489 8505 10527 8505 10556 14554 10557 14554 10558 14554 10558 14555 10557 14555 10559 14555 10558 14556 10559 14556 10560 14556 10560 14557 10559 14557 10561 14557 10560 14558 10561 14558 10562 14558 10560 14559 10562 14559 10563 14559 10563 14560 10562 14560 10564 14560 10563 14561 10564 14561 10565 14561 10565 14562 10564 14562 10566 14562 10565 14563 10566 14563 10567 14563 10565 14564 10567 14564 10568 14564 10568 14565 10567 14565 10569 14565 10568 14566 10569 14566 10570 14566 10570 14567 10569 14567 10571 14567 10570 14568 10571 14568 10572 14568 10572 14569 10571 14569 10573 14569 10572 14570 10573 14570 10574 14570 10574 14571 10573 14571 10575 14571 10574 14572 10575 14572 10576 14572 10576 14573 10575 14573 10577 14573 10576 14574 10577 14574 10578 14574 10578 14575 10577 14575 10579 14575 10578 14576 10579 14576 10556 14576 10556 14577 10579 14577 10557 14577 10580 324 10569 324 10567 324 10580 324 10567 324 10581 324 10582 324 10571 324 10569 324 10582 324 10569 324 10580 324 10583 324 10575 324 10573 324 10583 324 10573 324 10582 324 10582 324 10573 324 10571 324 10585 324 10557 324 10584 324 10584 324 10557 324 10579 324 10567 324 10566 324 10581 324 10581 324 10566 324 10564 324 10584 324 10579 324 10583 324 10583 324 10579 324 10577 324 10583 324 10577 324 10575 324 10586 324 10559 324 10585 324 10585 324 10559 324 10557 324 10586 324 10561 324 10559 324 10581 324 10564 324 10562 324 10581 324 10562 324 10586 324 10586 324 10562 324 10561 324 10584 14578 10587 14578 10585 14578 10585 14579 10587 14579 10588 14579 10585 14580 10588 14580 10586 14580 10586 14581 10588 14581 10589 14581 10586 14582 10589 14582 10581 14582 10581 14583 10589 14583 10590 14583 10581 14584 10590 14584 10580 14584 10580 14585 10590 14585 10591 14585 10580 14586 10591 14586 10582 14586 10582 14587 10591 14587 10592 14587 10582 14588 10592 14588 10593 14588 10582 14589 10593 14589 10583 14589 10583 14590 10593 14590 10594 14590 10583 14591 10594 14591 10584 14591 10584 14592 10594 14592 10587 14592 10587 348 10578 348 10556 348 10594 348 10576 348 10578 348 10594 348 10578 348 10587 348 10592 348 10572 348 10593 348 10572 348 10574 348 10593 348 10593 348 10574 348 10576 348 10593 348 10576 348 10594 348 10589 348 10563 348 10590 348 10590 348 10563 348 10565 348 10591 348 10568 348 10570 348 10591 348 10570 348 10592 348 10592 348 10570 348 10572 348 10590 348 10565 348 10591 348 10591 348 10565 348 10568 348 10589 348 10560 348 10563 348 10588 348 10558 348 10589 348 10589 348 10558 348 10560 348 10587 348 10556 348 10588 348 10588 348 10556 348 10558 348 10595 14593 10596 14593 10598 14593 10598 14594 10599 14594 10597 14594 10595 14595 10598 14595 10597 14595 10601 14596 10599 14596 10598 14596 10602 14597 10599 14597 10601 14597 10602 14598 10600 14598 10599 14598 10605 14599 10603 14599 10604 14599 10597 14600 10599 14600 10600 14600 10600 14601 10605 14601 10604 14601 10597 14602 10600 14602 10604 14602 10606 14603 10603 14603 10605 14603 10604 14604 10603 14604 10606 14604 10609 14605 10610 14605 10608 14605 10604 14606 10606 14606 10607 14606 10604 14607 10607 14607 10608 14607 10608 14608 10607 14608 10609 14608 10613 14609 10610 14609 10609 14609 10614 14610 10610 14610 10613 14610 10611 14611 10610 14611 10614 14611 10612 14612 10615 14612 10616 14612 10608 14613 10610 14613 10611 14613 10608 14614 10611 14614 10616 14614 10616 14615 10611 14615 10612 14615 10615 14616 10612 14616 10617 14616 10616 14617 10615 14617 10617 14617 10618 14618 10620 14618 10619 14618 10616 14619 10617 14619 10619 14619 10619 14620 10617 14620 10618 14620 10623 14621 10620 14621 10618 14621 10624 14622 10620 14622 10623 14622 10624 14623 10621 14623 10620 14623 10625 14624 10596 14624 10595 14624 10619 14625 10620 14625 10621 14625 10622 14626 10625 14626 10595 14626 10619 14627 10621 14627 10595 14627 10595 14628 10621 14628 10622 14628 10598 14629 10596 14629 10625 14629 10622 14630 10628 14630 10627 14630 10607 14631 10626 14631 10631 14631 10626 14632 10607 14632 10606 14632 10627 14633 10598 14633 10625 14633 10627 14634 10625 14634 10622 14634 10628 14635 10629 14635 10618 14635 10628 14636 10618 14636 10630 14636 10628 14637 10622 14637 10624 14637 10628 14638 10624 14638 10629 14638 10633 14639 10598 14639 10627 14639 10633 14640 10601 14640 10598 14640 10631 14641 10632 14641 10613 14641 10631 14642 10613 14642 10607 14642 10630 14643 10612 14643 10631 14643 10631 14644 10612 14644 10611 14644 10631 14645 10611 14645 10632 14645 10633 14646 10600 14646 10634 14646 10633 14647 10634 14647 10601 14647 10626 14648 10606 14648 10605 14648 10626 14649 10605 14649 10633 14649 10630 14650 10617 14650 10612 14650 10605 14651 10600 14651 10633 14651 10630 14652 10618 14652 10617 14652 10627 14653 10628 14653 10635 14653 10635 14654 10636 14654 10627 14654 10627 14655 10636 14655 10633 14655 10633 14656 10636 14656 10637 14656 10633 14657 10637 14657 10626 14657 10637 14658 10638 14658 10626 14658 10639 14659 10626 14659 10638 14659 10631 14660 10626 14660 10639 14660 10639 14661 10640 14661 10631 14661 10631 14662 10640 14662 10630 14662 10630 14663 10640 14663 10641 14663 10630 14664 10641 14664 10628 14664 10641 14665 10642 14665 10628 14665 10635 14666 10628 14666 10642 14666 10643 14667 10635 14667 10642 14667 10643 14668 10642 14668 10641 14668 10643 14669 10641 14669 10644 14669 10644 14670 10641 14670 10645 14670 10645 14671 10641 14671 10640 14671 10645 14672 10640 14672 10646 14672 10646 14673 10640 14673 10639 14673 10646 14674 10639 14674 10647 14674 10647 14675 10639 14675 10638 14675 10647 14676 10638 14676 10637 14676 10647 14677 10637 14677 10648 14677 10648 14678 10637 14678 10649 14678 10649 14679 10637 14679 10636 14679 10649 14680 10636 14680 10650 14680 10650 14681 10636 14681 10635 14681 10650 14682 10635 14682 10643 14682 10651 14683 10647 14683 10652 14683 10647 14684 10648 14684 10652 14684 10648 14685 10649 14685 10652 14685 10652 14686 10649 14686 10653 14686 10649 14687 10650 14687 10653 14687 10653 14688 10650 14688 10654 14688 10643 14689 10654 14689 10650 14689 10654 14690 10643 14690 10655 14690 10643 14691 10644 14691 10655 14691 10644 14692 10645 14692 10655 14692 10655 14693 10645 14693 10656 14693 10645 14694 10646 14694 10656 14694 10656 14695 10646 14695 10651 14695 10647 14696 10651 14696 10646 14696 10656 14697 10651 14697 10608 14697 10608 14698 10651 14698 10604 14698 10597 14699 10652 14699 10653 14699 10597 14700 10653 14700 10595 14700 10616 14701 10655 14701 10656 14701 10616 14702 10656 14702 10608 14702 10604 14703 10651 14703 10652 14703 10604 14704 10652 14704 10597 14704 10595 14705 10653 14705 10654 14705 10595 14706 10654 14706 10619 14706 10619 14707 10654 14707 10655 14707 10619 14708 10655 14708 10616 14708 10657 14709 10658 14709 10659 14709 10660 14710 10658 14710 10657 14710 10657 14711 10661 14711 10662 14711 10659 14712 10661 14712 10657 14712 10662 14713 10663 14713 10657 14713 10657 14714 10664 14714 10665 14714 10657 14715 10666 14715 10667 14715 10665 14716 10666 14716 10657 14716 10657 14717 10663 14717 10664 14717 10657 14718 10667 14718 10660 14718 10668 14719 10669 14719 10670 14719 10668 14720 10671 14720 10672 14720 10670 14721 10671 14721 10668 14721 10673 14722 10669 14722 10668 14722 10668 14723 10672 14723 10674 14723 10674 14724 10675 14724 10668 14724 10677 14725 10676 14725 10668 14725 10675 14726 10677 14726 10668 14726 10676 14727 10673 14727 10668 14727 10678 14728 10680 14728 10681 14728 10679 14729 10680 14729 10678 14729 10681 14730 10683 14730 10678 14730 10678 14731 10682 14731 10679 14731 10678 14732 10684 14732 10685 14732 10683 14733 10684 14733 10678 14733 10678 14734 10687 14734 10682 14734 10686 14735 10687 14735 10678 14735 10678 14736 10685 14736 10686 14736 10688 14737 10689 14737 10690 14737 10688 14738 10691 14738 10692 14738 10690 14739 10691 14739 10688 14739 10693 14740 10689 14740 10688 14740 10692 14741 10694 14741 10688 14741 10688 14742 10696 14742 10697 14742 10694 14743 10695 14743 10688 14743 10688 14744 10695 14744 10696 14744 10688 14745 10697 14745 10693 14745 10699 14746 10700 14746 10701 14746 10701 14747 10700 14747 10702 14747 10698 14748 10703 14748 10704 14748 10698 14749 10704 14749 10699 14749 10699 14750 10704 14750 10700 14750 10702 14751 10706 14751 10705 14751 10706 14752 10704 14752 10707 14752 10707 14753 10704 14753 10703 14753 10704 14754 10706 14754 10700 14754 10700 14755 10706 14755 10702 14755 10702 14756 10705 14756 10701 14756 10661 14757 10710 14757 10711 14757 10661 14758 10711 14758 10662 14758 10662 14759 10711 14759 10712 14759 10660 14760 10708 14760 10658 14760 10658 14761 10708 14761 10709 14761 10658 14762 10709 14762 10659 14762 10659 14763 10709 14763 10710 14763 10659 14764 10710 14764 10661 14764 10662 14765 10712 14765 10663 14765 10663 14766 10712 14766 10713 14766 10666 14767 10715 14767 10716 14767 10660 14768 10716 14768 10708 14768 10663 14769 10713 14769 10664 14769 10664 14770 10713 14770 10714 14770 10664 14771 10714 14771 10665 14771 10665 14772 10714 14772 10715 14772 10665 14773 10715 14773 10666 14773 10667 14774 10666 14774 10716 14774 10667 14775 10716 14775 10660 14775 10670 14776 10717 14776 10718 14776 10672 14777 10719 14777 10720 14777 10674 14778 10720 14778 10721 14778 10673 14779 10717 14779 10669 14779 10669 14780 10717 14780 10670 14780 10671 14781 10670 14781 10718 14781 10671 14782 10718 14782 10719 14782 10671 14783 10719 14783 10672 14783 10672 14784 10720 14784 10674 14784 10677 14785 10722 14785 10723 14785 10674 14786 10721 14786 10675 14786 10675 14787 10721 14787 10722 14787 10675 14788 10722 14788 10677 14788 10676 14789 10677 14789 10723 14789 10676 14790 10723 14790 10673 14790 10673 14791 10723 14791 10724 14791 10673 14792 10724 14792 10717 14792 10682 14793 10725 14793 10679 14793 10679 14794 10725 14794 10726 14794 10679 14795 10726 14795 10680 14795 10680 14796 10726 14796 10727 14796 10680 14797 10727 14797 10681 14797 10681 14798 10727 14798 10728 14798 10681 14799 10728 14799 10683 14799 10683 14800 10728 14800 10729 14800 10685 14801 10729 14801 10730 14801 10685 14802 10730 14802 10731 14802 10682 14803 10732 14803 10725 14803 10683 14804 10729 14804 10684 14804 10684 14805 10729 14805 10685 14805 10686 14806 10685 14806 10731 14806 10686 14807 10731 14807 10687 14807 10687 14808 10731 14808 10732 14808 10687 14809 10732 14809 10682 14809 10690 14810 10733 14810 10734 14810 10693 14811 10733 14811 10689 14811 10689 14812 10733 14812 10690 14812 10691 14813 10690 14813 10734 14813 10691 14814 10734 14814 10735 14814 10691 14815 10735 14815 10692 14815 10692 14816 10735 14816 10736 14816 10692 14817 10736 14817 10694 14817 10694 14818 10736 14818 10737 14818 10695 14819 10737 14819 10738 14819 10696 14820 10738 14820 10739 14820 10694 14821 10737 14821 10695 14821 10695 14822 10738 14822 10696 14822 10696 14823 10739 14823 10697 14823 10697 14824 10739 14824 10740 14824 10697 14825 10740 14825 10693 14825 10693 14826 10740 14826 10733 14826 10743 14827 10744 14827 10745 14827 10745 14828 10746 14828 10743 14828 10743 14829 10746 14829 10747 14829 10741 14830 10742 14830 10746 14830 10741 14831 10746 14831 10748 14831 10744 14832 10749 14832 10745 14832 10745 14833 10749 14833 10748 14833 10745 14834 10748 14834 10746 14834 10746 14835 10742 14835 10747 14835 10747 14836 10742 14836 10741 14836 10751 14837 10752 14837 10749 14837 10749 14838 10752 14838 10750 14838 10749 14839 10750 14839 10748 14839 10750 14840 10741 14840 10748 14840 10754 14841 10753 14841 10755 14841 10752 14842 10755 14842 10750 14842 10756 14843 10753 14843 10754 14843 10754 14844 10755 14844 10752 14844 10757 14845 10758 14845 10760 14845 10758 14846 10753 14846 10760 14846 10753 14847 10756 14847 10759 14847 10753 14848 10759 14848 10760 14848 10765 14849 10761 14849 10766 14849 10766 14850 10761 14850 10762 14850 10766 14851 10762 14851 10764 14851 10762 14852 10763 14852 10764 14852 10769 14853 10768 14853 10770 14853 10767 14854 10768 14854 10769 14854 10769 14855 10770 14855 10761 14855 10761 14856 10770 14856 10762 14856 10698 14857 10699 14857 10767 14857 10701 14858 10768 14858 10699 14858 10699 14859 10768 14859 10767 14859 10698 14860 10767 14860 10771 14860 10773 14861 10774 14861 10707 14861 10707 14862 10774 14862 10772 14862 10707 14863 10772 14863 10706 14863 10772 14864 10705 14864 10706 14864 10775 14865 10776 14865 10777 14865 10775 14866 10777 14866 10778 14866 10778 14867 10777 14867 10772 14867 10774 14868 10778 14868 10772 14868 10779 14869 10780 14869 10782 14869 10776 14870 10775 14870 10780 14870 10780 14871 10775 14871 10782 14871 10775 14872 10781 14872 10782 14872 10739 14873 10741 14873 10750 14873 10739 324 10750 324 10740 324 10753 324 10784 324 10785 324 10753 324 10785 324 10755 324 10733 324 10740 324 10783 324 10783 324 10740 324 10750 324 10783 324 10750 324 10786 324 10786 324 10750 324 10785 324 10785 324 10750 324 10755 324 10763 14874 10716 14874 10715 14874 10763 14875 10715 14875 10758 14875 10758 14876 10715 14876 10714 14876 10714 14877 10713 14877 10758 14877 10758 14878 10713 14878 10753 14878 10753 324 10713 324 10712 324 10753 324 10712 324 10711 324 10753 324 10711 324 10784 324 10784 324 10711 324 10710 324 10784 324 10710 324 10762 324 10762 324 10710 324 10709 324 10709 324 10708 324 10762 324 10762 14879 10708 14879 10763 14879 10763 14880 10708 14880 10716 14880 10701 14881 10723 14881 10768 14881 10768 324 10723 324 10722 324 10762 324 10770 324 10784 324 10784 14882 10770 14882 10787 14882 10787 14883 10770 14883 10768 14883 10787 14884 10768 14884 10722 14884 10787 14885 10722 14885 10721 14885 10720 14886 10772 14886 10787 14886 10720 14887 10787 14887 10721 14887 10718 14888 10705 14888 10719 14888 10719 14889 10705 14889 10772 14889 10719 324 10772 324 10720 324 10705 14890 10718 14890 10717 14890 10705 14891 10717 14891 10701 14891 10701 14892 10717 14892 10724 14892 10701 14893 10724 14893 10723 14893 10788 324 10772 324 10777 324 10788 324 10777 324 10789 324 10772 14894 10788 14894 10787 14894 10730 324 10729 324 10790 324 10732 324 10731 324 10776 324 10776 324 10731 324 10789 324 10776 324 10789 324 10777 324 10728 14895 10795 14895 10729 14895 10729 14896 10795 14896 10790 14896 10795 14897 10728 14897 10727 14897 10795 14898 10727 14898 10726 14898 10795 14899 10726 14899 10780 14899 10780 14900 10726 14900 10725 14900 10780 14901 10725 14901 10776 14901 10776 324 10725 324 10732 324 10790 324 10791 324 10792 324 10731 324 10730 324 10789 324 10789 324 10730 324 10790 324 10789 324 10790 324 10792 324 10739 14902 10738 14902 10741 14902 10741 14903 10738 14903 10737 14903 10741 14904 10737 14904 10747 14904 10747 14905 10737 14905 10736 14905 10747 14906 10736 14906 10735 14906 10747 14907 10735 14907 10734 14907 10747 14908 10734 14908 10793 14908 10793 324 10734 324 10733 324 10792 324 10791 324 10793 324 10792 324 10793 324 10783 324 10783 324 10793 324 10733 324 10797 14909 10794 14909 10798 14909 10798 14910 10794 14910 10790 14910 10798 14911 10790 14911 10796 14911 10790 14912 10795 14912 10796 14912 10799 14913 10793 14913 10791 14913 10799 14914 10791 14914 10790 14914 10800 14915 10793 14915 10799 14915 10794 14916 10799 14916 10790 14916 10747 14917 10793 14917 10743 14917 10800 14918 10801 14918 10793 14918 10793 14919 10801 14919 10743 14919 10802 324 10756 324 10803 324 10802 324 10804 324 10756 324 10756 14920 10804 14920 10759 14920 10803 14921 10756 14921 10754 14921 10803 14922 10754 14922 10752 14922 10803 324 10752 324 10805 324 10805 14923 10752 14923 10751 14923 10760 14924 10808 14924 10757 14924 10808 14925 10807 14925 10757 14925 10757 14926 10807 14926 10758 14926 10763 14927 10806 14927 10807 14927 10763 14928 10807 14928 10764 14928 10808 14929 10766 14929 10764 14929 10808 14930 10764 14930 10807 14930 10807 14931 10806 14931 10758 14931 10758 14932 10806 14932 10763 14932 10767 324 10769 324 10809 324 10771 14933 10767 14933 10810 14933 10767 324 10809 324 10810 324 10761 14934 10765 14934 10811 14934 10761 324 10811 324 10812 324 10809 324 10769 324 10761 324 10809 324 10761 324 10813 324 10813 324 10761 324 10812 324 10775 14935 10814 14935 10815 14935 10815 14936 10816 14936 10775 14936 10775 14937 10816 14937 10781 14937 10814 14938 10775 14938 10817 14938 10775 324 10778 324 10817 324 10817 14939 10778 14939 10774 14939 10817 14940 10774 14940 10818 14940 10818 14941 10774 14941 10773 14941 10782 14942 10821 14942 10779 14942 10821 14943 10820 14943 10779 14943 10779 14944 10820 14944 10780 14944 10795 14945 10819 14945 10820 14945 10795 14946 10820 14946 10796 14946 10821 14947 10798 14947 10796 14947 10821 14948 10796 14948 10820 14948 10820 14949 10819 14949 10780 14949 10780 14950 10819 14950 10795 14950 10800 14951 10822 14951 10823 14951 10800 14952 10823 14952 10801 14952 10799 324 10794 324 10822 324 10799 324 10822 324 10800 324 10797 14953 10824 14953 10794 14953 10794 324 10824 324 10825 324 10825 324 10826 324 10794 324 10794 324 10826 324 10822 324 10827 14954 10751 14954 10749 14954 10827 14955 10749 14955 10744 14955 10804 14956 10802 14956 10828 14956 10828 14957 10802 14957 10803 14957 10828 14958 10803 14958 10829 14958 10829 14959 10803 14959 10805 14959 10831 14960 10832 14960 10765 14960 10765 14961 10832 14961 10811 14961 10811 14962 10832 14962 10833 14962 10811 14963 10833 14963 10812 14963 10771 14964 10834 14964 10698 14964 10834 14965 10703 14965 10698 14965 10751 14966 10827 14966 10805 14966 10805 14967 10827 14967 10835 14967 10805 14968 10835 14968 10829 14968 10804 14969 10828 14969 10836 14969 10804 14970 10836 14970 10759 14970 10759 14971 10836 14971 10830 14971 10812 14972 10833 14972 10837 14972 10812 14973 10837 14973 10813 14973 10813 14974 10837 14974 10838 14974 10813 14975 10838 14975 10809 14975 10809 14976 10838 14976 10839 14976 10809 14977 10839 14977 10810 14977 10810 14978 10839 14978 10771 14978 10771 14979 10839 14979 10834 14979 10760 14980 10759 14980 10830 14980 10760 14981 10830 14981 10808 14981 10808 14982 10830 14982 10831 14982 10808 14983 10831 14983 10766 14983 10766 14984 10831 14984 10765 14984 10773 14985 10707 14985 10703 14985 10834 14986 10773 14986 10703 14986 10840 14987 10815 14987 10814 14987 10840 14988 10814 14988 10841 14988 10841 14989 10814 14989 10817 14989 10841 14990 10817 14990 10842 14990 10842 14991 10817 14991 10818 14991 10844 14992 10845 14992 10797 14992 10797 14993 10845 14993 10824 14993 10825 14994 10846 14994 10826 14994 10826 14995 10846 14995 10847 14995 10826 14996 10847 14996 10822 14996 10822 14997 10848 14997 10823 14997 10801 14998 10849 14998 10743 14998 10849 14999 10744 14999 10743 14999 10773 15000 10834 15000 10850 15000 10773 15001 10850 15001 10818 15001 10818 15002 10850 15002 10842 15002 10815 15003 10840 15003 10816 15003 10816 15004 10840 15004 10851 15004 10816 15005 10851 15005 10781 15005 10781 15006 10851 15006 10843 15006 10824 15007 10845 15007 10852 15007 10824 15008 10852 15008 10825 15008 10825 15009 10852 15009 10846 15009 10822 15010 10847 15010 10848 15010 10823 15011 10848 15011 10853 15011 10823 15012 10853 15012 10801 15012 10801 15013 10853 15013 10849 15013 10744 15014 10849 15014 10827 15014 10782 15015 10781 15015 10843 15015 10782 15016 10843 15016 10821 15016 10821 15017 10843 15017 10798 15017 10798 15018 10843 15018 10844 15018 10798 15019 10844 15019 10797 15019 10854 15020 10851 15020 10840 15020 10854 348 10840 348 10855 348 10855 15021 10840 15021 10856 15021 10856 15022 10840 15022 10841 15022 10856 348 10841 348 10857 348 10857 15023 10841 15023 10842 15023 10858 348 10852 348 10859 348 10859 15024 10852 15024 10845 15024 10859 348 10845 348 10860 348 10860 15025 10845 15025 10844 15025 10860 15026 10844 15026 10843 15026 10860 15027 10843 15027 10861 15027 10861 15028 10843 15028 10854 15028 10854 15029 10843 15029 10851 15029 10862 348 10853 348 10848 348 10862 15030 10848 15030 10863 15030 10863 348 10848 348 10847 348 10863 15031 10847 15031 10858 15031 10858 348 10847 348 10846 348 10858 15032 10846 15032 10852 15032 10864 15033 10827 15033 10865 15033 10865 15034 10827 15034 10849 15034 10865 15035 10849 15035 10862 15035 10862 15036 10849 15036 10853 15036 10866 348 10836 348 10867 348 10867 348 10836 348 10828 348 10867 348 10828 348 10868 348 10868 348 10828 348 10829 348 10868 348 10829 348 10869 348 10869 348 10829 348 10835 348 10869 348 10835 348 10864 348 10864 15037 10835 15037 10827 15037 10870 348 10832 348 10871 348 10871 15038 10832 15038 10831 15038 10871 15039 10831 15039 10872 15039 10872 15040 10831 15040 10830 15040 10872 15041 10830 15041 10866 15041 10866 15042 10830 15042 10836 15042 10873 348 10839 348 10874 348 10874 348 10839 348 10838 348 10874 15043 10838 15043 10875 15043 10875 15044 10838 15044 10837 15044 10875 348 10837 348 10876 348 10876 15045 10837 15045 10870 15045 10870 15046 10837 15046 10833 15046 10870 15047 10833 15047 10832 15047 10857 348 10842 348 10850 348 10857 348 10850 348 10877 348 10877 15048 10850 15048 10834 15048 10877 15049 10834 15049 10878 15049 10878 15050 10834 15050 10873 15050 10873 15051 10834 15051 10839 15051 10865 15052 10879 15052 10880 15052 10869 15053 10880 15053 10881 15053 10869 15054 10881 15054 10882 15054 10867 15055 10882 15055 10883 15055 10867 15056 10883 15056 10866 15056 10866 15057 10883 15057 10884 15057 10871 15058 10885 15058 10886 15058 10876 15059 10887 15059 10888 15059 10876 15060 10888 15060 10875 15060 10875 15061 10888 15061 10889 15061 10874 15062 10889 15062 10890 15062 10873 15063 10890 15063 10891 15063 10864 15064 10865 15064 10880 15064 10864 15065 10880 15065 10869 15065 10868 15066 10869 15066 10882 15066 10868 15067 10882 15067 10867 15067 10866 15068 10884 15068 10872 15068 10872 15069 10884 15069 10885 15069 10872 15070 10885 15070 10871 15070 10870 15071 10871 15071 10886 15071 10870 15072 10886 15072 10887 15072 10870 15073 10887 15073 10876 15073 10875 15074 10889 15074 10874 15074 10874 15075 10890 15075 10873 15075 10878 15076 10873 15076 10891 15076 10878 15077 10891 15077 10892 15077 10877 15078 10892 15078 10893 15078 10857 15079 10893 15079 10894 15079 10856 15080 10894 15080 10895 15080 10855 15081 10895 15081 10896 15081 10861 15082 10897 15082 10898 15082 10859 15083 10899 15083 10900 15083 10858 15084 10900 15084 10901 15084 10858 15085 10901 15085 10902 15085 10865 15086 10903 15086 10879 15086 10878 15087 10892 15087 10877 15087 10877 15088 10893 15088 10857 15088 10857 15089 10894 15089 10856 15089 10856 15090 10895 15090 10855 15090 10854 15091 10855 15091 10896 15091 10854 15092 10896 15092 10897 15092 10854 15093 10897 15093 10861 15093 10860 15094 10861 15094 10898 15094 10860 15095 10898 15095 10899 15095 10860 15096 10899 15096 10859 15096 10859 15097 10900 15097 10858 15097 10863 15098 10858 15098 10902 15098 10863 15099 10902 15099 10862 15099 10862 15100 10902 15100 10903 15100 10862 15101 10903 15101 10865 15101 10905 348 10895 348 10904 348 10904 348 10895 348 10894 348 10905 15102 10896 15102 10895 15102 10906 348 10898 348 10905 348 10905 15103 10898 15103 10897 15103 10905 15104 10897 15104 10896 15104 10906 15105 10899 15105 10898 15105 10907 15106 10900 15106 10906 15106 10906 15107 10900 15107 10899 15107 10908 15108 10901 15108 10907 15108 10907 15109 10901 15109 10900 15109 10908 15110 10902 15110 10901 15110 10909 15111 10903 15111 10908 15111 10908 348 10903 348 10902 348 10910 15112 10880 15112 10909 15112 10909 348 10880 348 10879 348 10909 348 10879 348 10903 348 10910 15113 10881 15113 10880 15113 10911 348 10882 348 10910 348 10910 15114 10882 15114 10881 15114 10911 15115 10883 15115 10882 15115 10912 348 10885 348 10911 348 10911 15116 10885 15116 10884 15116 10911 15117 10884 15117 10883 15117 10913 348 10886 348 10912 348 10912 15118 10886 15118 10885 15118 10913 15119 10887 15119 10886 15119 10914 15120 10888 15120 10913 15120 10913 15121 10888 15121 10887 15121 10914 348 10890 348 10889 348 10914 15122 10889 15122 10888 15122 10915 348 10891 348 10914 348 10914 348 10891 348 10890 348 10904 348 10894 348 10893 348 10904 348 10893 348 10915 348 10915 348 10893 348 10892 348 10915 348 10892 348 10891 348 10910 15123 10916 15123 10917 15123 10911 15124 10917 15124 10918 15124 10912 15125 10918 15125 10919 15125 10912 15126 10919 15126 10913 15126 10913 15127 10919 15127 10920 15127 10914 15128 10920 15128 10921 15128 10915 15129 10921 15129 10922 15129 10909 15130 10916 15130 10910 15130 10910 15131 10917 15131 10911 15131 10911 15132 10918 15132 10912 15132 10913 15133 10920 15133 10914 15133 10914 15134 10921 15134 10915 15134 10923 348 10924 348 10925 348 10925 348 10922 348 10923 348 10926 348 10923 348 10927 348 10927 15135 10923 15135 10916 15135 10916 15136 10923 15136 10922 15136 10916 348 10922 348 10920 348 10919 348 10918 348 10920 348 10920 348 10918 348 10917 348 10920 348 10917 348 10916 348 10920 15137 10922 15137 10921 15137 10915 15138 10922 15138 10904 15138 10904 15139 10922 15139 10925 15139 10906 15140 10924 15140 10923 15140 10907 15141 10923 15141 10926 15141 10909 15142 10927 15142 10916 15142 10905 15143 10904 15143 10925 15143 10905 15144 10925 15144 10924 15144 10905 15145 10924 15145 10906 15145 10906 15146 10923 15146 10907 15146 10908 15147 10907 15147 10926 15147 10908 15148 10926 15148 10927 15148 10908 15149 10927 15149 10909 15149 10928 15150 10787 15150 10929 15150 10929 15151 10787 15151 10788 15151 10929 15152 10788 15152 10930 15152 10930 15153 10788 15153 10789 15153 10930 15154 10789 15154 10931 15154 10931 15155 10789 15155 10792 15155 10931 15156 10792 15156 10932 15156 10932 15157 10792 15157 10783 15157 10932 15158 10783 15158 10933 15158 10933 15159 10783 15159 10786 15159 10933 15160 10786 15160 10934 15160 10934 15161 10786 15161 10785 15161 10934 15162 10785 15162 10935 15162 10935 15163 10785 15163 10784 15163 10935 15164 10784 15164 10928 15164 10928 15165 10784 15165 10787 15165 10931 324 10932 324 10930 324 10930 324 10932 324 10933 324 10928 15166 10929 15166 10930 15166 10930 15167 10935 15167 10928 15167 10933 324 10934 324 10930 324 10930 15168 10934 15168 10935 15168 10958 15169 10936 15169 10937 15169 10937 15170 10936 15170 10938 15170 10937 15171 10938 15171 10939 15171 10937 15172 10939 15172 10940 15172 10940 15173 10939 15173 10941 15173 10940 15174 10941 15174 10942 15174 10942 15175 10941 15175 10943 15175 10943 15176 10941 15176 10944 15176 10943 15177 10944 15177 10945 15177 10945 15178 10944 15178 10946 15178 10945 15179 10946 15179 10947 15179 10947 15180 10946 15180 10948 15180 10947 15181 10948 15181 10949 15181 10947 15182 10949 15182 10950 15182 10950 15183 10949 15183 10951 15183 10951 15184 10949 15184 10952 15184 10951 15185 10952 15185 10953 15185 10951 15186 10953 15186 10954 15186 10954 15187 10953 15187 10955 15187 10954 15188 10955 15188 10956 15188 10956 15189 10955 15189 10957 15189 10956 15190 10957 15190 10958 15190 10958 15191 10957 15191 10936 15191 10959 15192 10948 15192 10946 15192 10959 324 10946 324 10960 324 10961 324 10936 324 10962 324 10963 324 10939 324 10938 324 10963 324 10938 324 10961 324 10961 324 10938 324 10936 324 10936 324 10957 324 10962 324 10964 15193 10949 15193 10959 15193 10959 15194 10949 15194 10948 15194 10965 324 10952 324 10964 324 10964 15195 10952 15195 10949 15195 10966 324 10941 324 10939 324 10966 324 10939 324 10963 324 10957 324 10955 324 10962 324 10962 324 10955 324 10965 324 10965 324 10955 324 10953 324 10965 15196 10953 15196 10952 15196 10960 324 10946 324 10944 324 10960 324 10944 324 10941 324 10960 15197 10941 15197 10966 15197 10961 15198 10967 15198 10963 15198 10963 15199 10967 15199 10968 15199 10963 15200 10968 15200 10966 15200 10966 15201 10968 15201 10969 15201 10966 15202 10969 15202 10960 15202 10960 15203 10969 15203 10970 15203 10960 15204 10970 15204 10959 15204 10959 15205 10970 15205 10971 15205 10959 15206 10971 15206 10964 15206 10964 15207 10971 15207 10972 15207 10964 15208 10972 15208 10965 15208 10965 15209 10972 15209 10973 15209 10965 15210 10973 15210 10962 15210 10962 15211 10973 15211 10974 15211 10962 15212 10974 15212 10967 15212 10962 15213 10967 15213 10961 15213 10974 348 10958 348 10967 348 10973 15214 10956 15214 10974 15214 10974 348 10956 348 10958 348 10972 348 10951 348 10973 348 10973 15215 10951 15215 10954 15215 10973 15216 10954 15216 10956 15216 10947 348 10950 348 10971 348 10971 348 10950 348 10972 348 10972 15217 10950 15217 10951 15217 10970 348 10945 348 10971 348 10971 15218 10945 15218 10947 15218 10970 15219 10943 15219 10945 15219 10968 15220 10940 15220 10969 15220 10969 348 10940 348 10942 348 10969 348 10942 348 10970 348 10970 15221 10942 15221 10943 15221 10958 15222 10937 15222 10967 15222 10967 15223 10937 15223 10968 15223 10968 15224 10937 15224 10940 15224 10975 6618 10976 6618 10977 6618 10976 15225 10978 15225 10977 15225 10977 15226 10978 15226 10979 15226 10979 15227 10978 15227 10980 15227 10979 15228 10980 15228 10981 15228 10981 15229 10980 15229 10982 15229 10981 15230 10982 15230 10983 15230 10983 15231 10982 15231 10984 15231 10983 15232 10984 15232 10985 15232 10983 15233 10985 15233 10986 15233 10986 15234 10985 15234 10987 15234 10986 15235 10987 15235 10988 15235 10988 15236 10987 15236 10989 15236 10988 15237 10989 15237 10975 15237 10975 15238 10989 15238 10976 15238 10990 15239 10991 15239 10992 15239 10992 15240 10991 15240 10993 15240 10992 15241 10993 15241 10994 15241 10994 15242 10993 15242 10995 15242 10994 15243 10995 15243 10996 15243 10996 15244 10995 15244 10997 15244 10996 15245 10997 15245 10998 15245 10998 15246 10997 15246 10999 15246 10998 15247 10999 15247 11000 15247 11000 15248 10999 15248 11001 15248 10999 15249 11002 15249 11001 15249 11001 15250 11002 15250 11003 15250 11003 15251 11002 15251 11004 15251 11003 15252 11004 15252 11005 15252 11005 15253 11004 15253 11006 15253 11005 15254 11006 15254 11007 15254 11007 15255 11006 15255 11008 15255 11008 15256 11006 15256 11009 15256 11008 15257 11009 15257 10990 15257 10990 15258 11009 15258 10991 15258 11011 15259 11010 15259 11012 15259 11013 15260 11012 15260 11053 15260 11053 15261 11012 15261 11010 15261 11012 15262 11013 15262 11014 15262 11015 15263 11014 15263 11013 15263 11014 15264 11015 15264 11016 15264 11017 15265 11016 15265 11015 15265 11016 15266 11017 15266 11018 15266 11054 15267 11018 15267 11017 15267 11018 15268 11054 15268 11019 15268 11018 15269 11019 15269 11020 15269 11021 15270 11022 15270 11019 15270 11019 15271 11022 15271 11020 15271 11022 15272 11021 15272 11023 15272 11023 15273 11021 15273 11024 15273 11023 15274 11024 15274 11025 15274 11025 15275 11024 15275 11026 15275 11025 15276 11026 15276 11027 15276 11027 15277 11026 15277 11028 15277 11027 15278 11028 15278 11011 15278 11011 15279 11028 15279 11010 15279 11025 15280 11030 15280 11029 15280 11029 15281 11031 15281 11025 15281 11029 15282 11032 15282 11031 15282 11029 15283 11033 15283 11032 15283 11007 15284 11008 15284 11034 15284 11007 15285 11034 15285 11035 15285 11007 15286 11035 15286 11005 15286 11005 15287 11035 15287 11003 15287 11003 15288 11035 15288 11036 15288 11003 15289 11036 15289 11001 15289 11001 15290 11036 15290 11037 15290 11001 15291 11037 15291 11000 15291 11000 15292 11037 15292 10998 15292 10998 15293 11037 15293 11038 15293 10998 15294 11038 15294 10996 15294 10996 15295 11038 15295 11039 15295 10996 15296 11039 15296 10994 15296 10994 15297 11039 15297 11040 15297 10994 15298 11040 15298 10992 15298 10992 15299 11040 15299 11041 15299 10992 15300 11041 15300 10990 15300 10990 15301 11041 15301 11042 15301 10990 15302 11042 15302 11008 15302 11008 15303 11042 15303 11034 15303 10984 15304 11038 15304 11037 15304 10984 15305 11037 15305 10985 15305 11037 15306 11036 15306 10985 15306 10985 15307 11036 15307 10987 15307 10987 15308 11036 15308 11035 15308 10987 15309 11035 15309 10989 15309 11035 15310 11034 15310 10989 15310 10989 15311 11034 15311 10976 15311 11034 15312 11042 15312 10976 15312 10976 15313 11042 15313 10978 15313 11042 15314 11041 15314 10978 15314 10978 15315 11041 15315 10980 15315 11041 15316 11040 15316 10980 15316 10980 6709 11040 6709 10982 6709 11040 15317 11039 15317 10982 15317 10982 15318 11039 15318 11038 15318 10982 15319 11038 15319 10984 15319 11011 15320 11030 15320 11027 15320 11027 15321 11030 15321 11025 15321 11023 15322 11025 15322 11031 15322 11023 15323 11031 15323 11022 15323 11022 15324 11031 15324 11032 15324 11022 15325 11032 15325 11020 15325 11020 15326 11032 15326 11018 15326 11018 15327 11032 15327 11033 15327 11018 15328 11033 15328 11016 15328 11016 15329 11033 15329 11014 15329 11014 15330 11033 15330 11029 15330 11014 15331 11029 15331 11012 15331 11012 15332 11029 15332 11011 15332 11011 15333 11029 15333 11030 15333 10986 15334 11043 15334 10983 15334 10988 6729 11044 6729 10986 6729 10983 6730 11045 6730 10981 6730 11046 15335 11048 15335 11047 15335 11046 15336 11047 15336 11049 15336 11049 15337 11047 15337 11050 15337 11050 15338 11047 15338 11051 15338 11047 15339 11052 15339 11051 15339 11052 15340 11047 15340 11048 15340 10986 15341 11049 15341 11043 15341 11043 15342 11049 15342 11050 15342 11050 15343 10983 15343 11043 15343 10988 6740 11046 6740 11044 6740 11044 15344 11046 15344 11049 15344 11049 15345 10986 15345 11044 15345 11046 15346 10988 15346 10975 15346 11046 15347 10975 15347 11048 15347 10977 15348 11048 15348 10975 15348 10979 15349 11052 15349 10977 15349 10977 15350 11052 15350 11048 15350 10981 6748 11051 6748 10979 6748 11052 15351 10979 15351 11051 15351 10983 15352 11050 15352 11045 15352 11045 15353 11050 15353 11051 15353 11051 15354 10981 15354 11045 15354 11006 15355 11053 15355 11010 15355 11006 15356 11010 15356 11009 15356 11009 15357 11010 15357 11028 15357 11009 15358 11028 15358 10991 15358 11006 15359 11013 15359 11053 15359 11006 15360 11004 15360 11013 15360 11004 15361 11015 15361 11013 15361 11004 15362 11017 15362 11015 15362 11004 15363 11002 15363 11017 15363 11002 15364 10999 15364 11054 15364 11002 15365 11054 15365 11017 15365 10999 15366 11019 15366 11054 15366 10999 15367 10997 15367 11019 15367 10997 15368 11021 15368 11019 15368 10997 15369 10995 15369 11021 15369 10995 15370 11024 15370 11021 15370 10995 15371 10993 15371 11024 15371 10993 15372 10991 15372 11026 15372 10993 15373 11026 15373 11024 15373 10991 15374 11028 15374 11026 15374 11055 15375 11056 15375 11057 15375 11056 15376 11058 15376 11057 15376 11057 15377 11058 15377 11059 15377 11059 15378 11058 15378 11060 15378 11059 15379 11060 15379 11061 15379 11061 15380 11060 15380 11062 15380 11061 15381 11062 15381 11063 15381 11063 15382 11062 15382 11064 15382 11063 15383 11064 15383 11065 15383 11063 15384 11065 15384 11066 15384 11066 15385 11065 15385 11067 15385 11066 15386 11067 15386 11068 15386 11068 15387 11067 15387 11069 15387 11068 15388 11069 15388 11055 15388 11055 15389 11069 15389 11056 15389 11086 15390 11087 15390 11070 15390 11070 15391 11087 15391 11071 15391 11070 15392 11071 15392 11072 15392 11071 15393 11073 15393 11072 15393 11072 15394 11073 15394 11074 15394 11074 15395 11073 15395 11075 15395 11075 15396 11073 15396 11076 15396 11075 15397 11076 15397 11077 15397 11077 15398 11076 15398 11078 15398 11076 15399 11079 15399 11078 15399 11078 15400 11079 15400 11080 15400 11080 15401 11079 15401 11081 15401 11081 15402 11079 15402 11082 15402 11081 15403 11082 15403 11083 15403 11083 15404 11082 15404 11084 15404 11083 15405 11084 15405 11085 15405 11085 15406 11084 15406 11086 15406 11086 15407 11084 15407 11087 15407 11089 15408 11088 15408 11090 15408 11091 15409 11090 15409 11133 15409 11133 15410 11090 15410 11088 15410 11090 15411 11091 15411 11092 15411 11093 15412 11092 15412 11091 15412 11092 15413 11093 15413 11095 15413 11092 15414 11095 15414 11094 15414 11094 15415 11095 15415 11097 15415 11094 15416 11097 15416 11096 15416 11096 15417 11097 15417 11098 15417 11096 15418 11098 15418 11099 15418 11100 15419 11101 15419 11098 15419 11098 15420 11101 15420 11099 15420 11101 15421 11100 15421 11102 15421 11102 15422 11100 15422 11103 15422 11102 15423 11103 15423 11104 15423 11102 15424 11104 15424 11105 15424 11105 15425 11104 15425 11134 15425 11105 15426 11134 15426 11106 15426 11105 15427 11106 15427 11089 15427 11089 15428 11106 15428 11088 15428 11109 15429 11107 15429 11108 15429 11111 15430 11110 15430 11108 15430 11107 15431 11112 15431 11108 15431 11108 15432 11112 15432 11111 15432 11085 15433 11113 15433 11083 15433 11083 15434 11113 15434 11114 15434 11083 15435 11114 15435 11081 15435 11081 15436 11114 15436 11080 15436 11080 15437 11114 15437 11115 15437 11080 15438 11115 15438 11078 15438 11078 15439 11115 15439 11116 15439 11078 15440 11116 15440 11077 15440 11077 15441 11116 15441 11075 15441 11075 15442 11116 15442 11117 15442 11075 15443 11117 15443 11074 15443 11074 15444 11117 15444 11118 15444 11074 15445 11118 15445 11072 15445 11072 15446 11118 15446 11119 15446 11072 15447 11119 15447 11070 15447 11070 15448 11119 15448 11120 15448 11070 15449 11120 15449 11086 15449 11086 15450 11120 15450 11121 15450 11086 15451 11121 15451 11085 15451 11085 15452 11121 15452 11113 15452 11064 15453 11117 15453 11116 15453 11064 15454 11116 15454 11065 15454 11116 15455 11115 15455 11065 15455 11065 15456 11115 15456 11067 15456 11067 15457 11115 15457 11114 15457 11067 15458 11114 15458 11069 15458 11114 15459 11113 15459 11069 15459 11069 15460 11113 15460 11056 15460 11113 15461 11121 15461 11056 15461 11056 15462 11121 15462 11058 15462 11121 15463 11120 15463 11058 15463 11058 15464 11120 15464 11060 15464 11120 15465 11119 15465 11060 15465 11060 15466 11119 15466 11062 15466 11119 15467 11118 15467 11062 15467 11062 15468 11118 15468 11117 15468 11062 15469 11117 15469 11064 15469 11089 15470 11109 15470 11105 15470 11105 15471 11109 15471 11108 15471 11105 15472 11108 15472 11102 15472 11102 15473 11108 15473 11110 15473 11102 15474 11110 15474 11101 15474 11101 15475 11110 15475 11099 15475 11099 15476 11110 15476 11111 15476 11099 15477 11111 15477 11096 15477 11096 15478 11111 15478 11094 15478 11094 15479 11111 15479 11112 15479 11094 15480 11112 15480 11092 15480 11092 15481 11112 15481 11107 15481 11092 15482 11107 15482 11090 15482 11090 15483 11107 15483 11089 15483 11089 15484 11107 15484 11109 15484 11066 15485 11122 15485 11063 15485 11068 15486 11123 15486 11066 15486 11063 15487 11124 15487 11061 15487 11125 15488 11127 15488 11126 15488 11125 15489 11126 15489 11128 15489 11128 15490 11126 15490 11129 15490 11129 15491 11126 15491 11130 15491 11126 15492 11131 15492 11130 15492 11131 15493 11126 15493 11127 15493 11066 15494 11128 15494 11122 15494 11122 15495 11128 15495 11129 15495 11129 15496 11063 15496 11122 15496 11068 15497 11125 15497 11123 15497 11123 15498 11125 15498 11128 15498 11128 15499 11066 15499 11123 15499 11125 15500 11068 15500 11055 15500 11125 15501 11055 15501 11127 15501 11057 15502 11127 15502 11055 15502 11059 15503 11131 15503 11057 15503 11057 15504 11131 15504 11127 15504 11061 15505 11130 15505 11059 15505 11131 15506 11059 15506 11130 15506 11063 15507 11129 15507 11124 15507 11124 15508 11129 15508 11130 15508 11130 15509 11061 15509 11124 15509 11076 15510 11073 15510 11098 15510 11082 15511 11132 15511 11084 15511 11084 15512 11132 15512 11087 15512 11132 15513 11133 15513 11088 15513 11132 15514 11088 15514 11106 15514 11132 15515 11106 15515 11087 15515 11132 15516 11082 15516 11133 15516 11133 15517 11082 15517 11091 15517 11082 15518 11079 15518 11093 15518 11082 15519 11093 15519 11091 15519 11079 15520 11095 15520 11093 15520 11079 15521 11076 15521 11095 15521 11076 15522 11097 15522 11095 15522 11076 15523 11098 15523 11097 15523 11073 15524 11100 15524 11098 15524 11073 15525 11071 15525 11103 15525 11073 15526 11103 15526 11100 15526 11103 15527 11071 15527 11104 15527 11087 15528 11134 15528 11071 15528 11071 15529 11134 15529 11104 15529 11134 15530 11087 15530 11106 15530 11136 15531 11135 15531 11137 15531 11136 15532 11137 15532 11138 15532 11138 15533 11137 15533 11139 15533 11139 15534 11137 15534 11140 15534 11139 15535 11140 15535 11141 15535 11139 15536 11141 15536 11142 15536 11142 15537 11141 15537 11143 15537 11142 15538 11143 15538 11144 15538 11144 15539 11143 15539 11145 15539 11144 15540 11145 15540 11146 15540 11146 15541 11145 15541 11147 15541 11147 15542 11145 15542 11148 15542 11147 15543 11148 15543 11149 15543 11147 15544 11149 15544 11150 15544 11150 15545 11149 15545 11151 15545 11151 15546 11149 15546 11152 15546 11151 15547 11152 15547 11153 15547 11153 15548 11152 15548 11154 15548 11153 15549 11154 15549 11155 15549 11153 15550 11155 15550 11156 15550 11156 15551 11155 15551 11135 15551 11156 15552 11135 15552 11136 15552 11157 324 11135 324 11158 324 11158 324 11135 324 11155 324 11159 324 11137 324 11157 324 11157 324 11137 324 11135 324 11160 324 11143 324 11141 324 11160 324 11141 324 11161 324 11158 324 11155 324 11154 324 11158 324 11154 324 11162 324 11163 324 11143 324 11160 324 11164 324 11148 324 11165 324 11165 324 11148 324 11145 324 11165 324 11145 324 11163 324 11163 324 11145 324 11143 324 11161 324 11141 324 11140 324 11161 324 11140 324 11159 324 11159 324 11140 324 11137 324 11162 324 11154 324 11152 324 11162 324 11152 324 11166 324 11166 324 11152 324 11149 324 11166 324 11149 324 11164 324 11164 324 11149 324 11148 324 11167 15553 11168 15553 11169 15553 11169 15554 11168 15554 11170 15554 11169 15555 11170 15555 11171 15555 11171 15556 11170 15556 11172 15556 11171 15557 11172 15557 11173 15557 11173 15558 11172 15558 11174 15558 11173 15559 11174 15559 11175 15559 11175 15560 11174 15560 11176 15560 11175 15561 11176 15561 11177 15561 11175 15562 11177 15562 11178 15562 11178 15563 11177 15563 11179 15563 11178 15564 11179 15564 11180 15564 11180 15565 11179 15565 11181 15565 11180 15566 11181 15566 11182 15566 11182 15567 11181 15567 11183 15567 11182 15568 11183 15568 11184 15568 11184 15569 11183 15569 11185 15569 11184 15570 11185 15570 11186 15570 11186 15571 11185 15571 11187 15571 11187 15572 11185 15572 11188 15572 11187 15573 11188 15573 11189 15573 11189 15574 11188 15574 11190 15574 11189 15575 11190 15575 11191 15575 11191 15576 11190 15576 11192 15576 11191 15577 11192 15577 11193 15577 11193 15578 11192 15578 11194 15578 11193 15579 11194 15579 11195 15579 11195 15580 11194 15580 11196 15580 11196 15581 11194 15581 11197 15581 11196 15582 11197 15582 11198 15582 11196 15583 11198 15583 11199 15583 11199 15584 11198 15584 11167 15584 11167 15585 11198 15585 11168 15585 11200 348 11185 348 11183 348 11208 348 11198 348 11201 348 11201 348 11198 348 11197 348 11201 348 11197 348 11194 348 11202 348 11177 348 11176 348 11202 348 11176 348 11203 348 11203 348 11176 348 11174 348 11201 348 11194 348 11204 348 11204 348 11194 348 11192 348 11204 348 11192 348 11190 348 11204 348 11190 348 11205 348 11183 348 11181 348 11200 348 11200 348 11181 348 11206 348 11206 348 11181 348 11179 348 11206 348 11179 348 11202 348 11202 348 11179 348 11177 348 11205 348 11190 348 11188 348 11205 348 11188 348 11185 348 11205 348 11185 348 11200 348 11203 348 11174 348 11172 348 11203 348 11172 348 11207 348 11207 348 11172 348 11170 348 11207 348 11170 348 11208 348 11170 348 11168 348 11208 348 11208 348 11168 348 11198 348 11147 324 11180 324 11182 324 11147 324 11182 324 11146 324 11146 324 11182 324 11184 324 11146 324 11184 324 11144 324 11151 324 11175 324 11178 324 11151 324 11178 324 11150 324 11150 324 11178 324 11147 324 11147 324 11178 324 11180 324 11142 324 11191 324 11193 324 11142 324 11193 324 11139 324 11139 324 11193 324 11195 324 11184 324 11186 324 11144 324 11144 324 11186 324 11187 324 11144 324 11187 324 11189 324 11144 324 11189 324 11142 324 11142 324 11189 324 11191 324 11153 324 11171 324 11173 324 11153 324 11173 324 11151 324 11151 324 11173 324 11175 324 11139 324 11195 324 11196 324 11139 324 11196 324 11138 324 11138 324 11196 324 11199 324 11138 324 11199 324 11136 324 11136 324 11199 324 11167 324 11136 324 11167 324 11156 324 11156 324 11167 324 11169 324 11156 324 11169 324 11153 324 11153 324 11169 324 11171 324 11209 15586 11200 15586 11210 15586 11210 15587 11200 15587 11206 15587 11210 15588 11206 15588 11211 15588 11211 15589 11206 15589 11202 15589 11211 15590 11202 15590 11212 15590 11212 15591 11202 15591 11203 15591 11212 15592 11203 15592 11213 15592 11213 15593 11203 15593 11207 15593 11213 15594 11207 15594 11214 15594 11214 15595 11207 15595 11208 15595 11214 15596 11208 15596 11215 15596 11215 15597 11208 15597 11201 15597 11215 15598 11201 15598 11216 15598 11216 15599 11201 15599 11204 15599 11216 15600 11204 15600 11217 15600 11217 15601 11204 15601 11205 15601 11217 15602 11205 15602 11209 15602 11209 15603 11205 15603 11200 15603 11218 348 11209 348 11219 348 11220 348 11217 348 11218 348 11218 348 11217 348 11209 348 11219 348 11209 348 11210 348 11219 348 11210 348 11221 348 11221 348 11210 348 11211 348 11221 348 11211 348 11222 348 11223 348 11216 348 11220 348 11220 348 11216 348 11217 348 11224 348 11214 348 11225 348 11226 348 11212 348 11213 348 11226 348 11213 348 11224 348 11224 348 11213 348 11214 348 11225 348 11214 348 11215 348 11225 348 11215 348 11227 348 11227 348 11215 348 11223 348 11223 348 11215 348 11216 348 11222 348 11211 348 11226 348 11226 348 11211 348 11212 348 11165 15604 11219 15604 11164 15604 11164 15605 11219 15605 11221 15605 11164 15606 11221 15606 11166 15606 11166 15607 11221 15607 11222 15607 11166 15608 11222 15608 11162 15608 11162 15609 11222 15609 11226 15609 11162 15610 11226 15610 11158 15610 11158 15611 11226 15611 11224 15611 11158 15612 11224 15612 11157 15612 11157 15613 11224 15613 11225 15613 11157 15614 11225 15614 11159 15614 11159 15615 11225 15615 11227 15615 11159 15616 11227 15616 11161 15616 11161 15617 11227 15617 11223 15617 11161 15618 11223 15618 11220 15618 11161 15619 11220 15619 11160 15619 11160 15620 11220 15620 11218 15620 11160 15621 11218 15621 11163 15621 11163 15622 11218 15622 11165 15622 11165 15623 11218 15623 11219 15623 11229 15624 11228 15624 11230 15624 11229 15625 11230 15625 11231 15625 11231 15626 11230 15626 11232 15626 11231 15627 11232 15627 11233 15627 11233 15628 11232 15628 11234 15628 11233 15629 11234 15629 11235 15629 11235 15630 11234 15630 11236 15630 11235 15631 11236 15631 11237 15631 11237 15632 11236 15632 11238 15632 11237 15633 11238 15633 11239 15633 11239 15634 11238 15634 11240 15634 11239 15635 11240 15635 11241 15635 11241 15636 11240 15636 11242 15636 11241 15637 11242 15637 11243 15637 11243 15638 11242 15638 11244 15638 11243 15639 11244 15639 11245 15639 11245 15640 11244 15640 11246 15640 11245 15641 11246 15641 11247 15641 11247 15642 11246 15642 11228 15642 11247 15643 11228 15643 11229 15643 11248 324 11228 324 11246 324 11248 324 11246 324 11249 324 11250 324 11230 324 11248 324 11248 324 11230 324 11228 324 11251 324 11236 324 11252 324 11252 324 11236 324 11234 324 11252 324 11234 324 11253 324 11249 324 11246 324 11254 324 11255 324 11238 324 11251 324 11251 324 11238 324 11236 324 11256 324 11240 324 11238 324 11256 324 11238 324 11255 324 11253 324 11234 324 11232 324 11253 324 11232 324 11250 324 11250 324 11232 324 11230 324 11246 324 11244 324 11254 324 11254 324 11244 324 11257 324 11257 324 11244 324 11242 324 11257 324 11242 324 11240 324 11257 324 11240 324 11256 324 11258 15644 11259 15644 11260 15644 11260 15645 11259 15645 11261 15645 11260 15646 11261 15646 11262 15646 11262 15647 11261 15647 11263 15647 11262 15648 11263 15648 11264 15648 11264 15649 11263 15649 11265 15649 11264 15650 11265 15650 11266 15650 11266 15651 11265 15651 11267 15651 11267 15652 11265 15652 11268 15652 11267 15653 11268 15653 11269 15653 11269 15654 11268 15654 11270 15654 11269 15655 11270 15655 11271 15655 11269 15656 11271 15656 11272 15656 11272 15657 11271 15657 11273 15657 11273 15658 11271 15658 11274 15658 11273 15659 11274 15659 11275 15659 11275 15660 11274 15660 11276 15660 11275 15661 11276 15661 11277 15661 11275 15662 11277 15662 11278 15662 11278 15663 11277 15663 11279 15663 11278 15664 11279 15664 11280 15664 11280 15665 11279 15665 11281 15665 11280 15666 11281 15666 11282 15666 11282 15667 11281 15667 11283 15667 11282 15668 11283 15668 11284 15668 11284 15669 11283 15669 11285 15669 11284 15670 11285 15670 11286 15670 11286 15671 11285 15671 11287 15671 11286 15672 11287 15672 11288 15672 11288 15673 11287 15673 11289 15673 11288 15674 11289 15674 11290 15674 11290 15675 11289 15675 11291 15675 11290 15676 11291 15676 11258 15676 11258 15677 11291 15677 11259 15677 11292 348 11276 348 11293 348 11293 348 11276 348 11274 348 11293 348 11274 348 11294 348 11295 348 11289 348 11296 348 11296 348 11289 348 11287 348 11296 348 11287 348 11297 348 11298 348 11268 348 11265 348 11298 348 11265 348 11299 348 11287 348 11285 348 11297 348 11297 348 11285 348 11283 348 11297 348 11283 348 11281 348 11297 348 11281 348 11300 348 11294 348 11274 348 11271 348 11294 348 11271 348 11298 348 11298 348 11271 348 11270 348 11298 348 11270 348 11268 348 11300 348 11281 348 11279 348 11300 348 11279 348 11292 348 11292 348 11279 348 11277 348 11292 348 11277 348 11276 348 11299 348 11265 348 11263 348 11299 348 11263 348 11301 348 11301 348 11263 348 11261 348 11301 348 11261 348 11259 348 11301 348 11259 348 11295 348 11295 348 11259 348 11291 348 11295 348 11291 348 11289 348 11241 324 11272 324 11273 324 11241 324 11273 324 11239 324 11239 324 11273 324 11275 324 11243 324 11267 324 11269 324 11243 324 11269 324 11241 324 11241 324 11269 324 11272 324 11235 324 11282 324 11284 324 11235 324 11284 324 11233 324 11233 324 11284 324 11286 324 11233 324 11286 324 11231 324 11239 324 11275 324 11278 324 11239 324 11278 324 11237 324 11237 324 11278 324 11280 324 11237 324 11280 324 11235 324 11235 324 11280 324 11282 324 11247 324 11262 324 11245 324 11245 324 11262 324 11264 324 11245 324 11264 324 11266 324 11245 324 11266 324 11243 324 11243 324 11266 324 11267 324 11231 324 11286 324 11288 324 11231 324 11288 324 11290 324 11231 324 11290 324 11229 324 11229 324 11290 324 11258 324 11229 324 11258 324 11260 324 11229 324 11260 324 11247 324 11247 324 11260 324 11262 324 11302 15678 11293 15678 11303 15678 11303 15679 11293 15679 11294 15679 11303 15680 11294 15680 11304 15680 11304 15681 11294 15681 11298 15681 11304 15682 11298 15682 11305 15682 11305 15683 11298 15683 11299 15683 11305 15684 11299 15684 11301 15684 11305 15685 11301 15685 11306 15685 11306 15686 11301 15686 11307 15686 11307 15687 11301 15687 11295 15687 11307 15688 11295 15688 11308 15688 11308 15689 11295 15689 11296 15689 11308 15690 11296 15690 11309 15690 11309 15691 11296 15691 11297 15691 11309 15692 11297 15692 11310 15692 11310 15693 11297 15693 11300 15693 11310 15694 11300 15694 11311 15694 11311 15695 11300 15695 11292 15695 11311 15696 11292 15696 11302 15696 11302 15697 11292 15697 11293 15697 11312 348 11311 348 11313 348 11313 348 11311 348 11302 348 11313 348 11302 348 11314 348 11315 348 11310 348 11311 348 11315 348 11311 348 11312 348 11302 348 11303 348 11314 348 11314 348 11303 348 11316 348 11316 348 11303 348 11304 348 11317 348 11309 348 11310 348 11317 348 11310 348 11315 348 11318 348 11306 348 11319 348 11319 348 11306 348 11307 348 11320 348 11305 348 11318 348 11318 348 11305 348 11306 348 11319 348 11307 348 11308 348 11319 348 11308 348 11321 348 11321 348 11308 348 11317 348 11317 348 11308 348 11309 348 11316 348 11304 348 11320 348 11320 348 11304 348 11305 348 11255 15698 11313 15698 11256 15698 11256 15699 11313 15699 11314 15699 11256 15700 11314 15700 11257 15700 11257 15701 11314 15701 11316 15701 11257 15702 11316 15702 11254 15702 11254 15703 11316 15703 11320 15703 11254 15704 11320 15704 11249 15704 11249 15705 11320 15705 11318 15705 11249 15706 11318 15706 11248 15706 11248 15707 11318 15707 11319 15707 11248 15708 11319 15708 11250 15708 11250 15709 11319 15709 11321 15709 11250 15710 11321 15710 11253 15710 11253 15711 11321 15711 11317 15711 11253 15712 11317 15712 11252 15712 11252 15713 11317 15713 11315 15713 11252 15714 11315 15714 11251 15714 11251 15715 11315 15715 11312 15715 11251 15716 11312 15716 11255 15716 11255 15717 11312 15717 11313 15717 11323 15718 11322 15718 11324 15718 11323 15719 11324 15719 11325 15719 11325 15720 11324 15720 11326 15720 11326 15721 11324 15721 11327 15721 11326 15722 11327 15722 11328 15722 11326 15723 11328 15723 11329 15723 11329 15724 11328 15724 11330 15724 11329 15725 11330 15725 11331 15725 11331 15726 11330 15726 11332 15726 11331 15727 11332 15727 11333 15727 11333 15728 11332 15728 11334 15728 11334 15729 11332 15729 11335 15729 11334 15730 11335 15730 11336 15730 11334 15731 11336 15731 11337 15731 11337 15732 11336 15732 11338 15732 11338 15733 11336 15733 11339 15733 11338 15734 11339 15734 11340 15734 11340 15735 11339 15735 11341 15735 11340 15736 11341 15736 11342 15736 11340 15737 11342 15737 11343 15737 11343 15738 11342 15738 11322 15738 11343 15739 11322 15739 11323 15739 11344 324 11322 324 11345 324 11345 324 11322 324 11342 324 11346 324 11324 324 11344 324 11344 324 11324 324 11322 324 11347 324 11330 324 11328 324 11347 324 11328 324 11348 324 11345 324 11342 324 11341 324 11345 324 11341 324 11349 324 11350 324 11330 324 11347 324 11351 324 11335 324 11352 324 11352 324 11335 324 11332 324 11352 324 11332 324 11350 324 11350 324 11332 324 11330 324 11348 324 11328 324 11327 324 11348 324 11327 324 11346 324 11346 324 11327 324 11324 324 11349 324 11341 324 11339 324 11349 324 11339 324 11353 324 11353 324 11339 324 11336 324 11353 324 11336 324 11351 324 11351 324 11336 324 11335 324 11354 15740 11355 15740 11356 15740 11356 15741 11355 15741 11357 15741 11356 15742 11357 15742 11358 15742 11358 15743 11357 15743 11359 15743 11358 15744 11359 15744 11360 15744 11360 15745 11359 15745 11361 15745 11360 15746 11361 15746 11362 15746 11362 15747 11361 15747 11363 15747 11362 15748 11363 15748 11364 15748 11362 15749 11364 15749 11365 15749 11365 15750 11364 15750 11366 15750 11365 15751 11366 15751 11367 15751 11367 15752 11366 15752 11368 15752 11367 15753 11368 15753 11369 15753 11369 15754 11368 15754 11370 15754 11369 15755 11370 15755 11371 15755 11371 15756 11370 15756 11372 15756 11371 15757 11372 15757 11373 15757 11373 15758 11372 15758 11374 15758 11374 15759 11372 15759 11375 15759 11374 15760 11375 15760 11376 15760 11376 15761 11375 15761 11377 15761 11376 15762 11377 15762 11378 15762 11378 15763 11377 15763 11379 15763 11378 15764 11379 15764 11380 15764 11380 15765 11379 15765 11381 15765 11380 15766 11381 15766 11382 15766 11382 15767 11381 15767 11383 15767 11383 15768 11381 15768 11384 15768 11383 15769 11384 15769 11385 15769 11383 15770 11385 15770 11386 15770 11386 15771 11385 15771 11354 15771 11354 15772 11385 15772 11355 15772 11387 348 11372 348 11370 348 11395 348 11385 348 11388 348 11388 348 11385 348 11384 348 11388 348 11384 348 11381 348 11389 348 11364 348 11363 348 11389 348 11363 348 11390 348 11390 348 11363 348 11361 348 11388 348 11381 348 11391 348 11391 348 11381 348 11379 348 11391 348 11379 348 11377 348 11391 348 11377 348 11392 348 11370 348 11368 348 11387 348 11387 348 11368 348 11393 348 11393 348 11368 348 11366 348 11393 348 11366 348 11389 348 11389 348 11366 348 11364 348 11392 348 11377 348 11375 348 11392 348 11375 348 11372 348 11392 348 11372 348 11387 348 11390 348 11361 348 11359 348 11390 348 11359 348 11394 348 11394 348 11359 348 11357 348 11394 348 11357 348 11395 348 11357 348 11355 348 11395 348 11395 348 11355 348 11385 348 11334 324 11367 324 11369 324 11334 324 11369 324 11333 324 11333 324 11369 324 11371 324 11333 324 11371 324 11331 324 11338 324 11362 324 11365 324 11338 324 11365 324 11337 324 11337 324 11365 324 11334 324 11334 324 11365 324 11367 324 11329 324 11378 324 11380 324 11329 324 11380 324 11326 324 11326 324 11380 324 11382 324 11371 324 11373 324 11331 324 11331 324 11373 324 11374 324 11331 324 11374 324 11376 324 11331 324 11376 324 11329 324 11329 324 11376 324 11378 324 11340 324 11358 324 11360 324 11340 324 11360 324 11338 324 11338 324 11360 324 11362 324 11326 324 11382 324 11383 324 11326 324 11383 324 11325 324 11325 324 11383 324 11386 324 11325 324 11386 324 11323 324 11323 324 11386 324 11354 324 11323 324 11354 324 11343 324 11343 324 11354 324 11356 324 11343 324 11356 324 11340 324 11340 324 11356 324 11358 324 11396 15773 11387 15773 11397 15773 11397 15774 11387 15774 11393 15774 11397 15775 11393 15775 11398 15775 11398 15776 11393 15776 11389 15776 11398 15777 11389 15777 11399 15777 11399 15778 11389 15778 11390 15778 11399 15779 11390 15779 11400 15779 11400 15780 11390 15780 11394 15780 11400 15781 11394 15781 11401 15781 11401 15782 11394 15782 11395 15782 11401 15783 11395 15783 11402 15783 11402 15784 11395 15784 11388 15784 11402 15785 11388 15785 11403 15785 11403 15786 11388 15786 11391 15786 11403 15787 11391 15787 11404 15787 11404 15788 11391 15788 11392 15788 11404 15789 11392 15789 11396 15789 11396 15790 11392 15790 11387 15790 11405 348 11396 348 11406 348 11407 348 11404 348 11405 348 11405 348 11404 348 11396 348 11406 348 11396 348 11397 348 11406 348 11397 348 11408 348 11408 348 11397 348 11398 348 11408 348 11398 348 11409 348 11410 348 11403 348 11407 348 11407 348 11403 348 11404 348 11411 348 11401 348 11412 348 11413 348 11399 348 11400 348 11413 348 11400 348 11411 348 11411 348 11400 348 11401 348 11412 348 11401 348 11402 348 11412 348 11402 348 11414 348 11414 348 11402 348 11410 348 11410 348 11402 348 11403 348 11409 348 11398 348 11413 348 11413 348 11398 348 11399 348 11352 15791 11406 15791 11351 15791 11351 15792 11406 15792 11408 15792 11351 15793 11408 15793 11353 15793 11353 15794 11408 15794 11409 15794 11353 15795 11409 15795 11349 15795 11349 15796 11409 15796 11413 15796 11349 15797 11413 15797 11345 15797 11345 15798 11413 15798 11411 15798 11345 15799 11411 15799 11344 15799 11344 15800 11411 15800 11412 15800 11344 15801 11412 15801 11346 15801 11346 15802 11412 15802 11414 15802 11346 15803 11414 15803 11348 15803 11348 15804 11414 15804 11410 15804 11348 15805 11410 15805 11407 15805 11348 15806 11407 15806 11347 15806 11347 15807 11407 15807 11405 15807 11347 15808 11405 15808 11350 15808 11350 15809 11405 15809 11352 15809 11352 15810 11405 15810 11406 15810 11415 15375 11416 15375 11417 15375 11416 15811 11418 15811 11417 15811 11417 15812 11418 15812 11419 15812 11419 15813 11418 15813 11420 15813 11419 15814 11420 15814 11421 15814 11421 15815 11420 15815 11422 15815 11421 15816 11422 15816 11423 15816 11423 15817 11422 15817 11424 15817 11423 15818 11424 15818 11425 15818 11423 15819 11425 15819 11426 15819 11426 15820 11425 15820 11427 15820 11426 15821 11427 15821 11428 15821 11428 15822 11427 15822 11429 15822 11428 15823 11429 15823 11415 15823 11415 15824 11429 15824 11416 15824 11430 15825 11431 15825 11432 15825 11432 15826 11431 15826 11433 15826 11432 15827 11433 15827 11434 15827 11434 15828 11433 15828 11435 15828 11434 15829 11435 15829 11436 15829 11436 15830 11435 15830 11437 15830 11436 15831 11437 15831 11438 15831 11438 15832 11437 15832 11439 15832 11438 15833 11439 15833 11440 15833 11440 15834 11439 15834 11441 15834 11439 15835 11442 15835 11441 15835 11441 15836 11442 15836 11443 15836 11443 15837 11442 15837 11444 15837 11443 15838 11444 15838 11445 15838 11445 15839 11444 15839 11446 15839 11445 15840 11446 15840 11447 15840 11447 15841 11446 15841 11448 15841 11448 15842 11446 15842 11449 15842 11448 15843 11449 15843 11430 15843 11430 15844 11449 15844 11431 15844 11451 15845 11450 15845 11452 15845 11453 15846 11452 15846 11493 15846 11493 15847 11452 15847 11450 15847 11452 15848 11453 15848 11454 15848 11455 15849 11454 15849 11453 15849 11454 15850 11455 15850 11456 15850 11457 15851 11456 15851 11455 15851 11456 15852 11457 15852 11458 15852 11494 15853 11458 15853 11457 15853 11458 15854 11494 15854 11459 15854 11458 15855 11459 15855 11460 15855 11461 15856 11462 15856 11459 15856 11459 15857 11462 15857 11460 15857 11462 15858 11461 15858 11463 15858 11463 15859 11461 15859 11464 15859 11463 15860 11464 15860 11465 15860 11465 15861 11464 15861 11466 15861 11465 15862 11466 15862 11467 15862 11467 15863 11466 15863 11468 15863 11467 15864 11468 15864 11451 15864 11451 15865 11468 15865 11450 15865 11465 15866 11470 15866 11469 15866 11469 15867 11471 15867 11465 15867 11469 15868 11472 15868 11471 15868 11469 15869 11473 15869 11472 15869 11447 15870 11448 15870 11474 15870 11447 15871 11474 15871 11475 15871 11447 15872 11475 15872 11445 15872 11445 15873 11475 15873 11443 15873 11443 15874 11475 15874 11476 15874 11443 15875 11476 15875 11441 15875 11441 15876 11476 15876 11477 15876 11441 15877 11477 15877 11440 15877 11440 15878 11477 15878 11438 15878 11438 15879 11477 15879 11478 15879 11438 15880 11478 15880 11436 15880 11436 15881 11478 15881 11479 15881 11436 15882 11479 15882 11434 15882 11434 15883 11479 15883 11480 15883 11434 15884 11480 15884 11432 15884 11432 15885 11480 15885 11481 15885 11432 15886 11481 15886 11430 15886 11430 15887 11481 15887 11482 15887 11430 15888 11482 15888 11448 15888 11448 15889 11482 15889 11474 15889 11424 15890 11478 15890 11477 15890 11424 15891 11477 15891 11425 15891 11477 15892 11476 15892 11425 15892 11425 15893 11476 15893 11427 15893 11427 15894 11476 15894 11475 15894 11427 15895 11475 15895 11429 15895 11475 15896 11474 15896 11429 15896 11429 15897 11474 15897 11416 15897 11474 15898 11482 15898 11416 15898 11416 15899 11482 15899 11418 15899 11482 15900 11481 15900 11418 15900 11418 15901 11481 15901 11420 15901 11481 15902 11480 15902 11420 15902 11420 15466 11480 15466 11422 15466 11480 15903 11479 15903 11422 15903 11422 15904 11479 15904 11478 15904 11422 15905 11478 15905 11424 15905 11451 15906 11470 15906 11467 15906 11467 15907 11470 15907 11465 15907 11463 15908 11465 15908 11471 15908 11463 15909 11471 15909 11462 15909 11462 15910 11471 15910 11472 15910 11462 15911 11472 15911 11460 15911 11460 15912 11472 15912 11458 15912 11458 15913 11472 15913 11473 15913 11458 15914 11473 15914 11456 15914 11456 15915 11473 15915 11454 15915 11454 15916 11473 15916 11469 15916 11454 15917 11469 15917 11452 15917 11452 15918 11469 15918 11451 15918 11451 15919 11469 15919 11470 15919 11426 15920 11483 15920 11423 15920 11428 15486 11484 15486 11426 15486 11423 15487 11485 15487 11421 15487 11486 15921 11488 15921 11487 15921 11486 15922 11487 15922 11489 15922 11489 15923 11487 15923 11490 15923 11490 15924 11487 15924 11491 15924 11487 15925 11492 15925 11491 15925 11492 15926 11487 15926 11488 15926 11426 15927 11489 15927 11483 15927 11483 15928 11489 15928 11490 15928 11490 15929 11423 15929 11483 15929 11428 15497 11486 15497 11484 15497 11484 15930 11486 15930 11489 15930 11489 15931 11426 15931 11484 15931 11486 15932 11428 15932 11415 15932 11486 15933 11415 15933 11488 15933 11417 15934 11488 15934 11415 15934 11419 15935 11492 15935 11417 15935 11417 15936 11492 15936 11488 15936 11421 15505 11491 15505 11419 15505 11492 15937 11419 15937 11491 15937 11423 15938 11490 15938 11485 15938 11485 15939 11490 15939 11491 15939 11491 15940 11421 15940 11485 15940 11446 15941 11493 15941 11450 15941 11446 15942 11450 15942 11449 15942 11449 15943 11450 15943 11468 15943 11449 15944 11468 15944 11431 15944 11446 15945 11453 15945 11493 15945 11446 15946 11444 15946 11453 15946 11444 15947 11455 15947 11453 15947 11444 15948 11457 15948 11455 15948 11444 15949 11442 15949 11457 15949 11442 15950 11439 15950 11494 15950 11442 15951 11494 15951 11457 15951 11439 15952 11459 15952 11494 15952 11439 15953 11437 15953 11459 15953 11437 15954 11461 15954 11459 15954 11437 15955 11435 15955 11461 15955 11435 15956 11464 15956 11461 15956 11435 15957 11433 15957 11464 15957 11433 15958 11431 15958 11466 15958 11433 15959 11466 15959 11464 15959 11431 15960 11468 15960 11466 15960 11500 15961 11497 15961 11498 15961 11495 15962 11496 15962 11499 15962 11499 15963 11500 15963 11498 15963 11495 15964 11499 15964 11498 15964 11501 15965 11497 15965 11500 15965 11504 15966 11502 15966 11503 15966 11498 15967 11497 15967 11501 15967 11501 15968 11504 15968 11503 15968 11498 15969 11501 15969 11503 15969 11504 15970 11505 15970 11502 15970 11506 15971 11502 15971 11505 15971 11503 15972 11502 15972 11506 15972 11507 15973 11509 15973 11508 15973 11503 15974 11506 15974 11507 15974 11503 15975 11507 15975 11508 15975 11512 15976 11509 15976 11511 15976 11511 15977 11509 15977 11507 15977 11510 15978 11509 15978 11513 15978 11513 15979 11509 15979 11512 15979 11516 15980 11514 15980 11515 15980 11510 15981 11516 15981 11515 15981 11508 15982 11509 15982 11515 15982 11515 15983 11509 15983 11510 15983 11514 15984 11516 15984 11517 15984 11515 15985 11514 15985 11517 15985 11517 15986 11519 15986 11518 15986 11515 15987 11517 15987 11518 15987 11522 15988 11519 15988 11517 15988 11523 15989 11519 15989 11522 15989 11523 15990 11520 15990 11519 15990 11524 15991 11496 15991 11495 15991 11518 15992 11519 15992 11520 15992 11521 15993 11524 15993 11495 15993 11518 15994 11520 15994 11495 15994 11495 15995 11520 15995 11521 15995 11499 15996 11496 15996 11524 15996 11521 15997 11527 15997 11526 15997 11507 15998 11525 15998 11533 15998 11525 15999 11507 15999 11506 15999 11526 16000 11499 16000 11524 16000 11526 16001 11524 16001 11521 16001 11527 16002 11528 16002 11529 16002 11527 16003 11529 16003 11530 16003 11527 16004 11521 16004 11531 16004 11527 16005 11531 16005 11532 16005 11527 16006 11532 16006 11528 16006 11538 16007 11499 16007 11526 16007 11538 16008 11500 16008 11499 16008 11533 16009 11534 16009 11535 16009 11533 16010 11535 16010 11536 16010 11533 16011 11536 16011 11507 16011 11516 16012 11510 16012 11530 16012 11530 16013 11510 16013 11533 16013 11533 16014 11510 16014 11537 16014 11533 16015 11537 16015 11534 16015 11538 16016 11501 16016 11500 16016 11525 16017 11506 16017 11505 16017 11525 16018 11505 16018 11538 16018 11530 16019 11517 16019 11516 16019 11538 16020 11505 16020 11501 16020 11529 4711 11539 4711 11530 4711 11530 16021 11539 16021 11517 16021 11526 16022 11527 16022 11540 16022 11540 16023 11541 16023 11526 16023 11526 16024 11541 16024 11538 16024 11538 16025 11541 16025 11542 16025 11538 16026 11542 16026 11525 16026 11542 16027 11543 16027 11525 16027 11544 16028 11525 16028 11543 16028 11533 16029 11525 16029 11544 16029 11544 16030 11545 16030 11533 16030 11533 16031 11545 16031 11530 16031 11530 16032 11545 16032 11546 16032 11530 16033 11546 16033 11527 16033 11546 16034 11547 16034 11527 16034 11540 16035 11527 16035 11547 16035 11548 16036 11540 16036 11547 16036 11548 16037 11547 16037 11546 16037 11548 16038 11546 16038 11549 16038 11549 16039 11546 16039 11550 16039 11550 16040 11546 16040 11545 16040 11550 16041 11545 16041 11551 16041 11551 16042 11545 16042 11544 16042 11551 16043 11544 16043 11552 16043 11552 16044 11544 16044 11543 16044 11552 16045 11543 16045 11542 16045 11552 16046 11542 16046 11553 16046 11553 16047 11542 16047 11554 16047 11554 16048 11542 16048 11541 16048 11554 16049 11541 16049 11555 16049 11555 16050 11541 16050 11540 16050 11555 16051 11540 16051 11548 16051 11556 16052 11552 16052 11557 16052 11552 16053 11553 16053 11557 16053 11557 16054 11553 16054 11558 16054 11553 16055 11554 16055 11558 16055 11558 16056 11554 16056 11559 16056 11554 16057 11555 16057 11559 16057 11548 16058 11560 16058 11555 16058 11555 16059 11560 16059 11559 16059 11560 16060 11548 16060 11561 16060 11548 16061 11549 16061 11561 16061 11549 16062 11550 16062 11561 16062 11561 16063 11550 16063 11562 16063 11550 16064 11551 16064 11562 16064 11562 16065 11551 16065 11556 16065 11552 16066 11556 16066 11551 16066 11562 16067 11556 16067 11508 16067 11508 16068 11556 16068 11503 16068 11503 16069 11556 16069 11557 16069 11498 16070 11558 16070 11495 16070 11495 16071 11558 16071 11559 16071 11515 16072 11561 16072 11562 16072 11515 16073 11562 16073 11508 16073 11503 16074 11557 16074 11498 16074 11498 16075 11557 16075 11558 16075 11495 16076 11559 16076 11518 16076 11518 16077 11559 16077 11560 16077 11518 16078 11560 16078 11561 16078 11518 16079 11561 16079 11515 16079 11563 16080 11564 16080 11565 16080 11563 16081 11565 16081 11566 16081 11567 16082 11568 16082 11563 16082 11563 16083 11568 16083 11564 16083 11569 16084 11570 16084 11567 16084 11567 16085 11570 16085 11568 16085 11571 16086 11572 16086 11569 16086 11569 16087 11572 16087 11573 16087 11569 16088 11573 16088 11570 16088 11576 16089 11577 16089 11571 16089 11571 16090 11577 16090 11574 16090 11571 16091 11574 16091 11572 16091 11566 16092 11575 16092 11576 16092 11576 16093 11575 16093 11577 16093 11566 16094 11565 16094 11578 16094 11566 16095 11578 16095 11575 16095 11579 16096 11580 16096 11581 16096 11581 16097 11580 16097 11582 16097 11581 16098 11582 16098 11583 16098 11583 16099 11582 16099 11584 16099 11583 16100 11584 16100 11585 16100 11585 16101 11584 16101 11586 16101 11586 16102 11584 16102 11587 16102 11586 16103 11587 16103 11588 16103 11588 16104 11587 16104 11589 16104 11588 16105 11589 16105 11590 16105 11590 16106 11589 16106 11591 16106 11591 16107 11589 16107 11592 16107 11591 16108 11592 16108 11593 16108 11593 16109 11592 16109 11594 16109 11594 16110 11592 16110 11595 16110 11594 16111 11595 16111 11596 16111 11595 16112 11597 16112 11596 16112 11596 16113 11597 16113 11598 16113 11598 16114 11597 16114 11599 16114 11598 16115 11599 16115 11600 16115 11600 16116 11599 16116 11601 16116 11601 16117 11599 16117 11602 16117 11601 16118 11602 16118 11603 16118 11603 16119 11602 16119 11604 16119 11603 16120 11604 16120 11605 16120 11605 16121 11604 16121 11606 16121 11606 16122 11604 16122 11607 16122 11606 16123 11607 16123 11608 16123 11608 16124 11607 16124 11609 16124 11608 16125 11609 16125 11610 16125 11610 16126 11609 16126 11611 16126 11611 16127 11609 16127 11612 16127 11611 16128 11612 16128 11613 16128 11613 16129 11612 16129 11614 16129 11613 16130 11614 16130 11615 16130 11615 16131 11614 16131 11616 16131 11615 16132 11616 16132 11617 16132 11617 16133 11616 16133 11618 16133 11618 7913 11616 7913 11619 7913 11618 16134 11619 16134 11620 16134 11620 16135 11619 16135 11621 16135 11620 16136 11621 16136 11622 16136 11622 16137 11621 16137 11623 16137 11623 16138 11621 16138 11624 16138 11623 16139 11624 16139 11625 16139 11625 16140 11624 16140 11626 16140 11626 16141 11624 16141 11627 16141 11626 16142 11627 16142 11628 16142 11628 16143 11627 16143 11629 16143 11629 16144 11627 16144 11630 16144 11629 16145 11630 16145 11579 16145 11579 16146 11630 16146 11580 16146 11632 16147 11631 16147 11633 16147 11633 16148 11631 16148 11634 16148 11633 16149 11634 16149 11635 16149 11635 16150 11634 16150 11636 16150 11636 16151 11637 16151 11635 16151 11637 16152 11636 16152 11638 16152 11638 16153 11639 16153 11637 16153 11639 16154 11638 16154 11640 16154 11640 16155 11641 16155 11639 16155 11641 16156 11640 16156 11642 16156 11642 16157 11643 16157 11641 16157 11643 16158 11642 16158 11644 16158 11644 16159 11645 16159 11643 16159 11645 16160 11644 16160 11646 16160 11646 16161 11647 16161 11645 16161 11647 16162 11646 16162 11648 16162 11648 16163 11649 16163 11647 16163 11649 16164 11648 16164 11688 16164 11649 16165 11688 16165 11650 16165 11651 16166 11650 16166 11688 16166 11650 16167 11651 16167 11652 16167 11652 16168 11651 16168 11684 16168 11652 16169 11684 16169 11632 16169 11632 16170 11684 16170 11631 16170 11632 16171 11633 16171 11641 16171 11649 16172 11652 16172 11641 16172 11641 16173 11652 16173 11632 16173 11645 16174 11649 16174 11641 16174 11643 16175 11645 16175 11641 16175 11633 16176 11635 16176 11641 16176 11641 16177 11635 16177 11639 16177 11653 16178 11654 16178 11655 16178 11654 16179 11656 16179 11655 16179 11656 16180 11657 16180 11655 16180 11655 16181 11657 16181 11658 16181 11657 16182 11570 16182 11658 16182 11658 16183 11570 16183 11659 16183 11659 16184 11570 16184 11573 16184 11659 16185 11573 16185 11660 16185 11659 16186 11660 16186 11661 16186 11661 16187 11660 16187 11662 16187 11661 16188 11662 16188 11663 16188 11663 16189 11662 16189 11574 16189 11663 16190 11574 16190 11664 16190 11664 16191 11574 16191 11577 16191 11664 16192 11577 16192 11575 16192 11664 16193 11575 16193 11665 16193 11575 16194 11666 16194 11665 16194 11665 16195 11666 16195 11667 16195 11666 16196 11578 16196 11667 16196 11667 16197 11578 16197 11565 16197 11667 16198 11565 16198 11668 16198 11668 16199 11565 16199 11669 16199 11668 16200 11669 16200 11653 16200 11653 16201 11669 16201 11654 16201 11572 16202 11574 16202 11662 16202 11572 16203 11662 16203 11660 16203 11572 16204 11660 16204 11573 16204 11570 16205 11657 16205 11568 16205 11657 16206 11656 16206 11568 16206 11568 16207 11656 16207 11564 16207 11656 16208 11654 16208 11564 16208 11564 16209 11654 16209 11669 16209 11564 16210 11669 16210 11565 16210 11578 16211 11666 16211 11575 16211 11650 16212 11652 16212 11649 16212 11647 16213 11649 16213 11645 16213 11637 16214 11639 16214 11635 16214 11569 16215 11670 16215 11571 16215 11567 16216 11671 16216 11569 16216 11563 16217 11672 16217 11567 16217 11566 16218 11673 16218 11563 16218 11576 16219 11674 16219 11566 16219 11571 16220 11675 16220 11576 16220 11677 16221 11681 16221 11682 16221 11676 16222 11677 16222 11682 16222 11677 16223 11680 16223 11681 16223 11679 16224 11680 16224 11677 16224 11678 16225 11679 16225 11677 16225 11676 16226 11678 16226 11677 16226 11569 16227 11680 16227 11670 16227 11679 16228 11571 16228 11670 16228 11670 16229 11680 16229 11679 16229 11671 16230 11567 16230 11681 16230 11680 16231 11569 16231 11671 16231 11681 16232 11680 16232 11671 16232 11682 16233 11672 16233 11563 16233 11681 16234 11567 16234 11672 16234 11681 16235 11672 16235 11682 16235 11682 16236 11563 16236 11676 16236 11676 16237 11563 16237 11673 16237 11676 16238 11673 16238 11566 16238 11576 16239 11678 16239 11674 16239 11674 16240 11678 16240 11676 16240 11674 16241 11676 16241 11566 16241 11571 16242 11679 16242 11675 16242 11678 16243 11576 16243 11675 16243 11675 16244 11679 16244 11678 16244 11683 16245 11651 16245 11687 16245 11687 16246 11651 16246 11688 16246 11688 16247 11648 16247 11689 16247 11689 16248 11648 16248 11690 16248 11690 16249 11648 16249 11646 16249 11690 16250 11646 16250 11691 16250 11691 16251 11646 16251 11692 16251 11692 16252 11646 16252 11644 16252 11692 16253 11644 16253 11693 16253 11693 16254 11644 16254 11642 16254 11693 16255 11642 16255 11694 16255 11694 16256 11642 16256 11695 16256 11695 16257 11642 16257 11640 16257 11695 16258 11640 16258 11696 16258 11696 16259 11640 16259 11697 16259 11697 16260 11640 16260 11638 16260 11697 16261 11638 16261 11698 16261 11698 16262 11638 16262 11699 16262 11699 16263 11638 16263 11636 16263 11699 16264 11636 16264 11700 16264 11700 16265 11636 16265 11701 16265 11701 16266 11636 16266 11634 16266 11701 16267 11634 16267 11686 16267 11685 16268 11631 16268 11702 16268 11702 16269 11631 16269 11684 16269 11685 16270 11686 16270 11631 16270 11686 16271 11634 16271 11631 16271 11683 16272 11684 16272 11651 16272 11703 3222 11704 3222 11705 3222 11705 16273 11704 16273 11706 16273 11707 16274 11703 16274 11708 16274 11708 3225 11703 3225 11705 3225 11709 3218 11707 3218 11710 3218 11710 16275 11707 16275 11708 16275 11704 16276 11709 16276 11706 16276 11706 3221 11709 3221 11710 3221 11707 16277 11709 16277 11703 16277 11703 16278 11709 16278 11704 16278 11710 324 11708 324 11706 324 11706 324 11708 324 11705 324 11711 16279 11724 16279 11712 16279 11711 16280 11712 16280 11713 16280 11713 16281 11712 16281 11714 16281 11713 16282 11714 16282 11715 16282 11715 16283 11714 16283 11716 16283 11715 16284 11716 16284 11717 16284 11716 16285 11718 16285 11717 16285 11717 16286 11718 16286 11719 16286 11719 16287 11718 16287 11720 16287 11719 16288 11720 16288 11721 16288 11719 16289 11721 16289 11722 16289 11722 16290 11721 16290 11723 16290 11722 16291 11723 16291 11711 16291 11711 16292 11723 16292 11724 16292 11725 16293 11726 16293 11727 16293 11727 16294 11726 16294 11728 16294 11727 16295 11728 16295 11729 16295 11730 16296 11731 16296 11732 16296 11732 16297 11731 16297 11733 16297 11732 16298 11733 16298 11734 16298 11734 16299 11733 16299 11735 16299 11734 16300 11735 16300 11725 16300 11725 16301 11735 16301 11726 16301 11729 16302 11728 16302 11736 16302 11736 16303 11728 16303 11737 16303 11736 16304 11737 16304 11738 16304 11738 16305 11737 16305 11739 16305 11738 16306 11739 16306 11740 16306 11740 16307 11739 16307 11741 16307 11740 16308 11741 16308 11742 16308 11742 16309 11741 16309 11730 16309 11730 16310 11741 16310 11731 16310 11744 16311 11743 16311 11746 16311 11744 16312 11746 16312 11745 16312 11745 16313 11746 16313 11748 16313 11745 16314 11748 16314 11747 16314 11747 16315 11748 16315 11749 16315 11747 16316 11749 16316 11750 16316 11750 16317 11749 16317 11792 16317 11750 16318 11792 16318 11751 16318 11751 16319 11792 16319 11752 16319 11751 16320 11752 16320 11753 16320 11754 16321 11755 16321 11753 16321 11754 16322 11753 16322 11752 16322 11756 16323 11755 16323 11754 16323 11755 16324 11756 16324 11758 16324 11755 16325 11758 16325 11757 16325 11757 16326 11758 16326 11759 16326 11757 16327 11759 16327 11760 16327 11760 16328 11759 16328 11793 16328 11760 16329 11793 16329 11744 16329 11744 16330 11793 16330 11743 16330 11761 16331 11763 16331 11762 16331 11764 16332 11763 16332 11761 16332 11765 16333 11766 16333 11761 16333 11761 16334 11766 16334 11764 16334 11767 16335 11742 16335 11768 16335 11768 16336 11742 16336 11730 16336 11768 16337 11730 16337 11769 16337 11769 16338 11730 16338 11732 16338 11769 16339 11732 16339 11770 16339 11770 16340 11732 16340 11771 16340 11771 16341 11732 16341 11734 16341 11771 16342 11734 16342 11772 16342 11772 16343 11734 16343 11725 16343 11772 16344 11725 16344 11773 16344 11773 16345 11725 16345 11727 16345 11773 16346 11727 16346 11774 16346 11774 16347 11727 16347 11775 16347 11775 16348 11727 16348 11729 16348 11775 16349 11729 16349 11736 16349 11775 16350 11736 16350 11776 16350 11776 16351 11736 16351 11738 16351 11776 16352 11738 16352 11777 16352 11777 16353 11738 16353 11740 16353 11777 16354 11740 16354 11767 16354 11767 16355 11740 16355 11742 16355 11773 16356 11721 16356 11772 16356 11772 16357 11721 16357 11771 16357 11771 16358 11721 16358 11720 16358 11771 16359 11720 16359 11718 16359 11771 16360 11718 16360 11770 16360 11770 16361 11718 16361 11769 16361 11769 16362 11718 16362 11716 16362 11769 16363 11716 16363 11768 16363 11768 16364 11716 16364 11714 16364 11768 16365 11714 16365 11767 16365 11767 16366 11714 16366 11777 16366 11777 16367 11714 16367 11712 16367 11777 16368 11712 16368 11776 16368 11776 16369 11712 16369 11724 16369 11776 16370 11724 16370 11775 16370 11775 16371 11724 16371 11774 16371 11774 16372 11724 16372 11723 16372 11774 16373 11723 16373 11773 16373 11773 16374 11723 16374 11721 16374 11744 16375 11761 16375 11760 16375 11760 16376 11761 16376 11762 16376 11760 16377 11762 16377 11757 16377 11757 16378 11762 16378 11763 16378 11757 16379 11763 16379 11755 16379 11755 16380 11763 16380 11753 16380 11753 16381 11763 16381 11764 16381 11753 16382 11764 16382 11751 16382 11751 16383 11764 16383 11750 16383 11750 16384 11764 16384 11766 16384 11750 16385 11766 16385 11747 16385 11747 16386 11766 16386 11765 16386 11747 16387 11765 16387 11745 16387 11745 16388 11765 16388 11761 16388 11745 16389 11761 16389 11744 16389 11711 16390 11778 16390 11722 16390 11713 16391 11779 16391 11711 16391 11715 16392 11780 16392 11713 16392 11717 16393 11781 16393 11715 16393 11719 16394 11782 16394 11717 16394 11722 16395 11783 16395 11719 16395 11787 16396 11788 16396 11785 16396 11787 16397 11785 16397 11786 16397 11786 16398 11785 16398 11784 16398 11789 16399 11784 16399 11785 16399 11790 16400 11789 16400 11785 16400 11791 16401 11790 16401 11785 16401 11785 16402 11788 16402 11791 16402 11789 16403 11722 16403 11778 16403 11789 16404 11778 16404 11784 16404 11711 16405 11784 16405 11778 16405 11786 16406 11779 16406 11787 16406 11787 16407 11779 16407 11713 16407 11784 16408 11711 16408 11779 16408 11779 16409 11786 16409 11784 16409 11780 16410 11715 16410 11788 16410 11780 16411 11787 16411 11713 16411 11780 16412 11788 16412 11787 16412 11717 16413 11791 16413 11781 16413 11788 16414 11715 16414 11781 16414 11788 16415 11781 16415 11791 16415 11719 16416 11790 16416 11782 16416 11791 16417 11717 16417 11782 16417 11791 16418 11782 16418 11790 16418 11722 16419 11789 16419 11783 16419 11790 16420 11719 16420 11783 16420 11790 16421 11783 16421 11789 16421 11728 16422 11726 16422 11792 16422 11735 16423 11754 16423 11752 16423 11735 16424 11752 16424 11726 16424 11726 16425 11752 16425 11792 16425 11739 16426 11746 16426 11743 16426 11739 16427 11743 16427 11741 16427 11741 16428 11743 16428 11793 16428 11739 16429 11737 16429 11748 16429 11739 16430 11748 16430 11746 16430 11737 16431 11728 16431 11749 16431 11737 16432 11749 16432 11748 16432 11728 16433 11792 16433 11749 16433 11735 16434 11733 16434 11756 16434 11735 16435 11756 16435 11754 16435 11733 16436 11758 16436 11756 16436 11733 16437 11731 16437 11758 16437 11731 16438 11759 16438 11758 16438 11731 16439 11741 16439 11793 16439 11731 16440 11793 16440 11759 16440 11794 16441 11795 16441 11796 16441 11796 16442 11795 16442 11797 16442 11796 16443 11797 16443 11798 16443 11798 16444 11797 16444 11799 16444 11798 16445 11799 16445 11800 16445 11798 16446 11800 16446 11801 16446 11801 16447 11800 16447 11802 16447 11801 16448 11802 16448 11803 16448 11801 16449 11803 16449 11804 16449 11804 16450 11803 16450 11805 16450 11804 16451 11805 16451 11806 16451 11804 16452 11806 16452 11807 16452 11807 16453 11806 16453 11808 16453 11807 16454 11808 16454 11794 16454 11794 16455 11808 16455 11809 16455 11794 16456 11809 16456 11795 16456 11810 16457 11821 16457 11811 16457 11810 16458 11811 16458 11812 16458 11812 16459 11811 16459 11813 16459 11814 16460 11815 16460 11816 16460 11814 16461 11816 16461 11817 16461 11817 16462 11816 16462 11818 16462 11816 16463 11819 16463 11818 16463 11818 16464 11819 16464 11820 16464 11820 16465 11819 16465 11821 16465 11820 16466 11821 16466 11810 16466 11811 16467 11822 16467 11813 16467 11813 16468 11822 16468 11823 16468 11823 16469 11822 16469 11824 16469 11823 16470 11824 16470 11825 16470 11825 16471 11824 16471 11826 16471 11826 16472 11824 16472 11827 16472 11826 16473 11827 16473 11828 16473 11828 16474 11827 16474 11829 16474 11829 16475 11827 16475 11815 16475 11829 16476 11815 16476 11814 16476 11831 16477 11830 16477 11832 16477 11881 16478 11832 16478 11830 16478 11832 16479 11881 16479 11834 16479 11832 16480 11834 16480 11833 16480 11833 16481 11834 16481 11835 16481 11833 16482 11835 16482 11836 16482 11836 16483 11835 16483 11837 16483 11836 16484 11837 16484 11838 16484 11838 16485 11837 16485 11839 16485 11838 16486 11839 16486 11840 16486 11841 16487 11842 16487 11840 16487 11841 16488 11840 16488 11839 16488 11843 16489 11842 16489 11841 16489 11842 16490 11843 16490 11844 16490 11845 16491 11844 16491 11843 16491 11844 16492 11845 16492 11846 16492 11846 16493 11845 16493 11879 16493 11846 16494 11879 16494 11880 16494 11846 16495 11880 16495 11831 16495 11831 16496 11880 16496 11830 16496 11848 16497 11850 16497 11849 16497 11848 16498 11851 16498 11850 16498 11848 16499 11852 16499 11851 16499 11847 16500 11852 16500 11848 16500 11853 16501 11829 16501 11854 16501 11854 16502 11829 16502 11814 16502 11854 16503 11814 16503 11855 16503 11855 16504 11814 16504 11817 16504 11855 16505 11817 16505 11856 16505 11856 16506 11817 16506 11818 16506 11856 16507 11818 16507 11857 16507 11857 16508 11818 16508 11820 16508 11857 16509 11820 16509 11805 16509 11805 16510 11820 16510 11858 16510 11858 16511 11820 16511 11810 16511 11858 16512 11810 16512 11859 16512 11859 16513 11810 16513 11812 16513 11859 16514 11812 16514 11860 16514 11860 16515 11812 16515 11813 16515 11860 16516 11813 16516 11861 16516 11861 16517 11813 16517 11823 16517 11861 16518 11823 16518 11862 16518 11862 16519 11823 16519 11825 16519 11862 16520 11825 16520 11863 16520 11863 16521 11825 16521 11826 16521 11863 16522 11826 16522 11864 16522 11864 16523 11826 16523 11828 16523 11864 16524 11828 16524 11853 16524 11853 16525 11828 16525 11829 16525 11859 16526 11806 16526 11858 16526 11858 16527 11806 16527 11805 16527 11857 16528 11805 16528 11803 16528 11857 16529 11803 16529 11856 16529 11856 16530 11803 16530 11802 16530 11856 16531 11802 16531 11855 16531 11855 16532 11802 16532 11800 16532 11855 16533 11800 16533 11854 16533 11854 16534 11800 16534 11853 16534 11853 16535 11800 16535 11799 16535 11853 16536 11799 16536 11797 16536 11853 16537 11797 16537 11864 16537 11864 16538 11797 16538 11863 16538 11863 16539 11797 16539 11795 16539 11863 16540 11795 16540 11862 16540 11862 16541 11795 16541 11861 16541 11861 16542 11795 16542 11809 16542 11861 16543 11809 16543 11860 16543 11860 16544 11809 16544 11808 16544 11860 16545 11808 16545 11859 16545 11859 16546 11808 16546 11806 16546 11831 16547 11847 16547 11846 16547 11846 16548 11847 16548 11848 16548 11846 16549 11848 16549 11844 16549 11844 16550 11848 16550 11849 16550 11844 16551 11849 16551 11842 16551 11842 16552 11849 16552 11850 16552 11842 16553 11850 16553 11840 16553 11840 16554 11850 16554 11838 16554 11838 16555 11850 16555 11851 16555 11838 16556 11851 16556 11836 16556 11836 16557 11851 16557 11852 16557 11836 16558 11852 16558 11833 16558 11833 16559 11852 16559 11832 16559 11832 16560 11852 16560 11847 16560 11832 16561 11847 16561 11831 16561 11794 16562 11865 16562 11807 16562 11796 16563 11866 16563 11794 16563 11798 16564 11867 16564 11796 16564 11801 16565 11868 16565 11798 16565 11804 16566 11869 16566 11801 16566 11807 16567 11870 16567 11804 16567 11874 16568 11875 16568 11872 16568 11874 16569 11872 16569 11873 16569 11873 16570 11872 16570 11871 16570 11876 16571 11871 16571 11872 16571 11877 16572 11876 16572 11872 16572 11878 16573 11877 16573 11872 16573 11872 16574 11875 16574 11878 16574 11876 16575 11807 16575 11865 16575 11876 16576 11865 16576 11871 16576 11794 16577 11871 16577 11865 16577 11873 16578 11866 16578 11874 16578 11874 16579 11866 16579 11796 16579 11871 16580 11794 16580 11866 16580 11866 16581 11873 16581 11871 16581 11867 16582 11798 16582 11875 16582 11867 16583 11874 16583 11796 16583 11867 16584 11875 16584 11874 16584 11801 16585 11878 16585 11868 16585 11875 16586 11798 16586 11868 16586 11875 16587 11868 16587 11878 16587 11804 16588 11877 16588 11869 16588 11878 16589 11801 16589 11869 16589 11878 16590 11869 16590 11877 16590 11807 16591 11876 16591 11870 16591 11877 16592 11804 16592 11870 16592 11877 16593 11870 16593 11876 16593 11816 16594 11815 16594 11879 16594 11815 16595 11827 16595 11880 16595 11819 16596 11841 16596 11839 16596 11819 16597 11839 16597 11821 16597 11821 16598 11839 16598 11811 16598 11811 16599 11839 16599 11837 16599 11827 16600 11830 16600 11880 16600 11827 16601 11824 16601 11881 16601 11827 16602 11881 16602 11830 16602 11824 16603 11834 16603 11881 16603 11824 16604 11835 16604 11834 16604 11824 16605 11822 16605 11835 16605 11822 16606 11811 16606 11837 16606 11822 16607 11837 16607 11835 16607 11819 16608 11843 16608 11841 16608 11819 16609 11816 16609 11843 16609 11843 16610 11816 16610 11845 16610 11816 16611 11879 16611 11845 16611 11815 16612 11880 16612 11879 16612 11887 16613 11884 16613 11885 16613 11882 16614 11883 16614 11886 16614 11886 16615 11887 16615 11885 16615 11882 16616 11886 16616 11885 16616 11888 16617 11884 16617 11887 16617 11891 16618 11889 16618 11890 16618 11885 16619 11884 16619 11888 16619 11888 16620 11891 16620 11890 16620 11885 16621 11888 16621 11890 16621 11891 16622 11892 16622 11889 16622 11893 16623 11889 16623 11892 16623 11890 16624 11889 16624 11893 16624 11894 16625 11896 16625 11895 16625 11890 16626 11893 16626 11894 16626 11890 16627 11894 16627 11895 16627 11899 16628 11896 16628 11898 16628 11898 16629 11896 16629 11894 16629 11897 16630 11896 16630 11900 16630 11900 16631 11896 16631 11899 16631 11903 16632 11901 16632 11902 16632 11897 16633 11903 16633 11902 16633 11895 16634 11896 16634 11902 16634 11902 16635 11896 16635 11897 16635 11901 16636 11903 16636 11904 16636 11902 16637 11901 16637 11904 16637 11904 16638 11906 16638 11905 16638 11902 16639 11904 16639 11905 16639 11909 16640 11906 16640 11904 16640 11910 16641 11906 16641 11909 16641 11910 16642 11907 16642 11906 16642 11911 16643 11883 16643 11882 16643 11905 16644 11906 16644 11907 16644 11908 16645 11911 16645 11882 16645 11905 16646 11907 16646 11882 16646 11882 16647 11907 16647 11908 16647 11886 16648 11883 16648 11911 16648 11908 16649 11914 16649 11913 16649 11894 16650 11912 16650 11920 16650 11912 16651 11894 16651 11893 16651 11913 16652 11886 16652 11911 16652 11913 16653 11911 16653 11908 16653 11914 16654 11915 16654 11916 16654 11914 16655 11916 16655 11917 16655 11914 16656 11908 16656 11918 16656 11914 16657 11918 16657 11919 16657 11914 16658 11919 16658 11915 16658 11925 16659 11886 16659 11913 16659 11925 16660 11887 16660 11886 16660 11920 16661 11921 16661 11922 16661 11920 16662 11922 16662 11923 16662 11920 16663 11923 16663 11894 16663 11903 16664 11897 16664 11917 16664 11917 16665 11897 16665 11920 16665 11920 16666 11897 16666 11924 16666 11920 16667 11924 16667 11921 16667 11925 16668 11888 16668 11887 16668 11912 16669 11893 16669 11892 16669 11912 16670 11892 16670 11925 16670 11917 16671 11904 16671 11903 16671 11925 16672 11892 16672 11888 16672 11916 3288 11926 3288 11917 3288 11917 16673 11926 16673 11904 16673 11913 16674 11914 16674 11927 16674 11927 16675 11928 16675 11913 16675 11913 16676 11928 16676 11925 16676 11925 16677 11928 16677 11929 16677 11925 16678 11929 16678 11912 16678 11929 16679 11930 16679 11912 16679 11931 16680 11912 16680 11930 16680 11920 16681 11912 16681 11931 16681 11931 16682 11932 16682 11920 16682 11920 16683 11932 16683 11917 16683 11917 16684 11932 16684 11933 16684 11917 16685 11933 16685 11914 16685 11933 16686 11934 16686 11914 16686 11927 16687 11914 16687 11934 16687 11935 16688 11927 16688 11934 16688 11935 16689 11934 16689 11933 16689 11935 16690 11933 16690 11936 16690 11936 16691 11933 16691 11937 16691 11937 16692 11933 16692 11932 16692 11937 16693 11932 16693 11938 16693 11938 16694 11932 16694 11931 16694 11938 16695 11931 16695 11939 16695 11939 16696 11931 16696 11930 16696 11939 16697 11930 16697 11929 16697 11939 16698 11929 16698 11940 16698 11940 16699 11929 16699 11941 16699 11941 16700 11929 16700 11928 16700 11941 16701 11928 16701 11942 16701 11942 16702 11928 16702 11927 16702 11942 16703 11927 16703 11935 16703 11943 16704 11939 16704 11944 16704 11939 16705 11940 16705 11944 16705 11940 16706 11941 16706 11944 16706 11944 16707 11941 16707 11945 16707 11941 16708 11942 16708 11945 16708 11945 16709 11942 16709 11946 16709 11935 16710 11946 16710 11942 16710 11946 16711 11935 16711 11947 16711 11935 16712 11936 16712 11947 16712 11936 16713 11937 16713 11947 16713 11947 16714 11937 16714 11948 16714 11937 16715 11938 16715 11948 16715 11948 16716 11938 16716 11943 16716 11939 16717 11943 16717 11938 16717 11948 16718 11943 16718 11895 16718 11895 16719 11943 16719 11890 16719 11885 16720 11944 16720 11945 16720 11885 16721 11945 16721 11882 16721 11902 16722 11947 16722 11948 16722 11902 16723 11948 16723 11895 16723 11890 16724 11943 16724 11944 16724 11890 16725 11944 16725 11885 16725 11882 16726 11945 16726 11946 16726 11882 16727 11946 16727 11905 16727 11905 16728 11946 16728 11947 16728 11905 16729 11947 16729 11902 16729 11949 16730 11950 16730 11951 16730 11951 16731 11950 16731 11952 16731 11951 16732 11952 16732 11953 16732 11951 16733 11953 16733 11954 16733 11954 16734 11953 16734 11955 16734 11954 16735 11955 16735 11956 16735 11955 16736 11957 16736 11956 16736 11956 16737 11957 16737 11958 16737 11958 16738 11957 16738 11959 16738 11958 16739 11959 16739 11960 16739 11960 16740 11959 16740 11961 16740 11960 16741 11961 16741 11962 16741 11960 16742 11962 16742 11949 16742 11949 16743 11962 16743 11950 16743 11963 16744 11964 16744 11965 16744 11965 16745 11964 16745 11966 16745 11965 16746 11966 16746 11967 16746 11968 16747 11981 16747 11969 16747 11968 16748 11969 16748 11970 16748 11970 16749 11969 16749 11971 16749 11971 16750 11969 16750 11972 16750 11971 16751 11972 16751 11973 16751 11973 16752 11972 16752 11974 16752 11973 16753 11974 16753 11963 16753 11963 16754 11974 16754 11964 16754 11967 16755 11966 16755 11975 16755 11967 16756 11975 16756 11976 16756 11976 16757 11975 16757 11977 16757 11977 16758 11975 16758 11978 16758 11977 16759 11978 16759 11979 16759 11979 16760 11978 16760 11980 16760 11980 16761 11978 16761 11981 16761 11980 16762 11981 16762 11968 16762 11983 16763 11982 16763 11984 16763 11983 16764 11984 16764 11985 16764 11985 16765 11984 16765 11987 16765 11985 16766 11987 16766 11986 16766 11986 16767 11987 16767 11988 16767 11986 16768 11988 16768 11989 16768 11989 16769 11988 16769 11990 16769 11989 16770 11990 16770 11991 16770 11991 16771 11990 16771 11992 16771 11991 16772 11992 16772 11993 16772 11992 16773 12034 16773 11993 16773 11994 16774 11995 16774 11993 16774 11994 16775 11993 16775 12034 16775 11996 16776 11995 16776 11994 16776 11995 16777 11996 16777 11998 16777 11995 16778 11998 16778 11997 16778 11997 16779 11998 16779 11999 16779 11997 16780 11999 16780 12000 16780 12000 16781 11999 16781 12001 16781 12000 16782 12001 16782 11983 16782 11983 16783 12001 16783 11982 16783 12002 16784 12003 16784 12004 16784 12005 16785 12002 16785 12004 16785 12006 16786 12005 16786 12004 16786 12004 16787 12007 16787 12006 16787 12008 16788 11980 16788 12009 16788 12009 16789 11980 16789 11968 16789 12009 16790 11968 16790 12010 16790 12010 16791 11968 16791 11970 16791 12010 16792 11970 16792 12011 16792 12011 16793 11970 16793 11971 16793 12011 16794 11971 16794 12012 16794 12012 16795 11971 16795 11973 16795 12012 16796 11973 16796 12013 16796 12013 16797 11973 16797 11963 16797 12013 16798 11963 16798 12014 16798 12014 16799 11963 16799 11965 16799 12014 16800 11965 16800 12015 16800 12015 16801 11965 16801 11967 16801 12015 16802 11967 16802 12016 16802 12016 16803 11967 16803 11976 16803 12016 16804 11976 16804 12017 16804 12017 16805 11976 16805 11977 16805 12017 16806 11977 16806 12018 16806 12018 16807 11977 16807 11979 16807 12018 16808 11979 16808 12008 16808 12008 16809 11979 16809 11980 16809 12014 16810 11961 16810 11959 16810 12014 16811 11959 16811 12013 16811 12013 16812 11959 16812 12012 16812 12012 16813 11959 16813 11957 16813 12012 16814 11957 16814 12011 16814 12011 16815 11957 16815 11955 16815 12011 16816 11955 16816 12010 16816 12010 16817 11955 16817 12009 16817 12009 16818 11955 16818 11953 16818 12009 16819 11953 16819 12008 16819 12008 16820 11953 16820 12018 16820 12018 16821 11953 16821 11952 16821 12018 16822 11952 16822 12017 16822 12017 16823 11952 16823 11950 16823 12017 16824 11950 16824 12016 16824 12016 16825 11950 16825 12015 16825 12015 16826 11950 16826 11962 16826 12015 16827 11962 16827 12014 16827 12014 16828 11962 16828 11961 16828 11983 16829 12002 16829 12000 16829 12000 16830 12002 16830 12005 16830 12000 16831 12005 16831 11997 16831 11997 16832 12005 16832 11995 16832 11995 16833 12005 16833 12006 16833 11995 16834 12006 16834 11993 16834 11993 16835 12006 16835 12007 16835 11993 16836 12007 16836 11991 16836 11991 16837 12007 16837 12004 16837 11991 16838 12004 16838 11989 16838 11989 16839 12004 16839 11986 16839 11986 16840 12004 16840 12003 16840 11986 16841 12003 16841 11985 16841 11985 16842 12003 16842 11983 16842 11983 16843 12003 16843 12002 16843 11949 16844 12019 16844 11960 16844 11951 16845 12020 16845 11949 16845 11954 16846 12021 16846 11951 16846 11956 16847 12022 16847 11954 16847 11958 16848 12023 16848 11956 16848 11960 16849 12024 16849 11958 16849 12028 16850 12029 16850 12026 16850 12028 16851 12026 16851 12027 16851 12027 16852 12026 16852 12025 16852 12030 16853 12025 16853 12026 16853 12031 16854 12030 16854 12026 16854 12032 16855 12031 16855 12026 16855 12026 16856 12029 16856 12032 16856 12030 16857 11960 16857 12019 16857 12030 16858 12019 16858 12025 16858 11949 16859 12025 16859 12019 16859 12027 16860 12020 16860 12028 16860 12028 16861 12020 16861 11951 16861 12025 16862 11949 16862 12020 16862 12020 16863 12027 16863 12025 16863 12021 16864 11954 16864 12029 16864 12021 16865 12028 16865 11951 16865 12021 16866 12029 16866 12028 16866 11956 16867 12032 16867 12022 16867 12029 16868 11954 16868 12022 16868 12029 16869 12022 16869 12032 16869 11958 16870 12031 16870 12023 16870 12032 16871 11956 16871 12023 16871 12032 16872 12023 16872 12031 16872 11960 16873 12030 16873 12024 16873 12031 16874 11958 16874 12024 16874 12031 16875 12024 16875 12030 16875 11975 16876 11966 16876 12033 16876 11974 16877 12034 16877 11964 16877 11978 16878 11984 16878 11982 16878 11978 16879 11982 16879 11981 16879 11974 16880 11994 16880 12034 16880 12034 16881 11992 16881 11964 16881 11964 16882 11992 16882 11990 16882 11964 16883 11990 16883 11966 16883 11982 16884 12001 16884 11981 16884 11978 16885 11975 16885 11984 16885 11984 16886 11975 16886 11987 16886 11975 16887 12033 16887 11988 16887 11975 16888 11988 16888 11987 16888 12033 16889 11966 16889 11990 16889 12033 16890 11990 16890 11988 16890 11974 16891 11996 16891 11994 16891 11974 16892 11972 16892 11996 16892 11972 16893 11998 16893 11996 16893 11972 16894 11969 16894 11998 16894 11969 16895 11999 16895 11998 16895 11969 16896 11981 16896 11999 16896 11981 16897 12001 16897 11999 16897 12040 16898 12037 16898 12038 16898 12035 16899 12036 16899 12039 16899 12039 16900 12040 16900 12038 16900 12035 16901 12039 16901 12038 16901 12041 16902 12037 16902 12040 16902 12044 16903 12042 16903 12043 16903 12038 16904 12037 16904 12041 16904 12041 16905 12044 16905 12043 16905 12038 16906 12041 16906 12043 16906 12045 16907 12042 16907 12044 16907 12043 16908 12042 16908 12045 16908 12046 16909 12048 16909 12047 16909 12043 16910 12045 16910 12046 16910 12043 16911 12046 16911 12047 16911 12051 16912 12048 16912 12050 16912 12050 16913 12048 16913 12046 16913 12049 16914 12048 16914 12052 16914 12052 16915 12048 16915 12051 16915 12055 16916 12053 16916 12054 16916 12049 16917 12055 16917 12054 16917 12047 16918 12048 16918 12054 16918 12054 16919 12048 16919 12049 16919 12053 16920 12055 16920 12056 16920 12054 16921 12053 16921 12056 16921 12056 16922 12058 16922 12057 16922 12054 16923 12056 16923 12057 16923 12061 16924 12058 16924 12056 16924 12062 16925 12058 16925 12061 16925 12062 16926 12059 16926 12058 16926 12063 16927 12036 16927 12035 16927 12057 16928 12058 16928 12059 16928 12060 16929 12063 16929 12035 16929 12057 16930 12059 16930 12035 16930 12035 16931 12059 16931 12060 16931 12039 16932 12036 16932 12063 16932 12060 16933 12066 16933 12065 16933 12046 16934 12064 16934 12072 16934 12064 16935 12046 16935 12045 16935 12065 16936 12039 16936 12063 16936 12065 16937 12063 16937 12060 16937 12066 16938 12067 16938 12068 16938 12066 16939 12068 16939 12069 16939 12066 16940 12060 16940 12070 16940 12066 16941 12070 16941 12071 16941 12066 16942 12071 16942 12067 16942 12077 16943 12039 16943 12065 16943 12077 16944 12040 16944 12039 16944 12072 16945 12073 16945 12074 16945 12072 16946 12074 16946 12075 16946 12072 16947 12075 16947 12046 16947 12055 16948 12049 16948 12069 16948 12069 16949 12049 16949 12072 16949 12072 16950 12049 16950 12076 16950 12072 16951 12076 16951 12073 16951 12077 16952 12041 16952 12040 16952 12064 16953 12045 16953 12044 16953 12064 16954 12044 16954 12077 16954 12069 16955 12056 16955 12055 16955 12044 16956 12041 16956 12077 16956 12068 16957 12078 16957 12069 16957 12069 16958 12078 16958 12056 16958 12065 16959 12066 16959 12079 16959 12079 16960 12080 16960 12065 16960 12065 16961 12080 16961 12077 16961 12077 16962 12080 16962 12081 16962 12077 16963 12081 16963 12064 16963 12081 16964 12082 16964 12064 16964 12083 16965 12064 16965 12082 16965 12072 16966 12064 16966 12083 16966 12083 16967 12084 16967 12072 16967 12072 16968 12084 16968 12069 16968 12069 16969 12084 16969 12085 16969 12069 16970 12085 16970 12066 16970 12085 16971 12086 16971 12066 16971 12079 16972 12066 16972 12086 16972 12087 16973 12079 16973 12086 16973 12087 16974 12086 16974 12085 16974 12087 16975 12085 16975 12088 16975 12088 16976 12085 16976 12089 16976 12089 16977 12085 16977 12084 16977 12089 16978 12084 16978 12090 16978 12090 16979 12084 16979 12083 16979 12090 16980 12083 16980 12091 16980 12091 16981 12083 16981 12082 16981 12091 16982 12082 16982 12081 16982 12091 16983 12081 16983 12092 16983 12092 16984 12081 16984 12093 16984 12093 16985 12081 16985 12080 16985 12093 16986 12080 16986 12094 16986 12094 16987 12080 16987 12079 16987 12094 5868 12079 5868 12087 5868 12095 16988 12091 16988 12096 16988 12091 16989 12092 16989 12096 16989 12092 16990 12093 16990 12096 16990 12096 16991 12093 16991 12097 16991 12093 16992 12094 16992 12097 16992 12097 16993 12094 16993 12098 16993 12087 16994 12098 16994 12094 16994 12098 16995 12087 16995 12099 16995 12087 16996 12088 16996 12099 16996 12088 16997 12089 16997 12099 16997 12099 16998 12089 16998 12100 16998 12089 16999 12090 16999 12100 16999 12100 17000 12090 17000 12095 17000 12091 17001 12095 17001 12090 17001 12100 17002 12095 17002 12047 17002 12047 17003 12095 17003 12043 17003 12038 17004 12096 17004 12097 17004 12038 17005 12097 17005 12035 17005 12054 17006 12099 17006 12100 17006 12054 17007 12100 17007 12047 17007 12043 17008 12095 17008 12096 17008 12043 17009 12096 17009 12038 17009 12035 17010 12097 17010 12098 17010 12035 17011 12098 17011 12057 17011 12057 17012 12098 17012 12099 17012 12057 17013 12099 17013 12054 17013 12101 17014 12115 17014 12102 17014 12101 17015 12102 17015 12103 17015 12103 17016 12102 17016 12104 17016 12103 17017 12104 17017 12105 17017 12105 17018 12104 17018 12106 17018 12105 17019 12106 17019 12107 17019 12105 17020 12107 17020 12108 17020 12108 17021 12107 17021 12109 17021 12108 17022 12109 17022 12110 17022 12110 17023 12109 17023 12111 17023 12110 17024 12111 17024 12112 17024 12110 17025 12112 17025 12113 17025 12113 17026 12112 17026 12114 17026 12113 17027 12114 17027 12101 17027 12101 17028 12114 17028 12115 17028 12116 17029 12125 17029 12117 17029 12116 17030 12117 17030 12118 17030 12118 17031 12117 17031 12119 17031 12118 17032 12119 17032 12120 17032 12121 17033 12134 17033 12122 17033 12121 17034 12122 17034 12123 17034 12123 17035 12122 17035 12124 17035 12124 17036 12122 17036 12125 17036 12124 17037 12125 17037 12126 17037 12126 17038 12125 17038 12116 17038 12120 17039 12119 17039 12127 17039 12120 17040 12127 17040 12128 17040 12128 17041 12127 17041 12129 17041 12129 17042 12127 17042 12130 17042 12129 17043 12130 17043 12131 17043 12129 17044 12131 17044 12132 17044 12132 17045 12131 17045 12133 17045 12133 17046 12131 17046 12134 17046 12133 17047 12134 17047 12121 17047 12136 17048 12135 17048 12138 17048 12136 17049 12138 17049 12137 17049 12137 17050 12138 17050 12140 17050 12137 17051 12140 17051 12139 17051 12139 17052 12140 17052 12141 17052 12139 17053 12141 17053 12142 17053 12142 17054 12141 17054 12186 17054 12142 17055 12186 17055 12143 17055 12143 17056 12186 17056 12144 17056 12143 17057 12144 17057 12145 17057 12144 17058 12185 17058 12145 17058 12146 17059 12147 17059 12145 17059 12146 17060 12145 17060 12185 17060 12187 17061 12147 17061 12146 17061 12147 17062 12187 17062 12149 17062 12147 17063 12149 17063 12148 17063 12148 17064 12149 17064 12150 17064 12148 17065 12150 17065 12151 17065 12151 17066 12150 17066 12152 17066 12151 17067 12152 17067 12136 17067 12136 17068 12152 17068 12135 17068 12154 17069 12155 17069 12153 17069 12154 17070 12156 17070 12155 17070 12157 17071 12156 17071 12154 17071 12154 17072 12158 17072 12157 17072 12159 17073 12133 17073 12160 17073 12160 17074 12133 17074 12121 17074 12160 17075 12121 17075 12161 17075 12161 17076 12121 17076 12123 17076 12161 17077 12123 17077 12162 17077 12162 17078 12123 17078 12124 17078 12162 17079 12124 17079 12163 17079 12163 17080 12124 17080 12126 17080 12163 17081 12126 17081 12164 17081 12164 17082 12126 17082 12116 17082 12164 17083 12116 17083 12165 17083 12165 17084 12116 17084 12118 17084 12165 17085 12118 17085 12166 17085 12166 17086 12118 17086 12120 17086 12166 17087 12120 17087 12167 17087 12167 17088 12120 17088 12128 17088 12167 17089 12128 17089 12168 17089 12168 17090 12128 17090 12129 17090 12168 17091 12129 17091 12169 17091 12169 17092 12129 17092 12132 17092 12169 17093 12132 17093 12159 17093 12159 17094 12132 17094 12133 17094 12165 17095 12112 17095 12164 17095 12164 17096 12112 17096 12111 17096 12164 17097 12111 17097 12163 17097 12163 17098 12111 17098 12109 17098 12163 17099 12109 17099 12162 17099 12162 17100 12109 17100 12107 17100 12162 17101 12107 17101 12161 17101 12161 17102 12107 17102 12160 17102 12160 17103 12107 17103 12106 17103 12160 17104 12106 17104 12159 17104 12159 17105 12106 17105 12104 17105 12159 17106 12104 17106 12169 17106 12169 17107 12104 17107 12102 17107 12169 17108 12102 17108 12168 17108 12168 17109 12102 17109 12115 17109 12168 17110 12115 17110 12167 17110 12167 17111 12115 17111 12166 17111 12166 17112 12115 17112 12114 17112 12166 17113 12114 17113 12165 17113 12165 17114 12114 17114 12112 17114 12136 17115 12153 17115 12151 17115 12151 17116 12153 17116 12155 17116 12151 17117 12155 17117 12148 17117 12148 17118 12155 17118 12156 17118 12148 17119 12156 17119 12147 17119 12147 17120 12156 17120 12145 17120 12145 17121 12156 17121 12157 17121 12145 17122 12157 17122 12143 17122 12143 17123 12157 17123 12158 17123 12143 17124 12158 17124 12142 17124 12142 17125 12158 17125 12139 17125 12139 17126 12158 17126 12154 17126 12139 17127 12154 17127 12137 17127 12137 17128 12154 17128 12136 17128 12136 17129 12154 17129 12153 17129 12101 17130 12170 17130 12113 17130 12103 17131 12171 17131 12101 17131 12105 17132 12172 17132 12103 17132 12108 17133 12173 17133 12105 17133 12110 17134 12174 17134 12108 17134 12113 17135 12175 17135 12110 17135 12179 17136 12180 17136 12177 17136 12179 17137 12177 17137 12178 17137 12178 17138 12177 17138 12176 17138 12181 17139 12176 17139 12177 17139 12182 17140 12181 17140 12177 17140 12183 17141 12182 17141 12177 17141 12177 17142 12180 17142 12183 17142 12181 17143 12113 17143 12170 17143 12181 17144 12170 17144 12176 17144 12101 17145 12176 17145 12170 17145 12178 17146 12171 17146 12179 17146 12179 17147 12171 17147 12103 17147 12176 17148 12101 17148 12171 17148 12171 17149 12178 17149 12176 17149 12172 17150 12105 17150 12180 17150 12172 17151 12179 17151 12103 17151 12172 17152 12180 17152 12179 17152 12108 17153 12183 17153 12173 17153 12180 17154 12105 17154 12173 17154 12180 17155 12173 17155 12183 17155 12110 17156 12182 17156 12174 17156 12183 17157 12108 17157 12174 17157 12183 17158 12174 17158 12182 17158 12113 17159 12181 17159 12175 17159 12182 17160 12110 17160 12175 17160 12182 17161 12175 17161 12181 17161 12122 17162 12184 17162 12125 17162 12125 17163 12184 17163 12185 17163 12125 17164 12185 17164 12117 17164 12117 17165 12186 17165 12119 17165 12130 17166 12135 17166 12131 17166 12184 17167 12146 17167 12185 17167 12185 17168 12144 17168 12117 17168 12117 17169 12144 17169 12186 17169 12130 17170 12138 17170 12135 17170 12131 17171 12135 17171 12152 17171 12131 17172 12152 17172 12134 17172 12130 17173 12127 17173 12140 17173 12130 17174 12140 17174 12138 17174 12127 17175 12119 17175 12141 17175 12127 17176 12141 17176 12140 17176 12119 17177 12186 17177 12141 17177 12184 17178 12187 17178 12146 17178 12184 17179 12122 17179 12187 17179 12122 17180 12149 17180 12187 17180 12122 17181 12150 17181 12149 17181 12122 17182 12134 17182 12150 17182 12134 17183 12152 17183 12150 17183 12188 17184 12189 17184 12190 17184 12190 324 12189 324 12191 324 12192 324 12193 324 12188 324 12188 324 12193 324 12194 324 12188 324 12194 324 12189 324 12189 324 12195 324 12191 324 12191 17185 12195 17185 12196 17185 12191 324 12196 324 12197 324 12197 324 12196 324 12198 324 12197 17186 12198 17186 12199 17186 12199 324 12198 324 12200 324 12199 324 12200 324 12201 324 12201 324 12200 324 12202 324 12201 17187 12202 17187 12203 17187 12202 324 12204 324 12203 324 12203 17188 12204 17188 12205 17188 12203 324 12205 324 12192 324 12192 324 12205 324 12193 324 12206 348 12207 348 12208 348 12208 348 12207 348 12209 348 12208 348 12209 348 12210 348 12211 348 12212 348 12213 348 12211 17189 12213 17189 12206 17189 12206 17190 12213 17190 12207 17190 12214 17191 12215 17191 12216 17191 12214 348 12216 348 12217 348 12217 348 12216 348 12218 348 12218 348 12216 348 12219 348 12218 348 12219 348 12220 348 12218 17192 12220 17192 12221 17192 12221 348 12220 348 12211 348 12211 348 12220 348 12212 348 12209 17193 12222 17193 12210 17193 12210 17194 12222 17194 12223 17194 12210 348 12223 348 12214 348 12214 17195 12223 17195 12215 17195 12209 17196 12193 17196 12222 17196 12222 17197 12193 17197 12205 17197 12222 17198 12205 17198 12223 17198 12223 17199 12205 17199 12204 17199 12223 17200 12204 17200 12215 17200 12215 17201 12204 17201 12216 17201 12216 17202 12204 17202 12202 17202 12216 17203 12202 17203 12200 17203 12216 17204 12200 17204 12219 17204 12219 17205 12200 17205 12198 17205 12219 17206 12198 17206 12220 17206 12220 17207 12198 17207 12196 17207 12220 17208 12196 17208 12212 17208 12212 17209 12196 17209 12195 17209 12212 17210 12195 17210 12213 17210 12213 17211 12195 17211 12189 17211 12213 17212 12189 17212 12207 17212 12207 17213 12189 17213 12194 17213 12207 17214 12194 17214 12209 17214 12209 17215 12194 17215 12193 17215 12188 17216 12208 17216 12192 17216 12192 17217 12208 17217 12210 17217 12192 17218 12210 17218 12203 17218 12203 17219 12210 17219 12214 17219 12203 17220 12214 17220 12201 17220 12201 17221 12214 17221 12217 17221 12201 17222 12217 17222 12199 17222 12199 17223 12217 17223 12218 17223 12199 17224 12218 17224 12197 17224 12197 9613 12218 9613 12221 9613 12197 17225 12221 17225 12191 17225 12191 17226 12221 17226 12211 17226 12191 17227 12211 17227 12190 17227 12190 17228 12211 17228 12206 17228 12190 17229 12206 17229 12188 17229 12188 17230 12206 17230 12208 17230 12224 17231 12229 17231 12225 17231 12224 17232 12225 17232 12226 17232 12224 17233 12226 17233 12227 17233 12228 17234 12231 17234 12229 17234 12228 17235 12229 17235 12224 17235 12230 17236 12234 17236 12231 17236 12230 17237 12231 17237 12228 17237 12232 17238 12233 17238 12230 17238 12230 17239 12233 17239 12234 17239 12236 17240 12235 17240 12232 17240 12232 17241 12235 17241 12233 17241 12227 17242 12238 17242 12236 17242 12236 17243 12238 17243 12237 17243 12236 17244 12237 17244 12235 17244 12227 17245 12226 17245 12238 17245 12239 17246 12269 17246 12240 17246 12240 17247 12269 17247 12267 17247 12240 17248 12267 17248 12265 17248 12240 17249 12265 17249 12241 17249 12241 17250 12265 17250 12263 17250 12241 17251 12263 17251 12242 17251 12242 17252 12263 17252 12262 17252 12242 17253 12262 17253 12260 17253 12242 17254 12260 17254 12243 17254 12243 17255 12260 17255 12258 17255 12243 17256 12258 17256 12244 17256 12244 17257 12258 17257 12256 17257 12244 17258 12256 17258 12245 17258 12256 17259 12246 17259 12245 17259 12245 17260 12246 17260 12247 17260 12247 17261 12246 17261 12253 17261 12247 17262 12253 17262 12248 17262 12248 17263 12253 17263 12249 17263 12248 17264 12249 17264 12250 17264 12250 17265 12249 17265 12272 17265 12250 17266 12272 17266 12239 17266 12239 17267 12272 17267 12269 17267 12249 17268 12251 17268 12252 17268 12251 17269 12249 17269 12253 17269 12251 17270 12253 17270 12254 17270 12254 17271 12253 17271 12246 17271 12254 17272 12246 17272 12255 17272 12255 17273 12246 17273 12256 17273 12256 17274 12257 17274 12255 17274 12257 17275 12256 17275 12258 17275 12258 17276 12259 17276 12257 17276 12259 17277 12258 17277 12260 17277 12260 17278 12261 17278 12259 17278 12261 17279 12260 17279 12262 17279 12263 17280 12264 17280 12261 17280 12263 17281 12261 17281 12262 17281 12265 17282 12266 17282 12264 17282 12265 17283 12264 17283 12263 17283 12267 17284 12268 17284 12266 17284 12267 17285 12266 17285 12265 17285 12268 17286 12267 17286 12269 17286 12269 17287 12270 17287 12268 17287 12270 17288 12269 17288 12271 17288 12272 17289 12271 17289 12269 17289 12271 17290 12272 17290 12273 17290 12273 17291 12272 17291 12249 17291 12273 17292 12249 17292 12252 17292 12252 17293 12270 17293 12273 17293 12270 17294 12261 17294 12274 17294 12270 17295 12259 17295 12261 17295 12270 17296 12255 17296 12259 17296 12252 17297 12251 17297 12270 17297 12270 17298 12251 17298 12255 17298 12248 17299 12275 17299 12247 17299 12247 17300 12275 17300 12276 17300 12247 17301 12276 17301 12245 17301 12276 17302 12277 17302 12245 17302 12245 17303 12277 17303 12244 17303 12244 17304 12277 17304 12278 17304 12244 17305 12278 17305 12243 17305 12243 17306 12278 17306 12242 17306 12278 17307 12279 17307 12242 17307 12242 17308 12279 17308 12280 17308 12242 17309 12280 17309 12241 17309 12241 17310 12280 17310 12281 17310 12241 17311 12281 17311 12240 17311 12281 17312 12282 17312 12240 17312 12240 17313 12282 17313 12239 17313 12282 17314 12283 17314 12239 17314 12283 17315 12226 17315 12239 17315 12239 17316 12226 17316 12250 17316 12226 17317 12225 17317 12250 17317 12250 17318 12225 17318 12248 17318 12248 17319 12225 17319 12275 17319 12233 17320 12235 17320 12279 17320 12279 17321 12278 17321 12233 17321 12233 17322 12278 17322 12234 17322 12234 17323 12278 17323 12277 17323 12234 17324 12277 17324 12231 17324 12277 17325 12276 17325 12231 17325 12231 17326 12276 17326 12229 17326 12229 17327 12276 17327 12275 17327 12229 17328 12275 17328 12225 17328 12226 17329 12283 17329 12238 17329 12283 17330 12282 17330 12238 17330 12238 17331 12282 17331 12237 17331 12282 17332 12281 17332 12237 17332 12237 17333 12281 17333 12280 17333 12237 17334 12280 17334 12235 17334 12235 17335 12280 17335 12279 17335 12271 17336 12273 17336 12270 17336 12268 17337 12270 17337 12274 17337 12268 17338 12274 17338 12266 17338 12266 17339 12274 17339 12264 17339 12264 17340 12274 17340 12261 17340 12257 17341 12259 17341 12255 17341 12254 17342 12255 17342 12251 17342 12230 17343 12284 17343 12232 17343 12228 17344 12285 17344 12230 17344 12224 17345 12286 17345 12228 17345 12227 17346 12287 17346 12224 17346 12236 17347 12288 17347 12227 17347 12232 17348 12289 17348 12236 17348 12291 17349 12295 17349 12296 17349 12290 17350 12291 17350 12296 17350 12291 17351 12294 17351 12295 17351 12293 17352 12294 17352 12291 17352 12292 17353 12293 17353 12291 17353 12290 17354 12292 17354 12291 17354 12230 17355 12294 17355 12284 17355 12293 17356 12232 17356 12284 17356 12284 17357 12294 17357 12293 17357 12285 17358 12228 17358 12295 17358 12294 17359 12230 17359 12285 17359 12295 17360 12294 17360 12285 17360 12296 17361 12286 17361 12224 17361 12295 17362 12228 17362 12286 17362 12295 17363 12286 17363 12296 17363 12296 17364 12224 17364 12290 17364 12290 17365 12224 17365 12287 17365 12290 17366 12287 17366 12227 17366 12236 17367 12292 17367 12288 17367 12288 17368 12292 17368 12290 17368 12288 17369 12290 17369 12227 17369 12232 17370 12293 17370 12289 17370 12292 17371 12236 17371 12289 17371 12289 17372 12293 17372 12292 17372

+
+
+
+
+ + + + 0.001 0 0 0 0 0.001 0 0 0 0 0.001 0 0 0 0 1 + + + + + + + + + + 0.001 0 0 0 0 0.001 0 0 0 0 0.001 0 0 0 0 1 + + + + + + + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/robots/mini_quadrotor/urdf/mesh/prop_5inch.dae b/robots/mini_quadrotor/urdf/mesh/prop_5inch.dae new file mode 100644 index 000000000..cc2e16203 --- /dev/null +++ b/robots/mini_quadrotor/urdf/mesh/prop_5inch.dae @@ -0,0 +1,162 @@ + + + + + Blender User + Blender 3.0.1 commit date:2022-01-25, commit time:17:19, hash:dc2d18018171 + + 2022-12-17T17:05:28 + 2022-12-17T17:05:28 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0.00111109 + + + + + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + 0 + 1000 + 29.99998 + 75 + 0.15 + 0 + 1 + 2 + 0.04999995 + 30.002 + 1 + 3 + 2880 + 3 + 1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.005126015 0.005126015 0.005126015 1 + + + 0.5 + + + + + + + + + + + + + + + + + -0.005370795 0.001588106 -0.04137372 -0.003797888 0.002074897 -0.04177159 -0.003807485 0.001219987 -0.03394645 -0.003581583 0.006769299 -0.06201344 -0.002403557 0.006476521 -0.06033062 -0.003593564 0.005973935 -0.05937516 -3.90492e-4 0.007464051 -0.06200736 -6.74142e-4 0.007281422 -0.06171554 -0.001674413 0.007315695 -0.06235742 0.002398014 0.006995439 -0.0594452 0.001432836 0.006621718 -0.05910414 8.71047e-4 0.006916821 -0.06014531 -0.005411803 -1.98994e-4 -0.01107329 -0.005615532 -2.93548e-4 -0.0124486 -0.00291568 0.001028597 -0.006226003 -0.003946661 5.52898e-4 -0.005664348 -0.004203975 4.38451e-4 -0.005470693 -0.004442036 3.34728e-4 -0.00524789 0.004851877 0.005315124 -0.01079922 0.004268646 0.005413234 -0.005066215 0.002670586 0.004234075 -0.006129741 2.44275e-4 0.002511322 -0.01162445 0.001442134 0.003410995 -0.006578505 3.80057e-4 0.002759993 -0.006764292 0.004899203 0.005310952 -0.01134592 0.002760529 0.003775179 -0.01806658 0.005335569 0.00529927 -0.01772218 0.002725005 0.003737449 -0.02569133 0.005540728 0.005319595 -0.02338677 0.002558469 0.003878712 -0.03393781 0.003570079 0.00490731 -0.0440073 0.005466461 0.005405366 -0.0347535 0.00404632 0.004624724 -0.0339359 0.005563616 0.005366027 -0.03066229 0.004227101 0.005958795 -0.05167734 0.004832744 0.005644202 -0.04580944 0.005007565 0.005569577 -0.04355448 0.003148436 0.005207359 -0.0494014 0.0026021 0.005676388 -0.05418282 0.004042267 0.006067991 -0.05302262 0.002273082 0.005972743 -0.05616027 0.003408074 0.006456553 -0.05648672 0.00189048 0.006295621 -0.05779832 0.002554833 0.006923615 -0.05912762 0.003248333 0.006552219 -0.0571261 0.001405477 0.007316648 -0.06081753 1.75362e-4 0.007145822 -0.06099408 7.09706e-4 0.007416009 -0.0613597 -7.30849e-5 0.007459819 -0.06182914 -0.002854883 0.007102429 -0.06252121 -0.001903653 0.00735104 -0.06261026 -0.001524031 0.007405698 -0.0625211 -0.004461765 0.004769027 -0.05565887 -0.00429666 0.005786418 -0.05920708 -0.004012227 0.006406545 -0.06114637 -0.006502151 0.002039194 -0.04565805 -0.006204068 0.002621054 -0.04818379 -0.004988491 0.003000557 -0.04873114 -0.005614817 0.003680408 -0.05228447 -0.005294799 0.004206061 -0.05413347 -0.006625354 0.001783013 -0.04446166 -0.00719273 9.71897e-5 -0.03395026 -0.007124066 4.86144e-4 -0.03705292 -0.007110059 5.39378e-4 -0.03742742 -0.006910622 0.001126527 -0.04107081 -0.007044255 -4.58692e-4 -0.02680671 -0.007128059 -3.47346e-4 -0.02883541 -0.003609418 8.15997e-4 -0.02644973 -0.00714904 -3.01482e-4 -0.02952128 -0.007196426 2.67799e-5 -0.0332939 -0.006732642 -5.81398e-4 -0.02213424 -0.00319463 7.79411e-4 -0.01913809 -0.006554007 -5.79705e-4 -0.02016121 -0.00586915 -3.99213e-4 -0.01426875 -0.002570748 0.001068711 -0.01204794 -0.001732826 0.001608312 -0.006617128 -0.001241028 0.007005155 -0.06128162 -5.49287e-4 0.006801903 -0.06043106 1.2009e-5 0.006520211 -0.05947184 4.60347e-4 0.00618422 -0.05834591 8.21818e-4 0.005824923 -0.05698907 0.001379966 0.00514847 -0.05339461 0.001811563 0.004622101 -0.04877597 0.002151608 0.004262804 -0.04361915 -0.003740072 0.002685368 -0.04572969 -0.002033889 0.006154179 -0.05916142 -0.003545641 0.005105257 -0.05634653 -0.003585577 0.00423032 -0.05309283 -0.003662884 0.003409922 -0.04954218 -0.001743257 0.005788028 -0.05791485 -0.001520335 0.005393505 -0.05655688 -0.001348674 0.004990398 -0.05504953 -0.001098215 0.00423026 -0.05147749 -9.10483e-4 0.003595113 -0.04725992 -7.58401e-4 0.003103375 -0.04269921 -5.37668e-4 0.002481102 -0.0339421 -3.30129e-4 0.002220928 -0.02607017 -7.52678e-5 0.002244174 -0.01860177 -0.006522476 -4.83635e-4 -0.01936477 -0.006779432 -4.94134e-4 -0.02212971 -0.006791591 -5.0688e-4 -0.02212876 -0.007236063 1.71175e-4 -0.03380358 -0.006997108 0.001093506 -0.04035502 -0.007184624 5.52118e-4 -0.03706312 -0.005629301 0.00368005 -0.05228686 -0.004839718 0.005128085 -0.05688494 -0.004382848 0.005770325 -0.05884486 -0.004854679 0.00511831 -0.0568906 -0.004366457 0.00567919 -0.05887162 -0.004176855 0.006206929 -0.06054872 -0.004168748 0.006211876 -0.06056928 -0.00390613 0.006571114 -0.06157493 -0.003562629 0.006839871 -0.06210345 -0.002954959 0.007114589 -0.06251442 -0.00294882 0.007098138 -0.06251293 -0.00355333 0.00689578 -0.06207638 -0.003421664 0.006965279 -0.06217682 -0.003170073 0.007082581 -0.06235831 -0.005221068 -6.39137e-5 -0.009486973 -0.005206823 -7.43328e-5 -0.009488403 -0.004436612 3.62612e-4 -0.004988908 -0.004436552 3.54648e-4 -0.005035638 -0.005198061 -7.76754e-5 -0.009489536 -0.004437983 3.42493e-4 -0.005136966 -0.004438459 3.41005e-4 -0.005153536 -0.005179882 -7.90831e-5 -0.009492337 -0.004439771 3.37995e-4 -0.005192101 0.004268765 0.005414783 -0.005052804 0.004269123 0.005428433 -0.004961073 0.004920005 0.005369603 -0.01134479 0.004269063 0.005431234 -0.004946827 -0.004436552 3.71255e-4 -0.004947364 -0.004433333 3.92765e-4 -0.004860103 -0.00522983 -5.14744e-5 -0.009486615 -0.004430353 4.12778e-4 -0.004854619 -0.005234479 -3.6885e-5 -0.009487092 -0.004427969 4.28605e-4 -0.004850327 -0.005234479 -2.1125e-5 -0.009488403 -0.004426956 4.351e-4 -0.004848539 -0.005228698 -4.49002e-6 -0.009490728 -0.004425287 4.46208e-4 -0.004845499 -0.007251799 1.0337e-4 -0.03328609 -0.007259547 8.74665e-5 -0.03328776 -0.007213413 -2.41921e-4 -0.02951532 -0.007261276 7.18486e-5 -0.03328937 -0.007214903 -2.57655e-4 -0.02951639 -0.007258236 5.69243e-5 -0.03329092 -0.007211565 -2.72596e-4 -0.02951753 -0.007250845 4.37125e-5 -0.03329229 -0.007203876 -2.85719e-4 -0.02951866 -0.007237672 3.19485e-5 -0.03329348 -0.007190465 -2.97255e-4 -0.02951979 -0.007229208 2.77502e-5 -0.0332939 -0.007181942 -3.01284e-4 -0.02952033 0.005564749 0.005369603 -0.02338606 0.005338072 0.005356013 -0.01735246 0.005339384 0.005353033 -0.0173611 0.005149424 0.005365192 -0.01435148 0.004920721 0.00537002 -0.01135528 0.004268884 0.005416989 -0.005035042 0.004914104 0.005325376 -0.01134473 0.004906594 0.005316555 -0.01134532 0.005331099 0.005311787 -0.01736158 0.005323767 0.0053038 -0.01736199 0.005554437 0.005331575 -0.02338641 0.005490481 0.005463302 -0.03475362 0.005486845 0.005472362 -0.03475338 0.00551778 0.005460858 -0.0337482 0.005326807 0.005371868 -0.01729679 0.005564868 0.00537002 -0.02339553 0.005594551 0.005398809 -0.02566009 0.00560379 0.00541085 -0.02907001 0.005492269 0.005453824 -0.03475379 0.005050182 0.005378365 -0.01308894 0.004266798 0.005492091 -0.004986345 0.004269063 0.005431652 -0.00494486 0.0055871 0.005358278 -0.02907031 0.005548596 0.005381047 -0.03191238 0.005473136 0.005409717 -0.03475368 0.004853427 0.005714237 -0.04580849 0.004978299 0.005665004 -0.04416054 0.005260109 0.005553245 -0.03985935 0.005241155 0.005552709 -0.04028153 0.005225241 0.005494534 -0.04028183 0.004849493 0.005657911 -0.04581028 0.005480468 0.005416691 -0.03475379 0.005547285 0.005324244 -0.02338665 0.004846394 0.005723536 -0.0458076 0.004508733 0.005887329 -0.0494247 0.004415512 0.005942285 -0.05018013 0.004046618 0.006156384 -0.05301547 0.004300475 0.006003737 -0.05122369 0.004065275 0.006137311 -0.05301988 0.004858076 0.005703568 -0.04580932 0.00484091 0.005649387 -0.04580992 0.004499554 0.00581783 -0.04942762 0.004057109 0.006148278 -0.05301773 0.00377798 0.006320774 -0.05467551 0.003717124 0.006357848 -0.05507284 0.003532528 0.006472229 -0.05592429 0.003507137 0.006488084 -0.05609971 0.003270566 0.00662738 -0.05712032 0.003258764 0.006558477 -0.05712795 0.003269791 0.006569921 -0.05712914 0.003713905 0.006281256 -0.05508112 0.004061698 0.006084144 -0.05302405 0.004051804 0.006073892 -0.05302351 0.003247737 0.006644368 -0.05711144 0.003260195 0.006637871 -0.05711585 0.002909958 0.006836712 -0.05822688 0.002902507 0.00684148 -0.05829042 0.00241971 0.007074475 -0.05943864 0.002408027 0.007001578 -0.05944901 0.0026775 0.006876289 -0.05888062 0.002901673 0.006761312 -0.0583055 0.001387834 0.007413089 -0.06082618 0.001376688 0.007415354 -0.06081444 0.001796841 0.007311463 -0.0603578 0.002395927 0.00708872 -0.05942296 0.002408385 0.00708419 -0.05943048 0.002299785 0.007130205 -0.05960011 0.00195086 0.007263422 -0.06018185 0.001398503 0.007404983 -0.06083852 0.001108586 0.007461547 -0.06104332 0.001058101 0.007467985 -0.06110394 6.99089e-4 0.007510483 -0.0613361 7.0211e-4 0.007508873 -0.0613541 -8.48378e-5 0.007554471 -0.06180518 -6.88748e-5 0.007546126 -0.06183469 -7.64952e-5 0.00755316 -0.06182044 0.004269123 0.005425691 -0.004976451 0.004922211 0.005359888 -0.01134425 0.005340695 0.005343794 -0.01736104 0.005565166 0.005360901 -0.02338606 0.005492329 0.005445241 -0.03475385 0.004860043 0.005693376 -0.04580986 0.004069626 0.006126165 -0.05302149 0.003276526 0.006615936 -0.05712372 0.002426147 0.00706321 -0.05944454 0.001404762 0.007394373 -0.06084704 -6.35708e-5 0.007535696 -0.0618447 0.004269063 0.005423128 -0.004991888 0.004922568 0.005350291 -0.01134419 0.005340337 0.005334794 -0.01736104 0.005564212 0.005352556 -0.02338612 0.005491018 0.005437016 -0.03475391 0.004859983 0.005683362 -0.04581022 0.004071235 0.006114602 -0.05302274 0.003279149 0.006603658 -0.05712634 0.002429127 0.007050573 -0.05944901 0.001407921 0.007381677 -0.060853 -6.01938e-5 0.007522761 -0.0618512 0.004269003 0.005420744 -0.005007505 0.004921078 0.005340874 -0.01134425 0.00533837 0.005326032 -0.01736116 0.005561828 0.00534451 -0.02338624 0.005488276 0.005429148 -0.03475391 0.004857838 0.005673587 -0.0458104 0.004070103 0.006103038 -0.05302363 0.003278553 0.006590962 -0.05712819 0.00242871 0.007037222 -0.05945181 0.001407921 0.00736773 -0.0608561 -5.88888e-5 0.007508337 -0.061854 0.004268944 0.005418241 -0.005025625 0.004917144 0.005330443 -0.01134449 0.005334138 0.005316495 -0.0173614 0.005557417 0.005335807 -0.02338635 0.005483627 0.005420744 -0.03475385 0.00485301 0.005663037 -0.0458104 0.004065454 0.006090342 -0.05302405 0.003273904 0.006576776 -0.05712914 0.002424061 0.007021963 -0.05945283 0.001404166 0.007351338 -0.06085598 -6.0038e-5 0.007491171 -0.06185233 0.002419888 0.007014572 -0.05945235 0.001400649 0.007343173 -0.06085431 -6.17686e-5 0.007482588 -0.06184941 -0.001520276 0.007496953 -0.06253564 -0.001530349 0.007502079 -0.06251829 -7.94982e-4 0.007553279 -0.06221282 -0.001541137 0.007500767 -0.0624988 -7.37201e-4 0.007555067 -0.06216096 0.001391053 0.007329463 -0.06084781 -6.72165e-5 0.007468163 -0.06183975 -7.83558e-4 0.007467329 -0.06223064 -0.001509606 0.007431626 -0.06254905 -0.001517057 0.007414281 -0.06253409 -0.001867771 0.007365465 -0.06261992 -0.001507461 0.007441103 -0.06255364 -0.001506268 0.00745958 -0.06255733 -0.001508295 0.007474601 -0.06255501 -0.001513063 0.007487356 -0.06254768 -0.002206981 0.00731194 -0.06266087 -0.002189815 0.007309556 -0.06265634 -0.002587139 0.007196784 -0.06260943 -0.002206504 0.007321 -0.06266522 -0.002207458 0.00733906 -0.06266856 -0.002210259 0.00735414 -0.06266605 -0.00221461 0.007367312 -0.06265878 -0.002220273 0.007377505 -0.06264704 -0.002227246 0.007383465 -0.06263017 -0.002076148 0.007417082 -0.06260555 -0.00298655 0.007156431 -0.06245344 -0.00296092 0.007164478 -0.06248098 -0.00296241 0.007155537 -0.06249475 -0.003564 0.006883382 -0.06208628 -0.002961635 0.007143497 -0.06250476 -0.003568589 0.006869316 -0.06209409 -0.002959072 0.00712949 -0.0625115 -0.003568053 0.006854355 -0.06209993 -0.003551065 0.006825268 -0.06210422 -0.002945244 0.007090389 -0.06251007 -0.003543138 0.006819128 -0.06210315 -0.003892004 0.006658852 -0.06154334 -0.003692269 0.006809711 -0.06188404 -0.00375396 0.006772339 -0.06183165 -0.003659904 0.006830573 -0.0619266 -0.003768324 0.006714344 -0.06185621 -0.003754973 0.006700396 -0.06185781 -0.003911375 0.006650388 -0.06154906 -0.004144251 0.006336331 -0.06064701 -0.004185199 0.006284594 -0.06052529 -0.004164397 0.006294965 -0.06051987 -0.00420022 0.006269812 -0.06053155 -0.003929078 0.006634652 -0.06155729 -0.003936469 0.006619334 -0.06156361 -0.004207193 0.006254434 -0.06053709 -0.003937005 0.006603956 -0.06156885 -0.004207491 0.006239056 -0.06054192 -0.003930866 0.006589651 -0.06157267 -0.004201292 0.006224989 -0.06054568 -0.003916442 0.00657624 -0.06157487 -0.004186928 0.006211936 -0.06054824 -0.002929925 0.007088422 -0.06251084 -0.003525376 0.006811738 -0.0620982 -0.003904402 0.00655955 -0.06155407 -0.004864871 0.005104303 -0.05689674 -0.004405796 0.005747914 -0.05885821 -0.004409313 0.005733489 -0.05886393 -0.004868865 0.005089521 -0.05690199 -0.004408061 0.005718708 -0.05886864 -0.004867732 0.005074679 -0.05690634 -0.004402399 0.0057047 -0.05887192 -0.004861772 0.005060791 -0.05690956 -0.004391074 0.005691051 -0.05887371 -0.004849672 0.0050475 -0.05691152 -0.004383444 0.005685508 -0.05887371 -0.004841506 0.005042254 -0.05691164 -0.00567162 0.003746926 -0.05227524 -0.005674839 0.003732085 -0.05227982 -0.00567317 0.003717243 -0.05228364 -0.00566703 0.003703594 -0.05228644 -0.00565505 0.00369054 -0.05228811 -0.005647122 0.003685474 -0.05228823 -0.00484389 0.005035877 -0.05689412 -0.00564748 0.00377357 -0.05227255 -0.005662262 0.003761887 -0.05227357 -0.006153464 0.002873122 -0.0488277 -0.006226003 0.002752542 -0.04838383 -0.006249248 0.002694189 -0.04809397 -0.006662905 0.001873373 -0.04444646 -0.006676077 0.001862406 -0.04445004 -0.00668478 0.001847088 -0.04445409 -0.006191372 0.002671837 -0.04839897 -0.006640076 0.00178188 -0.04446333 -0.006983637 0.00115168 -0.04075956 -0.007185816 5.48056e-4 -0.03704643 -0.006687343 0.001831889 -0.04445755 -0.007187843 5.32579e-4 -0.03704869 -0.006685137 0.001817047 -0.04446041 -0.007185101 5.17679e-4 -0.03705072 -0.006678462 0.001803576 -0.04446256 -0.007177948 5.04372e-4 -0.03705233 -0.006666004 0.001791059 -0.04446399 -0.007165074 4.92355e-4 -0.03705352 -0.006657898 0.001786351 -0.04446417 -0.007156789 4.8797e-4 -0.03705382 -0.007138729 4.84281e-4 -0.0370537 -0.00723958 8.98323e-5 -0.03303408 -0.00721246 -2.41475e-4 -0.0294981 -0.00707978 -3.79569e-4 -0.02660578 -0.007050514 -4.24686e-4 -0.02582162 -0.006967127 -4.50091e-4 -0.02465522 -0.006798803 -5.23602e-4 -0.02212828 -0.007163345 -3.04106e-4 -0.02952104 -0.007211089 2.45114e-5 -0.0332942 -0.007007002 -5.0254e-4 -0.02582705 -0.0064103 -4.74595e-4 -0.01819151 -0.005938887 -3.42653e-4 -0.01427966 -0.006114661 -3.83537e-4 -0.01578062 -0.006746947 -5.84534e-4 -0.02213305 -0.006568789 -5.82994e-4 -0.02016299 -0.006765484 -5.82309e-4 -0.0221315 -0.006364524 -5.51368e-4 -0.01819479 -0.005883336 -4.02735e-4 -0.01426666 -0.005616188 -1.85871e-4 -0.01210415 -0.004422903 4.61955e-4 -0.004841208 -0.005217432 9.11576e-6 -0.009493649 -0.00593692 -3.43337e-4 -0.01426255 -0.006799817 -5.39465e-4 -0.02212834 -0.005937457 -3.59198e-4 -0.01426172 -0.006796061 -5.54392e-4 -0.02212876 -0.005933165 -3.73994e-4 -0.01426148 -0.006787955 -5.67354e-4 -0.02212953 -0.005924642 -3.86708e-4 -0.01426196 -0.006774127 -5.78533e-4 -0.02213072 -0.005910575 -3.97488e-4 -0.01426333 -0.005901813 -4.0102e-4 -0.01426428 -0.00554651 -2.59491e-4 -0.01187586 0.03851479 0.001587986 0.01603484 0.03807276 0.002074718 0.01759582 0.03130108 0.001220107 0.01367527 0.02809053 0.005415141 0.02249723 0.02736514 0.004624426 0.02047067 0.0363239 0.004907011 0.02509349 0.01268005 0.00529927 0.01348185 0.01426625 0.00377494 0.01142311 0.02088552 0.003737509 0.01520544 0.01064479 0.005297362 0.01214414 0.006927251 0.005315124 0.009602069 0.009945511 0.00251168 0.006023228 0.01238268 -2.05737e-4 8.83949e-4 0.01358836 -2.9353e-4 0.001360952 0.006849765 0.001028656 5.87934e-4 0.006878852 5.52898e-4 -5.85751e-4 0.006839752 4.38451e-4 -9.05442e-4 0.006765842 3.34728e-4 -0.001222968 0.002253115 0.005413234 0.006229877 0.003973245 0.004234015 0.00537765 0.004976093 0.003410995 0.004538178 0.005668044 0.002759993 0.003711283 0.02811068 0.003878533 0.01918333 0.02377247 0.005366027 0.0201494 0.02102112 0.005343079 0.01858615 0.03521561 0.005569577 0.02611398 0.0412054 0.005206823 0.02742487 0.04263961 0.005958735 0.02949917 0.04562014 0.005675852 0.02934324 0.04552745 0.006237208 0.03063315 0.04694932 0.006418704 0.03111362 0.04749542 0.005971968 0.0300455 0.04721301 0.006456375 0.03119444 0.04886293 0.006721973 0.0316199 0.04910749 0.006294548 0.0305345 0.04992932 0.006923913 0.03177684 0.05103456 0.007148921 0.03179019 0.05047225 0.006620764 0.03079485 0.05165231 0.006916463 0.03082811 0.05247998 0.007385909 0.03143846 0.05196642 0.007317006 0.03162693 0.05170542 0.007274389 0.03169423 0.05484485 0.007313787 0.02973037 0.05389517 0.007464766 0.03066724 0.05379027 0.007278621 0.03027528 0.05273371 0.007144927 0.03064829 0.0555703 0.007100701 0.02878427 0.05517041 0.007351398 0.02965855 0.05508911 0.007371783 0.02975475 0.05321687 0.005972981 0.02657479 0.05549323 0.006765127 0.02789485 0.05559504 0.006978988 0.02844035 0.04974389 0.004286825 0.02266168 0.05042958 0.00454235 0.02322179 0.05043148 0.00476855 0.02396446 0.0534594 0.005799174 0.0259065 0.04808461 0.003679692 0.02127808 0.04469525 0.003000199 0.02004444 0.04483121 0.002621293 0.01871967 0.04263478 0.001996874 0.01708322 0.04181754 0.001783013 0.01649302 0.03299719 9.70684e-5 0.01074546 0.03565078 4.86144e-4 0.01235681 0.03581166 5.12951e-4 0.01245766 0.0390225 0.001126289 0.01454985 0.02673661 -4.58733e-4 0.007302403 0.02861249 -3.418e-4 0.008285343 0.02471017 8.15696e-4 0.01009845 0.02914071 -3.01483e-4 0.008569359 0.0324316 2.67795e-5 0.0104146 0.02253514 -5.81398e-4 0.005236446 0.01817083 7.79844e-4 0.00680238 0.02081668 -5.80424e-4 0.004440844 0.01529169 -3.99213e-4 0.002051472 0.01171869 0.001069784 0.003798067 0.006596982 0.001608312 0.001807928 0.05369699 0.007002592 0.029567 0.05260837 0.006801009 0.02973908 0.05149835 0.006519794 0.02974712 0.05030137 0.006183266 0.02957314 0.04894107 0.005823969 0.02920442 0.04554879 0.005147874 0.0278908 0.04133236 0.004621565 0.0259546 0.03669708 0.004262447 0.02367109 0.04147148 0.00268501 0.01962471 0.04473471 0.003409504 0.02159786 0.05345195 0.006474792 0.02808392 0.05225086 0.006153464 0.02781838 0.05056911 0.00510478 0.02510195 0.04777103 0.004229784 0.02344006 0.05495357 0.006400942 0.02708572 0.05102688 0.005787551 0.0274477 0.04974073 0.00539273 0.02696228 0.04834687 0.004989683 0.02635532 0.04512804 0.004229784 0.02478635 0.04138123 0.003594696 0.02283978 0.03735589 0.003103137 0.02069151 0.02966248 0.002481043 0.01650452 0.02274149 0.002220809 0.01274883 0.01614719 0.002244293 0.009235262 -0.03314435 0.001587927 0.02533763 -0.03427529 0.002074718 0.02417433 -0.02749401 0.001219928 0.02027016 -0.007032275 -2.12638e-4 0.01034194 -0.007972836 -2.9353e-4 0.01108735 -0.003934025 0.001028656 0.005638122 -0.002932131 5.52898e-4 0.006250143 -0.002635717 4.38451e-4 0.006376087 -0.002323746 3.34728e-4 0.006470918 -0.01177823 0.005315124 0.001197636 -0.006521821 0.005413234 -0.001163661 -0.006643772 0.004234015 7.52184e-4 -0.01018905 0.002511382 0.005600512 -0.006418287 0.003410995 0.002040326 -0.006048083 0.002759993 0.003053009 -0.01232343 0.005310595 0.001452624 -0.01702606 0.003775179 0.006642341 -0.01801568 0.00529927 0.004240274 -0.02361124 0.003737449 0.01048535 -0.0230742 0.005319893 0.006922543 -0.03066945 0.003878712 0.01475262 -0.03989523 0.00490725 0.01891094 -0.03286969 0.005405902 0.01266688 -0.0314117 0.004624724 0.01346319 -0.02933615 0.005366027 0.01051288 -0.04686695 0.005958735 0.02217751 -0.04211562 0.005645453 0.01873821 -0.04022312 0.005569577 0.01744061 -0.04435575 0.00520724 0.02197313 -0.04822361 0.005676209 0.02483695 -0.04796236 0.006070494 0.02302819 -0.04977178 0.005972504 0.0261107 -0.05062192 0.006456375 0.02529072 -0.05099934 0.006295323 0.02726107 -0.05248397 0.006923854 0.02735149 -0.05111014 0.00655514 0.02576291 -0.05290985 0.007145643 0.0303443 -0.05337274 0.007316946 0.02919095 -0.05252248 0.006916642 0.02931749 -0.05268836 0.006998598 0.02765816 -0.05190151 0.006621479 0.02831035 -0.05316585 0.007315695 0.0326277 -0.05350583 0.007464587 0.03134119 -0.05311006 0.007281363 0.03144061 -0.05351012 0.007460832 0.03100198 -0.05349475 0.007416307 0.0300638 -0.0527141 0.007101118 0.03373312 -0.05327028 0.007351338 0.03295063 -0.05338174 0.00740534 0.03258401 -0.04444092 0.00426948 0.03172773 -0.04532831 0.004543244 0.03206348 -0.0459699 0.004768669 0.03169286 -0.04915624 0.005796194 0.03333932 -0.04247033 0.003679871 0.03100377 -0.03970706 0.003000319 0.02868515 -0.03862762 0.002621352 0.02946525 -0.03608399 0.001990318 0.02836883 -0.03519219 0.001783013 0.02796858 -0.02580469 9.70981e-5 0.02320379 -0.02852672 4.86144e-4 0.02469611 -0.02866858 5.08781e-4 0.02477121 -0.03211206 0.001126348 0.02651971 -0.01969265 -4.58721e-4 0.01950353 -0.02155697 -3.36036e-4 0.02068328 -0.02110087 8.15975e-4 0.01635038 -0.02199161 -3.01483e-4 0.02095192 -0.02523511 2.67796e-5 0.02287924 -0.0158025 -5.81398e-4 0.01689773 -0.01497638 7.79414e-4 0.01233541 -0.0143277 -5.81105e-4 0.01585978 -0.009422481 -3.99213e-4 0.01221728 -0.00914824 0.001068711 0.008250176 -0.004864275 0.001608371 0.004809141 -0.05245065 0.007005035 0.03171467 -0.05205976 0.006801664 0.03069037 -0.05150961 0.006519973 0.02972477 -0.05075854 0.006183922 0.02877354 -0.04976403 0.005824685 0.02778202 -0.04692995 0.005148231 0.02550131 -0.04314571 0.004621922 0.02281814 -0.03884983 0.004262685 0.01994538 -0.03773188 0.002685129 0.02610325 -0.04107218 0.003409624 0.02794265 -0.0519067 0.00676614 0.03411048 -0.05104541 0.006476283 0.03224611 -0.04962253 0.005973577 0.03279906 -0.05021756 0.006153941 0.03134137 -0.04702359 0.005104899 0.03124326 -0.04418587 0.004230022 0.02965104 -0.05093717 0.006402313 0.03404819 -0.04928332 0.00578773 0.03046649 -0.0482186 0.005393207 0.02959442 -0.04699897 0.0049901 0.02869206 -0.0440306 0.004230022 0.02668911 -0.04047191 0.003594934 0.02441769 -0.03659832 0.003103256 0.02200567 -0.02912515 0.002481043 0.0174362 -0.02241182 0.002220928 0.01332062 -0.01607167 0.002244174 0.009365856 -0.05135518 0.006569206 0.03417861 -0.05200707 0.006822347 0.0341264 -0.05201262 0.006812751 0.03410953 -0.05339884 0.007335901 0.02922886 -0.05269992 0.007008314 0.0276485 -0.001981556 4.59303e-4 0.006251692 -0.00561136 7.0614e-6 0.009267032 -0.005603134 -8.88246e-6 0.009275078 -0.008895754 0.005433201 -1.26265e-4 -0.006451725 0.005492091 -0.001201927 -0.007929205 0.005451917 -5.5736e-4 -0.002066254 3.71255e-4 0.006315827 -0.002043306 3.77473e-4 0.006302177 -0.005607128 -6.67263e-5 0.009262681 -0.005601823 -5.5363e-5 0.009270668 -0.002142667 3.54648e-4 0.006359994 -0.005615293 -7.54856e-5 0.009251415 -0.00222975 3.42493e-4 0.00641191 -0.005629897 -7.72771e-5 0.009262382 -0.002276539 3.37995e-4 0.006440997 -0.009400248 0.005422651 9.84998e-5 -0.006406247 0.005434393 -0.001230776 -0.006418645 0.005431234 -0.001223683 -0.01232838 0.00538659 0.001443266 -0.0115171 0.005395531 0.001066803 -0.001992285 3.92765e-4 0.006269454 -0.001989722 4.08753e-4 0.006265223 -0.005599021 -4.09877e-5 0.009275972 -0.001987278 4.23947e-4 0.00626111 -0.00559926 -2.56954e-5 0.009277641 -0.00198543 4.351e-4 0.00625813 -0.001984417 4.4144e-4 0.006256461 -0.01232779 0.005388081 0.001444578 -0.01776313 0.005360603 0.004088819 -0.02017349 0.005376756 0.005342721 -0.006489157 0.005417883 -0.001182794 -0.006505072 0.005415499 -0.001173496 -0.01233083 0.005328536 0.001437127 -0.01232784 0.005319058 0.001443326 -0.01775133 0.005315124 0.004086911 -0.01774829 0.005306482 0.004092991 -0.02308177 0.005334854 0.006908595 -0.02307856 0.005326867 0.006914496 -0.03046005 0.005441427 0.01116353 -0.02802044 0.005418479 0.009710371 -0.03288221 0.005461275 0.0126456 -0.02308279 0.00538671 0.006906211 -0.02308481 0.005376756 0.006902694 -0.02042824 0.005375981 0.005475997 -0.017753 0.005360305 0.004083573 -0.03287458 0.005412459 0.01265889 -0.02801501 0.005360901 0.009720444 -0.03343182 0.005481064 0.01299399 -0.03288024 0.005471348 0.01264852 -0.03405123 0.00548923 0.01338255 -0.03753614 0.005561292 0.01562654 -0.006420731 0.005430757 -0.001222491 -0.01233136 0.005376577 0.001436829 -0.03252559 0.00546801 0.01242917 -0.03521764 0.005509912 0.01412367 -0.04212611 0.005712628 0.01871865 -0.03287816 0.005420088 0.01265299 -0.03753226 0.005497753 0.01563483 -0.04212611 0.005662739 0.01872193 -0.04212188 0.005653321 0.01872867 -0.04797476 0.006090939 0.02300971 -0.04360675 0.00580132 0.0197696 -0.0435208 0.005797922 0.01971042 -0.0421217 0.005723237 0.01872432 -0.04212081 0.005724847 0.01872551 -0.04073262 0.005665004 0.01776844 -0.04795831 0.006158947 0.02302086 -0.04646748 0.006009161 0.02186673 -0.04652971 0.006013214 0.02191132 -0.04507762 0.005896627 0.02083122 -0.05057787 0.006541788 0.02525329 -0.05072718 0.006569445 0.02539128 -0.0507692 0.00657916 0.02543514 -0.051099 0.006646394 0.02575439 -0.05109709 0.006647288 0.02575606 -0.04795968 0.006157696 0.02301931 -0.04796743 0.006147861 0.0230109 -0.04956418 0.006367206 0.02433955 -0.05111008 0.00663799 0.02574515 -0.05034554 0.006497144 0.02503389 -0.04797005 0.006079614 0.02301722 -0.04957884 0.006287336 0.02433639 -0.05249738 0.007027029 0.02738469 -0.05252575 0.007038712 0.02743136 -0.05267035 0.007091403 0.02764743 -0.05266797 0.007091879 0.02764886 -0.05231624 0.006965219 0.02713149 -0.05193382 0.006849944 0.02665078 -0.0526852 0.007084846 0.02763962 -0.05111956 0.006564915 0.02575141 -0.05336946 0.007413923 0.02921074 -0.05324631 0.00734961 0.02881926 -0.05337983 0.007413208 0.02922147 -0.05308771 0.00726962 0.02841842 -0.0511251 0.00657761 0.02574324 -0.05195856 0.006767988 0.02664911 -0.05270755 0.007023036 0.02764028 -0.05340766 0.00735104 0.02922403 -0.05353641 0.00748986 0.03100204 -0.05338883 0.007438123 0.0293734 -0.05343556 0.007472336 0.02965223 -0.05346906 0.00751084 0.03006201 -0.05347365 0.007512867 0.03008759 -0.05348348 0.007555484 0.03100025 -0.05334669 0.007409811 0.02917599 -0.05340355 0.007446765 0.02943813 -0.05348664 0.007555723 0.03100031 -0.05350607 0.007552921 0.03100067 -0.05348116 0.007559835 0.0314033 -0.05338233 0.007501065 0.03258776 -0.05346375 0.007553696 0.03180915 -0.05335748 0.007501125 0.03258764 -0.006474733 0.005420148 -0.001191198 -0.01233267 0.005338013 0.001433491 -0.01775324 0.005323827 0.004083156 -0.02308386 0.005342721 0.00690478 -0.03288054 0.005427718 0.01264899 -0.04212862 0.005672335 0.01871776 -0.04797691 0.006102561 0.0230053 -0.05112707 0.006590545 0.02573853 -0.05270969 0.007036924 0.02763563 -0.05341053 0.00736612 0.02922075 -0.05353939 0.007505655 0.0310018 -0.05342233 0.007455289 0.03258597 -0.05341738 0.007438123 0.03258532 -0.05316984 0.007335662 0.03324025 -0.05340266 0.00741899 0.0325846 -0.0535072 0.007472455 0.03180819 -0.05352693 0.007473886 0.0310021 -0.05313181 0.007383108 0.03323972 -0.05318844 0.007420241 0.03308796 -0.05325567 0.007451772 0.03292989 -0.05322366 0.007437825 0.03299987 -0.0533539 0.007500469 0.03258776 -0.05347508 0.007559001 0.03149145 -0.05328446 0.007358014 0.03291827 -0.05316638 0.007318973 0.03323781 -0.0526604 0.007109999 0.03381407 -0.05316418 0.007410049 0.03312945 -0.05311036 0.00738424 0.03323644 -0.05261892 0.007166862 0.03379505 -0.05317175 0.007315218 0.03321981 -0.05242025 0.007083237 0.03392213 -0.05231499 0.007038295 0.0339803 -0.05213963 0.006966769 0.03404986 -0.05198049 0.006901383 0.03410148 -0.0518049 0.006832301 0.03413301 -0.05176705 0.00681746 0.03413826 -0.05253875 0.007133424 0.03384888 -0.05247128 0.007103919 0.03389543 -0.05198174 0.006891906 0.03412073 -0.05263096 0.007161915 0.03380614 -0.05266141 0.007095098 0.03380781 -0.05265825 0.007081687 0.03379768 -0.05234932 0.006962776 0.03399944 -0.05235064 0.006951272 0.03398579 -0.05182486 0.006839334 0.03413367 -0.05166548 0.006776928 0.03415232 -0.05133312 0.006640255 0.0341711 -0.05133813 0.006652414 0.03414773 -0.05133938 0.006653845 0.03414344 -0.05057603 0.00637871 0.03396654 -0.05050784 0.00635606 0.03393757 -0.05031633 0.006289064 0.0338695 -0.05031764 0.006290555 0.03386545 -0.05083346 0.00646919 0.03404825 -0.05031067 0.006276309 0.03389149 -0.04873508 0.005758523 0.03320819 -0.05133849 0.00655663 0.0341674 -0.0503537 0.006209909 0.03390103 -0.050332 0.006205618 0.03389734 -0.04876416 0.005668818 0.03321325 -0.04246264 0.003680646 0.03102338 -0.0424546 0.003688395 0.03103858 -0.04687106 0.005037665 0.03263843 -0.04686278 0.005045652 0.03265404 -0.04875695 0.005677402 0.03322809 -0.04684364 0.005127906 0.03263396 -0.04684293 0.005126535 0.03263705 -0.04244589 0.003773689 0.03102695 -0.0424357 0.003769457 0.03102618 -0.04061186 0.003251433 0.0303151 -0.03920912 0.002873122 0.02974277 -0.0397005 0.003002882 0.02994745 -0.03878992 0.002761483 0.02957218 -0.04243355 0.003757059 0.0310412 -0.03515625 0.001858234 0.02800995 -0.04684078 0.005114674 0.03265357 -0.03881543 0.002672612 0.02956664 -0.03518348 0.001782655 0.02798783 -0.03517508 0.00178951 0.02800297 -0.03852605 0.002694249 0.02945894 -0.0351594 0.001871645 0.02799618 -0.03516024 0.001873373 0.02799344 -0.03181004 0.001161515 0.02641749 -0.03144979 0.001093506 0.02623718 -0.028517 4.84803e-4 0.02471482 -0.03097778 0.001002788 0.02600568 -0.02849572 5.7385e-4 0.02472829 -0.0256567 1.71175e-4 0.02316838 -0.02520477 1.13828e-4 0.02291393 -0.02498859 8.98364e-5 0.02278673 -0.02357721 -6.67144e-5 0.02196472 -0.02195608 -2.29995e-4 0.02100008 -0.02519971 9.92354e-5 0.02292585 -0.02849131 5.59635e-4 0.02474087 -0.03014785 8.51853e-4 0.02558696 -0.028508 4.90909e-4 0.02472996 -0.02521544 3.05527e-5 0.02291274 -0.0252248 2.48672e-5 0.02289766 -0.02197104 -2.98604e-4 0.020985 -0.0219807 -3.03911e-4 0.02096992 -0.01578009 -5.79812e-4 0.01692992 -0.01807022 -4.4506e-4 0.01849889 -0.01786845 -4.50091e-4 0.01836133 -0.01884198 -4.13813e-4 0.01900827 -0.01950138 -3.79567e-4 0.01943421 -0.0219618 -2.15093e-4 0.02098882 -0.02196311 -2.13134e-4 0.02098649 -0.01576673 -5.11481e-4 0.01694834 -0.01577365 -4.9617e-4 0.0169382 -0.01730155 -4.69132e-4 0.01798397 -0.006434798 0.005427598 -0.001214385 -0.01233303 0.005366384 0.001433134 -0.01775431 0.00535041 0.00408101 -0.02308571 0.005367338 0.006901144 -0.03288298 0.005451858 0.01264452 -0.04212874 0.005701899 0.01871562 -0.04797273 0.006136715 0.02300578 -0.05111819 0.006627142 0.02573943 -0.0526964 0.007074713 0.02763503 -0.05339384 0.007404386 0.02921909 -0.05352115 0.007544696 0.03100103 -0.05340123 0.007494509 0.03258752 -0.05314892 0.007375657 0.03324156 -0.05264174 0.007151722 0.03381335 -0.05198526 0.006878554 0.03413349 -0.05133229 0.006624996 0.03418666 -0.05030936 0.006260812 0.03390598 -0.04873573 0.005731999 0.03323715 -0.04684168 0.005099952 0.032664 -0.04243445 0.003742158 0.03105032 -0.03515619 0.001842737 0.02801781 -0.02849024 5.43631e-4 0.02474761 -0.02519816 8.29891e-5 0.02293199 -0.02195405 -2.46442e-4 0.02100563 -0.01576381 -5.28174e-4 0.01695281 -0.006447911 0.005424976 -0.001206815 -0.01233369 0.005356907 0.001431584 -0.01775467 0.00534141 0.004080235 -0.02308571 0.005358874 0.006901144 -0.03288286 0.005443513 0.01264488 -0.04212981 0.005691945 0.01871466 -0.04797577 0.006125569 0.02300345 -0.05112344 0.006615579 0.02573674 -0.05270379 0.00706321 0.02763307 -0.05340319 0.0073933 0.02921831 -0.05353134 0.007533669 0.03100132 -0.05341368 0.007484078 0.03258705 -0.05316054 0.007364749 0.0332421 -0.05265009 0.007139205 0.03381669 -0.05198985 0.006864309 0.03413975 -0.05133461 0.006609678 0.0341944 -0.05031132 0.006245493 0.03391307 -0.04873931 0.005717575 0.03324168 -0.04684472 0.005085289 0.03266859 -0.04243731 0.003727495 0.03105396 -0.03515839 0.001827776 0.02802044 -0.02849179 5.28449e-4 0.02474927 -0.02519935 6.76993e-5 0.02293306 -0.02195495 -2.61819e-4 0.02100622 -0.01576411 -5.43639e-4 0.01695251 -0.00646156 0.005422413 -0.001198887 -0.01233351 0.005347132 0.001431703 -0.01775431 0.005332291 0.00408101 -0.02308511 0.00535047 0.006902396 -0.03288203 0.005435228 0.01264643 -0.04212975 0.005681753 0.01871544 -0.0479772 0.006113767 0.02300333 -0.05112648 0.006602883 0.02573645 -0.05270838 0.007050037 0.0276333 -0.05340898 0.007379889 0.02921891 -0.05353766 0.00752002 0.03100156 -0.05342102 0.007470309 0.03258651 -0.05316787 0.007350683 0.03324168 -0.05265665 0.007124543 0.03381693 -0.05199545 0.00684905 0.03414076 -0.05133956 0.006594121 0.03419572 -0.05031615 0.006230056 0.03391408 -0.04874444 0.005702614 0.03324168 -0.0468496 0.005070328 0.03266847 -0.04244196 0.003712594 0.03105318 -0.03516256 0.001812934 0.02801877 -0.02849555 5.13594e-4 0.02474671 -0.02520287 5.28542e-5 0.02293002 -0.02195829 -2.76651e-4 0.02100276 -0.01576715 -5.58416e-4 0.01694834 -0.05200111 0.006835222 0.03413641 -0.0513463 0.00658077 0.03419065 -0.05032289 0.006216943 0.03390896 -0.04875022 0.005689382 0.03323727 -0.0468555 0.005057275 0.03266376 -0.04244756 0.003699719 0.03104823 -0.03516805 0.001800358 0.02801311 -0.02850079 5.01243e-4 0.02474039 -0.02520811 4.06284e-5 0.0229234 -0.02196353 -2.88762e-4 0.02099585 -0.01577234 -5.7033e-4 0.01694101 -0.01350909 -4.83634e-4 0.01533097 -0.01577514 -4.94134e-4 0.016936 -0.009386301 -3.31113e-4 0.01226991 -0.009394168 -3.15491e-4 0.01226103 -0.01096749 -4.0326e-4 0.0134595 -0.01060909 -3.83536e-4 0.01318579 -0.01255506 -4.63456e-4 0.01463961 -0.01579046 -5.8456e-4 0.01691508 -0.01257103 -5.51469e-4 0.0146144 -0.009409666 -4.02949e-4 0.01223355 -0.001981139 4.61955e-4 0.006250977 -0.005613029 9.11587e-6 0.009265303 -0.007673978 -1.85834e-4 0.01091545 -0.009398579 -3.98697e-4 0.01224833 -0.009390532 -3.89602e-4 0.01225954 -0.009385287 -3.77957e-4 0.01226729 -0.009382486 -3.63348e-4 0.01227211 -0.009382665 -3.47923e-4 0.01227325 -3.68819e-4 0.004363834 -0.03378266 -0.002464175 0.003178179 -0.03378981 -0.002564609 0.002632439 -0.02624332 0.00420773 0.005748093 -0.01766836 0.003648281 0.005648314 -0.01779961 0.002992212 0.005448579 -0.01090222 0.0050565 0.005611598 -0.01741343 0.004679918 0.005738556 -0.0175395 0.004108548 0.005669116 -0.01069962 0.004644393 0.006068348 -0.03375774 0.005021691 0.005954682 -0.03375434 0.004443883 0.006042718 -0.04386508 0.002489805 0.005996882 -0.04303503 0.001073539 0.005534768 -0.04256439 0.001466274 0.005275249 -0.03377544 -0.001746773 0.00276643 -0.006452262 -6.00786e-4 0.00360918 -0.006702303 1.55763e-4 0.004000246 -0.01131647 -0.003915011 9.41734e-4 -0.005292952 -0.002791166 0.001927971 -0.006023824 -0.002822697 0.001947164 -0.0117309 -0.002747476 0.002176105 -0.01887857 -0.00478059 0.001759588 -0.03379666 -0.004692196 0.002583801 -0.04126 -0.004500269 0.003720819 -0.04865813 -0.00421971 0.005152344 -0.05565327 -0.003354728 0.006344258 -0.05940669 -0.001931309 0.007365643 -0.06209218 -0.002684116 0.006690025 -0.05987179 -0.002061188 0.006984174 -0.06035244 -9.85816e-4 0.007400393 -0.06129723 -1.62262e-4 0.007355272 -0.0604363 5.33319e-4 0.007234692 -0.05946648 0.001170992 0.007345557 -0.06014579 0.001816272 0.007146596 -0.05909568 0.002355873 0.006915986 -0.05777806 0.002818346 0.0066877 -0.05612444 0.003224253 0.006483972 -0.05412822 0.004229843 0.006065666 -0.04956173 0.00475192 0.005877554 -0.04402947 0.005312681 0.00575006 -0.03375107 0.005207896 0.005503177 -0.01735162 0.003989458 0.005674421 -0.005363285 0.004141032 0.005602002 -0.005169212 0.004703819 0.005507051 -0.01055115 0.003650784 0.005717694 -0.005692899 0.003832042 0.005709111 -0.005530893 0.004530906 0.005594551 -0.01060026 0.002558112 0.005439341 -0.006320416 0.003230869 0.005660712 -0.005988478 0.001654505 0.00501275 -0.006601631 0.002225875 0.005294919 -0.006442368 -0.002548098 0.003800988 -0.0416494 -6.17301e-4 0.004792332 -0.04209333 -0.002757191 0.004655122 -0.04946154 -8.64915e-4 0.005063414 -0.04636198 -0.001177847 0.005407273 -0.05039685 -0.002900779 0.005185902 -0.05304324 -0.00155723 0.00582695 -0.05399203 -0.003089427 0.005762875 -0.05633562 -0.002038657 0.006281018 -0.05709886 0.004180014 0.006090164 -0.0337612 0.003909945 0.006189882 -0.04930132 7.10385e-4 0.006669223 -0.05601215 0.001611769 0.006863713 -0.05695813 2.81364e-4 0.006853044 -0.05745482 0.001116454 0.007060945 -0.05832874 -2.17339e-4 0.007021129 -0.05870503 -0.001532554 0.006862342 -0.05916601 -0.001077353 0.006702482 -0.05790221 6.96752e-4 0.005710482 -0.04714941 0.002018868 0.0061149 -0.04793608 2.2369e-4 0.005971729 -0.05139756 0.001428425 0.006337404 -0.05239737 -3.48609e-4 0.006323695 -0.05500257 1.26704e-4 0.004103243 -0.00675565 0.001626491 0.004845023 -0.01110845 7.64312e-4 0.004379332 -0.01833897 0.002313196 0.005165636 -0.01806741 0.001302361 0.004874527 -0.02585339 0.002866268 0.005568087 -0.02565717 0.002992451 0.005861163 -0.03376829 0.003612875 0.006164193 -0.04347771 0.003088772 0.006270885 -0.04867053 0.002427518 0.006503939 -0.0533297 0.002043187 0.006671845 -0.05529385 0.004124045 0.00590825 -0.02546352 0.00462675 0.005934119 -0.02536845 0.005039274 0.005857646 -0.02527487 0.005359292 0.005676507 -0.0251832 0.005484938 0.005547046 -0.02513813 -0.003934919 3.91858e-4 -0.005174338 -0.004176199 3.15898e-4 -0.004996836 -0.003823637 5.58224e-4 -0.005474507 -0.003956079 9.06431e-5 -0.00487709 -0.004045724 2.12402e-4 -0.00491327 -0.003803431 2.5956e-4 -0.005086958 -0.003748655 1.74227e-4 -0.005066394 -0.003704369 8.07967e-5 -0.00506258 -0.003851294 6.98598e-5 -0.004948139 -0.004100263 2.6406e-4 -0.004944682 -0.003459513 10e-5 -0.005235135 -0.003499865 2.0592e-4 -0.005224168 -0.003552317 3.06346e-4 -0.005235314 -0.003560125 3.19067e-4 -0.005238413 -0.003833591 5.61086e-4 -0.00548768 -0.004273831 3.52339e-4 -0.005076646 -0.004314661 3.58078e-4 -0.005113959 -0.003682672 4.70596e-4 -0.005320847 -0.003941118 6.33959e-5 -0.004873991 -0.004233121 2.86439e-4 -0.004906237 -0.004377365 3.36726e-4 -0.004823565 -0.004357516 3.32899e-4 -0.004917144 -0.004294216 2.73485e-4 -0.004802465 -0.0043329 3.389e-4 -0.005017876 -0.00432223 3.47144e-4 -0.005067825 -0.004364848 7.65977e-5 -0.004504203 -0.004468977 10e-5 -0.004404902 -0.004340171 1.83387e-4 -0.004592955 -0.004403233 1.99837e-4 -0.004507303 -0.004344224 2.72579e-4 -0.00470221 -0.004378795 2.96702e-4 -0.004645466 -0.004388928 3.43396e-4 -0.004733622 -0.004252016 1.80443e-4 -0.004701197 -0.004233956 6.2089e-5 -0.004621148 -0.004423558 3.58217e-4 -0.004542112 -0.00444591 7.85975e-4 -0.004428148 -0.004408836 8.30573e-4 -0.004465103 -0.004360675 6.88081e-4 -0.004556238 -0.004435539 4.60485e-4 -0.004519402 -0.004415571 4.48925e-4 -0.004633426 -0.004410147 3.91052e-4 -0.004661679 -0.004548132 3.53959e-4 -0.004323124 -0.004534244 5.91114e-4 -0.004337608 -0.004481494 4.73512e-4 -0.004413306 -0.00435692 5.90781e-4 -0.00464791 -0.004409611 5.52902e-4 -0.004550874 -0.004374384 5.26298e-4 -0.004728853 -0.004401743 4.98463e-4 -0.004659712 0.002917885 0.006064414 -0.005564272 0.002952814 0.005955994 -0.005583882 0.001963734 0.00556904 -0.006004929 4.95186e-5 0.004232108 -0.006415247 0.001054406 0.004871368 -0.006341695 0.001129806 0.004778563 -0.006499707 -0.002762556 0.001984179 -0.005877792 -0.002768933 0.002073168 -0.005746364 -9.32493e-4 0.003536999 -0.006334543 -0.002842307 0.002248585 -0.005605041 -0.001891195 0.003170251 -0.005985319 -0.001048624 0.003733754 -0.006195485 -0.001098155 0.003807008 -0.00617814 -3.28504e-5 0.004594445 -0.006274402 -0.004125058 0.001122951 -0.004728972 -0.002881467 0.002312302 -0.005577623 -0.002412676 0.002727448 -0.005795776 -0.00281006 0.002186417 -0.00564301 0.002154827 0.005319774 -0.006252229 0.00206238 0.005415916 -0.006097495 0.003002107 0.005848169 -0.005631268 0.003114163 0.005704402 -0.005783498 0.003133237 0.005690157 -0.005813896 1.06094e-4 0.004140734 -0.006571054 -8.94215e-4 0.003446459 -0.006484568 0.002898871 0.006149947 -0.005565226 0.00173664 0.005682587 -0.006029903 5.47183e-4 0.004986047 -0.006251275 9.58789e-4 0.005013883 -0.006242632 -3.54903e-5 0.004365622 -0.006311357 -0.001003563 0.003662765 -0.006228208 0.003670036 0.005851805 -0.005267083 0.003844678 0.005840837 -0.005104959 0.003875434 0.005771398 -0.005174398 0.003741502 0.005753815 -0.005390286 0.003902852 0.005733132 -0.005226254 0.003556013 0.00575304 -0.005545198 0.003473103 0.005847096 -0.005417764 0.00341314 0.005989432 -0.005327403 0.0033831 0.006161391 -0.005284309 0.003838062 0.006149947 -0.004964351 0.003822445 0.005985677 -0.005014359 0.003826916 0.005923688 -0.005046606 0.004039049 0.005765199 -0.004927754 0.004074215 0.006029546 -0.004772245 0.004279196 0.005844473 -0.004589557 0.004222631 0.005712568 -0.004682362 0.004223287 0.005553066 -0.004868745 0.004074335 0.005665957 -0.005043148 0.004210472 0.005636572 -0.004757821 0.00421071 0.005613267 -0.004785239 0.004276394 0.005550801 -0.004671752 0.004258871 0.005509793 -0.004781305 0.00434947 0.00517857 -0.004522919 0.004211306 0.005000114 -0.004651844 0.004172861 0.00512439 -0.004714965 0.004201233 0.005351483 -0.004939258 0.004231095 0.005387127 -0.005002498 0.004252195 0.005408883 -0.0048877 0.004391849 0.005626916 -0.004481732 0.004410207 0.005396723 -0.004463732 0.004339635 0.005413115 -0.004552066 0.004178106 0.00530225 -0.004871904 0.004290878 0.005428671 -0.004654169 0.004266858 0.0054425 -0.004764974 0.004242718 0.005382299 -0.004828572 0.004246532 0.005318701 -0.004714608 0.004167497 0.00525546 -0.004820406 -6.90219e-4 0.002114832 -0.006573021 0.002416014 0.004032433 -0.006066501 0.00248748 0.003739476 -0.005769014 0.002526998 0.003665924 -0.005743324 0.00219202 0.003419399 -0.005879104 5.37336e-4 0.002411961 -0.006262004 4.93113e-4 0.002492427 -0.006294369 0.002455294 0.003810822 -0.005807876 4.21875e-4 0.002631962 -0.006408572 0.002416729 0.003938257 -0.005920171 0.003577589 0.004481732 -0.005155563 0.00142318 0.003368258 -0.006400585 3.82359e-4 0.002725601 -0.006573557 -0.002826392 0.00102359 -0.006025791 -0.002712428 9.33935e-4 -0.005861461 -0.002610385 5.21786e-4 -0.005704998 -0.002497851 5.792e-4 -0.005754888 -0.002595305 7.75356e-4 -0.00576502 -0.001531541 0.001088321 -0.006082713 -0.001580893 0.00130093 -0.006116926 -0.00148195 0.001115262 -0.006094992 -0.001770734 0.001544952 -0.006391286 -6.2796e-4 0.002021968 -0.006403684 -0.001683354 0.001453459 -0.00622195 -5.40958e-4 0.001875758 -0.0062927 -4.43817e-4 0.001700818 -0.006258308 -1.89022e-4 0.001851379 -0.00627166 9.01843e-4 0.002532243 -0.006210088 -0.02907222 0.004364013 0.01721078 -0.02803075 0.003178417 0.01902884 -0.02144485 0.0026322 0.01534265 -0.03851413 0.005996882 0.01936113 -0.03739845 0.005534827 0.02035236 -0.02998352 0.005275309 0.01561808 -0.004714369 0.00276643 0.004738926 -0.005503952 0.00360918 0.003871381 -0.009877681 0.004000544 0.005524635 -0.006692171 0.005294919 0.00129348 -0.006752669 0.005439221 9.45114e-4 -0.01093643 0.005448222 0.002862393 -0.02451241 0.005547344 0.007817745 -0.04977029 0.006344258 0.03260862 -0.00262618 9.41637e-4 0.006036996 -0.003821134 0.001928031 0.005429089 -0.008748054 0.001948297 0.008309781 -0.0149756 0.002176463 0.01181858 -0.02687853 0.001759886 0.02103823 -0.03338611 0.002583861 0.02469348 -0.03988897 0.003720819 0.02822643 -0.04608726 0.005152344 0.03148102 -0.05259197 0.007400393 0.0315023 -0.05123609 0.006984174 0.03196126 -0.05050837 0.006690025 0.03226041 -0.05280774 0.007365643 0.03271865 -0.05225813 0.007355272 0.03035861 -0.05001407 0.00668776 0.02562135 -0.05121511 0.006915986 0.02684873 -0.0405063 0.005877494 0.01789933 -0.04503679 0.006065547 0.0211178 -0.04848814 0.006483972 0.02427172 -0.03188544 0.005749821 0.01227521 -0.01763063 0.00550282 0.00416696 -0.01148778 0.005505979 0.001205742 -0.006547212 0.005602002 -0.001001656 -0.00663954 0.005674421 -7.73342e-4 -0.01144391 0.005593597 0.001379907 -0.006801605 0.005660712 1.96206e-4 -0.01131886 0.005668342 0.001795053 -0.00675559 0.005717694 -3.15238e-4 -0.006705939 0.005709111 -5.53183e-4 -0.006544411 0.00501275 0.001867949 -0.03479534 0.003801047 0.02303135 -0.03614515 0.004792332 0.02158117 -0.04145628 0.004655122 0.0271185 -0.03971827 0.005063354 0.02393007 -0.04305583 0.005407333 0.02621841 -0.04448634 0.005185902 0.02903378 -0.04597979 0.00582695 0.02834463 -0.04724329 0.005762875 0.03084331 -0.04842966 0.006281018 0.03031492 -0.04886305 0.006669282 0.02739083 -0.05013298 0.006863713 0.02708321 -0.04989796 0.006853103 0.02848374 -0.05107235 0.007060945 0.02819746 -0.05176603 0.007234692 0.02927136 -0.0507313 0.007021188 0.02954071 -0.05047291 0.006862342 0.03091019 -0.04960608 0.006702482 0.02988409 -0.04118102 0.005710482 0.02297133 -0.04252338 0.00611484 0.02221971 -0.04462325 0.005971729 0.025505 -0.04609137 0.006337404 0.02496147 -0.04745924 0.006323695 0.02780318 -0.005913913 0.004103243 0.003268063 -0.01043254 0.004844963 0.004147529 -0.01626414 0.004379451 0.008508026 -0.01680338 0.005165636 0.007031142 -0.02304065 0.004874527 0.01179832 -0.02365267 0.005568146 0.01034563 -0.03074038 0.005861163 0.01429289 -0.03945904 0.006164133 0.01860994 -0.04369437 0.006270766 0.02166038 -0.04739826 0.006503939 0.02456241 -0.04890722 0.006671905 0.02587741 -0.01740497 0.005747854 0.005191326 -0.01723897 0.005648136 0.005741298 -0.02428275 0.005934298 0.00867635 -0.02411383 0.005908429 0.009159326 -0.03155714 0.00606817 0.01285719 -0.0313279 0.006090044 0.01326107 -0.02448862 0.005676746 0.007949173 -0.01760852 0.00561124 0.004328966 -0.04465126 0.006189823 0.02126461 -0.04020994 0.006042659 0.01808398 -0.03174281 0.005954444 0.01252889 -0.02440804 0.005857884 0.00827223 -0.01752942 0.005738258 0.004718005 -0.05208647 0.007146596 0.02797484 -0.05267322 0.007345616 0.02905869 0.006018042 3.53959e-4 -0.001777172 0.006049275 10e-5 -0.001667737 0.005264341 10e-5 -0.003414928 0.006023645 5.91114e-4 -0.001757979 0.006057858 7.85975e-4 -0.001636147 0.005264341 0.006149947 -0.003414928 0.006071329 8.30573e-4 -0.001585602 0.006082952 0.006149947 -0.001540362 0.006157934 0.001122951 -0.001207888 0.006156861 0.006149947 -0.001211822 0.006271123 0.002312362 2.93425e-4 0.00625354 0.006149947 5.18185e-4 0.006225645 0.002727508 8.0846e-4 0.005899488 0.003807008 0.002138018 0.006129086 0.003170251 0.001354813 0.006126224 0.006149947 0.001358151 0.006169378 0.006149947 0.001146376 0.005450189 0.004594445 0.00310868 0.005746424 0.006149947 0.00252062 0.005140125 0.004986047 0.003599464 0.005129039 0.006149947 0.003615021 0.004353761 0.005682587 0.004518926 0.004616618 0.006149947 0.00424993 0.003370165 0.006149947 0.00529313 0.003854155 0.006149947 -0.004951834 0.003581941 10e-5 -0.005152165 0.002037465 10e-5 -0.005934953 0.003854155 10e-5 -0.004951834 8.94264e-4 10e-5 -0.006210923 0.001446723 10e-5 -0.006105899 -0.002037465 10e-5 -0.005934953 -0.001552104 10e-5 -0.006079971 0 10e-5 -0.006274998 -0.006170034 0.006029546 -0.001142263 -0.006218254 0.006149947 -8.41685e-4 -0.006082952 0.006149947 -0.001540362 -0.006070852 0.005396723 -0.00158751 -0.006077229 0.005626916 -0.001562595 -0.005589604 0.006149947 -0.002851545 -0.006114244 0.005844473 -0.00141108 -0.006091713 0.00517857 -0.001505315 -0.005589604 10e-5 -0.002851545 -0.006134331 0.005000114 -0.001321136 -0.006082952 10e-5 -0.001540362 -0.006253659 0.004481732 -5.20489e-4 -0.006252884 10e-5 -5.25968e-4 -0.006237328 0.003665924 6.83235e-4 -0.00625354 10e-5 5.18185e-4 -0.006187438 0.003419399 0.001041233 -0.00533694 0.001851439 0.003299534 -0.005829036 0.002532243 0.002324044 -0.005825936 10e-5 0.002331018 -0.006011247 10e-5 0.0018 -0.005197942 0.001700818 0.003513514 -0.005746424 10e-5 0.00252062 -0.004537463 0.001115262 0.004330933 -0.004616618 10e-5 0.00424993 -0.004501998 0.001088321 0.004367709 -0.004489362 10e-5 0.00438416 -0.003734946 5.79204e-4 0.005040645 -0.003635525 5.21841e-4 0.005113065 -0.00298655 10e-5 0.005518674 -0.00280404 10e-5 0.005613625 -0.005253195 0.006149947 -0.003432095 -0.005253195 10e-5 -0.003432095 -0.004127919 0.006149947 -0.004726052 -0.003854155 0.006149947 -0.004951834 -0.001886904 0.006149947 -0.005984544 -0.002091825 0.006149947 -0.005915999 0 0.006149947 -0.006274998 5.66179e-4 0.006149947 -0.006249368 0.002037465 0.006149947 -0.005934953 -0.002513289 1.74228e-4 0.005779683 -0.002532124 8.07967e-5 0.00573939 -0.002250373 6.33959e-5 0.005850136 -0.002513647 3.91861e-4 0.005994915 -0.002239286 3.15897e-4 0.006115078 -0.002829253 5.5823e-4 0.006048619 -0.002245604 9.064e-5 0.00586462 -0.002232134 2.12405e-4 0.005960345 -0.002503693 2.59561e-4 0.00583738 -0.002232074 2.64069e-4 0.006023287 -0.002774357 2.0592e-4 0.005643069 -0.002757728 3.0635e-4 0.005694091 -0.002756536 3.19084e-4 0.005702376 -0.002835631 5.61089e-4 0.006063818 -0.002259552 3.52341e-4 0.006239593 -0.002271473 3.58081e-4 0.006293594 -0.002766609 4.70607e-4 0.005849778 -0.002132356 2.86444e-4 0.006119132 -0.001885056 6.2089e-5 0.005977272 -0.002079606 3.329e-4 0.006232321 -0.002179145 3.38903e-4 0.006261348 -0.001904964 3.43397e-4 0.006167709 -0.001988649 3.36727e-4 0.006202697 -0.001718342 7.65977e-5 0.006032168 -0.001580297 10e-5 0.0060727 -0.00180751 1.83388e-4 0.006055176 -0.001701831 1.99854e-4 0.006066977 -0.001900076 2.72581e-4 0.00611335 -0.001833677 2.96699e-4 0.0061149 -0.002227723 3.47147e-4 0.006277084 -0.001945316 1.80445e-4 0.006032943 -0.002011954 2.73489e-4 0.006120145 -0.001721799 3.58217e-4 0.006101965 -0.001611948 7.85975e-4 0.006064355 -0.001662492 8.30573e-4 0.006050705 -0.001765489 6.88061e-4 0.006054639 -0.001696109 4.60485e-4 0.006101012 -0.001804828 4.48925e-4 0.006140708 -0.001832067 3.91053e-4 0.006150126 -0.00146985 3.53959e-4 0.006100356 -0.001489341 5.91114e-4 0.006095647 -0.001581251 4.73512e-4 0.006087779 -0.00184673 5.90786e-4 0.006097197 -0.001736342 5.52902e-4 0.006094276 -0.001908123 5.26298e-4 0.006152749 -0.001834571 4.98462e-4 0.006141841 -0.006277799 0.006064355 2.55137e-4 -0.006312191 0.005955994 2.34708e-4 -0.006182312 0.00556904 0.001301765 -0.005580484 0.004232108 0.003164708 -0.006019234 0.004871368 0.002257645 -0.006193816 0.004778563 0.002271413 -0.003709018 0.001984238 0.005331337 -0.003592014 0.002073168 0.005271136 -0.005019605 0.003536999 0.003974795 -0.003432869 0.002248585 0.005264043 -0.00423783 0.003170311 0.004630446 -0.004841089 0.003733754 0.004005849 -0.004801273 0.003807067 0.004040062 -0.005417346 0.004594445 0.003165602 -0.002032876 0.001122951 0.00593692 -0.003389596 0.002312302 0.005284249 -0.003812849 0.002727389 0.004987359 -0.003481924 0.002186417 0.005255103 -0.006492018 0.005319774 0.001259982 -0.006311774 0.005415916 0.001262605 -0.006377875 0.005848169 2.1574e-4 -0.00656569 0.005704462 1.94818e-4 -0.006601572 0.005690157 1.93483e-4 -0.005743741 0.004140734 0.003193616 -0.005168676 0.003446459 0.004016637 -0.006269097 0.006149947 2.72076e-4 -0.006090402 0.005682587 0.001510918 -0.005687355 0.004986047 0.002651751 -0.00588566 0.005013883 0.002290964 -0.005448043 0.004365622 0.003186404 -0.004891932 0.003662765 0.003983199 -0.006396412 0.005851805 -5.44835e-4 -0.006343424 0.005840837 -7.77132e-4 -0.006418883 0.005771398 -7.69038e-4 -0.006538867 0.005753815 -5.45106e-4 -0.006477475 0.005733132 -7.66891e-4 -0.006580293 0.00575304 -3.06984e-4 -0.006428539 0.005847096 -2.98933e-4 -0.006320238 0.005989432 -2.92188e-4 -0.006267905 0.006161391 -2.87685e-4 -0.006253778 0.005985677 -8.03183e-4 -0.006283998 0.005923688 -7.90922e-4 -0.006287097 0.005765199 -0.001034021 -0.006166398 0.005712509 -0.001315653 -0.006328105 0.005553066 -0.001223087 -0.006404638 0.005665957 -0.001006901 -0.006225645 0.005636572 -0.001267433 -0.006249487 0.005613267 -0.001253962 -0.006184041 0.005550801 -0.001367568 -0.00627017 0.005509793 -0.001297593 -0.006169676 0.00512439 -0.001256287 -0.006378173 0.005351483 -0.001168727 -0.006447851 0.005387127 -0.001162946 -0.006358981 0.005408883 -0.001238644 -0.006112039 0.005413115 -0.001482188 -0.006308257 0.00530225 -0.001182377 -0.006176054 0.005428671 -0.001388907 -0.006260037 0.0054425 -0.001312732 -0.006303012 0.005382299 -0.001259982 -0.006206214 0.005318701 -0.001320302 -0.006258368 0.00525546 -0.001198947 -0.005347371 0.002114832 0.003884255 -0.006461739 0.004032433 9.40906e-4 -0.006239891 0.003739535 7.30317e-4 -0.005691766 0.002412021 0.002665698 -0.005697667 0.002492487 0.002720117 -0.006257474 0.003810822 7.77611e-4 -0.005760967 0.002632021 0.002838969 -0.006335377 0.003938257 8.67167e-4 -0.006254673 0.003368258 0.001967787 -0.005884051 0.002725601 0.002955675 -0.003805279 0.00102359 0.005460619 -0.003719985 9.33949e-4 0.005279779 -0.003695011 7.75364e-4 0.005130112 -0.004507005 0.00130093 0.004427552 -0.004649639 0.001544952 0.004729151 -0.005231797 0.002021968 0.003745675 -0.004546642 0.001453518 0.004568815 -0.005179226 0.001875758 0.003614842 0.05498379 0.006486177 0.02704262 0.05357724 0.005938649 0.02596276 0.05495971 0.006483435 0.02703106 0.05466085 0.006362438 0.02678447 0.04885822 0.006731748 0.03163415 0.0329225 0.005512416 0.0249958 0.03781163 0.005685806 0.02737236 0.03782272 0.005686402 0.02737766 0.01563739 0.005325198 0.01537764 0.05232006 0.005387187 0.02483147 0.05230456 0.005399942 0.02484244 0.005731582 0.00533849 0.008770346 0.002236127 0.005415558 0.006220281 0.005732715 0.005406498 0.008770108 0.002137243 0.005434393 0.006163418 0.002149522 0.005431234 0.00617057 0.01083117 7.03921e-6 2.26071e-4 0.01083403 -8.94716e-6 2.14878e-4 0.006404936 4.59274e-4 -0.001409709 0.006410479 4.4137e-4 -0.00140959 0.006412446 4.351e-4 -0.00140959 0.01083433 -2.57693e-5 2.1029e-4 0.006415963 4.23872e-4 -0.00140953 0.01083272 -4.1025e-5 2.10954e-4 0.006420671 4.08716e-4 -0.001409411 0.01082956 -5.53629e-5 2.15995e-4 0.006425678 3.92765e-4 -0.001409351 0.006479203 3.77562e-4 -0.001381635 0.01082527 -6.66767e-5 2.24528e-4 0.006502807 3.71255e-4 -0.001368463 0.006579279 3.54648e-4 -0.001324355 0.01081967 -7.54475e-5 2.37193e-4 0.006646156 3.44929e-4 -0.001286685 0.01083642 -7.72416e-5 2.44359e-4 0.00671637 3.37995e-4 -0.001248896 0.006667733 3.42493e-4 -0.001274883 0.015643 0.005368351 0.01538807 0.01312875 0.005371332 0.01379001 0.01063746 0.005370795 0.01215523 0.01313197 0.005308091 0.0137853 0.01564615 0.005325436 0.0153833 0.01063543 0.005314469 0.01215821 0.02647227 0.005460917 0.02165502 0.02415663 0.005435526 0.02038645 0.02509963 0.005443513 0.02090835 0.02373099 0.005429863 0.02015012 0.0480867 0.003769218 0.02123689 0.04809308 0.003773689 0.02124583 0.05023026 0.004557669 0.02301889 0.05022799 0.00455904 0.02302092 0.002151668 0.005430757 0.006171822 0.005728363 0.005396485 0.008776068 0.010634 0.005360662 0.0121603 0.002220153 0.005417883 0.006211161 0.005727708 0.005348145 0.008776009 0.01063925 0.005305409 0.01215243 0.02101069 0.00540775 0.01860332 0.01893359 0.005395889 0.01738375 0.01564538 0.005378425 0.01538419 0.002184927 0.005492091 0.006188333 0.005733609 0.005407989 0.008768916 0.006681978 0.005395531 0.009440362 0.01325839 0.00537312 0.0138722 0.02100902 0.005397856 0.01860636 0.02647215 0.005449295 0.02165973 0.00220561 0.005420148 0.006202876 0.005725502 0.005357742 0.008779287 0.01063311 0.00532341 0.01216167 0.01564383 0.005333602 0.01538693 0.02101093 0.005364954 0.0186035 0.0210132 0.005357384 0.01859968 0.02647435 0.005416154 0.02165645 0.02647656 0.005408585 0.02165246 0.0280804 0.005437135 0.02251577 0.02646785 0.005408287 0.02164763 0.02373707 0.005372405 0.02014011 0.02101653 0.005349814 0.01859396 0.03782033 0.005696177 0.02738189 0.02808266 0.005429446 0.02251166 0.028086 0.005421817 0.02250564 0.03782278 0.005747437 0.02737176 0.03575557 0.005665004 0.02639192 0.03291743 0.00557661 0.02500277 0.02893322 0.005495965 0.02296388 0.03049159 0.005522072 0.02377372 0.02647215 0.005458652 0.02165615 0.02807998 0.005481064 0.02251547 0.02807837 0.005470931 0.02251875 0.029284 0.005500137 0.02314823 0.002192437 0.005422413 0.006195306 0.005724489 0.005366981 0.008780837 0.01063185 0.005332112 0.01216351 0.01564246 0.005341529 0.01538908 0.0210095 0.005372345 0.01860588 0.02647286 0.005423545 0.02165901 0.02807897 0.005444705 0.02251833 0.0378189 0.005705654 0.02738398 0.04245889 0.005987167 0.02945411 0.04013663 0.005869269 0.02842658 0.04246062 0.006020605 0.0294438 0.04129809 0.005944192 0.02893722 0.04188019 0.005985856 0.0291875 0.03949248 0.005833446 0.02813583 0.03897792 0.005804061 0.02790421 0.03781998 0.005736827 0.02737873 0.002178788 0.005424976 0.006187498 0.005724608 0.005376815 0.008780956 0.01063156 0.00534147 0.01216399 0.0156418 0.005350172 0.01539009 0.02100861 0.005380451 0.01860731 0.02647197 0.005431711 0.0216605 0.02807807 0.00545305 0.02251982 0.03781831 0.005715966 0.02738428 0.04245835 0.005998611 0.02945327 0.04693359 0.006477892 0.03113788 0.04194837 0.005992293 0.02921438 0.04246395 0.006030797 0.02943402 0.04246467 0.006032168 0.02943211 0.04693782 0.006509125 0.03111016 0.04546117 0.006320774 0.0306096 0.002165734 0.005427598 0.006179928 0.005725741 0.005386352 0.008779466 0.01063215 0.005350649 0.0121631 0.01564192 0.005358815 0.01538985 0.02100843 0.005388617 0.01860749 0.02647167 0.005439996 0.02166086 0.02807784 0.005461454 0.02252006 0.03781861 0.005726039 0.02738273 0.04245889 0.006009459 0.02945005 0.04693365 0.006489336 0.03113257 0.04884594 0.006795167 0.03163808 0.04694378 0.006428539 0.03112721 0.04789417 0.006652832 0.03138691 0.04741209 0.00657916 0.03124988 0.04702502 0.006522476 0.03113436 0.0469349 0.006500303 0.03112339 0.04884618 0.006805956 0.03162753 0.05101776 0.007236719 0.03179663 0.04884821 0.006814718 0.03160995 0.04884779 0.006813883 0.03161269 0.04991346 0.007016777 0.03176766 0.04885393 0.006744861 0.03164333 0.05103164 0.007174968 0.03181755 0.05102914 0.007189452 0.03182196 0.04992747 0.006934762 0.0317924 0.05103379 0.007159709 0.03180634 0.05176466 0.007381379 0.03166288 0.05101525 0.007242143 0.03177887 0.05194383 0.007410228 0.03161424 0.05246925 0.007476091 0.03144001 0.05102068 0.007227301 0.03180962 0.04884672 0.006783545 0.0316444 0.0469346 0.006465375 0.03114026 0.04246038 0.005976378 0.02945262 0.0524832 0.007442831 0.03146606 0.05248522 0.007428944 0.03146678 0.05248582 0.007413744 0.03146332 0.05178546 0.007300019 0.03169322 0.05248403 0.007397055 0.03145295 0.05197602 0.007415354 0.03160113 0.05211937 0.007436215 0.03155767 0.0524612 0.007480025 0.03141987 0.05246233 0.007480025 0.03142291 0.05276858 0.0075109 0.03127515 0.05508112 0.007467567 0.02973145 0.05414837 0.00755757 0.03048247 0.05415928 0.007556021 0.03050142 0.05371683 0.007558465 0.03074681 0.05383348 0.007559418 0.0306732 0.05329155 0.00754553 0.03099495 0.05101495 0.007242441 0.03177565 0.05047035 0.007131516 0.0317924 0.04991412 0.007017493 0.0317648 0.05417317 0.007537961 0.03052592 0.05417644 0.007524311 0.03053182 0.0541771 0.007509708 0.03053313 0.05417507 0.007493317 0.03052967 0.05416935 0.007476329 0.03051984 0.05546265 0.007316887 0.02914667 0.05509364 0.007467389 0.02975195 0.05416762 0.00754863 0.03051614 0.05247521 0.007467389 0.03145289 0.05247968 0.007456302 0.03146123 0.05102354 0.007216036 0.03181767 0.05102652 0.007202804 0.03182196 0.04884839 0.00677061 0.03164756 0.04885077 0.006758093 0.03164726 0.04693645 0.006453335 0.03113961 0.04693943 0.006440758 0.03113561 0.042463 0.005965292 0.0294485 0.04246699 0.005954444 0.02944093 0.05510312 0.007460713 0.02976816 0.05510908 0.007450282 0.02977907 0.05511224 0.007436454 0.02978575 0.0551123 0.007421433 0.02978742 0.05510902 0.007404327 0.02978378 0.05510145 0.007386624 0.02977317 0.05547511 0.007309973 0.02913546 0.05548578 0.007301688 0.02914679 0.05549234 0.007290244 0.02915525 0.05549561 0.007275998 0.02916151 0.05549526 0.007261216 0.02916461 0.05549108 0.007245123 0.02916467 0.05549335 0.007234156 0.02914953 0.0555619 0.007199168 0.02876675 0.05560582 0.007064938 0.0284053 0.05558949 0.007071673 0.02840572 0.05558484 0.00713694 0.02858638 0.05558365 0.00711447 0.02880066 0.05561077 0.006984412 0.02843552 0.05562287 0.006997168 0.02842831 0.05528587 0.007404804 0.02945613 0.05558419 0.007125556 0.02855348 0.05558711 0.007083415 0.02843701 0.05555796 0.006967246 0.02813059 0.05545103 0.006820082 0.02776861 0.05546337 0.006832897 0.02779912 0.05543059 0.006795763 0.02771139 0.05549669 0.006866335 0.02787989 0.05544823 0.006784796 0.02769875 0.05546915 0.00675565 0.02769207 0.05546128 0.006770431 0.02769267 0.05557507 0.006914198 0.02804309 0.05556237 0.006927251 0.02804541 0.05554521 0.006936252 0.0280525 0.05562883 0.00702542 0.02841633 0.05562812 0.007011294 0.02842193 0.0555855 0.006871163 0.02805566 0.0555799 0.00685805 0.02806514 0.05556821 0.006847977 0.02807724 0.05414646 0.007557094 0.03047919 0.05514168 0.007451415 0.0296545 0.05561798 0.007053494 0.02840751 0.05562531 0.007040321 0.0284112 0.05547279 0.006740272 0.02769601 0.05527555 0.006587922 0.02734953 0.05547183 0.006726741 0.0277037 0.05527454 0.00657463 0.02735793 0.05546593 0.006714522 0.0277158 0.05500078 0.006415069 0.02705729 0.05545383 0.006706058 0.02773237 0.0549888 0.006408214 0.02707785 0.05360722 0.005856692 0.02596855 0.0535975 0.005848407 0.02598369 0.0523318 0.005318522 0.02485084 0.05232262 0.005310118 0.02486485 0.05025279 0.004477024 0.02302891 0.05024367 0.004468977 0.02304327 0.0481069 0.003688275 0.02124702 0.04809778 0.003680467 0.02126157 0.04536247 0.002873063 0.01908469 0.04578518 0.003002762 0.01940762 0.0450049 0.002761363 0.01880675 0.04809868 0.003756821 0.02122753 0.04183548 0.001858174 0.01644116 0.05024278 0.004545629 0.02300959 0.04655915 0.003251314 0.02001303 0.04501295 0.002672553 0.01883155 0.04182994 0.001782715 0.01647579 0.04183888 0.001789569 0.01646095 0.04477518 0.002694249 0.01863509 0.04182511 0.001871645 0.01645082 0.04182314 0.001873314 0.0164529 0.03878331 0.001161515 0.0143395 0.03844696 0.001093506 0.01411771 0.03566223 4.84816e-4 0.01233893 0.03801053 0.001002788 0.01382464 0.03566324 5.7383e-4 0.01231378 0.03289252 1.71139e-4 0.01063495 0.03244644 1.13807e-4 0.01037096 0.03222817 8.98374e-5 0.01024734 0.03081065 -6.67355e-5 0.00943607 0.02916473 -2.30058e-4 0.008514463 0.03245425 9.91741e-5 0.01036059 0.03567194 5.59575e-4 0.0123037 0.03723293 8.51833e-4 0.01331526 0.03567081 4.90957e-4 0.01232361 0.03245079 3.05995e-5 0.01038074 0.03244239 2.48776e-5 0.01039642 0.02915912 -2.98559e-4 0.008534848 0.0291509 -3.03902e-4 0.008550763 0.02255183 -5.7977e-4 0.005200922 0.02505564 -4.45081e-4 0.00639975 0.02483564 -4.50091e-4 0.006293892 0.02588266 -4.13835e-4 0.006813466 0.02658128 -3.79565e-4 0.00717163 0.02915775 -2.15114e-4 0.008525073 0.02256107 -5.11544e-4 0.00518018 0.02255576 -4.96192e-4 0.005191266 0.02422541 -4.69154e-4 0.005991518 0.0549966 0.006470501 0.0270332 0.05360412 0.00591129 0.02594548 0.05232954 0.005372822 0.02482789 0.05025166 0.004530966 0.02300578 0.04810696 0.003741919 0.02122372 0.04184228 0.001842677 0.01643723 0.03567725 5.43559e-4 0.01229947 0.03245878 8.29163e-5 0.01035624 0.02916842 -2.46515e-4 0.008509933 0.02256345 -5.28249e-4 0.005175411 0.05500423 0.006455004 0.02703088 0.0536102 0.005896627 0.02594566 0.05233502 0.005358338 0.02482867 0.05025672 0.004516363 0.02300643 0.04811161 0.003727257 0.02122443 0.04184561 0.001827716 0.01643782 0.03567939 5.28411e-4 0.01230001 0.03246033 6.76614e-5 0.01035672 0.02916944 -2.61857e-4 0.00851041 0.02256339 -5.43677e-4 0.005175828 0.05500775 0.006439507 0.02703434 0.05361288 0.005881607 0.02594989 0.0523374 0.005343437 0.02483302 0.05025875 0.004501521 0.02301079 0.04811322 0.003712415 0.02122879 0.04184621 0.001812934 0.01644229 0.03567904 5.13595e-4 0.01230448 0.03245943 5.28542e-5 0.01036131 0.02916806 -2.76651e-4 0.008515059 0.02256131 -5.58416e-4 0.005180537 0.05500668 0.006426334 0.02704292 0.05361199 0.005868494 0.02595734 0.05233639 0.005330383 0.02484023 0.0502575 0.004488587 0.02301812 0.04811173 0.0036996 0.02123618 0.04184406 0.001800417 0.0164498 0.03567624 5.01299e-4 0.01231217 0.03245639 4.06832e-5 0.01036912 0.02916473 -2.88708e-4 0.008522987 0.02255755 -5.70278e-4 0.005188703 0.02003157 -4.83634e-4 0.004033684 0.02255463 -4.94134e-4 0.00519365 0.01531922 -3.31177e-4 0.001993775 0.01531547 -3.15514e-4 0.00200504 0.01714003 -4.03282e-4 0.002768278 0.01672375 -3.83536e-4 0.002594828 0.01895582 -4.63479e-4 0.003553152 0.02254414 -5.84555e-4 0.005217313 0.01894199 -5.51464e-4 0.003579497 0.01529949 -4.02945e-4 0.002032101 0.006404101 4.61955e-4 -0.001409769 0.01083046 9.11586e-6 2.28366e-4 0.0132901 -1.85835e-4 0.001188099 0.01530671 -3.98657e-4 0.002015113 0.01531237 -3.89551e-4 0.002002596 0.01531642 -3.77956e-4 0.001994252 0.01531922 -3.63386e-4 0.001989424 0.0153203 -3.47997e-4 0.001988947 0.0294426 0.004363834 0.01657253 0.03049552 0.003178417 0.01476132 0.02400863 0.0026322 0.0108999 0.03602522 0.005996763 0.02367401 0.03632557 0.005534708 0.02221214 0.0285198 0.005274951 0.01815837 0.006461083 0.002767086 0.001714169 0.006104826 0.003608942 0.002830624 0.009723186 0.004000604 0.005791962 0.004466235 0.005294978 0.005148887 0.004194915 0.005439221 0.005375385 0.007947027 0.005448222 0.00804001 0.006787836 0.005506038 0.00934571 0.006916761 0.005593597 0.009220659 0.002650022 0.005674421 0.006136655 0.05312508 0.006344258 0.026798 0.00654149 9.42446e-4 -7.4304e-4 0.00661236 0.001928031 5.94708e-4 0.01157039 0.001948297 0.003421068 0.01772338 0.002176463 0.00706011 0.03165906 0.001760005 0.01275855 0.0380783 0.002583861 0.01656651 0.0443893 0.003720819 0.02043163 0.05030697 0.005152344 0.02417218 0.05473911 0.007365643 0.02937352 0.05319261 0.006690025 0.02761137 0.05329734 0.006984174 0.02839118 0.05357784 0.007400393 0.02979487 0.05242049 0.007355272 0.03007757 0.05150234 0.007345616 0.03108704 0.05027031 0.007146656 0.03112083 0.04885947 0.006916046 0.03092932 0.04719603 0.00668776 0.03050291 0.04074192 0.006189882 0.02803713 0.0452643 0.006483972 0.02985626 0.0408076 0.006065666 0.02844446 0.03575581 0.005877315 0.02613031 0.02657818 0.005749046 0.02147775 0.01912266 0.00567758 0.0172308 0.01902067 0.005548119 0.01731705 0.01242566 0.005502581 0.01318573 0.00240612 0.005602002 0.006170868 0.003570675 0.005660712 0.00579226 0.00721383 0.005668342 0.008904814 0.003104805 0.005717694 0.006008148 0.002873897 0.005709111 0.006084084 0.004889905 0.00501275 0.004733622 0.03734362 0.003801047 0.0186181 0.03676289 0.004792273 0.02051222 0.04421353 0.004655122 0.02234292 0.04058349 0.005063414 0.02243214 0.04423385 0.005407333 0.02417832 0.04738724 0.005185902 0.02400946 0.04753714 0.00582695 0.0256474 0.05033278 0.005762875 0.02549225 0.05046838 0.006281018 0.02678388 0.0481528 0.006669282 0.02862125 0.04852139 0.006863772 0.02987492 0.04961675 0.006853103 0.02897107 0.04995602 0.007061004 0.03013128 0.05123287 0.007234692 0.03019505 0.05094873 0.007021188 0.02916425 0.05200558 0.006862342 0.02825576 0.05068349 0.006702542 0.02801805 0.0404846 0.005710542 0.02417832 0.04050493 0.0061149 0.02571672 0.04439973 0.005971729 0.02589243 0.04466319 0.006337404 0.02743566 0.04780799 0.006323754 0.02719938 0.005787193 0.004103243 0.003487586 0.008808016 0.004844963 0.006961047 0.01550108 0.004379332 0.009831488 0.01449185 0.005165457 0.01103699 0.02173501 0.004874825 0.01405334 0.02078193 0.005568623 0.01530933 0.0277515 0.005860626 0.01947677 0.0358473 0.006164014 0.02486801 0.04060608 0.006270885 0.02701056 0.0449711 0.006503939 0.02876704 0.04686433 0.006671905 0.02941632 0.01319962 0.005747675 0.01247805 0.01359283 0.005647957 0.01205921 0.01965004 0.005935013 0.01668918 0.01998424 0.005909025 0.01630151 0.02691763 0.006067454 0.02090233 0.02715247 0.006089389 0.02050179 0.01255482 0.005611062 0.01308554 0.01285213 0.005738079 0.0128225 0.01936239 0.005858659 0.0169996 0.0267263 0.005953669 0.02122735 0.03576743 0.00604248 0.02578133 -0.002938926 0.006249964 0.005430698 -0.004543066 0.006249964 0.004182159 -0.004579007 0.006237208 0.0042153 0.004543066 0.006249964 0.004182159 0.002938926 0.006249964 0.005430698 0.002962231 0.006237208 0.005473673 0.001024365 0.006237208 0.00613898 -0.001032829 0.006149947 0.006189405 0.001030087 0.006204783 0.006173253 0.002978742 0.006204783 0.00550431 0.003008723 0.006192147 0.005495965 0.003853857 0.00616014 -0.004951417 0.002884805 0.006161391 0.005572021 0.00103271 0.00616014 0.006188869 -0.006237268 0.006204783 5.16835e-4 -0.006253004 0.00616014 5.18143e-4 -0.00625354 0.006149947 5.18185e-4 0 0.00616014 -0.006274461 0.005252778 0.00616014 -0.003431797 0.006082475 0.00616014 -0.001540243 0.006253004 0.00616014 5.18143e-4 3.25275e-4 0.006149947 0.006266534 0.001032829 0.006149947 0.006189405 0.002380192 0.006149947 0.005806028 -0.00423932 0.006149947 0.004626393 -0.004077494 0.006149947 0.004769623 -0.00298655 0.006149947 0.005518674 -0.004616618 0.006149947 0.00424993 -0.00461626 0.00616014 0.004249572 -0.004604578 0.006204783 0.004238843 -0.005745947 0.00616014 0.002520382 -0.005746424 0.006149947 0.00252062 -0.005695223 0.006149947 0.002634346 -0.006082475 0.00616014 -0.001540243 -0.005252778 0.00616014 -0.003431797 -0.003853857 0.00616014 -0.004951417 -0.002037286 0.00616014 -0.005934476 0.003844082 0.006204783 -0.0049389 0.005239486 0.006204783 -0.003423154 0.006067097 0.006204783 -0.001536369 0.006237268 0.006204783 5.16835e-4 -0.005699634 0.006237208 0.002500057 -0.005731463 0.006204783 0.002514064 -0.006067097 0.006204783 -0.001536369 -0.005239486 0.006204783 -0.003423154 -0.003844082 0.006204783 -0.0049389 -0.00203216 0.006204783 -0.005919516 0 0.006204783 -0.006258606 0.003822743 0.006237208 -0.004911482 0.005210399 0.006237208 -0.00340408 0.00603342 0.006237208 -0.001527845 0.006202578 0.006237208 5.13963e-4 -0.006202578 0.006237208 5.13963e-4 -0.00603342 0.006237208 -0.001527845 -0.005210399 0.006237208 -0.00340408 -0.003822743 0.006237208 -0.004911482 -0.002020835 0.006237208 -0.005886614 0 0.006237208 -0.006223857 0.001016318 0.006249964 0.00609076 -0.001016318 0.006249964 0.00609076 -0.002028882 0.006149947 0.005937874 -0.005654871 0.006249964 0.002480447 -0.006153881 0.006249964 5.09927e-4 -0.006174981 0.006249964 0 -0.005986034 0.006249964 -0.001515865 -0.005169451 0.006249964 -0.003377377 -0.003792762 0.006249964 -0.004872918 -0.002004981 0.006249964 -0.00584042 0 0.006249964 -0.006174981 0.002004981 0.006249964 -0.00584042 0.003792762 0.006249964 -0.004872918 0.005169451 0.006249964 -0.003377377 0.005986034 0.006249964 -0.001515865 0.006153881 0.006249964 5.09927e-4 0.005654871 0.006249964 0.002480447 0.002095758 0.006029546 0.005914509 -0.001032829 10e-5 0.006189405 3.25275e-4 10e-5 0.006266534 0.002676069 0.004481732 0.00567609 0.001922965 0.005000114 0.005973041 0.001032829 10e-5 0.006189405 0.001742184 0.00517857 0.006028234 0.001660585 0.005396723 0.006051242 0.001685321 0.005626916 0.006044328 0.001835048 0.005844473 0.006000638 0.002670943 10e-5 0.005678117 0.00298655 10e-5 0.005518674 0.003710329 0.003665924 0.005060076 0.003995418 0.003419399 0.00483787 0.004564464 10e-5 0.004305899 0.004616618 10e-5 0.00424993 0.004927158 0.002532243 0.003886044 0.004931688 10e-5 0.003879904 0.005525946 0.001851439 0.002972126 0.005641758 0.001700818 0.002744793 0.006019413 0.001115262 0.001764059 0.005746424 10e-5 0.00252062 0.006033539 0.001088321 0.001715004 0.006041467 10e-5 0.001695811 0.006232857 5.79202e-4 7.14238e-4 0.006245851 5.21813e-4 5.91884e-4 0.00625354 10e-5 5.18185e-4 0.006263554 10e-5 -3.78451e-4 0.001025378 1.63529e-5 0.006144821 0.002965033 1.63529e-5 0.005478918 0.00298047 5.11288e-5 0.005507469 0.002022802 1.63529e-5 -0.005892217 0 1.63529e-5 -0.006229758 0 5.11288e-5 -0.006262242 0.006240844 5.11288e-5 5.17132e-4 -0.003846347 5.11288e-5 -0.004941761 -0.005242526 5.11288e-5 -0.003425121 -0.001030683 5.11288e-5 0.006176829 -0.00298047 5.11288e-5 0.005507469 0.006070613 5.11288e-5 -0.001537263 0.006080389 7.81947e-5 -0.001540541 0.00608319 7.65977e-5 -0.001527905 0.006119012 6.2089e-5 -0.001356065 0.006191551 6.33959e-5 -9.76149e-4 0.006236493 8.07981e-5 -6.76805e-4 0.005654871 0 0.002480447 0.006164014 5.16602e-7 5.10766e-4 0.006153881 0 5.09927e-4 0.005995869 5.16602e-7 -0.001518309 0.005986034 0 -0.001515865 0.005177974 5.16602e-7 -0.003382921 0.005169451 0 -0.003377377 0.003798961 5.16602e-7 -0.004880905 0.003792762 0 -0.004872918 0.002008259 5.16602e-7 -0.005850017 0.002004981 0 -0.00584042 0 5.16602e-7 -0.006185114 0 0 -0.006174981 0.004543066 0 0.004182159 0.004550516 5.16602e-7 0.004189074 0.002938926 0 0.005430698 0.002943754 5.16602e-7 0.005439639 0.001016318 0 0.00609076 0.001017987 5.16602e-7 0.006100773 -0.001016318 0 0.00609076 -0.001017987 5.16602e-7 0.006100773 -0.002938926 0 0.005430698 -0.002943754 5.16602e-7 0.005439639 -0.004543066 0 0.004182159 -0.004550516 5.16602e-7 0.004189074 -0.005654871 0 0.002480447 -0.005664169 5.16602e-7 0.0024845 -0.006153881 0 5.09927e-4 -0.006174981 0 0 -0.005986034 0 -0.001515865 -0.005169451 0 -0.003377377 -0.005177974 5.16602e-7 -0.003382921 -0.003792762 0 -0.004872918 -0.002004981 0 -0.00584042 -0.002008259 5.16602e-7 -0.005850017 0.002033293 5.11288e-5 -0.005922913 0.003826379 1.63529e-5 -0.004916131 0.003846347 5.11288e-5 -0.004941761 0.005215346 1.63529e-5 -0.003407359 0.005242526 5.11288e-5 -0.003425121 0.006039142 1.63529e-5 -0.001529276 0.006208479 1.63529e-5 5.14453e-4 0.00460726 5.11288e-5 0.004241287 -0.005734741 5.11288e-5 0.002515494 -0.005705058 1.63529e-5 0.002502441 -0.00460726 5.11288e-5 0.004241287 -0.004583358 1.63529e-5 0.004219293 -0.002965033 1.63529e-5 0.005478918 -0.001025378 1.63529e-5 0.006144821 0.001030683 5.11288e-5 0.006176829 -0.003798961 5.16602e-7 -0.004880905 -0.005215346 1.63529e-5 -0.003407359 -0.003826379 1.63529e-5 -0.004916131 -0.002033293 5.11288e-5 -0.005922913 -0.002022802 1.63529e-5 -0.005892217 0.004583358 1.63529e-5 0.004219293 0.006262004 1.74229e-4 -7.1326e-4 0.006448566 3.91871e-4 -8.20594e-4 0.006415486 3.15903e-4 -0.001118242 0.006652891 5.58227e-4 -5.741e-4 0.006201684 9.06369e-5 -9.87531e-4 0.006277859 2.12408e-4 -0.001047074 0.006307184 2.59565e-4 -7.50416e-4 0.006332337 2.64077e-4 -0.001078605 0.006274223 2.05922e-4 -4.18883e-4 0.006310105 3.06348e-4 -4.58774e-4 0.006316721 3.19075e-4 -4.63955e-4 0.006669282 5.61087e-4 -5.76166e-4 0.006533384 3.52343e-4 -0.001162886 0.006586194 3.58084e-4 -0.001179575 0.006449341 4.70601e-4 -5.28888e-4 0.006365537 2.86449e-4 -0.001212835 0.006105065 1.99858e-4 -0.001559615 0.006366014 3.36728e-4 -0.001379072 0.006437122 3.32902e-4 -0.001315116 0.006306171 2.73492e-4 -0.00131762 0.006512045 3.38905e-4 -0.001243472 0.006550014 3.4715e-4 -0.001209259 0.006147682 1.83389e-4 -0.001462161 0.006244361 2.72583e-4 -0.001411139 0.006212472 2.96698e-4 -0.001469433 0.006293892 3.43397e-4 -0.001434087 0.006197392 1.80447e-4 -0.001331746 0.001996815 0.00512439 0.005971252 0.00217688 0.005351483 0.006108045 0.002216756 0.005387127 0.006165444 0.002106726 0.005408883 0.006126344 0.001772403 0.005413115 0.006034255 0.002104759 0.005553066 0.006091833 0.002011299 0.005509793 0.006078958 0.002084791 0.005570471 0.006073713 0.001907646 0.005550801 0.006039381 0.001991391 0.005660891 0.00601381 0.001922845 0.005736291 0.00599426 0.00213015 0.00530225 0.006054341 0.001885175 0.005428671 0.006043076 0.001993119 0.0054425 0.006077706 0.002060294 0.005382299 0.006088614 0.001959681 0.005318701 0.00603491 0.002090871 0.00525546 0.006019413 0.006145358 3.58217e-4 -0.001559793 0.006126165 6.88083e-4 -0.001498341 0.006131708 4.60485e-4 -0.001581609 0.006220459 4.48926e-4 -0.001507282 0.006242215 3.91053e-4 -0.001488447 0.006062805 4.73513e-4 -0.001674473 0.006203711 5.90781e-4 -0.001449227 0.006145954 5.52902e-4 -0.001543402 0.006282508 5.26314e-4 -0.001423835 0.006236314 4.98462e-4 -0.001482129 0.003359854 0.006064414 0.005309104 0.003359377 0.005955994 0.005349159 0.004218518 0.0055691 0.004703164 0.005530953 0.004232168 0.003250539 0.004964768 0.004871428 0.00408405 0.005063891 0.004778623 0.004228353 0.006471633 0.001984238 5.46462e-4 0.006360948 0.002073168 4.75244e-4 0.005952119 0.003536999 0.002359688 0.006275296 0.002248585 3.41002e-4 0.005889773 0.003733754 0.002189576 0.006292045 0.002186417 3.87944e-4 0.004337131 0.005319833 0.004992306 0.004249334 0.005415976 0.00483489 0.003375768 0.005848169 0.005415558 0.003451585 0.005704402 0.00558871 0.003468334 0.005690157 0.00562036 0.005637586 0.004140734 0.003377437 0.006062924 0.003446459 0.00246787 0.0049268 0.005013942 0.003951728 0.005483508 0.004365622 0.003125011 0.005895614 0.003662765 0.002244949 0.002726376 0.005851805 0.00581187 0.002498686 0.005840837 0.005882143 0.002543389 0.005771398 0.005943417 0.002797365 0.005753815 0.00593537 0.002574563 0.005733132 0.005993127 0.00302428 0.00575304 0.005852222 0.002955377 0.005847096 0.005716741 0.002907037 0.005989432 0.005619585 0.002431333 0.005985677 0.005817532 0.002457022 0.005923688 0.005837559 0.002248048 0.005765199 0.005961835 0.002330303 0.005665957 0.00605005 0.006037533 0.002114832 0.002688765 0.004045724 0.004032433 0.005125582 0.00375241 0.003739535 0.005038738 0.00515443 0.002411961 0.003596365 0.005204558 0.002492427 0.003574192 0.00380212 0.003810822 0.005030333 0.005339086 0.002632021 0.003569602 0.003918647 0.003938257 0.005052983 0.004831492 0.003368258 0.004432797 0.005501687 0.002725601 0.003617882 0.006631672 0.00102359 5.65177e-4 0.006432414 9.33942e-4 5.81704e-4 0.006290316 7.7536e-4 6.34912e-4 0.006087899 0.00130093 0.001689374 0.006420373 0.001544952 0.001662075 0.005859732 0.002021968 0.002658009 0.006230056 0.001453459 0.001653075 0.005720138 0.001875758 0.002677857 -0.003095388 0 7.06504e-4 -0.00317496 0 0 -0.003095388 0 -7.06504e-4 -0.002482295 0 -0.001979529 0 0 0.00317496 -0.001377522 0 0.002860546 -0.002482295 0 0.001979529 0.003095388 0 7.06504e-4 0.002482295 0 0.001979529 0.001377522 0 0.002860546 0.001377522 0 -0.002860546 0.002482295 0 -0.001979529 0.003095388 0 -7.06504e-4 -0.001377522 0 -0.002860546 0 0 -0.00317496 -3.76027e-4 10e-5 0.003051877 0 10e-5 0.003074944 0 5.9133e-5 0.003083705 -0.001722216 10e-5 0.002547442 -0.00133419 10e-5 0.002770423 -0.001337945 5.9133e-5 0.002778291 -0.002707719 10e-5 0.001457273 -0.002404093 10e-5 0.001917183 -0.002410948 5.91318e-5 0.001922667 0.002174317 10e-5 0.002174317 0.002404093 10e-5 0.001917183 0.002410948 5.9133e-5 0.001922667 0.001116514 10e-5 0.002865076 0.00133419 10e-5 0.002770423 0.001337945 5.9133e-5 0.002778291 -0.001371324 1.02551e-6 0.002847671 -0.002471089 1.02551e-6 0.001970648 -0.002436995 1.84913e-5 0.001943409 -0.00308144 1.02551e-6 -7.03325e-4 -0.001371324 1.02551e-6 -0.002847671 0 1.02551e-6 -0.003160715 0.001371324 1.02551e-6 -0.002847671 0.002471089 1.02551e-6 -0.001970648 -0.002471089 1.02551e-6 -0.001970648 -0.00308144 1.02551e-6 7.03325e-4 -0.001352429 1.84913e-5 -0.002808332 0 1.84913e-5 -0.003117024 0.001352429 1.84913e-5 -0.002808332 0.002436995 1.84913e-5 -0.001943409 0.003038883 1.84913e-5 -6.93612e-4 -0.001338839 5.48148e-5 -0.002780199 0 5.48148e-5 -0.003085732 0.001338839 5.48148e-5 -0.002780199 0.002412557 5.48148e-5 -0.001923918 0.003008365 5.48148e-5 -6.86653e-4 0.003008365 5.48148e-5 6.86653e-4 -0.002436995 1.84913e-5 -0.001943409 -0.003038883 1.84913e-5 -6.93612e-4 -0.002412557 5.48148e-5 -0.001923918 -0.003006398 5.91318e-5 -6.86202e-4 -0.003006398 5.906e-5 6.86202e-4 -0.003038883 1.84913e-5 6.93612e-4 0.00308144 1.02551e-6 7.03325e-4 0.002471089 1.02551e-6 0.001970648 0.002436995 1.84913e-5 0.001943409 0.001352429 1.84913e-5 0.002808332 0.00308144 1.02551e-6 -7.03325e-4 0.003038883 1.84913e-5 6.93612e-4 0.00293827 10e-5 9.06595e-4 0.002997875 10e-5 6.84252e-4 0.003025591 10e-5 -5.48748e-4 0.002997875 10e-5 -6.84252e-4 0.002448976 10e-5 -0.001859545 0.00133419 10e-5 -0.002770423 0.001318871 10e-5 -0.002777755 0 10e-5 -0.003074944 -0.00133419 10e-5 -0.002770423 -0.001457691 10e-5 -0.002707481 -0.003051936 10e-5 -3.75661e-4 -0.003074944 10e-5 0 -0.002404093 10e-5 -0.001917183 -0.002547681 10e-5 -0.001721858 -0.002997875 10e-5 -6.84252e-4 -0.002997875 10e-5 6.84252e-4 0 1.02551e-6 0.003160715 -0.001352429 1.84913e-5 0.002808332 0.001371324 1.02551e-6 0.002847671 0 1.84913e-5 0.003117024 -0.00317496 0.006249964 0 -0.003095388 0.006249964 7.06504e-4 -0.002482295 0.006249964 0.001979529 -0.001377522 0.006249964 0.002860546 -0.001377522 0.006249964 -0.002860546 -0.002482295 0.006249964 -0.001979529 -0.003095388 0.006249964 -7.06504e-4 0.002482295 0.006249964 -0.001979529 0.001377522 0.006249964 -0.002860546 0 0.006249964 -0.00317496 0.002482295 0.006249964 0.001979529 0.003095388 0.006249964 7.06504e-4 0.003095388 0.006249964 -7.06504e-4 0 0.006249964 0.00317496 0.001377522 0.006249964 0.002860546 -0.003051936 0.006149947 -3.75661e-4 -0.003074944 0.006149947 0 -0.002997875 0.006149947 -6.84252e-4 -0.002547681 0.006149947 -0.001721858 -0.002404093 0.006149947 -0.001917183 -0.001457691 0.006149947 -0.002707481 -0.00133419 0.006149947 -0.002770423 0 0.006149947 -0.003074944 0.001318871 0.006149947 -0.002777755 0.002448976 0.006149947 -0.001859545 0.002997875 0.006149947 -6.84252e-4 0.003025591 0.006149947 -5.48748e-4 0.002997875 0.006149947 6.84252e-4 0.00293827 0.006149947 9.06595e-4 0.002404093 0.006149947 0.001917183 0.002174317 0.006149947 0.002174317 0.00133419 0.006149947 0.002770423 0.001116514 0.006149947 0.002865076 0 0.006149947 0.003074944 -3.76027e-4 0.006149947 0.003051877 -0.00133419 0.006149947 0.002770423 -0.001722216 0.006149947 0.002547442 -0.002404093 0.006149947 0.001917183 -0.002707719 0.006149947 0.001457273 -0.002997875 0.006149947 6.84252e-4 0 0.006163299 0.003075838 0.001334547 0.006163299 0.002771258 0.002404808 0.006163299 0.001917779 0.002998769 0.006163299 6.84451e-4 0.002998769 0.006163477 -6.84472e-4 -0.002404808 0.006163299 -0.001917779 -0.001334547 0.006163299 -0.002771258 0 0.006164252 -0.003076016 0.001334607 0.006164252 -0.002771377 0.002425134 0.006182253 -0.001899182 -0.002998769 0.006163299 -6.84451e-4 -0.002998769 0.006163299 6.84451e-4 -0.002404808 0.006163299 0.001917779 -0.001334547 0.006163299 0.002771258 -0.001342177 0.006207883 0.002787113 -0.002418577 0.006207883 0.001928746 -0.003015875 0.006207883 6.88367e-4 -0.003015875 0.006207883 -6.88367e-4 -0.002418577 0.006207883 -0.001928746 -0.001342177 0.006207883 -0.002787113 0 0.006207883 -0.003093481 0.001342177 0.006207883 -0.002787113 0.002418577 0.006207883 -0.001928746 0.003015875 0.006207883 -6.88367e-4 0.003015875 0.006207883 6.88367e-4 0.002418577 0.006207883 0.001928746 0.001342177 0.006207883 0.002787113 0 0.006207883 0.003093481 0 0.006239175 0.00312978 0.001357972 0.006239175 0.002819836 0.002446949 0.006239175 0.001951396 0.00305134 0.006239175 6.96449e-4 0.00305134 0.006239175 -6.96449e-4 0.002446949 0.006239175 -0.001951396 0.001357972 0.006239175 -0.002819836 0 0.006239175 -0.00312978 -0.001357972 0.006239175 -0.002819836 -0.002446949 0.006239175 -0.001951396 -0.00305134 0.006239175 -6.96449e-4 -0.00305134 0.006239175 6.96449e-4 -0.002446949 0.006239175 0.001951396 -0.001357972 0.006239175 0.002819836 + + + + + + + + + + 0.2698697 -0.9572368 -0.1042507 0.1707469 -0.9435898 -0.283697 0.2051935 -0.9068329 -0.3681707 0.2174224 -0.9020077 -0.372974 0.4493614 -0.8933352 -0.00514853 0.4239347 -0.9056252 0.01105844 0.415133 -0.909653 0.0140022 0.4111833 -0.9114285 0.01505607 0.5611174 -0.8246684 0.07120001 0.5139146 -0.8568271 0.04170411 0.5521222 -0.8335787 0.01754403 0.5186415 -0.8544924 0.02922075 0.5054214 -0.8621143 0.03617149 0.5091544 -0.8606732 0.001883387 0.4809167 -0.8766502 0.01426482 0.5051729 -0.8626567 -0.02497971 0.4604204 -0.8864746 -0.04664552 0.4728734 -0.8809102 -0.01970183 0.4025974 -0.9109037 -0.09038716 0.4339935 -0.8986832 -0.06339102 0.4282642 -0.902804 -0.03917706 0.4436479 -0.8922266 -0.08431035 0.363789 -0.922079 -0.1320151 0.3519397 -0.9278151 -0.1236842 0.4045432 -0.8921537 -0.2010137 0.3456414 -0.9234133 -0.1668534 0.3396717 -0.9045763 -0.2576141 0.2815272 -0.9212305 -0.2684715 0.3284608 -0.9186505 -0.219533 0.214976 -0.9049144 -0.3673081 0.1815383 -0.9018461 -0.3920685 0.1820468 -0.8989616 -0.3984059 0.1841244 -0.9036514 -0.3866685 0.2118296 -0.8923289 -0.3985942 0.1858144 -0.9002114 -0.3938177 0.2113129 -0.9232926 -0.3207455 0.2077901 -0.9251056 -0.3178095 0.1962133 -0.9241096 -0.3279052 0.1895478 -0.9461389 -0.2624743 0.1859791 -0.9434589 -0.2744032 0.221826 -0.9338606 -0.2805309 0.2108803 -0.9577155 -0.1957307 0.2000632 -0.955216 -0.2180301 0.2394725 -0.9449439 -0.2230115 0.2155026 -0.948461 -0.2323369 0.1567311 -0.9512919 -0.2654791 0.2799884 -0.9442222 -0.1733526 0.3129708 -0.9432165 -0.1113201 0.3215478 -0.9390721 -0.121453 0.3130705 -0.9430267 -0.1126395 0.2589643 -0.9557082 -0.1398557 0.2536783 -0.9534147 -0.1632417 0.3531722 -0.9332408 -0.06581085 0.3574636 -0.9310534 -0.07320892 0.3471933 -0.9358972 -0.05960935 0.3160661 -0.9448149 -0.08618056 0.3133524 -0.9444072 -0.09952539 0.3519032 -0.934804 -0.04801851 0.3780269 -0.9254274 -0.02607625 0.3836936 -0.9228364 -0.03394567 0.3791075 -0.9252191 -0.01571857 0.4056987 -0.9140056 0.001601576 0.4088385 -0.9125981 -0.003992974 0.4051377 -0.9138182 0.02828264 0.4400222 -0.897987 -1.07492e-4 0.2132964 -0.9124135 -0.349294 0.1875312 -0.9210215 -0.3413966 0.1720924 -0.917267 -0.3591734 0.1578397 -0.9199729 -0.3587988 0.1557646 -0.9194144 -0.3611297 0.140308 -0.9209931 -0.3634358 0.1607934 -0.9263963 -0.3404929 0.1494204 -0.9272186 -0.3434231 0.1886468 -0.9357349 -0.2980144 0.2393592 -0.9148988 -0.3250651 0.2405575 -0.9185318 -0.3137381 0.1858451 -0.9360048 -0.2989261 0.2331222 -0.9423233 -0.2401686 0.2187153 -0.9522186 -0.2131747 0.2846555 -0.9399685 -0.1882303 0.3172926 -0.9384378 -0.1366013 0.3457005 -0.9292053 -0.1306475 0.3644077 -0.9270136 -0.08861613 0.3936865 -0.9156065 -0.08170497 0.4010164 -0.9145287 -0.05313295 0.4477856 -0.8929451 -0.04622972 0.4482164 -0.8939132 -0.004612565 0.4464371 -0.8948048 -0.004301667 0.2607268 -0.9505182 -0.1689282 0.1798558 -0.9677407 -0.1764366 0.2592689 -0.9550822 -0.1435187 0.1506685 -0.939801 -0.3067135 0.1474895 -0.950109 -0.2748454 0.1425506 -0.9508255 -0.2749732 0.159007 -0.953898 -0.25455 0.1048491 -0.9654693 -0.238487 0.1632524 -0.9620317 -0.2187322 0.1882274 -0.9655478 -0.1796887 0.09715706 -0.9485661 -0.3013021 0.1047891 -0.9502686 -0.2932729 0.1099823 -0.9601755 -0.2568403 0.09236323 -0.9592508 -0.2670337 0.1355736 -0.9659769 -0.2202464 0.1460592 -0.9654747 -0.2156972 0.1734868 -0.9681571 -0.1804834 0.2254855 -0.9618551 -0.1548907 0.2309057 -0.9621086 -0.1450164 0.2876216 -0.951156 -0.1121443 0.2902902 -0.9513165 -0.1035789 0.3589173 -0.9303385 -0.07515805 0.3592759 -0.9313212 -0.05968195 0.397466 -0.9167104 -0.04077762 0.3963113 -0.9177169 -0.02707493 0.4266701 -0.9043311 -0.01174604 0.4251116 -0.9051408 -4.68333e-4 0.4544442 -0.890676 0.01329463 0.4537853 -0.890919 0.01850152 0.4800386 -0.876684 0.03143465 0.2098609 -0.9278397 -0.3083375 0.1770323 -0.9360999 -0.3039354 0.170243 -0.9348587 -0.3115392 0.1280121 -0.9360324 -0.3278052 0.1449648 -0.9396735 -0.3098371 0.09676396 -0.9382538 -0.3321393 0.1316492 -0.9459396 -0.2964237 0.09000819 -0.9439602 -0.3175495 0.1362504 -0.9530644 -0.270378 0.1137753 -0.9524946 -0.2825057 0.1756069 -0.9603204 -0.2166726 0.192456 -0.9585107 -0.2102807 0.235575 -0.9594205 -0.1549733 0.283223 -0.9495499 -0.1346842 0.2954716 -0.9487465 -0.1121463 0.3445986 -0.9346314 -0.08784085 0.3484709 -0.9343001 -0.07517629 0.4109027 -0.9101155 -0.05337339 0.4111296 -0.9106573 -0.04093766 0.4469071 -0.8942492 -0.02434486 0.4458198 -0.8950365 -0.0124284 0.4747482 -0.8801192 0.002139985 0.4732651 -0.8808376 0.01205593 0.5136931 -0.85736 0.03245282 0.5124837 -0.8571861 0.05091685 -0.7200483 0.6909393 0.06429129 -0.7546761 0.6529289 0.0644049 0.07076156 -0.9626277 -0.2614206 -0.5739294 0.8083421 0.1311036 -0.2492055 -0.9153801 -0.3161898 -0.6144788 -0.6782584 -0.4029659 -0.4630131 -0.2486747 -0.8507525 -0.3200088 -0.5290256 -0.7859557 -0.5698015 -0.8028231 0.1755033 -0.3877538 -0.9087033 0.1546138 -0.3364182 -0.9300419 0.1478001 -0.1431201 -0.9824248 0.1198257 0.04623925 -0.9950491 0.08797413 -0.06061232 -0.9924684 0.1064545 0.1356378 -0.9881033 0.07248634 0.6631344 -0.744189 0.08022183 0.8782255 -0.4689399 0.09389048 -0.5387287 -0.8247011 0.1721612 -0.7284497 -0.6585103 0.1890111 -0.7988295 -0.5700101 0.1922497 -0.9817281 0.1045863 0.1589707 -0.9369822 -0.2925179 0.1910437 -0.9815528 0.1042383 0.1602761 -0.9853448 0.01342678 0.1700453 -0.9815106 0.1041444 0.1605954 -0.9307442 0.3424163 0.1283219 -0.9816482 0.1042923 0.159656 -0.9007722 0.4315524 0.04870593 -0.9936926 0.1100081 0.02175748 -0.9954379 0.0932095 0.02038431 -0.9800404 -0.1987283 -0.005293905 -0.9763851 -0.2159313 -0.006777942 -0.8723247 -0.4878911 -0.03181248 -0.8631485 -0.5038547 -0.03324359 -0.6681652 -0.7418686 -0.05644845 -0.6536755 -0.7545762 -0.05764639 -0.4475232 -0.8913561 -0.07216382 -0.4295982 -0.9000574 -0.07308983 0.9517014 0.3048562 0.03643459 0.9681317 0.2431262 0.0600897 0.1787974 -0.9837677 0.01525062 0.7034287 -0.7060031 0.08214515 0.753203 -0.6520715 0.08653414 0.7559306 -0.6524323 0.0538634 0.7358049 -0.6751595 0.05245023 0.7372446 -0.6751593 0.02510613 0.9273596 0.3733853 -0.02424371 0.4486434 0.8935446 0.01724207 0.6620889 -0.7494249 -8.44969e-4 -0.01177954 -0.9999038 -0.007334172 0.9793376 -0.2021644 0.005243122 0.8944097 0.4459083 0.03459906 0.8668913 0.4973579 0.03368479 0.8949506 0.4427732 0.05491179 0.5685682 0.8218429 0.03611862 0.9658558 0.2484882 0.07332259 0.6493328 0.7587156 0.05213129 0.9893419 0.1062702 0.09954488 0.1582504 0.9873822 0.005767703 -0.3533885 -0.935476 -0.001152098 0.9269821 0.3734462 -0.03524321 0.9989331 0.01092386 -0.04487079 0.7692071 0.6380227 -0.03532034 0.5788471 0.8152937 -0.01524448 0.7161183 -0.6975594 0.02419841 0.7167074 -0.6973735 8.4326e-4 0.2221055 0.9750051 0.005853235 0.6892135 -0.7242718 -0.02037566 0.6884813 -0.7240382 -0.04197847 0.7955318 0.6044377 -0.042243 0.7951148 0.6046465 -0.04685091 0.6746118 0.7375798 -0.02958083 0.6409025 0.7672005 -0.02544713 0.7244214 0.6882367 -0.03929352 -0.5350395 -0.8447959 0.007260859 -0.6113409 -0.7911044 0.02040249 0.911233 0.4048494 -0.07584005 0.9132347 0.4040685 -0.05226039 -0.3661729 -0.9305469 -1.42133e-5 0.9812953 0.1880444 -0.0412175 0.9820783 0.1876272 -0.01784223 0.6853099 -0.727966 -0.02039051 0.3220501 0.9467133 0.004202127 0.5303485 -0.8449605 -0.06908124 0.5276963 -0.8435624 -0.09969562 -0.5160073 -0.8565389 0.008811891 0.6087204 0.7931339 -0.01996111 0.5752615 0.8178848 -0.01177346 0.5413603 0.8407792 -0.004425406 0.5210217 0.8535419 0.001659512 0.608846 0.7930678 -0.01871752 0.7962657 0.6020122 -0.05951905 0.794704 0.6029503 -0.06997686 -0.4460247 -0.894786 -0.0204972 -0.3329799 -0.9415377 -0.05129671 0.6857992 -0.6852061 -0.2452999 0.6860164 0.7261045 -0.04640853 0.925144 0.3690581 -0.08890843 0.510925 -0.8483026 -0.1390631 0.5035601 -0.8435201 -0.1868185 0.9928545 0.0657131 0.09960776 0.6032959 -0.7953833 0.05830729 0.6045041 -0.7954072 0.0436142 0.2893488 -0.956981 0.0215618 0.9644932 -0.2617918 0.03490006 0.5775151 -0.816182 0.01797962 0.5779542 -0.8160688 -8.38134e-4 0.08475166 -0.9963836 -0.00608766 0.9354918 -0.3530085 -0.01550036 0.2016114 -0.9793627 -0.01420426 0.5474804 -0.8365028 -0.02298533 0.5467812 -0.8361125 -0.04411584 -0.3304403 -0.9438269 3.42034e-4 0.85977 0.5086477 -0.04553145 0.7012872 -0.7095676 -0.06863111 0.6987674 -0.7084782 -0.09890836 0.7659789 0.6412346 -0.04576903 0.7100092 -0.6906239 -0.1375706 0.7032526 -0.6865404 -0.1846571 -0.4095054 -0.9119749 -0.02464318 0.9038641 0.4019442 -0.1465284 0.4654625 0.8849911 0.01164698 0.4639366 0.8857838 0.01224833 -0.18342 -0.9755805 -0.12083 0.690833 0.7178859 -0.08596354 0.6967629 0.7144412 -0.06399351 0.466728 0.8842394 0.01689839 0.4981511 0.8670678 0.006238818 0.7028329 -0.5476731 -0.4539607 0.07475602 -0.9718574 -0.2233933 -0.1542351 -0.979667 -0.1283138 0.2184631 0.9756203 0.0209515 0.3538804 0.9348948 0.02721315 0.698575 0.6638594 -0.2669903 0.1569897 0.9790094 0.1299802 0.1698982 -0.9241514 -0.342168 0.5746528 0.8029147 -0.1584367 0.6075929 0.7884914 -0.09545838 0.3613759 0.9314863 0.04172283 0.3976015 0.9172848 0.02239984 0.1822623 0.9831345 -0.01507723 0.2486589 0.9629194 -0.1046675 0.106911 0.9941304 0.0165795 0.1558595 0.9859207 -0.06056684 0.09812039 0.9926446 -0.07091641 0.7558245 0.02703613 -0.654216 0.4473498 0.8744413 -0.1876984 0.3707929 0.8903155 -0.2642934 0.3528255 -0.7015866 -0.6191046 0.3419668 -0.7196435 -0.6042947 0.2455294 0.9139425 -0.3231476 0.08042132 0.995971 -0.03967785 0.8901793 -0.445633 0.0948258 0.8386226 0.5387921 0.08009642 0.9962571 0.05179011 0.06920766 0.8548913 -0.5106098 0.09186333 0.9684172 0.2297116 0.09695869 0.9711593 0.2288059 0.0670638 0.987433 0.142515 0.06830459 0.9890975 0.1424364 0.03738951 0.9978789 0.05333125 0.03732925 0.9985514 0.05347579 -0.005965113 0.9999629 0.00580573 -0.006363391 0.9983458 0.006493926 -0.05712741 0.979705 0.193669 -0.05167698 0.9761006 0.1951718 -0.09558105 0.9234337 0.3756046 -0.07868593 0.9154406 0.3801922 -0.1319947 0.8681919 0.4838632 -0.1100873 0.8399741 0.49954 -0.2119045 0.8072848 0.5594149 -0.1880065 0.7070933 0.600076 -0.3740695 0.6718935 0.66149 -0.3331518 0.4436206 0.7048558 -0.5535153 0.4314031 0.7288975 -0.5316013 0.8255183 -0.5570847 0.09042233 0.9941513 0.03589057 0.1018581 0.9969615 0.0356785 0.06924486 0.9967661 -0.04067289 0.06930452 0.9984942 -0.04041981 0.03709053 0.9923932 -0.1175664 0.03652417 0.9930768 -0.117244 -0.007233738 0.9866557 -0.162645 -0.007562637 0.9849741 -0.1619547 -0.05997294 0.9983211 -0.009232759 -0.05718111 0.993974 -0.007186412 -0.109381 0.9843512 0.1458424 -0.098908 0.9736224 0.1521031 -0.1700715 0.9582458 0.2393428 -0.156461 0.9218085 0.2598361 -0.2876707 0.9102303 0.3111528 -0.2732486 0.7924942 0.3601871 -0.4921569 0.7796561 0.4145952 -0.4693051 0.5276622 0.4651595 -0.7107737 0.521928 0.4897162 -0.6984048 0.7951504 -0.5998944 0.08867257 0.9822668 -0.1566318 0.1030468 0.9852182 -0.156875 0.06881392 0.9731184 -0.2200285 0.0680294 0.9748281 -0.220102 0.03557366 0.9585725 -0.2827292 0.0346843 0.9592365 -0.2824835 -0.00827527 0.9458954 -0.3243594 -0.008534014 0.9441576 -0.323779 -0.06110447 0.9759046 -0.2097052 -0.06028288 0.9710385 -0.2074111 -0.1185957 0.9894735 -0.08987796 -0.1134205 0.9766649 -0.08238363 -0.1983398 0.9812622 -0.02016335 -0.1916195 0.9393001 0.003641307 -0.3430777 0.9408475 0.03995162 -0.3364667 0.8155208 0.09325075 -0.5711655 0.8163666 0.1286899 -0.5630139 0.5647432 0.1822192 -0.8048984 0.5639372 0.2044402 -0.8001119 0.761245 -0.6426758 0.086452 0.9291105 -0.3559535 0.1002534 0.9320877 -0.3562583 0.06551772 0.9125173 -0.4039723 0.06417775 0.9141792 -0.403992 0.03266263 0.8921117 -0.4507072 0.03161776 0.8927963 -0.4503682 -0.009128808 0.8729673 -0.4876899 -0.00931406 0.8713247 -0.4869688 -0.06045377 0.9082499 -0.4139776 -0.06086736 0.9029678 -0.4116926 -0.1231202 0.9343517 -0.3348727 -0.1218498 0.9201208 -0.3265202 -0.2162459 0.9319708 -0.292387 -0.2143371 0.8874887 -0.2667307 -0.3757907 0.8933397 -0.248586 -0.374365 0.7707955 -0.1955574 -0.6063264 0.7743828 -0.1826493 -0.605781 0.5488134 -0.132223 -0.8254217 0.5510995 -0.1165335 -0.8262624 0.7316462 -0.6764382 0.08441197 0.8558326 -0.5084714 0.09490847 0.8587581 -0.5087724 0.06070578 0.837127 -0.5437912 0.0592398 0.8385221 -0.5440775 0.02933204 0.815722 -0.5777493 0.02834457 0.8163307 -0.5775048 -0.009618818 0.7921863 -0.610202 -0.009723484 0.7905784 -0.6095656 -0.05844336 0.8210249 -0.5678097 -0.05924856 0.8157084 -0.5653312 -0.1225585 0.8450546 -0.520332 -0.1230351 0.8304569 -0.5114691 -0.2207733 0.8387008 -0.4978703 -0.220695 0.7947103 -0.4723466 -0.3812143 0.7971305 -0.4682356 -0.3812326 0.6847486 -0.4194872 -0.5959445 0.6843772 -0.4199692 -0.5960318 0.4961032 -0.3771929 -0.7820532 0.4985688 -0.3690047 -0.7843881 0.0415154 0.9642825 -0.2616026 -0.07903712 0.9966011 0.02322721 -0.09949076 0.9920241 0.07739526 0.4635084 -0.852033 -0.2433101 0.4525949 -0.8456207 -0.2829904 0.6664909 -0.6741706 -0.3182517 0.4354574 0.900152 0.01016688 0.5118476 0.8587713 -0.02289617 0.6054515 -0.6670864 -0.4340786 0.5432897 -0.6388256 -0.5447368 0.5437507 -0.6383097 -0.5448816 0.4064084 -0.6074838 -0.6824922 0.4063422 -0.6078489 -0.6822065 0.3808557 -0.6079034 -0.6967083 0.2075005 -0.902108 -0.3783446 0.2469639 -0.8596603 -0.4472058 0.3777306 -0.8454076 -0.3776316 0.3429623 -0.8287824 -0.4421499 0.5095096 -0.6783853 -0.529333 0.2496948 -0.8437714 -0.4750815 -0.1889911 0.8954567 0.403038 0.2564334 -0.8244326 -0.5045325 0.2684866 -0.8245437 -0.4980388 0.2609636 -0.6932281 -0.6718131 0.2288069 -0.8666538 -0.4433494 0.2302646 -0.8631873 -0.4493173 0.2450094 -0.8632085 -0.4414086 0.3172798 -0.6946396 -0.6456078 -0.1748512 0.9398695 0.293381 0.3973008 -0.4705091 -0.7878916 0.4156509 -0.3684623 -0.8315467 0.4326268 -0.2029261 -0.878439 0.4372715 -0.1152267 -0.8919173 0.4234266 0.1944667 -0.8848123 0.421995 0.2074353 -0.8825479 0.3469501 0.5600522 -0.752308 0.3659152 0.4944077 -0.7884587 0.2249829 0.8236917 -0.5204948 0.2747927 0.7343917 -0.6206109 0.361433 -0.6094205 -0.7056719 0.1925541 0.9158565 -0.3523206 0.0471611 0.9951733 -0.08605766 0.03587704 0.9972928 -0.06418871 0.1030591 -0.6684116 -0.7366172 0.2056196 -0.9129546 -0.3524691 0.197552 -0.8777676 -0.4364601 0.2028103 -0.8407825 -0.501949 0.1749665 -0.4324135 -0.8845369 -0.1082577 0.9380499 -0.3291545 0.2143081 -0.4291282 -0.8774514 0.2168151 -0.4639626 -0.8589121 0.1835272 -0.1686553 -0.9684385 0.187381 -0.2032546 -0.9610286 0.1232629 0.1822826 -0.9754893 0.1258358 0.1687263 -0.9775975 0.05172729 0.4970859 -0.8661582 0.04873204 0.510021 -0.8587804 -0.02370715 0.7507139 -0.660202 -0.03107297 0.7725359 -0.6342104 -0.09899288 0.9242212 -0.3688033 -0.1049278 0.9353739 -0.3377366 0.150424 0.04740345 -0.9874845 -0.1511706 0.988353 -0.01748758 -0.4332463 0.8896794 -0.1441123 0.01332116 -0.8418755 -0.5395074 -0.5892081 0.7053007 -0.3941887 -0.5664778 0.7543396 -0.3317751 -0.6312295 0.4726477 -0.6149418 -0.6270657 0.5223211 -0.577901 -0.6165855 0.2435017 -0.748685 -0.6194939 0.2668679 -0.7382472 -0.4380562 -0.3014538 -0.8468958 -0.3435502 -0.4646263 -0.816147 -0.3005971 -0.528039 -0.7942394 -0.4106501 0.8981545 0.157115 -0.4718592 0.8788111 0.07099336 -0.5623253 0.008232533 -0.8268752 -0.5577852 -0.007992863 -0.8299469 -0.734812 -0.1128041 -0.6688249 -0.5800749 -0.4216746 -0.6969245 -0.5587268 -0.4554183 -0.6931223 -0.4032946 -0.6372222 -0.6567354 0.07544273 -0.9214948 -0.3809931 -0.439645 0.8774228 0.1919415 -0.6981567 0.7127141 0.06794124 -0.478375 0.8545881 0.202081 -0.4786721 0.8537297 0.2049849 -0.886053 0.4580672 -0.07130563 -0.8966323 0.4351572 -0.08178615 -0.9700943 0.1076049 -0.2175735 -0.9705474 0.08780086 -0.2243407 -0.8936002 -0.2934539 -0.3396519 -0.8900701 -0.3018783 -0.3415331 -0.6550068 -0.6410279 -0.4000617 -0.6563024 -0.6397454 -0.3999913 -0.4190236 -0.8152427 -0.3997483 -0.414301 -0.817841 -0.399363 -0.3803898 -0.7473623 -0.5447506 -0.5982242 -0.5501655 -0.5826198 -0.6180461 -0.5249186 -0.5852175 -0.8093034 -0.2005991 -0.5520763 -0.6286464 0.7743925 -0.07155585 -0.8462847 0.19772 -0.4946807 -0.8453119 0.1680049 -0.5071707 -0.798682 0.5149499 -0.3113419 -0.8178552 0.4572554 -0.3493285 -0.4148386 -0.679017 -0.6056774 -0.6669633 0.7223652 -0.1826158 -0.5359616 0.8441348 -0.01348584 -0.3899558 0.9129527 0.1202164 -0.1300604 -0.7260462 -0.6752342 -0.1192411 -0.7364567 -0.6658927 -0.1971112 -0.828351 -0.5243871 -0.09951025 -0.8745316 -0.4746495 -0.4511673 -0.796561 -0.4024162 -0.9508379 0.2809123 -0.1303675 -0.9465569 0.2977693 -0.1239507 -0.9730181 -0.008080303 -0.2305873 -0.9731638 -0.006313443 -0.230027 -0.9046969 -0.2940045 -0.3083584 -0.8970763 -0.3123489 -0.3125579 -0.7407941 -0.5673866 -0.3595783 -0.7155799 -0.5968245 -0.3629683 -0.5452418 -0.7504073 -0.3736314 -0.5087903 -0.7758432 -0.3730952 -0.9548027 0.2854632 -0.08284133 -0.9663664 0.237457 -0.09874266 -0.983757 -0.02236258 -0.1781075 -0.9802319 -0.06013691 -0.1884917 -0.9086568 -0.3303658 -0.2553454 -0.8994774 -0.3513675 -0.2597721 -0.7263672 -0.6148967 -0.3070715 -0.7200964 -0.6217985 -0.3079415 -0.5179174 -0.7922219 -0.3227168 -0.5157076 -0.7936446 -0.3227602 -0.6279583 -0.7110771 -0.3162876 0.29376 -0.9275895 -0.2308307 0.583832 -0.8006531 -0.1345174 0.06252241 -0.954315 -0.2921884 0.1341149 -0.9494228 -0.2839186 -0.9352309 -0.1695486 -0.3107995 0.1735247 -0.9362426 -0.3055144 -0.5745022 -0.5123857 -0.6382853 0.1862831 -0.9223377 -0.3385142 0.1045072 -0.8892475 -0.4453282 0.05091643 -0.7554797 -0.6531906 -0.1066429 -0.462702 -0.8800764 -0.2946178 0.9548102 -0.03921651 -0.0741654 -0.3791854 -0.9223438 -0.05719769 -0.4265378 -0.9026594 -0.1565554 -0.146021 -0.9768155 -0.1442018 -0.1873152 -0.9716578 -0.2362034 0.1254006 -0.9635781 -0.2338538 0.1147534 -0.9654762 -0.2923128 0.3671071 -0.8830547 -0.2960124 0.3863703 -0.8735529 -0.3291703 0.5926188 -0.735153 -0.3320329 0.6291199 -0.7028247 -0.340431 0.8049309 -0.4859969 -0.3377113 0.8342649 -0.4358365 -0.283095 0.9589641 0.01565867 -0.2419023 0.9526242 0.1843656 -0.5748717 0.80682 0.1362492 -0.6205606 0.775048 0.1191852 -0.6206659 0.7760792 0.1116913 -0.5447714 0.8275249 0.1357451 -0.6416991 0.7601882 0.1016673 -0.6513088 0.7527748 0.09553605 -0.5843228 0.8033427 0.1149245 -0.8704452 0.4921241 0.01179158 0.7158027 -0.6941137 -0.07637238 -0.7984037 0.6004568 0.04475861 0.06755912 -0.9681031 -0.2412723 -0.2591849 -0.9251394 -0.2773811 -0.2535153 -0.9154141 -0.3126455 -0.8429433 -0.4585654 -0.2813619 -0.3185681 -0.8760623 -0.3619796 -0.2882399 -0.8879376 -0.3584477 -0.2982946 -0.9002795 -0.3170445 -0.5593563 -0.7693706 -0.3085277 -0.4298455 -0.8459726 -0.3155363 -0.7572292 -0.5918002 -0.2763631 -0.6731212 -0.6794113 -0.2920758 -0.9220691 -0.3241053 -0.211529 -0.9131127 -0.3452528 -0.2168545 -0.9904793 -0.04090064 -0.1314454 -0.9932716 0.05040746 -0.1042621 -0.9677747 0.2487093 -0.0394442 -0.9130592 0.4075537 0.01493591 -0.6565172 0.7494078 0.08586806 -0.6933552 0.716157 0.07986098 -0.6508638 0.7537325 0.0909056 0.7216827 -0.6884245 -0.0724281 -0.8718447 0.489053 0.02672237 -0.9976809 0.02654772 -0.06267619 -0.9839457 0.1748221 -0.03588956 -0.9895507 0.1377165 -0.04270631 -0.9874293 -0.1302477 -0.08954852 -0.9812412 -0.1674365 -0.0955553 -0.8963057 -0.4225215 -0.1345798 -0.8791512 -0.4557715 -0.1391596 -0.7075637 -0.68638 -0.1680362 -0.6806181 -0.7124742 -0.1707035 -0.4964295 -0.848743 -0.1821901 -0.4639782 -0.866715 -0.1831104 -0.9393889 -0.3213582 -0.1194886 -0.7866875 0.6148041 0.05602389 0.2478951 -0.9460254 -0.2087678 -0.09557253 -0.967493 -0.2341437 -0.9812738 -0.1307587 -0.1414356 0.09951668 -0.9750244 -0.1985551 0.09760326 -0.9785805 -0.1812565 -0.6970848 0.7133429 0.07221388 -0.6917033 0.7184776 0.07305181 -0.9239524 0.3814159 0.02887886 -0.9006862 0.4330264 0.03539156 -0.991225 0.1321456 -0.003252625 -0.9935992 0.1128247 -0.005583941 -0.9837022 -0.1751424 -0.04068613 -0.9799197 -0.1947168 -0.04292756 -0.8820874 -0.4652109 -0.07416808 -0.8721597 -0.4832645 -0.07611167 -0.6836375 -0.7226883 -0.1017911 -0.6680022 -0.7369786 -0.1031292 -0.4666628 -0.8767443 -0.1163846 -0.4473916 -0.8866339 -0.1171381 -0.7673718 0.6378332 0.06564748 -0.7538156 0.6537843 0.06578993 -0.7219215 0.6887618 0.06660699 0.6896899 -0.7210618 -0.06631535 -0.9150503 0.3966817 0.07298493 -0.3282415 0.9435671 0.04403197 -0.7199299 0.6909444 0.06555062 -0.625409 -0.7801123 -0.01698583 0.1318861 -0.9820768 -0.134652 0.1313274 -0.9839943 -0.1204504 -0.791422 -0.6047275 -0.0891968 0.1539219 -0.9825393 -0.1045213 0.1538339 -0.9842005 -0.0876615 0.1782107 -0.9800929 -0.08751529 0.1786444 -0.9813416 -0.07109731 -0.4314522 0.8905453 0.1441457 -0.6534217 0.7560641 -0.03751283 -0.6816536 0.7275491 0.07759255 -0.7126433 0.6989386 0.06020396 -0.7214983 0.6812852 0.1236553 -0.7279825 0.6748259 0.1210436 -0.7143351 0.6972198 0.06008315 -0.8104592 0.5857895 0.002563655 -0.8151924 0.5785432 0.02737581 -0.8487899 0.5286823 0.007121741 -0.849169 0.5278078 0.01819097 -0.9707891 0.2294979 -0.06999427 -0.9794102 0.1844853 -0.08198124 -0.9867706 -0.07206195 -0.145227 -0.9809849 -0.1165352 -0.1552042 -0.9074942 -0.3659261 -0.2062827 -0.8885664 -0.4060551 -0.2134695 -0.7290821 -0.6374979 -0.2490699 -0.6992878 -0.6686876 -0.2526925 -0.5246399 -0.8092764 -0.2642437 -0.4884725 -0.8313939 -0.2649127 -0.225106 -0.9397783 -0.2571851 -0.2324454 -0.9552357 -0.1830142 -0.1960842 -0.9635599 -0.1819437 -0.1983872 -0.9723952 -0.122842 -0.1763097 -0.9766414 -0.1228275 -0.1765787 -0.9807552 -0.08330327 -0.1530078 -0.9846634 -0.08382511 -0.1519814 -0.9872841 -0.04660338 -0.9001199 -0.4353937 0.01471316 0.5407812 -0.8391542 -0.05810326 -0.8826757 0.4611264 0.09080827 -0.1180654 -0.9929398 0.01145082 -0.9683429 0.2300804 0.09682631 -0.8210729 0.5653035 0.07919102 -0.8178381 0.5698243 0.0802564 -0.9816372 0.1044097 0.1596466 -0.7617284 0.6443849 0.06736379 -0.7616078 0.6444411 0.06818521 -0.7427305 0.6663397 0.06590002 -0.3793581 0.9247905 0.02915924 0.7319399 -0.6782306 -0.06532394 -0.9134996 0.396545 0.09094262 -0.9917367 -0.06573867 0.110167 -0.9921292 0.06467193 0.1072256 -0.993488 0.03604501 0.1080858 -0.9628771 -0.2459745 0.1111948 -0.955419 -0.2735674 0.1110659 -0.8401448 -0.5322285 0.1043531 -0.8246473 -0.5561434 0.1032549 -0.6225874 -0.7777912 0.08617466 -0.6003107 -0.7953224 0.08419883 -0.3940274 -0.9168434 0.0643481 -0.3679288 -0.9277999 0.06177264 -0.0880106 -0.995586 0.03260207 -0.08288764 -0.99401 0.07123172 -0.9890082 0.03161019 0.1444426 -0.9475571 0.2963578 0.1196147 -0.9330091 0.3412353 0.1142477 -0.9890047 0.03786063 0.1429558 -0.9893819 0.01136833 0.144894 -0.9494457 -0.2712192 0.1580919 -0.9421578 -0.2952083 0.1587157 -0.8177152 -0.5535618 0.1578333 -0.8044463 -0.5728307 0.1572617 -0.5929651 -0.7927934 0.1409651 -0.5755389 -0.8058118 0.139365 -0.360787 -0.9254314 0.1157991 -0.3418519 -0.9328671 0.1135624 -0.9755188 -0.1566124 0.1543883 -0.06402999 -0.9943125 0.08510583 -0.6967424 0.7136771 0.07221573 -0.9350811 0.3519675 0.04174274 -0.9981287 -0.02677738 0.0549739 -0.9941418 0.09039896 0.05924665 -0.9961726 0.06499582 0.05844396 -0.9744851 -0.2196105 0.04636991 -0.9683494 -0.2454914 0.0450921 -0.8609074 -0.5079324 0.02904242 -0.846552 -0.5316014 0.02738487 -0.6514292 -0.7586699 0.007753491 -0.6292509 -0.7771801 0.005867481 -0.42761 -0.9039045 -0.01031583 -0.4004189 -0.9162499 -0.01228111 -0.8753343 0.4787774 0.0675435 -0.1201428 -0.9926639 -0.01357585 0.2110621 -0.9767894 -0.03654301 0.2125796 -0.9769695 -0.01845532 0.2186933 -0.9756095 -0.01896214 0.2173171 -0.9760769 -0.006875693 0.6318826 -0.7734661 -0.04974466 0.2428428 -0.9700407 0.006956517 0.2448862 -0.969299 0.02214318 0.02220869 -0.9981458 0.05667316 0.3182851 -0.947824 0.01801258 -0.02196598 -0.9966471 0.0788179 0.6230803 -0.781498 -0.03212308 0.2811098 -0.9586387 0.04459899 -0.04467624 -0.9572362 0.2858375 -0.1855775 -0.891111 0.4141042 -0.2562203 -0.8607314 0.4398781 -0.2937231 -0.8569304 0.4235528 -0.2202366 -0.8931089 0.3922401 -0.2213976 -0.9056546 0.3616256 -0.2195206 -0.9096964 0.3525101 -0.2184469 -0.9114824 0.3485412 -0.3422168 -0.8246697 0.4503417 -0.2929736 -0.85689 0.4241533 -0.2911452 -0.8335585 0.4694837 -0.2845174 -0.8544852 0.434632 -0.2111053 -0.8850795 0.4148119 -0.2340173 -0.8745544 0.424724 -0.254401 -0.869594 0.4231864 -0.1791495 -0.9025815 0.3914744 -0.1465089 -0.894755 0.4218397 -0.1471887 -0.8929317 0.425451 -0.067595 -0.9221045 0.3809911 -0.06638604 -0.9166378 0.3941677 -0.01739621 -0.9172432 0.3979479 9.82845e-4 -0.9223699 0.3863067 0.0115621 -0.9203662 0.3908867 0.04505366 -0.9165033 0.397482 0.06966388 -0.9227398 0.3790755 0.1163666 -0.9149117 0.3865171 0.2173413 -0.907724 0.3588872 0.2506229 -0.9012758 0.3533979 0.2395958 -0.9023512 0.3582684 0.2211454 -0.906 0.3609137 0.2209937 -0.902579 0.3694766 0.246843 -0.8993041 0.3609996 0.2390241 -0.9046966 0.352692 0.2493798 -0.9010328 0.354894 0.1829167 -0.9197131 0.3473748 0.1833299 -0.9187523 0.3496921 0.1856144 -0.9230611 0.3369058 0.1260325 -0.9313745 0.3415513 0.1179659 -0.9500253 0.2890261 0.1376653 -0.9476112 0.2882382 0.09756517 -0.9491098 0.2994524 0.07337886 -0.944945 0.3188961 0.08875572 -0.9552105 0.2823038 0.06334215 -0.9577823 0.2804298 0.01505488 -0.9501457 0.3114425 0.01026117 -0.9445816 0.3281166 -0.06011092 -0.9432001 0.3267419 -0.05585289 -0.9392735 0.3385938 -0.05923801 -0.9427829 0.3281027 -0.009012699 -0.9557486 0.2940467 0.01449346 -0.9534021 0.3013544 -0.1193758 -0.9332365 0.33885 -0.1151956 -0.9309834 0.3464102 -0.1219289 -0.9359003 0.3304909 -0.083422 -0.9447996 0.3168513 -0.07051473 -0.9443916 0.3211731 -0.1343469 -0.9348222 0.3287225 -0.1665027 -0.9254192 0.3404058 -0.1623739 -0.9227305 0.3495758 -0.1757048 -0.9252871 0.3361127 -0.2043497 -0.9139378 0.3506551 -0.2010307 -0.9125114 0.356244 -0.2270234 -0.9137294 0.3369851 -0.2199185 -0.8979855 0.3811272 0.1968414 -0.9132821 0.3566081 0.2024319 -0.9211751 0.3323521 0.2219322 -0.918038 0.3285608 0.228343 -0.9206201 0.3167304 0.2352156 -0.919375 0.3153148 0.2449662 -0.9209542 0.3030431 0.215482 -0.9262648 0.3091946 0.2238333 -0.9270859 0.3006834 0.1625242 -0.9359367 0.3124236 0.1801269 -0.9073898 0.3797345 0.149636 -0.9183965 0.3662747 0.1644967 -0.9361832 0.3106475 0.09088808 -0.9423524 0.3220427 0.07497221 -0.952116 0.2964022 0.02086389 -0.9399623 0.3406402 -0.04040759 -0.9384315 0.3430946 -0.05977374 -0.9291949 0.3647244 -0.1054856 -0.9270061 0.3599066 -0.1261064 -0.9156004 0.3818027 -0.1545096 -0.914524 0.3738619 -0.1838709 -0.8929417 0.4109098 -0.2194677 -0.8939059 0.3908532 -0.2193162 -0.8797827 0.4217617 -0.005371332 -0.9550813 0.2962955 0.06283909 -0.967741 0.2439849 0.06146961 -0.9655491 0.252857 0.1740562 -0.9422301 0.2861939 0.1889426 -0.9402598 0.2832175 0.1639962 -0.9501238 0.2652738 0.107762 -0.9620341 0.2507549 0.1541156 -0.9654754 0.2100135 0.1409559 -0.9539147 0.264912 0.1556669 -0.9522539 0.2626414 0.1438589 -0.9437522 0.2977185 0.1448242 -0.9435138 0.2980061 0.1324622 -0.9339327 0.3319996 0.21252 -0.9485701 0.2346277 0.2021902 -0.9502062 0.2371233 0.1676456 -0.9602268 0.2232922 0.184408 -0.9593524 0.2136275 0.1229391 -0.965986 0.2275023 0.113685 -0.9654797 0.2343599 0.0695225 -0.9681572 0.2404958 0.02134025 -0.9618505 0.2727422 0.01009541 -0.9621035 0.2724975 -0.04671573 -0.9511525 0.3051667 -0.05547153 -0.9513135 0.3031925 -0.1143807 -0.9303408 0.348401 -0.127913 -0.9313203 0.341 -0.1633977 -0.9167032 0.364632 -0.1747694 -0.9177169 0.3567232 -0.2032062 -0.9043385 0.3753387 -0.2121942 -0.9051476 0.36835 -0.2387802 -0.890679 0.3868784 -0.2428197 -0.8909137 0.3838115 -0.2671266 -0.8766903 0.400072 0.1614801 -0.9265819 0.339662 0.1760937 -0.9362294 0.3040817 0.1833469 -0.9353286 0.302563 0.2169508 -0.9365402 0.2753634 0.1960322 -0.9396789 0.2803121 0.2395213 -0.9382427 0.2496599 0.1914949 -0.9458938 0.2619443 0.2310399 -0.9438487 0.2361574 0.1654565 -0.953194 0.2530722 0.1865551 -0.9526644 0.2400579 0.09977686 -0.9603312 0.2604011 0.08575773 -0.9585131 0.2718425 0.01637017 -0.9594178 0.2815133 -0.02503699 -0.9495411 0.312642 -0.05064421 -0.9487392 0.311976 -0.0962513 -0.9346256 0.3423607 -0.1091516 -0.9342949 0.3393805 -0.1592401 -0.910115 0.3825355 -0.1700846 -0.9106549 0.3765354 -0.202347 -0.8942439 0.3992288 -0.2121979 -0.895037 0.3922767 -0.2392802 -0.8801206 0.41004 -0.2471206 -0.8808383 0.4038013 -0.2779387 -0.8619401 0.4240395 -0.2779043 -0.8619547 0.4240322 -0.225217 -0.9572355 -0.1815978 -0.2300187 -0.8928748 -0.3871255 -0.2025693 -0.9056847 -0.3724259 -0.1956062 -0.9097416 -0.3662081 -0.1926936 -0.911538 -0.3632735 -0.2188945 -0.8246725 -0.5215366 -0.220839 -0.8568257 -0.4659184 -0.2608553 -0.8335841 -0.4869211 -0.2340076 -0.8544932 -0.4637691 -0.2214856 -0.8621088 -0.455755 -0.2529447 -0.860673 -0.4418835 -0.2282639 -0.87655 -0.4237401 -0.2739697 -0.8629415 -0.4245852 -0.2703207 -0.8867526 -0.3749624 -0.2536208 -0.8808422 -0.399742 -0.2793488 -0.9111562 -0.3029169 -0.2719912 -0.898664 -0.3441276 -0.2481504 -0.9027799 -0.3512973 -0.2948443 -0.8922136 -0.3420844 -0.2962105 -0.9220772 -0.2490641 -0.2834585 -0.927647 -0.243151 -0.375606 -0.8927444 -0.2488526 -0.3174965 -0.9233971 -0.2157171 -0.3929728 -0.9045358 -0.1654913 -0.3729084 -0.9214878 -0.1086264 -0.3545447 -0.9186134 -0.1744922 -0.4303324 -0.9018366 0.03879398 -0.425675 -0.9048736 -0.002162396 -0.4312154 -0.9022479 -0.001478791 -0.4214641 -0.9068225 0.006407797 -0.4232755 -0.9058708 0.01536178 -0.4375566 -0.8986445 0.03134387 -0.4337455 -0.9003307 0.03563219 -0.4359381 -0.8990213 0.04145807 -0.3839664 -0.923079 -0.02224743 -0.3799339 -0.9247809 -0.02075278 -0.3825585 -0.9239128 -0.005845785 -0.3091953 -0.9500473 -0.04252666 -0.3184793 -0.947601 -0.02497023 -0.3083051 -0.9489697 -0.06636613 -0.3128662 -0.9449437 -0.09589689 -0.2888612 -0.9552108 -0.06427884 -0.2744658 -0.9577926 -0.08545124 -0.2773326 -0.9500955 -0.1428469 -0.2891308 -0.9446555 -0.1550136 -0.2528905 -0.9432156 -0.2153851 -0.265184 -0.9393205 -0.2176112 -0.2545738 -0.9427631 -0.2153833 -0.2500514 -0.9557693 -0.1548531 -0.2682079 -0.9534145 -0.1380774 -0.2340077 -0.9331945 -0.2727428 -0.2427253 -0.9308768 -0.2730439 -0.2252153 -0.9358983 -0.2708739 -0.2326677 -0.9448149 -0.2306308 -0.2428666 -0.9444066 -0.2216121 -0.2175363 -0.9348036 -0.2807496 -0.2115932 -0.9254282 -0.3143423 -0.2217807 -0.9226893 -0.3153697 -0.203196 -0.9254241 -0.3198465 -0.20146 -0.9140063 -0.3521456 -0.2078768 -0.9125981 -0.3520681 -0.1780709 -0.9138182 -0.3650027 -0.2201089 -0.8979843 -0.3810203 -0.4090377 -0.9124634 -0.009945631 -0.3894309 -0.9210181 0.008323848 -0.3970996 -0.9172664 0.03056633 -0.3896432 -0.919974 0.04273402 -0.3906205 -0.919418 0.0456742 -0.3848928 -0.9209952 0.0602113 -0.3752552 -0.926404 0.03097277 -0.3721099 -0.9272251 0.04228317 -0.3523943 -0.9357407 -0.01441085 -0.4015532 -0.9147543 -0.04449433 -0.3919584 -0.9185397 -0.0515142 -0.3517842 -0.9360101 -0.01153385 -0.3245332 -0.9423257 -0.0818572 -0.2939621 -0.9522175 -0.08287507 -0.3053286 -0.9399648 -0.1524488 -0.2769386 -0.9384344 -0.2065091 -0.2859869 -0.9292002 -0.2340912 -0.2589452 -0.9270095 -0.2712946 -0.2675995 -0.9156015 -0.3001074 -0.2465244 -0.9145244 -0.3207349 -0.2639281 -0.8929421 -0.3646867 -0.2281512 -0.8939094 -0.3858407 -0.227077 -0.8947347 -0.3845592 -0.2539224 -0.9550809 -0.1527873 -0.2427263 -0.9677394 -0.06756055 -0.2497233 -0.965548 -0.07318061 -0.3309828 -0.9436165 -0.006199657 -0.340942 -0.9398056 0.02289724 -0.3117552 -0.9501129 0.009706974 -0.2710471 -0.962033 -0.03203511 -0.2589529 -0.9654713 0.02843517 -0.2999365 -0.9539022 -0.01042777 -0.3053144 -0.9522456 0.003407955 -0.330226 -0.943576 -0.02480101 -0.3307425 -0.9434083 -0.02429276 -0.3537999 -0.933885 -0.051813 -0.3095018 -0.9485688 0.06652855 -0.3063592 -0.950274 0.05588704 -0.2774094 -0.9601789 0.0331735 -0.2774279 -0.9592555 0.0535041 -0.2585176 -0.9659791 -0.007299721 -0.2598229 -0.9654757 -0.01867854 -0.2430457 -0.9681559 -0.06002581 -0.2468782 -0.961853 -0.1178569 -0.2410416 -0.9621058 -0.1274812 -0.2409293 -0.9511527 -0.1930329 -0.2348474 -0.9513136 -0.1996231 -0.2445454 -0.9303373 -0.2732584 -0.2313228 -0.9313198 -0.2813063 -0.2340455 -0.9167099 -0.3238297 -0.221602 -0.9177165 -0.3296802 -0.2235058 -0.9043309 -0.3636356 -0.2129606 -0.9051406 -0.3679245 -0.2157072 -0.8906763 -0.400208 -0.2108664 -0.8909192 -0.4022417 -0.212793 -0.8766809 -0.4314509 -0.3720285 -0.9278103 -0.02761906 -0.3517165 -0.9361056 -0.001338481 -0.3549169 -0.9348606 0.008353352 -0.3478835 -0.9360345 0.05307209 -0.3407979 -0.9396772 0.02938938 -0.3360097 -0.9382576 0.08228147 -0.3225209 -0.9459446 0.03419601 -0.3199974 -0.9439659 0.08080917 -0.3022645 -0.9530695 0.01717263 -0.3015318 -0.9525004 0.04267954 -0.2754372 -0.960322 -0.04377472 -0.2783262 -0.9585106 -0.06157982 -0.2519953 -0.9594176 -0.1265555 -0.2582471 -0.9495453 -0.1779671 -0.2448575 -0.948742 -0.1998336 -0.2483713 -0.9346264 -0.2545301 -0.2393426 -0.9342955 -0.2642104 -0.2516736 -0.9101127 -0.3291734 -0.2410185 -0.9106544 -0.335587 -0.2445363 -0.8942473 -0.3748652 -0.2336738 -0.8950343 -0.3798818 -0.235521 -0.8801173 -0.4122177 -0.2261918 -0.8808363 -0.4158903 -0.2287333 -0.8574454 -0.4609431 -0.2122609 -0.8571801 -0.4692416 -0.3403528 -0.7633018 0.549118 -0.7508715 -0.6289404 -0.2015595 0.4760294 0.581 0.660178 -0.2816997 0.7496079 -0.5989435 0.480057 -0.7429555 0.4664359 0.5373811 -0.6383503 0.5511175 0.3738997 -0.8705622 0.3198758 0.404578 -0.8402808 0.3608946 0.1761375 -0.9821885 0.06543177 -0.1782822 -0.9207461 -0.3470478 -0.09341257 -0.9630106 -0.2527544 -0.3650262 -0.4296214 -0.8259427 -0.399165 0.1389592 -0.9062879 -0.4031972 -0.1054596 -0.9090162 -0.3906651 0.3223989 -0.8622295 -0.2452092 0.8233168 -0.5118809 0.1707722 -0.9225296 0.3460869 0.5474539 -0.6159883 0.5664386 0.6280941 0.1047576 0.7710536 0.6212129 -0.3734232 0.6889483 0.6293715 0.1042922 0.7700746 0.6446706 -0.07501548 0.760771 0.6298562 0.1040904 0.7697054 0.6012144 0.2526276 0.7581033 0.6294023 0.1041639 0.7700667 0.6293924 0.1042659 0.770061 -0.3120241 0.6873263 -0.6559144 -0.3206523 0.6866009 -0.652504 -0.1629773 0.9314582 -0.3253062 -0.2868732 -0.6912558 -0.6632265 -0.3236162 -0.5874487 -0.7417389 -0.3541457 -0.5877104 -0.7274458 -0.3447555 -0.6160503 -0.7082554 -0.3703334 -0.6160251 -0.6952455 -0.3598713 -0.643911 -0.6751824 -0.2863087 -0.7955977 -0.5339024 -0.3998201 -0.5247635 -0.7515101 -0.1806925 -0.9102032 -0.3726665 -0.2784327 -0.770644 -0.5732219 -0.2646678 -0.7706189 -0.5797394 -0.406988 -0.09177923 -0.908811 -0.264814 -0.738257 -0.620363 -0.0526511 -0.9959644 -0.07268375 0.03100609 -0.997345 0.06589168 -0.4656682 0.3784243 -0.7999677 -0.4378582 0.3784825 -0.8154944 -0.1693801 -0.9338931 -0.3148875 -0.4349426 0.5291682 -0.7285644 -0.5240198 -0.1858186 -0.8311887 -0.2373586 0.886612 -0.3969636 -0.3596952 -0.4559011 -0.8141091 -0.2947725 -0.682251 -0.6690611 -0.3472176 0.575354 -0.7405455 -0.360236 0.5752611 -0.7343737 -0.3275241 0.6710361 -0.6651606 -0.4599585 0.03479444 -0.8872584 -0.4492656 -0.2417389 -0.8600713 -0.2133073 0.8901498 -0.402658 -0.06557571 0.9897738 -0.1266795 -0.1090123 0.9740415 -0.1983922 -0.3070742 -0.8194143 -0.48401 -0.4903191 0.3321876 -0.8057535 -0.4973806 0.3319063 -0.8015303 -0.4524335 -0.556738 -0.6966683 -0.1888611 0.9273688 -0.3229838 0.03480279 -0.995534 0.0877552 0.1862053 -0.9283027 0.3218412 -0.305841 -0.7953904 -0.523274 -0.06083792 -0.9936168 -0.09499663 -0.3814103 -0.6438914 -0.6632723 -0.08119535 0.9851053 -0.1515752 -0.3784254 -0.6730858 -0.6354131 -0.4069344 -0.6730177 -0.6176176 -0.3056027 0.811466 -0.4981266 -0.3442414 -0.8218342 -0.4539675 -0.3066865 -0.8171778 -0.4880203 -0.3268853 -0.8167042 -0.475542 0.1422162 -0.9577404 0.2500156 -0.5194783 0.3320774 -0.7873163 -0.4417966 -0.6455214 -0.6229912 -0.4825369 -0.6436806 -0.5939978 -0.389559 0.6945726 -0.6048245 -0.3989958 0.6774867 -0.6179112 -0.396618 0.6785978 -0.6182226 -0.3083853 0.8074093 -0.5029799 -0.288676 0.8297276 -0.4777219 0.3157428 -0.799627 0.5107868 -0.339108 0.771086 -0.5389175 -0.3627672 0.7379317 -0.5690843 0.2118223 -0.9026665 0.374599 -0.4563481 0.5615393 -0.6902319 -0.4496608 0.5610682 -0.6949874 0.272335 -0.8517187 0.4476706 -0.2383174 0.8856441 -0.3985467 -0.1570656 0.921714 -0.354646 -0.1372808 0.9310511 -0.3380797 -0.1350199 0.9321922 -0.3358384 -0.3559855 0.7538924 -0.5521962 0.2363101 -0.8723449 0.4279859 0.1931581 -0.9019427 0.3862504 -0.3995751 -0.8216347 -0.4065174 -0.4378679 -0.8168929 -0.3754432 0.1455844 -0.9345399 0.3247159 -0.0644499 0.9580981 -0.2790954 -0.09738129 0.9499934 -0.2966978 -0.04089444 0.9642664 -0.2617593 -0.0624485 -0.9806572 0.1855041 0.02283465 -0.9686369 0.2474293 -0.6551386 0.1442447 -0.7416111 -0.4709854 -0.824122 -0.3146362 -0.5215119 -0.8118276 -0.2626049 -0.3248681 0.9115476 -0.2520751 -0.5450593 -0.8369905 -0.04855018 -0.3566312 -0.9335048 0.03719002 -0.2510312 0.8746159 -0.4147657 -0.7115334 -0.5867097 -0.386642 -0.7997128 -0.5505281 -0.239538 -0.8031169 -0.5442999 -0.2423656 -0.861078 -0.507965 -0.02272564 -0.3697532 -0.8204182 -0.4361152 -0.4744632 0.533682 -0.7000488 -0.494783 -0.615437 -0.6135365 -0.5478665 -0.6102908 -0.5721778 -0.3844033 0.7245981 -0.5720068 -0.596143 -0.60213 -0.5310868 -0.6519913 -0.5903391 -0.4758227 -0.02273279 -0.9794659 0.2003246 -0.7471113 0.2523044 -0.6149531 -0.5498415 -0.8184441 -0.1668039 -0.591645 -0.800207 -0.09810805 0.3171394 0.9462869 -0.06295859 -0.1363963 0.9852317 -0.1035111 0.1976389 0.9793041 -0.04361462 0.315832 -0.7995284 0.5108862 -0.3534675 0.753453 -0.5544089 -0.2590351 0.856522 -0.4463979 -0.2567994 0.8562374 -0.4482316 -0.2608116 0.8528829 -0.4522922 -0.2144957 0.8876343 -0.4075498 -0.1121597 0.9437313 -0.3111135 -0.4147371 0.6977611 -0.5840571 -0.2658755 0.8511447 -0.4526178 -0.2716866 0.85257 -0.4464424 -0.1342245 0.9318064 -0.3372251 -0.09042185 0.9497352 -0.2997117 -0.07309591 0.9555534 -0.2856128 -0.5385072 0.6444855 -0.5428153 -0.2120038 0.9078264 -0.361809 -0.2287727 0.9139614 -0.3351681 -0.04938292 0.9670212 -0.2498629 0.2038941 0.9723989 -0.113435 0.2341434 0.9673227 -0.09728187 -0.1303696 0.9709896 -0.200457 -0.05588984 0.9865621 -0.1535307 -0.1426445 0.9763569 -0.1624184 0.1684147 0.9813696 -0.09246802 -0.9892235 -0.01792472 -0.145312 -0.5318447 -0.8462275 0.03225338 -0.2064797 0.9692468 -0.1338917 -0.1445953 0.9894586 -0.007995903 -0.9499282 -0.3058276 0.06407946 -0.6479542 -0.7615051 0.01629382 -0.001654386 0.99771 0.06761699 -0.3028342 -0.6505357 -0.6964874 -0.3708007 -0.3956447 -0.8402215 -0.4024126 -0.3959724 -0.8253908 -0.3933786 -0.4407604 -0.8068357 -0.421176 -0.4405208 -0.7928129 -0.4107491 -0.4840784 -0.7726275 -0.4457699 -0.4837889 -0.7531519 -0.4355598 -0.5196359 -0.7350282 -0.4786786 -0.5185064 -0.7085322 -0.4972106 -0.4537422 -0.7395266 -0.5489549 -0.4514439 -0.7034537 -0.5642741 -0.3826828 -0.7315386 -0.6401655 -0.3740122 -0.6710463 -0.6448849 -0.3456368 -0.6816588 -0.7631942 -0.3199598 -0.5613917 -0.7650861 -0.3069141 -0.5660806 -0.9029355 -0.2545009 -0.346319 -0.9042297 -0.2466021 -0.3486489 -0.9787665 -0.1973654 -0.05534583 -0.9807179 -0.1871233 -0.05636835 -0.9803475 -0.1857206 0.06653416 -0.9580545 -0.2796062 0.06286638 -0.9127593 -0.2751831 0.3019022 -0.7905478 -0.6089981 0.06446379 0.2739995 0.9616691 0.01081234 -0.861454 -0.5074325 0.02023559 -0.8612445 -0.5076833 -0.0227068 0.3982478 0.9162911 -0.04253655 -0.5761251 -0.8172648 0.01257866 -0.6026331 0.6934962 0.3948373 -0.004725456 0.9803815 0.1970528 0.3180241 0.9470899 0.0433765 -0.6996972 -0.7144105 0.00644499 -0.1452054 0.9882135 -0.04847311 0.07315284 0.9962726 -0.0457139 0.07368046 0.9972206 -0.01106089 0.2991383 0.9541352 -0.01193147 -0.2221375 0.9747148 0.02420783 0.4399722 0.8980112 -6.49712e-4 0.186324 0.9816411 0.04079377 0.1850303 0.9789651 0.08597272 -0.001285493 0.9896941 0.1431928 -0.8963872 -0.3413674 0.2827693 -0.6112968 -0.7909224 0.02753138 -0.611657 -0.7909516 0.01647323 -0.560916 -0.8277812 0.01231944 -0.5318751 -0.8467272 0.01272958 -0.5455598 -0.8379244 0.01572716 -0.5447647 -0.8376339 0.04001408 -0.7793472 -0.6042749 0.1657406 -0.921265 -0.2321151 0.3120791 -0.9202764 -0.2380258 0.3105402 -0.7708001 -0.2473214 0.5871112 0.3645785 0.9302571 0.04128259 -0.4733378 -0.879144 0.05529314 0.3363698 0.9349188 0.1130592 -0.38946 -0.9203163 0.03658938 0.3464527 0.9313669 0.1119212 -0.3666446 -0.9303608 7.63843e-4 0.3561916 0.9331201 0.0491355 -0.1949098 0.6733248 0.7131928 0.2872923 0.940836 0.1796967 -0.5265343 -0.6943355 0.4905711 0.06254988 0.8844532 0.4624177 -0.02640187 0.9230481 0.3837776 0.005624055 0.9335956 0.3582845 -0.0139786 0.9700402 0.2425421 0.0479092 0.9762632 0.2112224 0.2380151 0.9663283 0.09776777 -0.5916978 -0.5700068 0.5700755 -0.5881822 -0.5900822 0.5530324 -0.4840949 -0.6463287 0.5898401 -0.734737 -0.5104794 0.4467353 -0.770063 -0.1752632 0.6134214 -0.44995 -0.8845804 0.1227293 -0.3875015 -0.9218057 0.01081198 0.1023646 0.5142865 0.8514876 -0.303134 -0.6408662 0.7052662 0.3334358 0.8629336 0.3796924 0.3631369 0.922091 0.1337158 0.3921467 0.8918538 0.2254284 0.3867384 0.8998068 0.2019436 0.3575524 0.9287088 0.09826737 0.4273348 0.6407574 0.6378204 0.4237198 0.8266965 0.3701817 0.4303449 0.8245551 0.3673039 0.3861225 0.9000588 0.2019993 0.02758681 0.813812 0.5804733 -0.4475656 -0.8829525 0.1417037 0.1970824 0.8742721 0.4436294 0.2521464 0.8613281 0.4410625 0.341201 0.929175 0.1421824 0.3165606 0.9000718 0.2994333 0.3535453 0.9277772 0.1193119 0.3512528 0.916412 0.1918607 0.3676782 0.911234 0.1856485 0.3804266 0.8505427 0.3631156 -0.1949872 -0.8802801 0.4325358 -0.3539953 -0.8385474 0.4141566 -0.05625605 -0.703982 0.7079864 0.03366941 -0.5505921 0.8340952 -0.09233444 -0.8747104 0.4757691 -0.0879814 -0.8678203 0.4890268 -0.08740359 -0.8672834 0.4900819 -0.1307789 -0.852729 0.5057175 -0.1147584 -0.834137 0.5394869 -0.0626325 -0.8499186 0.5231785 0.3793829 0.874772 0.301401 0.3851773 0.8627582 0.3275466 0.3826729 0.8496726 0.362792 0.3308089 0.9197076 0.2114318 -0.4277846 -0.6694408 -0.6073298 -0.4284124 -0.6644275 -0.6123716 0.3830022 0.873629 0.3001363 0.4061526 0.7659294 0.4983898 0.415899 0.7628451 0.4950711 0.4219673 0.7277661 0.540648 0.418321 0.7288481 0.5420222 -0.4309116 -0.6453545 -0.6307399 0.4204141 0.7146735 0.5590116 0.4157277 0.7400674 0.5286501 -0.05268281 -0.8781108 0.4755482 0.4384242 0.5962656 0.6724966 -0.05231457 -0.8982722 0.4363144 -0.4811358 -0.6829745 0.5495947 -0.402033 -0.9124378 0.0763337 -0.3322106 -0.7442427 0.5794299 -0.3490144 -0.9363672 0.03748905 -0.01250809 -0.6312205 0.7755026 -0.2964965 -0.9524949 0.06959426 -0.2671315 -0.9543738 0.1334593 -0.2457816 -0.9495753 0.1946746 -0.3581162 -0.917741 -0.171769 0.428609 0.3880355 0.8159184 0.03781867 -0.7117626 0.7014014 -0.2402222 -0.9619984 0.1298167 -0.2189969 -0.9681028 0.1217265 0.3780692 0.8348296 0.4001539 0.3683817 0.8369914 0.4046484 0.4158173 0.716172 0.5605298 -0.0419327 -0.9550701 0.2933988 0.4480292 0.5856625 0.6754772 -0.2726086 -0.9619385 -0.01894658 -0.1452895 -0.964993 0.2183567 0.1822147 -0.6160355 0.7663538 -0.1956077 -0.9781245 0.07078188 -0.1794635 -0.9817157 0.06345969 0.3187955 0.9001561 0.2967974 0.4150223 0.711129 0.5674964 0.42508 0.6792204 0.5983031 -0.448728 -0.6008966 -0.6614881 0.3763619 0.7854258 0.4913841 0.1054937 0.9943766 -0.009287118 -0.3623595 -0.8031209 -0.4729615 0.4332839 0.6557863 0.6182308 0.4327863 0.6558637 0.6184974 0.4281835 0.6695824 0.6068924 0.4281195 0.669617 0.6068993 0.4272966 0.6719959 0.6048464 -0.4264258 -0.6753311 -0.6017383 -0.4275642 -0.6716924 -0.6049944 -0.4290345 -0.6660762 -0.610141 0.421289 0.696852 0.5804419 0.4224446 0.6965597 0.5799527 -0.4457134 -0.4044553 -0.798596 0.3897927 0.8182626 0.4225021 0.01984727 -0.9147381 0.4035598 0.002592384 -0.927772 0.3731386 0.05864918 -0.9372522 0.3436838 0.04795724 -0.9442064 0.3258442 0.08481574 -0.9486592 0.3047165 0.07453083 -0.9546526 0.2882425 0.1248659 -0.9582888 0.2570821 -0.1531049 -0.9881722 0.00863111 -0.1404582 -0.9900848 0.00192213 0.1735796 -0.8330107 0.5253221 -0.137099 -0.9902139 -0.02608519 -0.1213897 -0.9919847 -0.03508567 -0.1319294 -0.989816 -0.05347007 0.3831519 0.7534518 0.5343267 0.4040141 0.7172482 0.5677392 -0.450343 -0.6145136 -0.6477378 0.3559576 0.8027217 0.4784685 0.4480415 0.6258814 0.6383817 -0.3577649 -0.4741152 -0.8044993 -0.383224 0.3728802 -0.8450444 -0.4080018 0.3726047 -0.8334869 -0.4219176 0.2804667 -0.8621624 -0.4479851 0.280449 -0.8489157 -0.4591119 0.1840613 -0.8691016 -0.4958945 0.1839042 -0.848686 -0.5000969 0.1368149 -0.8550934 -0.5412859 0.1368625 -0.8296254 -0.5081729 0.3471437 -0.7881953 -0.5380291 0.3483437 -0.7675816 -0.4712246 0.5408591 -0.6967201 -0.5009847 0.5437498 -0.6733131 -0.4367003 0.6522147 -0.6196039 -0.4906527 0.6638417 -0.5644239 -0.4347089 0.7256266 -0.53338 -0.5243739 0.7581183 -0.3876711 -0.4492903 0.814389 -0.3672996 -0.5166869 0.849905 -0.103423 -0.4768142 0.8729708 -0.1028116 -0.4751368 0.877457 0.06568288 -0.33032 0.942277 0.05479776 -0.3200776 0.9030534 0.2864347 -0.3527455 0.8872358 0.2972933 -0.2803615 0.7839365 0.5539324 -0.321726 0.7493048 0.578822 -0.1005455 0.6427372 0.75946 -0.05822873 0.6974093 0.7143037 0.1951584 0.6498987 0.7345373 0.2176879 0.7026214 0.6774477 0.407625 0.66254 0.6283969 0.4068467 0.6421629 0.6496943 0.4744713 0.6223263 0.6225648 0.4721535 0.6450599 0.6008068 0.4090424 0.6686202 0.6209923 0.4009666 0.5134435 0.7586841 0.4293696 0.5049268 0.7487929 0.4264677 0.4550238 0.7817153 0.4409227 0.4506868 0.7761885 0.4398143 0.4086497 0.7997305 0.4651585 0.4028005 0.7882762 0.4662762 0.3681098 0.8044139 0.488238 0.3645555 0.7929207 0.4897199 0.3468459 0.7999202 0.5047939 0.3450696 0.7912712 0.5065481 0.3297493 0.7966647 0.5277943 0.3280974 0.7834446 0.5314175 0.3044527 0.7905088 -0.3441565 -0.5234984 -0.7794266 -0.4044932 0.1743264 -0.8977726 -0.432592 0.1741824 -0.8846042 -0.4374497 0.08991318 -0.8947365 -0.4654756 0.0898081 -0.8804925 -0.4677351 0.004287064 -0.8838585 -0.5057167 0.004249691 -0.8626891 -0.5055744 -0.04136592 -0.8617908 -0.5492401 -0.04026788 -0.834694 -0.5409552 0.1374537 -0.8297433 -0.5793429 0.1391039 -0.8031263 -0.5466387 0.3125476 -0.7768528 -0.5931739 0.318051 -0.7395865 -0.5575395 0.4182721 -0.7170762 -0.6383889 0.4359674 -0.6343438 -0.6062924 0.4951388 -0.6222918 -0.723821 0.538936 -0.4308494 -0.6780837 0.6002125 -0.4242023 -0.7562952 0.6457748 -0.1048457 -0.7325798 0.6724345 -0.1056351 -0.7320547 0.6769019 0.07681143 -0.6400527 0.7650053 0.07141023 -0.6043722 0.7096271 0.3621653 -0.6268471 0.6870791 0.3674032 -0.4961332 0.5631743 0.6608226 -0.5204983 0.5293951 0.6699422 -0.257617 0.407641 0.8760493 -0.231995 0.4537507 0.8604002 0.07326573 0.3820114 0.9212489 0.09556406 0.4383848 0.8936925 0.3672663 0.3754299 0.8509806 0.3621817 0.3507918 0.8635795 0.4599205 0.3212865 0.8277972 0.4348539 0.1697565 0.8843556 0.3448712 0.2022629 0.9165989 0.3478477 0.2153396 0.9124861 0.3909171 0.2018188 0.8980273 0.3813683 0.15386 0.9115291 0.4124063 0.1445284 0.8994625 0.4047676 0.0992484 0.9090176 0.4525035 0.08831173 0.8873791 0.4479681 0.05058515 0.8926174 0.487235 0.04456144 0.8721333 0.4855045 0.02486079 0.8738807 0.5120952 0.02211695 0.858644 0.5109841 0.004611432 0.8595778 0.5478143 0.00165826 0.8365984 0.5468605 -0.02427381 0.8368718 -0.3311778 -0.568513 -0.7530699 -0.4085398 -0.01870262 -0.912549 -0.4388244 -0.01889622 -0.8983742 -0.437082 -0.09185379 -0.8947191 -0.4659199 -0.09173721 -0.8800586 -0.461815 -0.1648741 -0.871518 -0.4998974 -0.16492 -0.8502377 -0.4960345 -0.2085992 -0.8428739 -0.5405836 -0.2081894 -0.8151237 -0.5487219 -0.06545364 -0.8334388 -0.5933994 -0.06281435 -0.8024535 -0.585497 0.0807901 -0.8066389 -0.6452921 0.0879662 -0.7588545 -0.6310735 0.1681095 -0.7572882 -0.7316883 0.1898962 -0.6546539 -0.7174956 0.2382125 -0.6545647 -0.8518679 0.2901359 -0.4360533 -0.8321802 0.3395673 -0.4383724 -0.9152027 0.3912571 -0.09655076 -0.9039642 0.4162253 -0.09800714 -0.9038026 0.4203636 0.08022087 -0.8803908 0.4675497 0.07943087 -0.8175527 0.4213085 0.3925643 -0.8210403 0.4142243 0.3928246 -0.6457993 0.3127496 0.6965135 -0.6509607 0.3012034 0.6967976 -0.3711177 0.17921 0.9111288 -0.3653773 0.1935188 0.9105219 -0.05027616 0.08378046 0.9952151 -0.04434698 0.1005699 0.9939412 0.2649481 -4.9523e-4 0.9642626 0.2591023 -0.01853591 0.9656721 0.3757203 -0.05704915 0.9249755 0.3561573 -0.1204782 0.9266267 0.2613395 -0.08788895 0.9612373 0.2599995 -0.09218263 0.9611986 0.3121593 -0.109029 0.9437528 0.301462 -0.1427174 0.9427366 0.3451415 -0.1555551 0.9255701 0.3323466 -0.1992694 0.9218663 0.3963655 -0.2138149 0.892848 0.3868964 -0.2501801 0.8875365 0.4385738 -0.2586722 0.8606635 0.4339447 -0.2780407 0.8569629 0.4685203 -0.2821835 0.8371746 0.4646829 -0.2990921 0.8334349 0.5124002 -0.3027855 0.8035964 0.5069792 -0.328315 0.7969827 -0.3171967 -0.6106946 -0.7255608 -0.3973817 -0.2098912 -0.8933272 -0.4288145 -0.2100558 -0.8786323 -0.4223722 -0.2694154 -0.8654577 -0.4512088 -0.2693606 -0.8507969 -0.4429427 -0.3278507 -0.8344553 -0.4799802 -0.3274877 -0.8138617 -0.4728531 -0.3673822 -0.8008996 -0.5173226 -0.3663941 -0.7733905 -0.5340392 -0.2639017 -0.8032173 -0.5834322 -0.2605799 -0.7692236 -0.5914915 -0.1547474 -0.7913224 -0.6612884 -0.146674 -0.7356524 -0.6607404 -0.09239572 -0.7449063 -0.7740259 -0.06755805 -0.6295395 -0.7716438 -0.03771251 -0.6349359 -0.9132536 0.01665365 -0.4070513 -0.9100747 0.04594546 -0.4118898 -0.991888 0.09928309 -0.07937932 -0.9896876 0.118243 -0.08085221 -0.9897582 0.1204485 0.07662248 -0.9935943 0.08355474 0.07608574 -0.9265251 0.06652581 0.3703046 -0.9238449 0.08813738 0.3724815 -0.7399767 0.03609275 0.6716636 -0.7355597 0.05609947 0.6751334 -0.4582493 -0.05773699 0.8869466 -0.4662815 -0.0853247 0.880512 -0.1699478 -0.2308568 0.9580308 -0.1831921 -0.2698549 0.9453143 0.1072384 -0.4022724 0.9092178 0.1053682 -0.4060052 0.9077761 0.219919 -0.4486868 0.8662077 0.2433655 -0.3998053 0.8837019 0.1533713 -0.3708797 0.9159288 0.1436117 -0.3933361 0.9081094 0.1992639 -0.4115621 0.8893315 0.1918969 -0.4277244 0.8833048 0.2441742 -0.4425094 0.8628814 0.2276266 -0.480639 0.8468604 0.3020026 -0.497745 0.8130464 0.2885679 -0.5292472 0.7978885 0.3478462 -0.5390223 0.7671102 0.340482 -0.5562478 0.7580637 0.3799 -0.5609956 0.7354998 0.3733388 -0.5763511 0.7269371 0.4274326 -0.5805176 0.6930374 0.4177035 -0.6030035 0.6796401 -0.4073991 -0.9131892 -0.01055932 -0.7013064 -0.6938084 0.1637048 -0.9281058 -0.1914066 0.3193481 -0.6744542 -0.6553658 0.3400108 -0.7710821 -0.2022052 0.6037762 -0.5857093 -0.279474 0.7608146 0.1389387 0.8757101 0.4624153 -0.459297 -0.4049228 0.7906224 -0.2669337 -0.5137504 0.8153571 -0.2856158 -0.5771642 0.7650525 -0.05291706 -0.7001205 0.7120612 -0.05119526 -0.6972189 0.7150279 0.04293292 -0.7343395 0.6774233 0.1067774 -0.6426326 0.7586976 0.03078687 -0.6196524 0.7842723 0.01469343 -0.6478673 0.7616114 0.06749713 -0.6655823 0.7432661 0.06531769 -0.6690992 0.7402973 0.1208684 -0.6849936 0.7184531 0.1024773 -0.7141665 0.6924338 0.1799945 -0.7318758 0.6572364 0.1638209 -0.7560513 0.6336792 0.2249024 -0.7662691 0.6018727 0.2154662 -0.7797046 0.5879074 0.2558956 -0.7845435 0.5648088 0.2471735 -0.7963734 0.5519915 0.3025152 -0.8004361 0.5174809 0.2891741 -0.8174302 0.498183 0.3523844 0.7893916 0.5026789 0.3568783 0.7892367 0.4997434 0.4133225 0.6971125 0.5858318 0.322898 0.836385 0.4429412 -0.3941248 -0.7332447 -0.5540919 -0.4236429 -0.6783611 -0.600294 -0.4271143 -0.6712464 -0.6058068 0.4388803 0.6439191 0.6266995 0.438098 0.6439945 0.6271693 0.3608695 0.8022474 0.4755758 0.4198462 0.6901443 0.5894321 0.4617498 0.6032059 0.6503306 -0.304408 0.8919074 -0.3344206 0.4086621 0.7001419 0.5854884 -0.1173947 -0.9911193 -0.06245744 0.4543768 -0.5118261 0.7290925 0.1085201 -0.9665082 0.2325627 0.1538023 -0.967377 0.2013122 0.4821673 0.5583905 0.6750665 0.6277134 0.1049907 0.771332 0.3633547 0.7514565 0.5507147 0.3673811 0.7517275 0.5476649 0.01710259 -0.9919276 -0.1256479 0.1159722 -0.9932197 -0.008063673 0.5096031 -0.6407743 0.5742065 0.3761613 -0.8432694 0.3839265 0.386744 -0.8315689 0.3986505 0.5093143 -0.641275 0.5739037 0.5173636 -0.6235789 0.5860755 0.5947639 -0.3762281 0.7104283 0.599093 -0.3533586 0.7184882 0.6230028 -0.07733577 0.7783873 0.6226258 -0.05121719 0.7808418 0.5876177 0.2511597 0.7691711 0.5815079 0.2781568 0.7645112 0.4742563 0.5808397 0.6615937 0.4626925 0.6032798 0.6495915 -0.46057 -0.6073036 -0.6473466 0.4287533 0.664398 0.6121651 -0.06431889 -0.9825671 -0.1744279 -0.07751041 -0.9833671 -0.1642603 -0.3307546 -0.8090649 -0.4858143 0.4805182 -0.5726765 0.6641866 -0.08532088 -0.9889169 -0.1215063 -0.1105088 -0.9884261 -0.1039308 0.4314124 0.6620045 0.6128894 0.4224336 0.6770144 0.602662 -0.452732 -0.6179978 -0.6427383 -0.4363204 -0.6518612 -0.6202431 0.4493454 0.6258024 0.6375423 -0.4269224 -0.6693415 -0.6080455 0.5576695 0.3042827 0.7722803 0.5631347 0.2769335 0.7785803 0.5916386 -0.02458018 0.8058286 0.591548 -0.053267 0.8045083 0.5645185 -0.3289496 0.757041 0.5592667 -0.3558132 0.7487441 0.4825669 -0.6036418 0.6346226 0.4726162 -0.6261835 0.6201034 0.3550679 -0.8180595 0.4524438 0.3414701 -0.8341107 0.4331945 0.150421 -0.9743557 0.1673454 0.1908622 -0.9721145 0.1362539 0.5001653 -0.6568177 0.5642919 0.3799643 -0.8395436 0.3883218 -0.491834 0.8688677 0.0562871 -0.1781921 0.9839281 0.0115391 0.30861 0.9505286 0.03543221 0.2885792 0.9574214 -0.008150398 -0.2974579 0.9538344 0.04145807 -0.5963537 0.8021689 -0.02978903 -0.5575326 0.8268296 0.07423287 -0.6663992 0.744448 0.04134565 -0.6475433 0.7613674 0.03174287 -0.6256425 0.7800864 0.006076335 -0.5936127 0.8045142 0.01952266 -0.60978 0.7915545 0.04012328 -0.6093966 0.7921401 0.03390794 -0.5573198 0.8279701 0.06213176 -0.5590394 0.8272498 0.05597186 -0.5721217 0.8193533 0.03656572 -0.5795871 0.8133271 0.05077344 -0.5791403 0.8140847 0.04316043 -0.5413255 0.8364097 0.0859403 -0.5413234 0.8364097 0.08595269 -0.511753 0.8531219 0.1014493 -0.4729235 0.8726373 0.1218509 -0.5175405 0.8454816 0.1315774 -0.5047926 0.8546256 0.1216542 -0.5405971 0.8203569 0.1864657 -0.4185956 0.8873829 0.1932078 -0.4116979 0.8913668 0.1896583 -0.4633647 0.8716419 0.1597928 -0.463335 0.8716592 0.1597837 -0.4632759 0.8730049 0.1524403 -0.3611086 0.9052029 0.2240726 -0.3249279 0.9204553 0.2172188 -0.1817408 0.9720394 0.1486933 -0.2458365 0.955149 0.1650904 -0.2624567 0.938804 0.2230777 -0.3109443 0.9254956 0.2162674 -0.3242346 0.9207613 0.2169576 -0.3058937 0.9288858 0.2088065 -0.2854896 0.9365932 0.2031966 -0.2880756 0.9353779 0.2051361 -0.222266 0.9600566 0.1699684 -0.2708923 0.9203971 0.2819336 -0.1478012 0.9800423 0.1329358 -0.1435251 0.9721274 0.1853888 -0.0296384 0.9893797 0.1423013 -0.02846479 0.9892547 0.1434046 0.06532913 0.9902029 0.1234121 0.09889906 0.9861277 0.133309 0.09697067 0.987092 0.1274605 0.1638607 0.978493 0.1253038 0.1734325 0.9756073 0.1345795 0.1584134 0.9815671 0.1069175 0.2253858 0.9683582 0.107162 0.2203125 0.9702315 0.1005646 0.2461912 0.967063 0.06464666 0.268776 0.9602964 0.07476943 0.2779355 0.9597052 0.04144716 0.327522 0.9435163 0.05006569 0.5305457 0.8475988 -0.009881496 0.6327366 0.7736464 -0.03340327 0.6756126 0.7367277 -0.02792865 0.6765097 0.7360023 -0.02520209 0.8157587 0.5783829 -0.00331068 0.8156945 0.5781882 -0.01846456 0.7355102 0.677025 0.02572757 0.403618 0.9145562 0.02606874 0.6147952 0.7870749 0.05039852 0.6765934 0.7342917 0.05511069 0.06000262 0.9980961 -0.01427841 -0.2888051 0.9559696 -0.0520935 -0.4326411 0.9005256 -0.04330742 -0.4913102 0.8678345 0.07401108 -0.4451018 0.8935096 0.05937319 -0.4339846 0.8942549 0.1093878 -0.332131 0.9399229 0.07895684 -0.3748593 0.9208213 0.1075583 -0.3507323 0.9242169 0.1510297 -0.3411753 0.928839 0.1444212 -0.513968 0.8363832 0.1905258 -0.3636575 0.9076246 0.2096924 -0.3281714 0.9225488 0.2029958 -0.3107178 0.9286499 0.2026422 -0.3276051 0.9207098 0.2120574 -0.5469666 0.8347038 0.06401067 -0.52159 0.8514454 0.05463129 -0.5204322 0.8493943 0.08763414 -0.4820794 0.8729698 0.07431942 -0.473185 0.8724995 0.121823 -0.429892 0.8962167 0.1094927 -0.4045338 0.8990058 0.1677525 -0.3233554 0.9340883 0.1513949 -0.3807235 0.906854 0.1807358 -0.3162491 0.93119 0.1813061 -0.3227747 0.9280881 0.1856585 0.8017201 0.5971279 -0.02614021 0.6963977 0.717066 -0.02909845 0.5751335 0.817784 -0.0212332 0.04693943 0.9988918 -0.003460943 0.4646164 0.8853117 -0.0188387 0.4666798 0.8843161 -0.01396924 0.3551211 0.9347714 -0.009574949 0.2847136 0.9528777 -0.1047022 0.4310471 0.9023077 -0.00626564 0.3380633 0.9407343 0.02706336 0.3202786 0.9463974 0.0418756 -0.06174063 0.9876197 0.1442065 -0.07017034 0.983477 0.1668806 -0.08968812 0.9784531 0.1859724 -0.1801446 0.9668701 0.1808596 -0.1823517 0.9651421 0.1877464 -0.2913967 0.954685 0.06053489 -0.2655275 0.962873 0.04869061 -0.2439287 0.9659228 0.08655631 -0.2291501 0.9702032 0.07871544 -0.1913745 0.9734696 0.1254307 -0.1951993 0.9723691 0.128046 -0.158384 0.9731637 0.1669341 -0.1644731 0.9711524 0.1726601 -0.172265 0.9648562 0.1984375 -0.0751239 0.9838864 0.1622472 -0.08334952 0.9778392 0.1920508 -0.5628183 0.8262813 -0.02224689 -0.4955108 0.8683034 -0.02276706 -0.4984437 0.8669146 0.00360471 -0.4521714 0.8919242 -0.003523886 -0.4561287 0.8895351 0.02595907 -0.4072796 0.9131115 0.01873582 -0.4090438 0.9117375 0.03765451 -0.3583738 0.9331539 0.0281437 -0.3583396 0.9330043 0.03310459 -0.1387766 0.9900788 0.02203094 -0.1330749 0.9904291 0.03662568 -0.1221753 0.9919694 0.0327121 -0.1015408 0.9928374 0.06295579 -0.1051803 0.9923548 0.06456881 -0.06782996 0.9922024 0.1045642 -0.05339163 0.9940031 0.09543216 -0.07363831 0.9883734 0.133024 0.2084302 0.9780148 0.006639659 0.444173 0.8953597 0.03227216 0.4441395 0.8953713 0.0324127 0.625956 0.7785031 0.04595649 0.7304699 0.6813273 0.04697751 0.0169816 0.9997889 0.01157069 -0.1952372 0.9807206 0.008335232 -0.1909484 0.9814679 -0.01610964 -0.3876528 0.9211459 -0.03486704 -0.05703693 0.997912 0.03030866 -0.1787548 0.9837935 0.01403969 0.1747893 0.9840431 0.03328478 0.01573818 0.9997462 0.01612347 0.4845069 0.8740479 0.03596395 0.3133555 0.9494224 0.0201407 0.7112575 0.7021291 0.03357958 -0.1202023 0.9925354 -0.02061688 0.1723979 0.9850079 0.006208479 0.1702373 0.9852797 0.01559668 0.5692791 0.8208582 0.0459696 0.5754016 0.8174864 0.02508056 0.8561275 0.5156863 0.03336709 0.7243487 0.688075 -0.04326498 0.7641128 0.6450813 0.001384079 0.4915986 0.8708087 0.00480324 0.5750222 0.8180971 0.008163392 0.1797958 0.9836439 0.01087677 0.2883545 0.9573914 0.0159254 -0.05432778 0.9983972 0.01585888 0.04673713 0.9986604 0.02220463 0.02825915 0.9916058 0.1261723 -0.01829797 0.9893618 0.1443204 0.01663911 0.9842004 0.1762744 0.02851885 0.990216 0.1365982 0.04729557 0.9870355 0.1533759 0.06258308 0.990804 0.1199619 0.06201428 0.9909016 0.1194499 0.08005917 0.9923816 0.09364551 0.07255458 0.9935921 0.0866639 0.09200894 0.9935057 0.06693863 0.07509577 0.9959218 0.05000388 0.1225607 0.9919377 0.0322265 0.1103267 0.9937656 0.01606494 0.1471026 0.9891061 0.005472719 0.144207 0.9895473 -8.76843e-4 -0.1894116 0.9817228 0.01853448 -0.1894153 0.9816884 0.02024096 -0.265373 0.9636573 0.03069281 -0.2634074 0.964546 0.01636439 -0.3442651 0.9385482 0.02467685 -0.3391008 0.9407368 -0.005016684 -0.4045283 0.9145229 0.002218902 -0.4000502 0.9159481 -0.03160756 -0.509162 0.8601869 -0.02885395 -0.6245141 0.7809901 0.006073117 -0.5663158 0.8240939 -0.01247894 -0.5693364 0.8218533 0.02033329 -0.5314103 0.8471146 -3.21031e-4 -0.5353339 0.8437401 0.03899049 -0.5030515 0.8640034 0.0209164 -0.504769 0.8617535 0.05088627 -0.4446321 0.8949868 0.03607106 -0.4442105 0.8939532 0.05936926 -0.3912041 0.9192215 0.04462462 -0.3818305 0.9207096 0.08061939 -0.3539183 0.9330258 0.06484305 -0.3346741 0.9363796 0.1057676 -0.3140423 0.9448366 0.09306746 -0.2818728 0.9491046 0.1405292 -0.2765903 0.9512034 0.1367853 -0.2438013 0.9535112 0.1771362 -0.257868 0.9475945 0.1885968 -0.250083 0.9477627 0.198001 -0.2732093 0.9371746 0.2169343 -0.2739279 0.9366639 0.2182299 -0.18101 0.9668817 0.1799313 -0.1777119 0.9591141 0.2202694 -0.09063446 0.9862219 0.1383905 -0.08237081 0.9848453 0.1526263 -0.1088083 -0.8518058 -0.5124331 -0.423423 -0.5301846 -0.7345865 -0.5714646 -0.3023847 -0.7628839 -0.3077382 -0.7180755 -0.6242313 -0.3163674 -0.7137324 -0.6248982 -0.1623661 -0.8079356 -0.5664604 -0.5643627 -0.1304921 -0.8151482 -0.4915541 -0.2671972 -0.8288427 -0.4731248 -0.3372966 -0.8138698 -0.3955529 -0.4415939 -0.8053153 0.3044297 -0.9404492 -0.1512548 0.02325159 -0.8983831 -0.438597 0.153315 -0.9377142 -0.3117477 0.1492738 -0.93671 -0.3166889 0.3029057 -0.9449922 -0.1234421 0.3077688 -0.9449567 -0.1110648 -0.01091533 -0.8728789 -0.4878148 -0.2472326 -0.6096376 -0.7531387 -0.250272 -0.6943267 -0.6747403 -0.392102 -0.4455554 -0.8048208 -0.4763162 -0.4827636 -0.7348892 -0.5757927 -0.2968896 -0.7617871 -0.5683129 -0.3939005 -0.7224007 -0.2729597 -0.8511139 -0.4484397 -0.5878366 -0.8037408 -0.09191823 -0.4184773 -0.9010566 0.1139022 0.07924646 -0.9861304 -0.1458318 -0.4916194 -0.8538604 -0.1709765 0.02608138 -0.9982471 -0.05312651 0.1210362 -0.9832246 -0.1364546 -0.01360344 -0.9958682 0.08978676 -0.004857301 -0.996941 0.07800704 -0.7525513 -0.6324609 0.1834662 -0.6838771 -0.3663017 -0.6309796 -0.8095019 -0.06513881 -0.5834926 -0.7188045 -0.5514724 -0.4233184 -0.861909 -0.3308469 -0.384257 -0.7769696 -0.5887769 -0.2228453 0.0166561 -0.9981921 0.05775159 0.3410702 -0.9257783 -0.163113 0.06436061 -0.9733751 -0.2199971 -0.09666013 -0.9448012 -0.3130616 -0.08840417 -0.9295606 -0.3579133 -0.2198156 -0.9437273 -0.2471032 -0.2314237 -0.9392779 -0.2533773 -0.4147183 -0.7495443 -0.5159381 -0.4138728 -0.7502175 -0.5156385 -0.5731847 -0.5172953 -0.6355037 -0.5227367 -0.5726791 -0.6314943 -0.5962404 -0.4058089 -0.692688 -0.4197759 -0.906134 -0.05205255 -0.4838824 -0.8566841 0.1787467 -0.4629873 -0.873817 0.1486157 -0.6047057 -0.5074704 -0.6138443 -0.7384934 -0.3217363 -0.5925482 -0.5505452 -0.7162704 -0.4287853 -0.7676478 -0.5102276 -0.3877947 -0.5366986 -0.7976651 -0.2751091 -0.8306903 -0.5528609 -0.06556344 -0.6950982 -0.7180165 -0.0359289 -0.9371731 -0.1853535 -0.2955515 -0.7751944 0.1330805 -0.6175463 -0.8917449 -0.4341254 -0.1277746 -0.9851359 -0.009138226 -0.1715338 -0.8115991 0.01168829 -0.584098 -0.7742041 0.05816322 -0.630258 -0.992077 -0.1165349 0.04693472 -0.986302 0.1167913 0.1164827 -0.9862979 0.1168355 0.1164734 -0.936618 0.04637545 0.3472694 -0.9366236 0.04633659 0.3472594 -0.9111614 -0.4120295 0.00409758 -0.9687523 -0.1889421 -0.1606859 -0.987191 -0.08589488 -0.1344474 -0.9922236 -0.1219439 0.02494454 -0.9154139 -0.1312 -0.3805311 -0.8223539 -0.04032248 -0.567546 -0.7774665 -0.04015845 -0.627641 -0.8819568 0.3047137 -0.3595858 -0.8182072 0.5224074 -0.2400574 -0.9161266 0.3280656 -0.2304022 -0.7616869 0.6466424 -0.04106909 -0.8075441 0.06405603 -0.5863186 -0.9034892 0.3152608 -0.2903755 -0.9061256 0.1158277 -0.4068421 -0.9618313 0.2104609 -0.174891 -0.9673145 0.1715632 -0.1867319 -0.9541339 0.2947963 0.05218988 -0.9895708 0.1373013 0.04356771 -0.7217745 0.6872994 -0.08161526 0.2902885 0.2600921 -0.9209151 -0.3984128 0.6951645 -0.5983424 -0.6401132 0.6216447 -0.4514565 0.0762968 -0.4465822 -0.8914837 -0.2700871 0.04518985 -0.9617749 -0.1731152 0.1146299 -0.9782082 -0.5672961 0.005565524 -0.8234951 -0.4789113 0.08153045 -0.874069 -0.1012499 -0.2883892 -0.952145 -0.7533577 0.1543237 -0.6392468 -0.5370824 -0.04357832 -0.8424034 -0.6469877 0.1238687 -0.752372 -0.4874197 0.2569204 -0.8345143 -0.2666893 0.7700877 -0.5795186 -0.254056 0.7462184 -0.6153159 -0.09588015 0.818843 -0.5659534 0.03280937 0.73864 -0.6733012 -0.1138553 0.8695329 -0.4805722 -0.2257857 0.9320074 -0.2835188 -0.2912507 0.9555003 -0.04682165 -0.3128264 0.9197372 -0.2371144 -0.3997008 0.877777 -0.2640963 -0.420538 0.9027351 -0.09064894 -0.4370989 0.8028939 -0.4053468 -0.5069386 0.6504874 -0.5655789 -0.5122212 0.6712859 -0.5357283 -0.6260054 0.5867007 -0.5137116 -0.623961 0.7803973 -0.04065483 -0.6564618 0.7381201 -0.1556816 0.3470737 0.06698644 -0.9354426 0.2580181 0.3153756 -0.9132168 0.1431347 0.06932544 -0.9872723 -0.008261144 0.4061321 -0.9137771 0.01890027 0.031008 -0.9993405 -0.03602522 0.1598907 -0.9864771 -0.2091767 0.15841 -0.964962 -0.2674382 0.2585394 -0.9282426 -0.4143009 0.1511766 -0.8974968 -0.7010874 0.7006533 -0.1325197 -0.6709383 0.7415133 -2.92128e-4 -0.7549623 0.5256661 -0.3920551 -0.7537853 0.58336 -0.3024882 -0.4065312 0.7159794 -0.5675438 -0.5037977 0.8338421 -0.2255998 -0.5686705 0.7914139 -0.2242282 -0.5629384 0.8124868 -0.1515446 -0.6082304 0.7502905 -0.2590754 -0.7507344 0.4374246 -0.4950329 -0.7251477 0.3013871 -0.619134 -0.5685968 0.4320508 -0.7000214 -0.5343747 0.3486502 -0.7699914 -0.3889016 0.4564883 -0.8002339 -0.3704948 0.4118271 -0.8325455 -0.250599 0.4900172 -0.8349152 -0.2310252 0.4460663 -0.8646689 -0.0825138 0.530953 -0.8433746 -0.06255537 0.4863305 -0.8715329 0.1357886 0.5749813 -0.8068197 0.1863098 0.4653317 -0.8653063 0.5008174 0.7125331 -0.4914049 0.4768083 0.801459 -0.3609953 0.4636929 0.8123172 -0.3537368 0.3182947 0.9274634 -0.1962147 0.3131542 0.9445618 -0.09867864 0.02203756 0.9753813 -0.2194215 -0.03016448 0.9827141 -0.1826556 0.09902995 0.9229512 -0.3719598 0.1798725 0.8437308 -0.5057315 0.25474 0.7896792 -0.5581348 0.3309452 0.6013736 -0.7272036 0.3888694 0.5136834 -0.7647941 0.4496617 0.2901447 -0.8447605 0.4463277 0.2965005 -0.8443217 0.4974246 0.1011968 -0.8615846 0.5551128 0.2920647 -0.7788119 0.5985059 0.1808758 -0.7804324 0.5550789 0.4150705 -0.7208356 0.5234455 0.5629903 -0.6395676 0.4983639 0.7162266 -0.488521 0.4744411 0.6056882 -0.6387859 0.3331553 0.8224807 -0.461013 0.3368326 0.8488457 -0.407437 0.1641762 0.9656782 -0.2012753 0.1624582 0.9781217 -0.1299434 0.6532625 0.3860009 -0.651346 0.492577 0.8681484 -0.06071496 0.7314109 0.1540369 -0.6643123 0.76276 0.5868785 -0.2716078 0.6848349 0.7188072 -0.1196557 0.6733689 0.7390691 -0.01873934 0.6701253 0.1573239 -0.7253836 0.6785905 0.1118439 -0.7259518 0.7318333 0.4178595 -0.5383434 0.7375351 0.6153334 -0.2782207 0.7712525 0.488101 -0.408567 0.7598776 0.5762421 -0.3008843 0.5055189 0.8473688 -0.1625329 0.5808981 0.7709453 -0.2611531 0.6197595 0.6785962 -0.3942149 0.6240395 0.6729047 -0.3972077 0.678317 0.5149055 -0.5241742 0.8746022 0.2642115 -0.4065259 0.7936924 0.6079245 -0.02191716 0.7463195 -0.1027016 -0.6576166 0.7540473 -0.6566631 -0.01436406 0.7823299 0.01379394 -0.6227118 0.9319037 0.2644452 -0.2482424 0.8456065 0.485251 -0.2224442 0.8780784 0.3682276 -0.3055925 0.8018085 -0.578975 -0.1479564 0.6648538 -0.7372083 0.1203883 0.6672435 -0.7366834 0.1099259 0.6576376 -0.7489896 0.08079266 0.662522 -0.7439556 0.08714765 0.6652103 -0.7407986 0.09334242 0.6672414 -0.738075 0.1001717 0.7810798 0.09909307 -0.6165184 0.7688984 0.02242791 -0.6389776 0.9412781 0.3033993 -0.148137 0.9040335 0.04571908 -0.4250097 0.9778688 0.08832728 -0.1896606 0.9768624 0.06664741 -0.2032193 0.9918305 0.1245718 0.02746355 0.6590959 -0.7401689 0.1332015 0.7401005 -0.6724386 -0.008814752 0.8932417 -0.4408065 0.08836829 0.896539 -0.4333291 0.09189057 0.8049917 -0.578657 -0.1309371 0.8151516 -0.4937452 -0.3028921 0.8067387 -0.5105595 -0.2974921 0.8408409 -0.3181494 -0.4379128 0.8789633 0.2924759 0.3766715 0.9711844 -0.2324829 -0.0524649 0.932558 -0.3607985 -0.01264894 0.9628441 -0.146524 -0.2268523 0.9424989 -0.2773464 -0.1864807 0.8893561 -0.1151781 -0.44247 0.8881037 -0.3363066 -0.3133205 0.770038 -0.08842563 -0.6318405 0.7389821 -0.02308911 -0.6733293 0.4096933 -0.8061882 -0.4268631 0.639649 -0.7583321 -0.1256248 0.4275172 -0.08518534 -0.8999847 0.3480641 -0.1784766 -0.9203246 0.4669842 -0.4049916 -0.7860711 0.4944184 -0.4854657 -0.7210227 0.505645 -0.03001642 -0.8622193 0.230895 0.395596 -0.8889271 0.6868783 -0.1484384 -0.7114523 0.6764372 -0.6856383 -0.2689478 0.6975673 -0.6010917 -0.3899856 0.5971142 -0.6733105 -0.4360135 0.5727823 -0.7761387 -0.2636842 0.510964 -0.6893539 -0.5135242 0.3344471 -0.9267523 -0.1711005 0.3336634 -0.9268431 -0.1721355 0.2209774 -0.904761 -0.3641108 0.1004433 -0.8423736 -0.5294506 -0.4518455 -0.08002948 -0.8884993 -0.5429716 0.4448204 -0.7122617 -0.3842796 -0.237062 -0.8922617 -0.2366569 -0.1670746 -0.9571205 -0.3542143 -0.2837068 -0.8910907 -0.2900472 -0.393489 -0.8723756 -0.1513954 -0.5927736 -0.7910115 -0.1717313 -0.5742902 -0.8004369 0.08761465 -0.8286082 -0.5529304 -0.1381782 -0.1886445 -0.9722757 0.4362324 -0.8827901 -0.1743071 0.3184084 -0.776993 -0.5430452 0.3109361 -0.7598165 -0.5709621 0.1484298 -0.5403816 -0.8282248 0.1318928 -0.5002635 -0.8557691 -0.0686534 -0.1531985 -0.9858078 -0.04492926 -0.2168761 -0.9751647 0.04725503 -0.1675658 -0.9847278 -0.2240473 -0.2054278 -0.9526816 -0.01953643 -0.5299352 -0.8478131 -0.001761138 -0.5676611 -0.8232605 0.2005804 -0.7947157 -0.5728826 0.2109549 -0.8103438 -0.5466637 0.3802195 -0.9046742 -0.192348 0.3807194 -0.9049895 -0.1898597 0.6978939 -0.5958197 -0.3974207 0.6905604 -0.4361639 -0.5769639 0.680451 -0.3574524 -0.6396985 0.6096327 -0.1493796 -0.7784817 0.4128485 -0.2852597 -0.8649758 0.04836142 0.2845172 -0.9574504 0.03549939 0.3036206 -0.9521315 0.2235558 -0.2735626 -0.935514 0.05576765 -0.05509543 -0.9969225 0.169079 -0.2860332 -0.9431847 0.2788657 -0.4698421 -0.8375454 0.2933799 -0.5113533 -0.8077414 0.4176663 -0.7231932 -0.5500423 0.4219651 -0.7414335 -0.5217489 0.4883629 -0.8577539 -0.160499 0.5375671 -0.8286926 -0.1558532 0.5352639 -0.8325157 -0.1428648 0.5812789 -0.803108 -0.1308906 0.5888162 -0.7927016 -0.1578603 0.6137796 -0.7882868 -0.04334163 0.5873553 -0.8091974 0.01461094 0.2946967 0.8688657 0.3977766 0.184622 0.9538357 0.2368798 0.2725738 0.8021982 0.5312076 0.1637985 0.9211245 0.3531286 -0.4595903 0.4024718 -0.7917027 0.3737208 0.9058652 0.1993517 0.3385546 0.8273422 0.4482029 0.3690078 0.7444456 0.5564477 0.3512654 0.7613645 0.5449192 0.3182491 0.7799957 0.5388175 0.3136954 0.8044475 0.5044398 0.3397475 0.7914231 0.5081546 0.3341786 0.792008 0.5109287 0.332457 0.827983 0.4515714 0.3279815 0.8272642 0.4561384 0.3176879 0.8193451 0.4772295 0.333791 0.8132945 0.4765875 0.3269761 0.8140518 0.4800066 0.3400691 0.835901 0.4308395 0.345105 0.8363878 0.4258617 0.3451035 0.8363879 0.4258626 0.3437376 0.8531165 0.3924752 0.3419945 0.872627 0.3486576 0.3727149 0.8454806 0.3824216 0.3577537 0.8546201 0.3763467 0.4309425 0.822062 0.3721597 0.3765592 0.8874273 0.2658494 0.3701183 0.8913601 0.2617052 0.3700871 0.8716125 0.3214455 0.3700384 0.8716503 0.321399 0.3636482 0.8729971 0.325017 0.2583332 0.9600557 0.1075043 0.3213474 0.9355138 0.1467987 0.3187111 0.9365922 0.1456652 0.3333646 0.9290898 0.160188 0.3500066 0.9207579 0.1723379 0.342157 0.9258853 0.1602037 0.3501579 0.9207133 0.1722691 0.2213184 0.9720911 0.07782649 0.2349585 0.9669167 0.09933155 0.2704779 0.9536936 0.1315688 0.3262475 0.9382491 0.1151145 0.3797954 0.9203152 0.09367817 0.223841 0.9722857 0.06749695 0.1762948 0.9837822 0.03305923 0.1478227 0.9851992 -0.08678132 0.1381224 0.9893931 -0.04498243 -0.07005101 0.9588686 -0.275071 -0.06663155 0.9672096 -0.2450831 -0.3618115 0.7370204 -0.5708708 -0.3601474 0.7408871 -0.5669041 -0.3209378 0.8050944 -0.4988209 -0.2706735 0.8493725 -0.4531033 -0.2293971 0.9000874 -0.3704318 -0.1411539 0.9419755 -0.3045618 -0.1448796 0.9409818 -0.3058813 -0.08009868 0.9625364 -0.259052 -0.07094407 0.959691 -0.2719561 -0.3577539 0.7354825 -0.5753936 -0.4119774 0.6425387 -0.6460795 -0.4233928 0.58414 -0.6924731 -0.3659027 0.6301206 -0.6848819 -0.3151059 0.7329403 -0.6029152 -0.3751887 0.5398036 -0.7535552 -0.2679821 0.7809692 -0.5641568 -0.2644569 0.7867305 -0.5577793 -0.2029723 0.9067158 -0.3696874 -0.2319594 0.8361281 -0.4970762 -0.1948174 0.8950901 -0.4010734 0.09936416 0.9559563 0.2761781 0.04216599 0.9925399 0.1143971 -0.08132416 0.984904 -0.1528093 -0.04264855 0.9980815 -0.04488492 -0.09889662 0.9779488 -0.1839451 0.1790024 0.9005152 0.3962709 0.3097376 0.8678358 0.3884892 0.2739586 0.8935089 0.3557931 0.3117257 0.8942544 0.3211482 0.2344094 0.93994 0.2481229 0.2805926 0.9208199 0.2708479 0.306163 0.9242127 0.2282435 0.2956581 0.9288366 0.2232686 0.4197975 0.8400068 0.3437421 0.3636646 0.9076246 0.2096807 0.3378004 0.9239909 0.179254 0.3308523 0.9286487 0.1677751 0.3474498 0.920708 0.1776951 0.3370375 0.827888 0.4483384 0.3081412 0.8514411 0.4243785 0.3360987 0.8493939 0.4069004 0.30539 0.8729699 0.3803428 0.3420925 0.8724997 0.34888 0.3097739 0.8962123 0.317559 0.3475481 0.8990012 0.2664719 0.2927829 0.9340904 0.2043362 0.3468858 0.9068512 0.2393559 0.3151424 0.9311882 0.1832318 0.322174 0.9280862 0.186708 0.1557586 0.9876195 -0.01862591 0.1796076 0.9834774 -0.02265894 0.1163063 0.9863322 -0.1167122 0.1207786 0.991141 -0.05524522 0.2059043 0.9784523 -0.01531112 0.2467064 0.9668685 0.06558579 0.2537696 0.9651417 0.0640518 0.1981109 0.9546865 0.2220941 0.1749169 0.962875 0.2056112 0.1969281 0.9659272 0.1679405 0.1827551 0.9702053 0.1590673 0.2043126 0.9734686 0.1030303 0.2084904 0.9723678 0.1050363 0.2237648 0.9731626 0.05370301 0.2317528 0.9711551 0.05611121 0.2579872 0.9648556 0.04996401 0.1780761 0.9838856 -0.01606643 0.2079963 0.977839 -0.02384305 0.2623351 0.8262944 0.4984154 0.2282466 0.8682793 0.4404482 0.2522684 0.8669046 0.4299268 0.2229457 0.891933 0.3933838 0.2504901 0.889544 0.3820555 0.2198259 0.9131107 0.3433737 0.237166 0.9117305 0.3354099 0.2035717 0.9331598 0.2962624 0.2078234 0.9330108 0.2937693 0.088458 0.9900808 0.1091571 0.09824019 0.9904308 0.09693109 0.0894007 0.991971 0.08944833 0.1052904 0.9928397 0.05642253 0.1085175 0.9923555 0.05877554 0.1244694 0.9922024 0.006466269 0.1093626 0.9940009 -0.001461565 0.1520202 0.9883737 -0.002715885 0.08148127 0.981507 0.1732195 0.1047438 0.9807613 0.1647306 0.09904354 0.9839417 0.1484901 0.1015191 0.9838057 0.1477175 0.0548321 0.9979064 0.03429639 0.04090297 0.9983941 0.03919506 -0.004219293 0.998657 -0.05163842 -0.4234277 0.583052 -0.6933681 -0.4167795 0.5523489 -0.7219457 -0.3634512 0.6957063 -0.6195935 -0.326269 0.7022482 -0.6327686 -0.2658092 0.8174386 -0.5110183 -0.1785087 0.9308521 -0.3188247 -0.1858749 0.9347591 -0.3027803 -0.2454684 0.8842889 -0.3972135 -0.2486276 0.8852784 -0.3930227 -0.3059869 0.8176966 -0.4875903 -0.2806223 0.8180123 -0.5021027 -0.2417015 0.870871 -0.4279767 -0.2108573 0.8741443 -0.4375057 -0.1391556 0.9493761 -0.2816397 -0.2697888 0.7807459 -0.5636044 -0.2684677 0.786577 -0.5560771 -0.19393 0.8951656 -0.4013352 -0.2445769 0.8208144 -0.5161839 -0.07168829 0.9851898 -0.1557626 -0.123512 0.9504821 -0.2851818 0.001553714 0.999786 -0.02062952 0.006107509 0.9997432 -0.02182477 -0.05841499 0.9840667 -0.1679306 -0.08049219 0.9836647 -0.1610116 -0.1305259 0.9573522 -0.2577593 -0.1513967 0.9573817 -0.2459665 -0.02650439 0.9988875 -0.03900408 -0.01600617 0.9705334 -0.2404347 -0.02053058 0.9680084 -0.2500765 0.01418411 0.9816728 -0.190046 0.01775538 0.9804018 -0.1962067 0.06908649 0.9871859 -0.143844 0.1059885 0.9922208 0.0653032 0.1443413 0.9841998 -0.10255 0.1040369 0.9902161 -0.09299784 0.1091771 0.9870368 -0.1176387 0.07259535 0.9908047 -0.1141749 0.07243478 0.9909042 -0.1134116 0.04106914 0.9923832 -0.1161425 0.03877961 0.9935915 -0.1061699 0.01196914 0.9935048 -0.1131593 0.005765557 0.9959191 -0.09006673 -0.03338235 0.991932 -0.1222972 -0.04127264 0.9937629 -0.1035954 -0.0688368 0.9891014 -0.1301531 -0.07287305 0.9895411 -0.1244918 0.1107327 0.9817318 0.1547287 0.1122074 0.9816976 0.1538815 0.1592952 0.9636473 0.2144975 0.1458792 0.964538 0.2199677 0.1934562 0.938562 0.2857907 0.1651345 0.9407508 0.2961735 0.2041007 0.9145364 0.3492363 0.1728116 0.9159529 0.3621692 0.229803 0.8601846 0.4552724 0.3176121 0.7810113 0.537721 0.2725387 0.8240424 0.4966657 0.3022402 0.8218167 0.4829787 0.2653407 0.8471155 0.4604235 0.301386 0.8437408 0.4441486 0.2695844 0.8640078 0.4252235 0.2964873 0.8617498 0.4116827 0.2535818 0.8949881 0.3670049 0.2735059 0.8939566 0.3550158 0.2342379 0.9192221 0.3164864 0.2607241 0.9207102 0.290372 0.2331017 0.933028 0.2740847 0.2589403 0.9363838 0.236929 0.2376323 0.9448384 0.2254142 0.2626364 0.9491024 0.1738585 0.2567533 0.9512015 0.1711539 0.2753075 0.9535099 0.122576 0.2922654 0.9475932 0.129028 0.2965162 0.9477616 0.117585 0.3244878 0.9371688 0.1281504 0.3259507 0.9366647 0.1281232 0.2463294 0.966881 0.06680607 0.2796124 0.9591141 0.04378437 0.166157 0.9860526 0.009603917 0.1768975 0.9841781 -0.01004356 0.9102937 -0.06418532 -0.4089568 0.9076164 0.01250088 -0.4196144 0.888418 0.1206893 -0.4428856 0.9132429 0 -0.4074156 0.9551275 0.04417955 -0.2928818 0.9164254 0.001397371 -0.4002034 0.9747353 -2.32072e-4 -0.2233628 0.9756383 4.43205e-5 -0.2193857 0.9971607 1.62362e-4 -0.07530367 0.9984109 0.007847845 -0.0558049 0.9960789 -6.12987e-4 0.08846795 0.9597541 6.03804e-4 0.2808414 0.9848386 7.48336e-4 0.1734724 0.9798712 -0.003593623 0.1995989 0.9911369 0.003187954 0.1328064 0.9191174 0.04146796 0.3917955 0.9486395 -0.0634998 0.3099208 0.8562715 0.03182828 0.5155447 0.8709514 0.001771628 0.491366 0.7594125 -0.001418054 0.6506079 0.7759448 -0.07604134 0.6262009 0.6397455 0.08010464 0.7644012 0.7555331 0.06852132 -0.6515172 0.7345926 0.1632163 -0.658585 0.6979579 0.3204978 -0.6404186 0.6118889 -0.05801993 -0.7888128 0.4520801 -0.006028413 -0.8919571 0.397168 -0.03452771 -0.9170963 0.4883303 -1.91055e-4 -0.8726589 0.5927354 -3.485e-5 -0.8053973 0.6208336 0.002736449 -0.7839377 0.7367695 -0.01231944 -0.6760318 0.7016832 -0.02891314 -0.7119022 0.771113 0 -0.6366982 0.7937033 -0.05668109 -0.6056588 0.7711768 0.01182341 -0.6365115 0.05626744 1.68743e-4 -0.9984157 0.2487916 -4.41454e-4 -0.968557 0.1866639 0.02520203 -0.9821006 0.2779613 0.00323373 -0.9605869 -0.4388745 -0.1098327 -0.8918106 -0.3920183 -0.03113311 -0.9194305 -0.2852289 0.08472675 -0.9547073 -0.3231914 0.004114151 -0.9463247 -0.1246458 -1.42617e-4 -0.9922013 -0.1873918 -0.1003139 -0.9771497 0.06877279 0.2706175 -0.9602274 -0.09456402 -0.1083166 -0.9896087 -0.02345424 -0.04914408 -0.9985163 -0.978542 0.0809217 -0.1894924 -0.9368234 0.0118221 -0.3496032 -0.9359292 0.004696309 -0.3521571 -0.9716237 -5.98194e-4 -0.2365317 -0.9775509 0.01106846 -0.2104086 -0.9213677 -0.05667203 -0.3845386 -0.9369531 0 -0.3494552 -0.9673672 -0.02891445 -0.2517236 -0.9359227 0.005947589 -0.3521554 -0.9887186 -0.003661572 -0.1497398 -0.9862588 3.43052e-5 -0.1652086 -0.9999099 -1.91051e-4 0.01341795 -0.9999894 0.004570066 -6.22569e-4 -0.9905982 -0.001832544 0.1367918 -0.8927949 1.53301e-4 0.4504637 -0.9631975 -4.57423e-4 0.2687942 -0.943856 0.02519714 0.329395 -0.9825555 -0.009701848 0.1857168 -0.8530147 -0.04916387 0.5195662 -0.9195679 0.07595539 0.38552 -0.8047554 -0.08833938 0.5869965 -0.8369702 0.02165883 0.5468198 -0.7201598 8.181e-4 0.6938077 -0.7256602 0.002140343 0.6880499 -0.6579429 0.004089176 0.7530568 -0.6201988 -0.09106904 0.7791405 -0.5949816 -0.1576407 0.7881284 -0.4568173 0.1415488 0.8782266 -0.6963645 0.0287308 -0.717113 -0.864521 -0.03992891 -0.5010082 -0.7312125 0.04417377 -0.680718 -0.8094539 0 -0.5871835 -0.8277584 0.1206982 -0.5479488 -0.8172057 0.01249587 -0.5762107 -0.7278063 0.5407401 -0.4217798 -0.7779093 -0.04047966 -0.6270715 -0.7545794 -4.56965e-5 -0.6562088 -0.63628 8.88438e-5 -0.7714583 -0.5593502 -0.006603002 -0.8289052 -0.4455024 0.03297746 -0.8946732 -0.2366761 5.9698e-4 -0.9715884 -0.3421959 7.40803e-4 -0.9396284 -0.3170702 -0.003602027 -0.9483953 -0.4799297 0.01416796 -0.8771926 -0.1202687 0.04146021 -0.9918752 -0.1521214 0.00283885 -0.9883578 0.04066383 -0.001236498 -0.9991722 0.04515969 8.81611e-4 -0.9989795 0.1837539 -0.001406252 -0.9829714 0.2085429 0.06398773 -0.9759178 0.3935534 -0.06708019 -0.9168512 -0.3646414 -0.305814 0.8794967 -0.3893721 -0.8517928 0.3504832 -0.4244591 -0.5301623 0.7340043 -0.3867207 -0.7180755 0.5786319 -0.3829867 -0.7137196 0.5864518 -0.409375 -0.807927 0.4238706 -0.4237601 -0.1304806 0.8963271 -0.4720247 -0.2671891 0.8401207 -0.4682722 -0.3372821 0.8166774 -0.4996182 -0.4415541 0.7452595 -0.2831987 -0.9404481 -0.1880322 -0.3914608 -0.898379 0.1991823 -0.3466478 -0.9377114 0.02308237 -0.3488643 -0.9367238 0.02902263 -0.2583527 -0.9449907 -0.2006156 -0.2500612 -0.9449558 -0.2110161 -0.3854403 -0.3796133 0.8410289 -0.39827 -0.4827548 0.7799543 -0.500959 -0.4455386 0.7419808 -0.4592332 -0.6943134 0.5541064 -0.5286399 -0.6096259 0.5906744 -0.4170194 -0.8728799 0.2533293 -0.2519073 -0.8510993 0.4606221 -0.3017637 -0.4058222 0.8626977 0.3806025 -0.8620423 0.3347012 0.3078762 -0.9010645 0.3054425 -0.05906224 -0.9982465 0.003955245 0.3164342 -0.7180243 0.6199279 0.5445075 -0.6276192 0.5564222 -0.2045126 -0.3663035 0.9077425 -0.1005913 -0.06519865 0.9927893 -0.00714457 -0.5514295 0.8341909 0.09820008 -0.3308189 0.9385712 0.1954793 -0.5887869 0.7842946 -0.1787059 -0.9832211 -0.03661489 0.0750001 -0.9966274 -0.03330051 0.04167246 -0.9981918 -0.04331988 -0.2228444 -0.9447865 0.2402475 -0.1659247 -0.9861291 0.0042997 -0.2227036 -0.9733758 0.05424642 -0.3118113 -0.9257676 -0.2138414 -0.2855226 -0.5726558 0.7684674 -0.2637698 -0.5172895 0.8141482 -0.2396218 -0.7502033 0.6162601 -0.2394595 -0.7495358 0.6171347 -0.1037291 -0.9392794 0.3271001 0.5083987 -0.6620406 0.5506659 0.1647908 -0.9061468 0.3895407 0.2143039 -0.8037524 0.555028 0.09772336 -0.8538741 0.5112234 -0.1040989 -0.9437326 0.3138985 -0.2657546 -0.9295663 0.2555015 -0.2292574 -0.5074592 0.830618 -0.1439191 -0.3217363 0.9358275 -0.09607887 -0.7162573 0.6911906 0.04797428 -0.5102229 0.8587033 0.03008651 -0.7976847 0.6023238 0.3585777 -0.5528651 0.7521717 0.2126243 -0.1853718 0.9593895 -0.1472132 0.1330971 0.9801089 0.3352223 -0.4341177 0.8361626 0.3440206 -0.0091421 0.9389177 -0.1000531 0.01168465 0.9949135 -0.1587237 0.05816006 0.9856086 0.5940399 0.1168293 0.7959068 0.5940337 0.1168395 0.7959098 0.4651856 -0.4252125 0.7763998 0.7690571 0.04635953 0.6374968 0.7690629 0.04634571 0.6374908 0.345223 -0.1889718 0.9192991 0.3771657 -0.08589839 0.9221537 0.5178452 -0.1219728 0.8467344 0.128142 -0.1312025 0.983039 -0.08030807 -0.0403189 0.9959543 -0.1548221 -0.04015398 0.987126 0.1295574 0.304723 0.9435883 0.2012138 0.5223948 0.8286234 0.2585219 0.3280798 0.9085869 0.3452866 0.6466459 0.6801664 -0.1039728 0.06405693 0.9925153 0.2002784 0.3152796 0.9276246 0.1007122 0.1158226 0.9881509 0.3294608 0.2104538 0.9204156 0.3219554 0.1715906 0.9310755 0.5222678 0.2948074 0.8002031 0.5214603 -0.1076391 0.8464592 0.5939717 0.11695 0.7959399 0.5940356 0.1168568 0.795906 0.2902157 0.6873051 0.6658728 -0.9426811 0.2600845 0.2090655 -0.3189336 0.6951829 0.6442067 -0.07090073 0.6216534 0.780077 -0.8102015 -0.4465658 0.3796743 -0.6978715 0.04519289 0.7147957 -0.7605941 0.11462 0.6390298 -0.4295275 0.005573332 0.9030366 -0.5175123 0.08153784 0.8517822 -0.7739374 -0.2883492 0.5638048 -0.1769077 0.1543394 0.972051 -0.4609794 -0.04353708 0.8863423 -0.3280972 0.1238554 0.9364894 -0.4789953 0.2569109 0.839381 -0.3684983 0.7701057 0.5207172 -0.4058224 0.7462343 0.5276766 -0.4421646 0.8188553 0.3660144 -0.5995037 0.7386428 0.3082242 -0.3592432 0.8695418 0.3388828 -0.1326154 0.9320139 0.3372882 0.1049573 0.9555025 0.275679 -0.04890674 0.9197326 0.3894869 -0.02884238 0.8777819 0.4781916 0.1317763 0.9027377 0.4095114 -0.1324648 0.8029024 0.5812066 -0.2363083 0.6505025 0.7218067 -0.2078164 0.6712961 0.711459 -0.1318694 0.5867189 0.7989816 0.2767907 0.780399 0.5606822 0.1934158 0.7381234 0.6463468 -0.98365 0.06700849 0.1671602 -0.9198764 0.3153853 0.2331514 -0.9265732 0.0693041 0.3696742 -0.7872157 0.4061434 0.4640465 -0.8749026 0.03099566 0.4833064 -0.8363 0.1598793 0.5244434 -0.7310911 0.1584038 0.6636371 -0.6701757 0.2585307 0.69572 -0.5701299 0.1511668 0.8075274 0.2357866 0.7006565 0.6734132 0.3352183 0.7415096 0.5811989 0.03795737 0.5256798 0.8498353 0.1149257 0.5833585 0.8040429 -0.2882044 0.7159954 0.6358371 0.0565437 0.8338437 0.5490971 0.09016895 0.7914183 0.6045881 0.1502523 0.8124935 0.563275 0.07976883 0.7502955 0.6562727 -0.05333274 0.4374327 0.8976683 -0.1736372 0.3013735 0.9375629 -0.321954 0.4320363 0.8424312 -0.3996675 0.34863 0.8477753 -0.4985877 0.4564695 0.7369165 -0.5357726 0.4118058 0.7371321 -0.5977685 0.4900063 0.6344815 -0.6333213 0.4460485 0.632412 -0.6891401 0.5309379 0.4931439 -0.7235032 0.486315 0.4899398 -0.7666321 0.5749709 0.2858039 -0.842552 0.4653062 0.2712867 -0.6759908 0.7125235 -0.1880072 -0.5510174 0.801473 -0.232424 -0.5381799 0.8123285 -0.2246885 -0.329059 0.9274717 -0.1775291 -0.2420089 0.9445691 -0.2218584 -0.2010162 0.9753865 0.09062904 -0.1430748 0.9827177 0.1174548 -0.371632 0.9229538 0.1002304 -0.5278905 0.8437427 0.097108 -0.610731 0.7896769 0.05846697 -0.795273 0.6013411 0.07700544 -0.8567835 0.5136541 0.0456261 -0.9564245 0.2901134 0.0329585 -0.9543671 0.2965021 0.0356397 -0.9948621 0.1012398 6.75921e-6 -0.9520333 0.2920466 -0.09133189 -0.9751331 0.180846 -0.1281023 -0.9018017 0.4150701 -0.120294 -0.8155951 0.5630041 -0.1335327 -0.6722732 0.7162086 -0.1873336 -0.7904459 0.6056624 -0.09147995 -0.5658084 0.8224937 -0.05800962 -0.5212436 0.848861 -0.08797848 -0.2563774 0.9656838 -0.04153817 -0.1937394 0.978127 -0.07571458 -0.8907237 0.3859828 -0.2400596 -0.2988542 0.8681548 -0.3962239 -0.9410107 0.1540572 -0.3012729 -0.6165891 0.5868926 -0.524762 -0.4460339 0.7188125 -0.5332565 -0.3528964 0.7390754 -0.5737872 -0.9632682 0.1573048 -0.2176457 -0.9679885 0.1118569 -0.2246919 -0.8321273 0.41787 -0.3646215 -0.6097289 0.615324 -0.4996068 -0.7394485 0.4881052 -0.4636478 -0.6405202 0.5762407 -0.5076225 -0.393501 0.8473784 -0.3565204 -0.5165954 0.7709585 -0.3724945 -0.6512739 0.6786099 -0.3396043 -0.6560162 0.6729013 -0.3418285 -0.7931005 0.5149173 -0.3253487 -0.7893515 0.2642264 -0.5541738 -0.4158183 0.6079322 -0.6763977 -0.9426734 -0.1026973 -0.3175221 -0.3894463 -0.6566846 -0.6458304 -0.9304594 0.01379173 -0.3661356 -0.6809334 0.2644462 -0.6829333 -0.6154398 0.4852465 -0.6211037 -0.7036953 0.368234 -0.607632 -0.5290443 -0.5789781 -0.6204003 -0.231339 -0.7368068 -0.6352937 -0.2408381 -0.7369107 -0.6316326 -0.2584529 -0.7478314 -0.6115149 -0.2541203 -0.7422859 -0.6200279 -0.2482254 -0.7386254 -0.626751 -0.3688861 -0.4350375 -0.8213803 -0.398943 -0.6435507 -0.6532129 -0.2007883 -0.7443692 -0.6368663 -0.2185974 -0.739059 -0.6371868 -0.9526103 -0.02308744 -0.3033159 -0.9244524 0.09910893 -0.3681918 -0.9378143 0.02240478 -0.3464137 -0.5988696 0.3034647 -0.7411238 -0.8200907 0.04569852 -0.5704059 -0.6531786 0.08831214 -0.7520363 -0.6644064 0.06668692 -0.7443904 -0.4721181 0.1245951 -0.8726859 -0.3667996 -0.4256383 -0.8272184 -0.4916264 -0.8338743 -0.2509127 -0.5158745 -0.578661 -0.6316843 -0.6698844 -0.4937488 -0.5544971 -0.661001 -0.5105412 -0.5499323 -0.7996555 -0.3181439 -0.5092502 -0.9322207 -0.08839154 -0.3509296 -0.7154105 -0.3362956 -0.6124486 -0.8278732 -0.1151903 -0.5489603 -0.6327383 -0.2773605 -0.7229893 -0.6778544 -0.1465656 -0.7204388 -0.4307476 -0.4005569 -0.8087094 -0.4901976 0.04920804 -0.8702213 -0.5744937 -0.8062014 -0.1414082 -0.4286108 -0.7583371 -0.4911392 -0.9931687 -0.08518278 0.07974952 -0.9710612 -0.1784642 0.1587162 -0.9142517 -0.4049869 -0.01138794 -0.8716397 -0.4854537 -0.06766891 -0.9995269 -0.0300002 -0.006796419 -0.8852995 0.3955705 0.2444769 -0.9595759 -0.1484353 -0.2391257 -0.5711243 -0.6856494 -0.4513337 -0.6865181 -0.6010972 -0.4091151 -0.6761511 -0.673312 -0.2991166 -0.514751 -0.7761371 -0.3642015 -0.7002012 -0.6893562 -0.1857591 -0.3153951 -0.926751 -0.2041045 -0.3158937 -0.9268417 -0.2029173 -0.4258093 -0.9047648 -0.009334206 -0.50873 -0.8423832 0.1777203 -0.5435399 -0.08001679 0.8355607 -0.3453315 0.4448596 0.826345 -0.5805765 -0.237057 0.778932 -0.7105504 -0.1670746 0.6835234 -0.5945935 -0.2836928 0.7523145 -0.6104682 -0.3934594 0.6873997 -0.6093305 -0.5927643 0.5266374 -0.6073306 -0.5742891 0.5489459 -0.52265 -0.8286187 0.2005696 -0.7729198 -0.1886451 0.6058117 -0.369047 -0.8827922 -0.2906585 -0.629482 -0.7770037 -0.004238963 -0.6499206 -0.7598296 0.01618915 -0.7914736 -0.540385 0.2855762 -0.8070619 -0.5002608 0.3136723 -0.8194015 -0.1531996 0.5523688 -0.8220434 -0.2168895 0.5265014 -0.8764255 -0.1675708 0.4514403 -0.7130115 -0.2054259 0.6703841 -0.7244542 -0.529926 0.4408453 -0.7120772 -0.5676614 0.4131668 -0.5964083 -0.7947275 0.1127196 -0.5788892 -0.810355 0.09062159 -0.3566703 -0.9046759 -0.233126 -0.3547799 -0.9049881 -0.2347931 -0.693129 -0.5958141 -0.405682 -0.8449449 -0.4361677 -0.3095574 -0.8942295 -0.3574364 -0.2694303 -0.9790009 -0.1493843 -0.1387143 -0.9555153 -0.2852623 0.07494074 -0.8533526 0.2845391 0.4368376 -0.8423147 0.3036413 0.4453177 -0.921957 -0.2735874 0.2741265 -0.8912414 -0.05508482 0.4501714 -0.9013597 -0.2860418 0.3251629 -0.8647712 -0.4698361 0.1772702 -0.8462129 -0.5113554 0.1497981 -0.6851722 -0.7232022 -0.08670443 -0.6628241 -0.7414379 -0.1045669 -0.3831691 -0.8577525 -0.3426985 -0.4037451 -0.828696 -0.3876248 -0.39135 -0.8325164 -0.3921247 -0.4039875 -0.8031125 -0.437955 -0.4310958 -0.7927107 -0.4310061 -0.3444331 -0.78829 -0.5098675 -0.2810196 -0.8091999 -0.5159685 0.2408686 0.7023803 -0.6698092 0.2246479 -0.9545527 0.1958634 -0.01182484 -0.8269369 0.5621706 -0.3830839 0.5479269 0.7436552 -0.06811761 -0.9904581 0.1198033 0.206768 0.7690778 -0.6047864 -0.396479 -0.7561447 0.5206242 -0.5328608 -0.4272468 0.7304243 0.3338477 0.5801343 -0.7429603 0.3521901 0.1042443 -0.930105 0.3521856 0.1043267 -0.9300975 0.3559339 0.2512785 -0.9000945 0.3516609 0.104064 -0.9303255 0.3363789 -0.07605743 -0.9386504 0.3522232 0.1042675 -0.9300899 0.2859363 -0.3738672 -0.882306 0.3537012 0.1047467 -0.929475 0.217058 -0.6153384 -0.7577891 0.2088121 -0.637758 -0.7413921 0.1641713 -0.7423959 -0.6495353 0.09007751 -0.8705707 -0.4837279 0.1108312 -0.839372 -0.5321383 -0.01801395 -0.9753927 -0.2197379 -0.2074168 -0.9260107 0.3154086 -0.1721628 -0.9630308 0.2071996 -0.1173496 -0.991933 0.04793894 -0.04360044 -0.9968135 0.06679892 -0.3107046 0.820428 0.4799589 -0.2255971 0.8909395 0.3941228 -0.4570035 -0.3177172 0.8307849 0.102432 0.8578681 -0.5035574 0.09425544 0.8636953 -0.4951227 0.08945339 0.861459 -0.4998867 -0.5257262 -0.4523134 0.7204336 -0.4701964 0.5931345 0.6535341 -0.4544885 0.5929123 0.6647521 -0.4832511 0.5177683 0.7059634 -0.4639786 0.5177779 0.7187697 -0.4210937 -0.7163022 0.5564095 -0.4893516 -0.5776948 0.6533022 -0.4657459 -0.5780276 0.6700485 -0.4543952 -0.6054768 0.6533934 -0.4356104 -0.6055927 0.6659588 0.01636278 -0.9997009 -0.01817864 -0.5808019 0.1333675 0.8030457 -0.4131495 0.7043467 0.5772377 -0.4041385 0.7041494 0.5838201 0.1689958 -0.9520882 -0.2548894 -0.1451126 0.9646008 0.2201992 -0.3262706 0.8040305 0.497074 -0.5345779 -0.03718638 0.8443008 -0.4884818 0.4119622 0.7692028 -0.4704382 0.4120677 0.7803129 -0.4867101 0.3308961 0.8084685 -0.4627525 0.3309366 0.8223996 -0.4437312 -0.6748176 0.5896812 -0.5502631 -0.3826376 0.7421584 -0.5260106 -0.3830209 0.759347 -0.5162075 -0.4228621 0.7447937 -0.4898549 -0.4228889 0.7623695 -0.4773799 -0.4685657 0.7433403 -0.452149 -0.4684277 0.7590368 -0.4415622 -0.504716 0.7418118 -0.4175339 -0.5046775 0.7556232 -0.4133378 -0.5186108 0.7484616 -0.398091 -0.5186095 0.756682 -0.1692224 -0.9284594 0.3306463 -0.2834547 -0.7975571 0.5325 -0.2795102 -0.8172724 0.5039247 -0.2897086 -0.8025292 0.5215513 -0.3033735 -0.8026056 0.5136038 -0.3715742 -0.5167803 0.7712787 -0.3984609 -0.5172758 0.7574 -0.3425226 -0.6719672 0.6566113 0.01932758 -0.9982536 -0.05582344 -0.4692631 0.5510174 0.6900523 -0.3593055 -0.7790496 0.5137913 -0.3437605 -0.7791916 0.5241081 -0.4388435 -0.5976977 0.6709499 -0.2011092 -0.9235959 0.3263829 -0.5190204 -0.2342886 0.8220261 -0.293696 -0.8171797 0.4959436 -0.3845019 -0.6573738 0.6480879 -0.3681683 -0.6574679 0.6574102 -0.2743869 0.834952 0.4770399 -0.4652523 -0.2540627 0.8479343 -0.3293845 -0.699234 0.6344901 -0.2642869 -0.8177515 0.5113072 0.25834 -0.8416285 -0.4742596 -0.236243 0.8727974 0.4270997 -0.2181767 0.8941652 0.3909828 -0.4505278 0.3170633 0.8345631 -0.4470736 0.339903 0.8274004 -0.4416583 0.3403463 0.8301219 -0.4634604 -0.6336871 0.6193911 -0.5815466 -0.1950041 0.7897955 -0.5575033 -0.1953247 0.8068695 -0.5511486 -0.2464362 0.7971854 -0.5242861 -0.2465711 0.8150624 -0.5145165 -0.3079404 0.8002785 -0.4878461 -0.3077836 0.8168693 -0.4791455 -0.3544885 0.802968 -0.4536671 -0.3544188 0.8176634 -0.4506922 -0.3690258 0.8128324 -0.4347299 -0.3688144 0.8215752 -0.4355832 -0.3643308 0.8231223 -0.4084108 -0.3639084 0.8371209 -0.4268343 -0.2545133 0.8677762 -0.3813742 -0.2522876 0.8893283 -0.4372113 0.1290825 0.8900472 0.1944314 -0.9319611 -0.3060146 -0.333296 0.669744 0.6635939 -0.2964096 0.7732904 0.5605028 -0.2917512 0.7827868 0.54966 -0.3650666 0.5770149 0.7306026 -0.3714993 0.5765807 0.7276972 0.1979531 -0.9168756 -0.3466323 0.07069474 -0.9929164 -0.09549576 -0.3839674 -0.5248017 0.7597054 -0.3211485 0.73729 0.5943629 -0.4652931 0.01578623 0.8850159 -0.2441763 0.8662617 0.4358542 -0.429785 0.4317625 0.7930107 -0.4355552 0.4306837 0.790445 -0.4566468 0.3156418 0.8317717 -0.3362498 -0.709236 0.6196131 -0.02549028 -0.9979251 0.05912631 -0.2051873 0.9148883 0.3476747 -0.09470784 0.9838683 0.151768 -0.4819006 -0.5902152 0.6476247 -0.5907056 -0.002451717 0.8068835 -0.5676137 -0.002856254 0.8232901 -0.5667241 -0.06422072 0.821401 -0.5401648 -0.06416147 0.8391098 -0.5356984 -0.1407711 0.8325927 -0.5084518 -0.1404601 0.8495574 -0.5030135 -0.1987517 0.8411155 -0.4767073 -0.1986953 0.8563122 -0.4751926 -0.2120943 0.8539368 -0.4588741 -0.211811 0.8628851 -0.4596891 -0.2046726 0.8641732 -0.4330104 -0.2042495 0.8779432 -0.4451045 -0.05365163 0.89387 -0.4040606 -0.05214577 0.9132448 -0.4094477 0.04832047 0.9110531 -0.3567246 0.05249631 0.9327335 -0.2753651 0.8193511 0.5028297 -0.2759908 0.8198053 0.5017455 0.2699036 -0.8331916 -0.4826424 -0.4992302 -0.5431147 0.6751264 -0.5776403 0.1919767 0.7933956 -0.5562198 0.1916635 0.8086314 -0.5628084 0.122159 0.8175109 -0.5375678 0.122236 0.8343136 -0.541115 0.03200483 0.8403394 -0.5141 0.0325042 0.8571142 -0.5137169 -0.03523564 0.857236 -0.4873445 -0.03465938 0.8725218 -0.4869461 -0.04754549 0.8721371 -0.4707153 -0.04736757 0.8810127 -0.4710549 -0.03607094 0.8813661 -0.4455884 -0.03556841 0.8945311 -0.4449444 0.1503012 0.8828557 -0.4100058 0.151607 0.8993946 -0.4055995 0.2730045 0.8723288 -0.3640428 0.2761198 0.8895115 -0.360509 0.3927145 0.8460547 -0.2934996 0.4021925 0.8672366 -0.08448439 -0.8234928 0.5610011 -0.3150721 0.7119688 0.6275587 0.2536504 -0.8681951 -0.4264963 -0.2251578 0.9274431 0.2985855 -0.2409074 0.8956574 0.3738468 0.200465 -0.9248011 -0.3233525 0.2862551 -0.7943369 -0.5358051 -0.3483251 0.6302048 0.6939103 -0.3009765 0.7623372 0.5729357 -0.2949419 0.7761935 0.5572549 -0.2824953 0.8038653 0.5234472 -0.2797054 0.8105478 0.514565 -0.3191734 0.711425 0.6261014 -0.3118192 0.7120121 0.6291324 -0.2726614 0.8280203 0.489937 -0.26686 0.8288027 0.4918047 0.1788095 -0.9803389 -0.08344441 -0.5158059 -0.4909376 0.7020859 -0.5398686 0.3907951 0.7455341 -0.5208327 0.3904017 0.7591574 -0.5371797 0.3155988 0.7821992 -0.5143423 0.3155839 0.7974077 -0.5290493 0.2153728 0.8208054 -0.5031272 0.2154101 0.8369359 -0.5097519 0.1397461 0.8488957 -0.4840641 0.139959 0.863767 -0.4846425 0.1294954 0.8650739 -0.4689698 0.1299108 0.8736078 -0.4682681 0.1438239 0.8718025 -0.444918 0.1439612 0.8839249 -0.4243372 0.3610313 0.8304182 -0.3973043 0.3624249 0.8430882 -0.3782971 0.4969736 0.7809665 -0.3510096 0.4987073 0.7925171 -0.3324242 0.62569 0.7056956 -0.2906016 0.6314839 0.7188733 -0.2877207 0.6731191 0.681269 -0.1911454 0.6887788 0.6993191 -0.2166463 0.9424697 0.2545884 -0.01802986 -0.2950444 0.9553135 0.06862592 -0.8124904 0.5789214 0.06968826 -0.8151069 0.5751037 0.1558877 -0.8022552 0.5762687 -0.1282821 0.9439684 0.3040847 -0.1935724 0.9310721 0.3092484 0.1957256 -0.9805362 -0.01550161 -0.2292402 0.8689119 0.4386811 -0.2490685 0.865459 0.4346787 -0.2193245 0.9420841 0.2537213 -0.2288188 0.9230932 0.3090972 0.2664129 -0.8303126 0.4894949 0.2414717 -0.8908396 0.384833 0.01072317 0.809415 0.5871393 -0.2006964 0.7699501 0.6057209 -0.1609183 0.4640253 0.8710833 -0.2950111 0.441796 0.8472218 -0.276435 0.1597807 0.9476571 -0.3624603 0.1474415 0.9202628 -0.3311328 -0.1722396 0.9277309 -0.3921896 -0.1772652 0.9026431 -0.3423839 -0.4450675 0.8274589 -0.3902838 -0.4470716 0.8048637 -0.2886612 0.7933987 0.5359042 -0.3291552 -0.6716279 0.6637567 0.1316142 -0.9664762 -0.2204574 -0.2466294 -0.817322 0.520729 0.2228808 0.08506965 0.9711269 0.2670981 -0.2392258 0.9335041 0.2633122 -0.2049523 0.9426884 -0.1670596 0.9857142 -0.02141523 0.3413112 -0.5219618 0.7817049 -0.05746769 -0.8199222 0.5695834 -0.2088022 -0.258494 0.9431769 -0.1167822 -0.5937073 0.7961618 -0.01191294 -0.575013 0.8180576 -0.2081967 0.9230102 0.3235837 0.107573 -0.5790398 0.8081714 0.224289 -0.5568045 0.7997895 -0.1923815 0.9664231 -0.1703401 -0.1127037 0.9930111 0.03502953 -0.08816742 0.9957734 0.02572411 0.1100251 0.9937735 0.01757526 0.03820663 0.9975151 0.05919408 -0.3401232 0.7701417 -0.5396277 0.328952 -0.7907687 0.5162127 0.03147542 0.9770656 0.2105997 -0.03174626 0.9715144 0.2348444 0.3340556 -0.3601086 0.8710504 -0.1074593 0.9867971 0.1211776 -0.1635523 0.9863896 -0.01691919 -0.2040105 0.9644204 -0.1681465 -0.1660793 0.9803758 0.1062127 -0.1952195 0.9747634 0.1082859 0.1997963 -0.9789152 0.04250353 -0.2062712 0.9579971 0.1992331 -0.2108446 0.9572293 0.1981332 0.4164866 0.4436274 0.7935576 0.475466 0.1165546 0.8719788 0.4770956 0.1001236 0.8731295 0.4819825 -0.1767118 0.8581759 0.4785322 -0.2363466 0.8456638 0.4347875 -0.508262 0.7433907 0.4224034 -0.5562628 0.7156446 -0.115103 -0.9504978 -0.2886267 0.277341 -0.849173 0.4494299 0.1596684 -0.8173249 0.553612 0.2289767 -0.8043106 0.5483193 0.2323044 -0.7001368 0.6751616 0.2662929 -0.8123409 0.5188356 0.3468426 -0.4186216 0.8393189 0.3002434 -0.7948269 0.5273557 0.3259707 -0.7913188 0.51726 0.2050608 0.9717627 -0.1167362 0.06831592 0.9971244 -0.0328018 0.3110181 0.9081245 0.280317 0.1605727 0.9152643 0.3694696 0.3444858 0.6485986 0.6787116 0.08837628 0.6205248 0.7791911 0.1710004 0.3369618 0.9258594 -0.1313988 0.2778131 0.9516062 -0.07265716 -0.03569692 0.996718 -0.245683 -0.06708842 0.9670259 -0.1906269 -0.3381438 0.9215857 -0.2969968 -0.352626 0.8873826 -0.2207723 -0.6129994 0.7586115 0.4513758 0.7540516 0.477144 0.585823 0.4364687 0.6828665 0.5795087 0.4600664 0.6726876 0.6259754 0.09832763 0.7736191 0.6260896 0.08593827 0.7750008 0.5924022 -0.2350037 0.7706055 0.5845739 -0.271861 0.7644378 0.4865351 -0.5542695 0.6753288 0.4681308 -0.5925557 0.655539 0.2963502 -0.8315105 0.4698584 0.3246255 -0.8316376 0.4505524 0.5330219 0.838452 0.1135171 0.6983472 0.6671693 0.2592227 0.7247349 0.6276215 0.2843424 0.8261216 0.3887237 0.4079422 0.8300586 0.3742743 0.4134266 0.8572431 0.0582723 0.511604 0.8584194 0.0867902 0.5055529 0.7889069 -0.2663177 0.5538058 0.8072426 -0.209345 0.5518461 0.6171391 -0.5813112 0.5302987 0.6011567 -0.6023634 0.5251373 0.7622383 -0.3267841 0.5587529 0.2805073 -0.8810186 0.3809486 0.3327519 0.9218384 -0.1987214 0.5852528 0.7950925 0.1590823 0.4843893 0.8714333 0.07727324 0.2704677 0.9352582 0.2283405 0.4761271 0.715394 0.5113849 0.3061434 0.7245392 0.6175106 0.4280182 0.4009699 0.8099528 0.1625837 0.3696194 0.9148486 0.229645 0.04803687 0.9720883 -0.07747918 -0.01253336 0.9969152 -0.01904195 -0.2915611 0.9563627 -0.1939733 -0.324679 0.9257203 -0.1180416 -0.5900962 0.7986569 -0.2241012 -0.6039968 0.764831 -0.2808668 -0.4191111 0.8634002 0.355934 0.8818643 -0.3092355 0.768691 -0.5823872 0.2644609 -0.09973371 0.9407516 -0.3240985 0.2954648 0.9010521 -0.3174993 0.2557189 0.9116935 -0.3215943 -0.01948684 0.9353697 -0.3531345 0.08695214 0.9064103 -0.4133521 0.195201 0.8749644 -0.4430956 0.2173569 0.8669447 -0.448512 0.7883278 0.4352885 -0.434814 0.5494281 0.6951377 -0.4635865 0.5908043 0.6591321 -0.4652906 0.4752001 0.7478044 -0.4636523 0.2763119 0.8612689 -0.4264596 -0.06770586 0.9313177 -0.3578594 -0.06341445 0.9311495 -0.3590812 0.9930098 -0.08345633 -0.08346581 0.9404917 -0.3392105 0.02028959 0.9267255 -0.3742438 0.03348898 0.7576379 -0.634403 0.153355 0.7364882 -0.6566373 0.1625196 0.165448 -0.9531409 -0.2532773 -0.07462263 -0.9535616 0.2918081 0.1287846 -0.9780513 -0.1637998 -0.2888501 -0.6187181 0.7305845 -0.3542735 -0.3959972 0.847158 -0.2879307 -0.3905582 0.8743914 -0.3408163 -0.1055291 0.9341884 -0.2414199 -0.09197658 0.9660522 -0.2801519 0.1941182 0.940124 -0.1209231 0.2215195 0.9676294 -0.1733996 0.5435058 0.8213003 0.09732192 0.5954914 0.797445 6.10892e-4 0.8283781 0.5601693 0.2229667 0.8517907 0.4740661 0.4723152 -0.3137728 0.8236899 0.3992333 0.5749404 0.7141823 -0.2630676 0.8754212 -0.4055038 0.282884 0.8421776 0.4590358 -0.06364291 0.9914002 -0.1143469 -0.01783502 0.9898965 -0.1406652 -0.1800962 0.9245796 -0.3357352 0.3046996 -0.8551165 0.4194449 0.2747486 -0.8721547 0.4047955 -0.07881736 0.9461867 -0.3138765 -0.1581392 0.9270821 -0.3398688 0.3560813 -0.8685069 0.3448217 0.6589447 -0.6696271 0.3426242 0.6856787 0.7182372 -0.118238 0.6931118 0.7116023 -0.11497 0.8704265 0.4922024 -0.009728133 0.8738092 0.4862218 -0.006765365 0.9618669 0.2601967 0.08431953 0.9623769 0.2579567 0.08537727 0.9850491 0.01277232 0.1717999 0.9852143 0.01623356 0.1705561 0.9372908 -0.2431608 0.2497175 0.9397432 -0.2357206 0.2476261 0.9767512 -0.07634681 0.2003205 0.1714097 0.9446928 -0.2795966 0.3875926 -0.8364952 0.3873599 0.451762 -0.8292599 0.3289971 0.3984754 -0.8551353 0.3316037 0.3911868 -0.8745614 0.2865576 0.2538242 -0.9157052 0.3115403 0.8531174 0.07120215 -0.5168375 0.8819707 -0.2805609 -0.3786997 0.8791912 -0.3016552 -0.3688185 0.7917484 -0.5780066 -0.197593 0.3432289 -0.9224173 0.1770319 0.5580846 -0.8296165 -0.01668184 0.5204305 -0.8537018 0.01858675 0.412922 -0.9086183 -0.06251597 0.4775939 -0.8628144 -0.1656968 0.4938517 -0.8562648 -0.1513975 0.5086289 -0.8432604 -0.1738065 0.5008154 -0.8464902 -0.1806616 0.4919589 -0.8544972 -0.1667662 0.4706313 -0.8627572 -0.1848145 0.4637652 -0.8686946 -0.174045 0.01989138 0.9183189 -0.3953413 -0.311759 -0.6696924 0.6740315 -0.315905 -0.6646866 0.6770494 0.2131192 0.7719919 -0.5988395 0.2466937 0.7415514 -0.623894 0.2462849 0.7414674 -0.6241554 0.2597215 0.7278608 -0.6346365 0.2609125 0.7281535 -0.6338117 -0.3305154 -0.6465218 0.6875823 0.2885347 0.6980606 -0.6553314 0.254939 0.7346462 -0.6287297 0.1293939 0.8464161 -0.5165627 0.4392982 -0.8771691 -0.193885 0.3631774 0.5962601 -0.7159442 0.404999 -0.8975616 -0.1742382 0.3200455 -0.8970618 0.3047148 0.3457666 0.8608329 -0.3733794 0.306483 0.876087 -0.3722095 0.678771 0.6547474 -0.3325294 0.6432835 0.686804 -0.3383588 0.8727064 0.4129567 -0.2604812 0.5389582 -0.8167044 0.2061994 0.9552206 0.1377574 -0.2618714 0.950446 0.1569908 -0.2683402 0.2870036 0.8677807 -0.4056918 0.9534779 -0.1990226 -0.2264288 0.8856049 -0.4535277 -0.1000828 0.8650663 -0.4954494 -0.07867819 0.692762 -0.7178654 0.06892174 0.653051 -0.7516226 0.09267139 0.4644947 -0.862532 0.2007076 0.1835216 -0.9373447 0.2961497 0.2494565 -0.9344094 0.2542648 0.2379756 -0.9534469 0.1852208 0.2331164 -0.9534593 0.1912385 0.2301378 -0.9531461 0.1963394 -0.03280699 -0.8904578 0.4538819 0.4497672 -0.8870875 -0.1038528 0.2372217 -0.9601559 0.1477383 0.3133699 -0.9486832 0.04242241 0.2332127 -0.9619547 0.142321 0.2154747 -0.9680886 0.1279659 0.1574708 0.8354046 -0.5265946 0.1665235 0.8366793 -0.5217641 0.2774026 0.7163411 -0.6402368 0.3096246 -0.9359188 -0.1678949 0.3614574 0.5848016 -0.7261925 0.1206619 -0.9620715 0.2446616 0.2611577 -0.9651318 0.01781928 0.5770137 -0.6016535 -0.55233 0.1596889 -0.9781234 0.13332 0.1452001 -0.9817377 0.1229149 0.09949666 0.8988291 -0.4268569 0.2838209 0.7114457 -0.642877 0.3055496 0.6793093 -0.6672169 -0.3490369 -0.5997722 0.7200324 0.2375086 0.785202 -0.5718808 -0.05057245 0.9934045 -0.1029071 -0.222822 -0.8105903 0.5415661 0.3191047 0.6550929 -0.6848543 0.3196834 0.6550702 -0.6846062 0.3119562 0.6687503 -0.6748751 0.3119992 0.668964 -0.6746434 0.3100225 0.6720685 -0.6724657 -0.306676 -0.6774421 0.6685971 -0.3100321 -0.6719471 0.6725826 -0.3137062 -0.6663308 0.6764553 0.2926896 0.6959719 -0.6557103 0.2917436 0.6956645 -0.6564576 -0.4716871 -0.3984752 0.7865933 0.1709488 0.8186366 -0.5482798 0.3404134 -0.9140534 -0.2205112 0.3227078 -0.9271598 -0.1903535 0.2692167 -0.9366123 -0.2242318 0.259049 -0.9436437 -0.2059861 0.2223112 -0.9480886 -0.2273894 0.2131717 -0.9541346 -0.2102021 0.1609935 -0.9577619 -0.2382715 0.08461308 -0.9882027 0.1276562 0.07234257 -0.990139 0.1199643 0.3670448 -0.834589 -0.4107792 0.04640567 -0.9902911 0.1310352 0.03073936 -0.9920638 0.1219205 0.02008783 -0.9899118 0.1402544 0.2709676 0.7538235 -0.598604 0.289479 0.7176457 -0.633393 -0.336071 -0.6138319 0.7143296 0.3291376 0.6250416 -0.7078076 0.2848051 0.6528394 -0.7019165 0.2578944 0.6843546 -0.6820186 0.2862206 0.6967918 -0.6576921 0.4519169 0.4845463 -0.74899 0.4562802 0.4865649 -0.7450256 0.4636507 0.4747669 -0.7480806 0.4546965 0.471357 -0.7556943 0.464635 0.4539331 -0.760302 0.4523108 0.4494848 -0.7703105 0.4733712 0.407221 -0.7810831 0.4505889 0.4017325 -0.7972331 0.4639742 0.3666243 -0.8064208 0.4430115 0.3630943 -0.819697 0.448296 0.3455704 -0.8243857 0.4332106 0.3436896 -0.8331903 0.4370023 0.3283756 -0.837376 0.4148594 0.3266973 -0.8492118 0.4191403 0.3030533 -0.8558505 0.4807991 0.3588945 -0.8000168 0.5448272 0.2147811 -0.8105754 0.5841131 0.2319405 -0.7778274 0.6009981 0.1880468 -0.7768139 0.6030306 0.1890205 -0.7750003 0.6075651 0.1762663 -0.7744643 0.5920233 0.1702168 -0.7877402 0.597925 0.1517037 -0.7870653 0.5730934 0.1430109 -0.8069151 0.5851102 0.09842646 -0.8049586 0.5423508 0.08750236 -0.835583 0.5493268 0.04944282 -0.8341436 0.5118435 0.0434103 -0.8579813 0.5141499 0.02379018 -0.8573704 0.4876866 0.02053976 -0.8727771 0.4890043 0.003497779 -0.8722745 0.4506576 5.11423e-4 -0.8926969 0.4513431 -0.02522164 -0.8919941 0.6225246 -0.03398871 -0.781862 0.6350709 -0.09887552 -0.7660996 0.6760585 -0.08207941 -0.7322623 0.6796558 -0.1038417 -0.7261438 0.6792529 -0.104143 -0.7264777 0.6814718 -0.1195112 -0.7220203 0.661141 -0.1275069 -0.7393474 0.6630169 -0.1441306 -0.7345985 0.6290152 -0.1556112 -0.7616594 0.6322419 -0.2001124 -0.748482 0.5749841 -0.2145793 -0.7895245 0.5751842 -0.2507764 -0.7786363 0.5260992 -0.2587012 -0.8101194 0.5251781 -0.2782384 -0.804221 0.4907695 -0.2821553 -0.8243384 0.4893933 -0.29946 -0.8190348 0.4396777 -0.3032641 -0.8454079 0.4366554 -0.3288514 -0.8373702 0.6532684 -0.450573 -0.6084607 0.6570081 -0.4060301 -0.6352008 0.6941248 -0.3913115 -0.604207 0.6943632 -0.3881491 -0.6059705 0.691169 -0.3896659 -0.6086426 0.6898392 -0.4056883 -0.5996158 0.6669375 -0.4142866 -0.6193231 0.6652526 -0.4283875 -0.6114926 0.6253365 -0.4416843 -0.6433268 0.6197102 -0.4797756 -0.6211077 0.5534273 -0.4964107 -0.668801 0.5468576 -0.5286453 -0.6492156 0.4906393 -0.5382717 -0.6852275 0.4863463 -0.5558429 -0.6741706 0.4471233 -0.5605177 -0.6970658 0.4430045 -0.5758256 -0.6871477 0.3866309 -0.5799547 -0.7170559 0.3799138 -0.6024389 -0.7019494 0.2874303 -0.816472 -0.5007568 0.2975071 -0.7993538 -0.5220376 0.3550645 -0.7953048 -0.4913446 0.3617973 -0.7834559 -0.5052718 0.4019873 -0.77866 -0.4817622 0.4093421 -0.7651935 -0.4969086 0.4674039 -0.7550212 -0.4598661 0.4797161 -0.7307937 -0.485606 0.548944 -0.7131449 -0.4359874 0.5622033 -0.6838994 -0.4649828 0.604371 -0.6698095 -0.4313827 0.6085705 -0.6598865 -0.4406719 0.6321053 -0.6507146 -0.4207299 0.6377866 -0.6366448 -0.4334878 0.6431233 -0.6346555 -0.4284913 0.6369515 -0.6504985 -0.4136963 0.607602 -0.6625235 -0.438044 0.569608 -0.7438271 -0.3496685 0.6817573 -0.6848185 -0.2573536 0.7848827 -0.3824392 -0.4875445 0.7865691 -0.3721969 -0.4927259 0.7560644 0.02437913 -0.6540431 0.2094023 0.8262619 -0.5229169 0.6444004 0.4152201 -0.6421374 0.6659657 0.3799015 -0.6420006 0.4057818 0.6896732 -0.5997433 0.4398062 0.6582905 -0.6109207 0.135174 0.8621574 -0.4882751 0.1657519 0.84773 -0.5038654 -0.05584019 0.9214553 -0.3844504 -0.08436441 0.9277394 -0.363569 0.2592591 0.7891706 -0.5567715 0.2544367 0.7891013 -0.5590896 0.3004981 0.6975219 -0.6505106 0.2225204 0.8358461 -0.5018427 -0.2818943 -0.7350321 0.6166551 -0.3078551 -0.6787968 0.6666785 -0.3109584 -0.6715435 0.672558 0.3236118 0.6432416 -0.6939134 0.3244646 0.6433158 -0.6934462 0.3108144 0.6709625 -0.6732041 0.3079978 0.6766988 -0.6687422 0.3325287 0.6023958 -0.7256336 -0.1196081 0.9126642 0.3908174 0.3026458 0.7003508 -0.646463 0.004708528 -0.9912434 0.1319646 0.4346444 -0.3435266 -0.8325106 0.1479638 -0.9660177 -0.2119354 0.09820657 -0.9668933 -0.2355265 0.3436194 0.5580859 -0.7552919 0.3541696 0.1049187 -0.9292772 0.2952741 0.7513403 -0.5901703 0.2905802 0.751734 -0.591996 -0.07586437 -0.9948877 -0.066657 -0.06372034 -0.9930053 -0.09939932 0.2414978 -0.6435753 -0.7262848 0.1450038 -0.8423389 -0.5190752 0.1524341 -0.8306628 -0.5355028 0.2425624 -0.6407287 -0.7284438 0.249108 -0.6229463 -0.741541 0.3177837 -0.3766313 -0.8701509 0.3225981 -0.35378 -0.8779352 0.3625018 -0.07839739 -0.92868 0.3648297 -0.05231088 -0.9296037 0.3723489 0.2498914 -0.893818 0.371392 0.2767366 -0.8862758 0.3360229 0.5798923 -0.7421682 0.3313925 0.6024552 -0.7261038 -0.3303861 -0.6070467 0.7227306 0.3157153 0.6645961 -0.6772266 -0.1184293 -0.9827952 0.1417324 -0.1030135 -0.9835965 0.1480748 -0.2529747 -0.8137695 0.523243 0.3354574 -0.5709418 -0.7493289 -0.0624727 -0.9890484 0.1337184 -0.03466302 -0.9885616 0.146781 0.3150913 0.6619548 -0.6800981 0.3106285 0.6772215 -0.666994 -0.3303828 -0.6176128 0.7137239 -0.3189855 -0.6518623 0.6879854 0.3276895 0.6250555 -0.7084669 -0.3129562 -0.6698235 0.6733461 0.390132 0.3028854 -0.8695157 0.3928398 0.2754738 -0.8773774 0.4020143 -0.02574789 -0.9152713 0.4009069 -0.05428445 -0.9145092 0.3732798 -0.3294079 -0.8672674 0.3687133 -0.3563088 -0.8585422 0.3085109 -0.6030372 -0.7356407 0.3009513 -0.6254959 -0.7198495 0.2148429 -0.8171406 -0.5349055 0.2050095 -0.8331734 -0.513608 0.07064342 -0.9738287 -0.2160261 0.02344435 -0.9715807 -0.2355452 0.2375007 -0.6596342 -0.7130752 0.1322606 -0.8601723 -0.4925553 0.1971224 0.8688883 -0.4540659 0.1127942 0.9538441 -0.2783145 0.3237378 0.8022127 -0.5016459 0.2239237 0.9211222 -0.3184213 -0.2499284 0.8951019 0.369227 -0.01441323 0.911033 -0.4120817 0.2144719 0.8268381 -0.5199431 0.2973909 0.7444558 -0.5977829 0.2962859 0.7613735 -0.5766499 0.307505 0.7799967 -0.5450192 0.2800105 0.8044487 -0.523886 0.270201 0.7914232 -0.5483072 0.2753878 0.7920077 -0.544872 0.2248448 0.8279798 -0.5137065 0.23104 0.8272606 -0.5121137 0.2544449 0.8193459 -0.5137414 0.2458394 0.8132975 -0.5273615 0.2522082 0.8140547 -0.5231693 0.1962602 0.8363833 -0.5118057 0.1962637 0.8363829 -0.5118051 0.1680266 0.8531152 -0.4939246 0.1309531 0.8726242 -0.4705088 0.1448313 0.8454806 -0.5139908 0.1470503 0.8546193 -0.4979981 0.05288302 0.8751816 -0.4808956 0.04445129 0.8867806 -0.4600482 0.05696433 0.8858604 -0.4604415 0.09334731 0.871604 -0.4812408 0.09332984 0.8716478 -0.4811648 0.09965503 0.872992 -0.4774453 -0.03151369 0.9676393 -0.2503622 -0.02261352 0.9529392 -0.302317 -0.06392669 0.938048 -0.3405573 -0.03250533 0.9260169 -0.3760802 -0.0257495 0.9207598 -0.3892793 -0.02798569 0.9291533 -0.3686341 -0.03320044 0.9365915 -0.3488472 -0.0335229 0.9355562 -0.3515831 -0.03606933 0.9600561 -0.2774733 -0.1087998 0.9202888 -0.3758076 -0.04004192 0.9807175 -0.1912845 -0.06560504 0.9767096 -0.2042902 -0.1011655 0.989906 -0.09925663 -0.1994119 0.9798993 0.005695343 -0.1725742 0.984669 0.02540081 -0.1355463 0.9907251 -0.009542942 -0.1572072 0.9851506 0.06902396 -0.1705063 0.9826539 0.07293158 -0.2054956 0.96833 0.1418051 -0.2047621 0.968625 0.1408481 -0.170314 0.9750503 0.1423733 -0.2070095 0.9578646 0.1991044 -0.2008096 0.9144408 0.351388 -0.1916283 0.9476553 0.2553977 -0.1851819 0.9492935 0.2540662 -0.1910061 0.961042 0.1997874 -0.1994128 0.9598678 0.1972013 -0.2584928 0.8474036 0.4637766 -0.2642886 0.8183592 0.5103331 -0.3955028 0.5822809 0.7103003 -0.3882522 0.5821382 0.7144056 -0.3425204 0.6714491 0.6571423 -0.3183202 0.7362216 0.5972019 -0.3125092 0.7377228 0.5984172 -0.3802195 0.651479 0.6565122 -0.3569064 0.6962647 0.6227627 -0.4180058 0.5542411 0.7197833 -0.4333904 0.5578147 0.7078245 -0.4302484 0.6349479 0.64166 -0.3358982 0.8129041 0.4757723 -0.2209842 0.9099364 0.3509729 -0.3507865 0.786682 0.5080161 0.1894934 0.9559571 -0.2241388 0.07798898 0.9925397 -0.09371709 -0.09166818 0.9849079 0.1468116 -0.01754796 0.9980821 0.05936694 -0.1098553 0.9779503 0.1776092 0.253692 0.9005075 -0.3531664 0.1815445 0.8678613 -0.4624484 0.1711259 0.893516 -0.4151449 0.1222463 0.8942636 -0.4305214 0.09767258 0.9399315 -0.3270919 0.09426236 0.9208203 -0.3784238 0.04458308 0.924214 -0.3792639 0.04552787 0.928837 -0.3676806 0.1218653 0.8074859 -0.5771616 -3.92689e-4 0.9076279 -0.4197757 -0.01429826 0.9244576 -0.3810169 -0.02012848 0.9286495 -0.3704122 -0.01983779 0.920709 -0.3897454 0.2180249 0.8346801 -0.5057415 0.2134461 0.8514564 -0.4790228 0.1843225 0.8494119 -0.4944945 0.1766825 0.8729743 -0.4546421 0.1310858 0.8725058 -0.4706912 0.120123 0.8962126 -0.427052 0.0569967 0.8990017 -0.4342206 0.03056728 0.9340937 -0.3557173 0.03384226 0.9068515 -0.4200895 0.001109957 0.9311885 -0.3645364 6.04264e-4 0.9280865 -0.3723643 -0.09400969 0.9876199 -0.125576 -0.1094303 0.983477 -0.1442154 -0.116212 0.9784528 -0.170661 -0.06655341 0.9668701 -0.2464404 -0.07141572 0.9651419 -0.2517956 0.09324806 0.9546949 -0.2825997 0.09057271 0.9628756 -0.2542975 0.04698294 0.9659244 -0.2545244 0.04638606 0.9702055 -0.2378017 -0.01293343 0.9734697 -0.22845 -0.01328605 0.9723681 -0.2330745 -0.06537288 0.9731628 -0.2206369 -0.06728506 0.9711534 -0.2287657 -0.08571928 0.9648563 -0.2484041 -0.102945 0.9838865 -0.1461845 -0.1246412 0.9778398 -0.1682081 0.300469 0.826294 -0.4763997 0.2673116 0.8682796 -0.4178937 0.2461969 0.8669058 -0.4334299 0.2292088 0.8919374 -0.3897579 0.2055914 0.8895466 -0.4079697 0.1874492 0.9130824 -0.3621376 0.171979 0.9117059 -0.3731162 0.1548281 0.9331902 -0.3243214 0.1504365 0.9330387 -0.3268145 0.05024611 0.9900864 -0.1311657 0.03477215 0.9904359 -0.1335207 0.03271675 0.991972 -0.1221523 -0.003768742 0.9928386 -0.1194039 -0.00334531 0.9923554 -0.123368 -0.05663907 0.9922025 -0.111024 -0.05595129 0.9940022 -0.09396326 -0.07837736 0.9883731 -0.1302909 0.1092743 0.9815056 -0.157181 0.09031426 0.9807606 -0.1730667 0.07907426 0.9839485 -0.1599773 0.0770725 0.9838055 -0.1618226 0.00227493 0.9978929 -0.06484353 0.01370298 0.9983911 -0.05502295 -0.04252934 0.9986534 0.02971047 -0.3754189 0.7146728 0.5901725 -0.3703195 0.7230204 0.5831853 -0.309833 0.8174453 0.4855788 -0.3849921 0.7023645 0.5987196 -0.1744947 0.949373 0.2612331 -0.2735319 0.8742526 0.401077 -0.2495161 0.8709186 0.4233704 -0.2943524 0.8179284 0.4943176 -0.2693869 0.8176201 0.5088499 -0.2161417 0.8852519 0.4118395 -0.2213355 0.8842638 0.4112032 -0.16935 0.9347414 0.3123766 -0.1490708 0.9388605 0.3103526 -0.2324996 0.8918624 0.3879759 -0.3542849 0.7806398 0.514863 -0.3517884 0.7802355 0.5171823 -0.2505432 0.8951656 0.368655 -0.3247174 0.8207745 0.469987 -0.09900146 0.9851922 0.1399824 -0.1852136 0.9504596 0.2496447 -0.01864176 0.9997854 0.009034395 -0.02208602 0.9997407 0.00555849 -0.11625 0.9841004 0.1342853 -0.0989409 0.9836884 0.1502265 -0.1578449 0.9573055 0.2421801 -0.1374432 0.9573364 0.2541977 -0.02064442 0.9988808 0.04255515 0.2793807 0.8601784 -0.4266611 0.2272416 0.9159526 -0.3307449 0.200405 0.9145373 -0.3513681 0.1739292 0.9407566 -0.2910768 0.1507143 0.9385637 -0.3104567 0.1175428 0.964508 -0.236449 0.1062547 0.9636266 -0.2452222 0.07722914 0.9817225 -0.1739439 0.07854044 0.9817528 -0.1731849 -0.07145589 0.9895321 0.1253811 -0.07836633 0.9890923 0.1247204 -0.06914293 0.9937582 0.0875439 -0.08920508 0.9919337 0.09005522 -0.08086913 0.9959205 0.04003286 -0.1039779 0.9935056 0.04620969 -0.1113337 0.9935917 0.01950132 -0.1211305 0.9923814 0.02250957 -0.1344514 0.990902 -0.006017386 -0.1351757 0.9908048 -0.005780994 -0.156472 0.987036 -0.03572905 -0.132549 0.990217 -0.04360234 -0.1609759 0.9842005 -0.07373046 -0.1093967 0.9899134 -0.09002131 -0.1079773 0.990186 -0.08872854 -0.140383 0.9862343 -0.08737754 0.3068653 0.7810263 -0.5439043 0.2938641 0.8240433 -0.4843517 0.2671531 0.8218171 -0.5032356 0.2660679 0.8471191 -0.4599968 0.2339422 0.8437464 -0.4830768 0.2334579 0.8639884 -0.4461183 0.2083368 0.8617283 -0.4626231 0.191069 0.8950145 -0.4030407 0.1706578 0.893985 -0.414327 0.1569352 0.9192297 -0.3610932 0.1210845 0.9207183 -0.3709669 0.1207912 0.9330278 -0.3389232 0.07571655 0.9363824 -0.3427174 0.07640057 0.9448385 -0.3185016 0.0192455 0.9491037 -0.3143754 0.019845 0.9512013 -0.3079324 -0.03150135 0.9535095 -0.299712 -0.03439313 0.9475948 -0.3176181 -0.04642707 0.947763 -0.3155788 -0.05126333 0.9371697 -0.3450872 -0.05202186 0.9366627 -0.3463478 -0.06531488 0.9668811 -0.2467285 -0.1018967 0.9591142 -0.2640398 -0.07650566 0.9847897 -0.1560006 -0.08742392 0.9843904 -0.1527504 -0.1571197 0.9667279 0.2018677 0.1571196 0.9667271 0.2018717 -0.01388585 0.7252783 0.6883159 0.4487128 0.700254 0.5552489 0.3102672 0.8753805 0.3707334 0.06614238 0.985841 -0.1540868 0.6121397 0.05085742 -0.7891125 0.4965811 0.1234757 0.8591629 0.4004325 0.4110861 0.8189396 0.2466213 0.6237148 0.7417262 -0.9425226 0.3336609 0.0179373 -0.6755539 0.7371845 0.01363915 -0.9967263 0.05079591 0.06289958 0.0225138 0.9941785 -0.1053676 0.7359145 0.05006241 -0.6752213 0.7076717 -0.2733929 -0.6515038 0.8562328 0.3564223 -0.3739365 0.9146115 0.05007678 -0.4012209 0.974375 0.05087709 -0.2191004 0.2104128 0.9774571 -0.01743984 0.9971767 0.05032277 -0.05573523 0.9898643 0.05075645 0.1326365 0.09223085 0.995333 0.02838546 0 1 0 0.1082488 0.05083012 0.9928236 0.2733126 0.05039435 0.9606043 0.05442059 0.9847242 0.1653988 0 1 2.59494e-5 -0.7053594 0.050843 0.7070242 -0.06638818 0.993431 0.0932061 -0.5786684 0.3302112 0.7457235 -0.9105708 0.05083423 0.4102156 -0.934753 0.05045688 -0.3516973 -0.1221902 0.9910583 -0.05360227 -0.1492733 0.9792008 -0.1374167 -0.7536402 0.05029988 -0.6553598 -0.8641058 0.05074137 -0.5007461 0.04509836 0.05082386 -0.997689 -0.1519221 0.05029058 -0.9871123 -0.06274259 0.924513 -0.3759511 -0.3170084 -0.02077507 -0.9481952 -0.3436703 0.6918285 -0.6350309 -0.4793957 0.05017781 -0.8761632 -0.6354653 0.05084037 -0.7704539 0.5721362 0.1377519 -0.8085076 0.5448332 0.3339736 -0.7691675 0.6944481 0.3302138 -0.6392971 0.6944557 0.3302319 -0.6392795 0.8644035 0.3302167 -0.3791619 0.8643999 0.3302296 -0.3791583 0.9406812 0.3302167 -0.07794868 0.9406608 0.330276 -0.07794368 0.9146866 0.3302 0.2330594 -0.6661449 0.7264943 0.1686925 -0.9150153 0.3302369 0.2317121 -0.9150273 0.3301998 0.231718 -0.9681746 0.05019444 0.2451907 -0.9681863 0.05007344 0.2451695 -0.8644035 0.3302167 -0.3791619 -0.8643999 0.3302296 -0.3791583 -0.6944481 0.3302138 -0.6392971 -0.6944557 0.3302319 -0.6392795 -0.4492445 0.3302183 -0.8301418 -0.4492486 0.3302207 -0.8301386 -0.1553642 0.3302274 -0.9310274 -0.1553553 0.3302726 -0.9310128 0.1567381 0.3302145 -0.9308016 0.1388804 0.9425746 -0.3037523 0.3153893 0.7252821 -0.6119604 0.5055553 0.7265027 -0.4654113 0.5055556 0.7265107 -0.4653986 0.6292845 0.7265022 -0.2760357 0.6292684 0.7265187 -0.2760289 0.6848344 0.7264857 -0.05674821 0.6847796 0.7265377 -0.05674338 0.6638341 0.7252887 0.18243 0.2231225 0.7265179 0.6499139 -0.6848163 0.7265031 -0.05674529 -0.6292845 0.7265021 -0.2760357 -0.6292684 0.7265188 -0.276029 -0.5055553 0.7265027 -0.4654113 -0.5055556 0.7265107 -0.4653986 -0.3270508 0.7265117 -0.6043332 -0.3270457 0.7265125 -0.6043349 -0.113103 0.7265225 -0.6777706 -0.1131013 0.7265076 -0.6777867 0.1269875 0.725281 -0.67664 0.08306026 0.9667266 0.2419521 0.0830605 0.9667277 0.2419472 -0.03451263 0.9647126 0.2610337 0 0.7022302 0.71195 -0.1733829 0.7059157 0.686747 -0.1549103 0.878854 0.451241 -0.2840701 0.7058745 0.6488801 -0.426844 0.7032111 0.5685934 -0.4118109 0.7252878 0.5516968 -0.2141501 0.966729 0.1399101 -0.575262 0.7265083 0.375845 -0.575271 0.7265051 0.3758375 -0.7902051 0.330218 0.5162673 -0.7901866 0.3302791 0.5162566 -0.3816801 0.8900253 0.2493501 -0.8306511 0.05014836 0.5545306 -0.2141548 0.9667279 0.1399105 -0.2479761 0.966729 0.06279301 -0.6661201 0.7265193 0.1686828 -0.6847973 0.726521 -0.05674511 -0.4068769 0.9128608 -0.03371399 -0.9327816 0.3327959 -0.1384393 -0.317589 0.9470137 -0.04798144 -0.9805043 0.05063676 -0.1898612 -0.2479777 0.9667282 0.06280022 -0.2525237 0.9675344 0.01044404 -0.6474689 -0.7602011 -0.05365121 -0.252417 0.9671069 -0.03146356 -0.2342582 0.9667292 -0.1027514 -0.2342607 0.9667279 -0.1027582 -0.1882013 0.9667306 -0.1732409 -0.1882014 0.9667292 -0.1732484 -0.121751 0.9667257 -0.2249847 -0.1217505 0.9667292 -0.2249701 -0.04210448 0.966724 -0.2523334 -0.04210484 0.9667317 -0.2523038 0.07700687 0.9647151 -0.251783 0.1171823 0.7022312 -0.7022392 0.3274363 0.7032123 -0.6310928 0.1217496 0.9667255 -0.2249861 0.1882028 0.9667299 -0.1732423 0.1881999 0.9667298 -0.1732469 0.2342622 0.966728 -0.1027532 0.2342567 0.966729 -0.1027565 0.2549343 0.9667277 -0.02112346 0.2549284 0.9667292 -0.02112418 0.2445743 0.9647122 0.09754002 0.6901611 0.7022337 0.1747732 0.6174072 0.7053223 0.3483229 0.4060067 0.8745266 0.2652583 0.5508527 0.7063597 0.4445417 0.4464075 0.7032134 0.5533638 0.433726 0.725286 0.5346419 0.2231176 0.7265167 0.649917 0.3064762 0.3302991 0.8927345 -0.001389682 0.3301432 0.94393 -0.004879772 0.9962941 0.0858739 0.2672627 0.2150914 0.9393118 -0.2083989 -0.01585865 0.9779154 -0.05498898 0.2447052 0.9680371 -0.09041208 0.01249361 0.9958261 -0.06065487 0.1206954 0.9908348 -0.1037891 0 0.9945994 -0.2239382 0.04417747 0.9736016 -0.05670291 -0.01930713 0.9982045 -0.2872325 0.009033977 0.9578184 -0.2447872 -9.79566e-7 0.969577 -0.4333856 1.61856e-4 0.9012087 -0.4009969 -0.01383715 0.915975 -0.5680379 0.009390294 0.8229488 -0.7230887 5.8784e-4 0.690755 -0.6426518 7.32358e-4 0.7661581 -0.6627929 -0.003608882 0.7487941 -0.566011 0.008682727 0.824352 -0.9757955 -0.2098364 0.06157839 -0.7988559 0.04144924 0.6000929 -0.7004117 -0.1288216 0.7020174 -0.8547984 0.08289849 0.5122964 -0.8316853 0.002670168 0.555241 -0.9431532 -0.001414716 0.3323555 -0.8911022 -0.2115516 0.4014759 -0.9535601 0.1800377 0.2414741 0.3531146 -0.02285498 0.935301 0.1083592 0.02419048 0.9938175 0.2656901 -0.02891409 0.9636248 0.1658388 0 0.986153 0.1276648 -0.05667674 0.9901967 0.1656462 0.01182252 0.9861144 0.1073377 -0.1390805 0.9844467 0.2397027 0.02994513 0.9703844 0.2583635 0.08388066 0.9623994 0.2979205 1.04147e-4 0.9545907 0.4509783 -1.04336e-4 0.8925349 0.5149976 0.005702078 0.8571727 0.6037753 -0.02006906 0.796902 0.6092364 -0.02259689 0.7926667 0.7314812 0.01615172 0.6816704 0.7200525 0.01185852 0.6938183 0.7613976 -2.31991e-4 0.6482853 0.8365155 1.60823e-4 0.5479433 0.876466 -0.04915434 0.478948 0.9043069 -0.1083303 0.4129088 0.8479133 0.1507688 0.5082439 0.9546575 -0.03648179 0.2954627 0.9415771 0.001001119 0.336796 0.9811372 0.004101037 0.1932694 0.984856 -0.09106367 0.147534 0.984087 -0.01303201 0.1772093 0.9998053 0.0162695 0.01116156 0.2389331 -0.6771344 0.6959886 0.1211177 -0.6771393 -0.7258188 0.9676839 -0.2519352 0.01080298 -0.5672551 -0.397211 -0.7214187 -0.5452347 -0.3971148 -0.738254 -0.7535498 -0.2513654 -0.6074357 -0.6296636 -0.5720506 -0.5256254 -0.4070698 -0.8432695 -0.3509852 -0.2045026 -0.3663585 0.9077226 -0.1747887 -0.6810619 0.7110581 -0.03981715 -0.9924528 0.1159835 -0.0611155 -0.9843227 0.1654504 -0.3092253 -0.6622082 0.6825394 -0.414608 -0.3381943 0.8448223 0.9016766 -0.3561468 -0.2452324 0.9040529 -0.3667528 -0.2195017 0.5944052 -0.7965072 -0.1107195 0.1625317 -0.9866115 -0.01346772 0.4927359 -0.8698642 -0.02340376 0.7155686 -0.6982576 -0.01994913 0.6890756 -0.7025076 0.1779267 0.0499553 -0.9986714 0.01265037 0.0513488 -0.9986717 -0.004254877 0.05134701 -0.9986719 -0.004254698 0.047185 -0.9986717 -0.02069723 0.04717916 -0.9986721 -0.02069467 0.03790634 -0.9986718 -0.03489524 0.03790837 -0.9986717 -0.03489708 0.02452307 -0.9986717 -0.04531466 0.02452278 -0.9986718 -0.04531413 0.008480608 -0.9986717 -0.05082148 0.008480668 -0.9986717 -0.05082207 0.03164744 -0.9986717 0.04066067 0.03164714 -0.9986717 0.04066032 0.01672971 -0.9986718 0.04873186 0.01672989 -0.9986718 0.04873251 0 -0.9986718 0.05152398 0 -0.9986718 0.05152398 -0.01672989 -0.9986718 0.04873239 -0.01672971 -0.9986718 0.04873198 -0.03164607 -0.9986718 0.04065889 -0.03164857 -0.9986717 0.0406621 -0.04313331 -0.9986718 0.02818036 -0.0431348 -0.9986717 0.02818137 -0.04995083 -0.9986717 0.01264923 -0.6907047 -0.7025108 0.1714808 -0.7068021 -0.706807 0.02923411 -0.7875686 -0.6162269 -4.90317e-4 -0.5703459 -0.8183223 -0.07109385 -0.6985669 -0.7059116 -0.1170172 -0.6519806 -0.7022349 -0.2859852 -0.07251614 -0.9972008 0.01822358 -0.0379067 -0.9986718 -0.03489553 -0.008480608 -0.9986717 -0.0508216 0.3502295 -0.677137 -0.6471669 0.350225 -0.6771459 -0.6471599 0.5413857 -0.6771396 -0.4983808 0.5413886 -0.6771356 -0.4983832 0.6738845 -0.6771295 -0.2955933 0.6738752 -0.6771407 -0.295589 0.7333506 -0.6771294 -0.06076705 0.7333403 -0.6771407 -0.06076622 0.4519736 -0.6771355 0.5806956 -0.6160318 -0.6771408 0.4024737 -0.6160247 -0.6771498 0.4024694 -0.4519708 -0.6771405 0.580692 -0.4519742 -0.6771345 0.5806964 -0.238933 -0.6771357 0.6959874 -0.2389296 -0.6771458 0.6959785 0 -0.6771459 0.7358489 -0.2489501 -0.9410117 -0.2291747 -0.5413848 -0.677141 -0.4983801 -0.5413888 -0.6771356 -0.4983831 -0.1169992 -0.9872744 -0.1077054 -0.4985443 -0.6435621 -0.5807593 -0.289678 -0.7934503 -0.5352787 -0.3502261 -0.6771439 -0.6471613 -0.3502281 -0.6771395 -0.6471649 -0.161049 -0.9410112 -0.2975925 -0.1610488 -0.9410114 -0.2975922 -0.02452307 -0.9986717 -0.04531466 0.06913441 -0.2519362 -0.9652713 0.1211179 -0.6771397 -0.7258183 0.07430469 -0.8923017 -0.4452826 0.1066285 -0.8209115 -0.5610122 0.2689744 -0.2522567 -0.9295265 0.4377003 -0.2502787 -0.863585 0.3029541 -0.7712535 -0.5598098 0.5735356 -0.2524548 -0.7793096 0.7124908 -0.249319 -0.6558939 0.7240478 -0.1854237 -0.664359 0.8707808 -0.3095927 -0.3819599 0.7485466 -0.5714777 -0.3362905 0.8915727 -0.3566065 -0.2791594 0.05569446 -0.9410117 -0.333759 0.05569505 -0.941011 -0.3337613 0.1610488 -0.9410114 -0.2975922 0.1610491 -0.9410111 -0.2975928 0.2489486 -0.9410123 -0.2291734 0.2489501 -0.9410117 -0.2291747 0.3098722 -0.9410125 -0.1359224 0.3098661 -0.9410148 -0.1359199 0.3372104 -0.9410146 -0.02794206 0.3372218 -0.9410105 -0.02794295 0.3247065 -0.9389279 0.1139304 0.7113153 -0.6761369 0.1920141 0.2141197 -0.9738003 0.07658922 0.9525432 -0.2514744 0.171529 0.4519716 -0.677139 0.5806931 0.6230291 -0.6761387 0.3932828 0.4007517 -0.8841357 0.2402129 0.5901108 -0.2495581 0.7677826 0.5481274 -0.4512324 0.7042342 0.7078699 -0.2525264 0.6596595 0.7367507 -0.2523763 0.6272994 0.4363698 -0.2524532 0.8636255 0.2031532 -0.7800917 0.5917652 0.2389297 -0.6771464 0.6959781 0 -0.6771458 0.735849 0.2884375 -0.2503071 0.9242025 0.1048882 -0.252148 0.9619876 0 -0.8781887 0.4783143 -0.05489569 -0.2511346 0.9663943 -0.2016838 -0.2522927 0.9463995 -0.4465066 -0.2525172 0.8584097 -0.5834033 -0.2498667 0.7727918 -0.473712 -0.6365316 0.6086251 -0.7021422 -0.2525312 0.665751 -0.8107335 -0.2493028 0.5296787 -0.8107303 -0.2493184 0.5296763 -0.8923457 -0.2525123 0.374108 -0.8384999 -0.4596605 0.2926266 -0.3263556 -0.9432321 0.0616858 -0.7169794 -0.6761285 0.169679 -0.3398075 -0.9389235 0.05434674 -0.2832732 -0.9410126 0.1850717 -0.2832789 -0.9410103 0.1850753 -0.2078338 -0.9410116 0.2670249 -0.2078327 -0.9410123 0.2670233 -0.1098694 -0.9410121 0.320039 -0.1098709 -0.9410104 0.3200433 0 -0.9410103 0.3383779 0 -0.9410104 0.3383779 0.1098707 -0.9410105 0.3200432 0.1098696 -0.9410122 0.320039 0.2078338 -0.9410116 0.2670249 0.2078327 -0.9410123 0.2670233 0.3037496 -0.9389234 0.1617378 0.0745387 -0.9971998 -0.006036996 0.5960168 -0.7022349 0.3893972 -0.02452301 -0.9986717 -0.04531461 -0.03790801 -0.9986717 -0.03489679 -0.2489505 -0.9410114 -0.2291752 -0.3262275 -0.9389235 -0.1095362 -0.6792641 -0.6761385 -0.2853717 -0.3458719 -0.9292128 -0.1301397 -0.8372392 -0.2522164 -0.4851983 -0.2410081 -0.8659421 -0.4382458 -0.4274503 -0.2506461 -0.8685982 -0.2769932 -0.2523476 -0.9271437 -0.008480668 -0.9986717 -0.05082207 -0.05569499 -0.941011 -0.3337612 -0.05569452 -0.9410118 -0.3337591 -0.1211179 -0.6771399 -0.7258182 -0.1211177 -0.6771391 -0.725819 -0.08925199 -0.8402147 -0.5348584 -0.1206656 -0.2506951 -0.9605164 0.9439759 -0.3058607 -0.1239314 0.4981408 -0.8518284 0.1620001 0.8479073 -0.5301442 5.8752e-4 0.6944894 -0.7180567 0.04559725 0.6993907 -0.7137045 0.03845506 0.5717734 -0.8079233 0.1426017 0.9881179 -0.1304936 -0.0812062 0.9635584 -0.2672606 -0.01126813 0.9413962 -0.3372914 -0.00280708 0.8952019 -0.4415959 0.06005704 -0.0212323 -0.9404479 0.3392745 0.3682264 -0.8983836 0.2394083 0.1933031 -0.9377166 0.288655 0.1995848 -0.9367191 0.2876164 -0.04458355 -0.9449918 0.3240414 -0.0577057 -0.9449563 0.3220677 0.92106 -0.3796451 -0.08670753 0.8746114 -0.4827253 -0.04506921 0.8930619 -0.445526 0.06282669 0.7095019 -0.694304 0.1206195 0.7758548 -0.6096431 0.1624347 0.4279026 -0.8728936 0.2344274 0.5248759 -0.8510922 -0.01214116 0.9350221 -0.2317306 -0.268393 0.3735052 -0.8037665 -0.4630911 0.3938595 -0.8538842 -0.3402304 0.08670008 -0.9861282 0.1415429 0.05763226 -0.9832177 0.1730942 -0.06635248 -0.9966275 -0.04828047 0.8892242 -0.3855692 -0.2462048 0.872808 -0.2433603 -0.4230627 0.7260062 -0.5514296 -0.4109021 0.7637284 -0.3308497 -0.5543082 0.5814747 -0.5888197 -0.5614078 -0.05836415 -0.9981914 -0.0144065 -0.02929747 -0.9257577 0.3769806 0.1583254 -0.973374 0.1657594 0.3195025 -0.9447761 0.07291382 0.3541369 -0.9295679 0.1024236 0.3238806 -0.9437381 -0.06678247 0.3351313 -0.9392839 -0.07370835 0.6541962 -0.7495256 -0.1011878 0.6535236 -0.7501897 -0.1006109 0.8369716 -0.5172668 -0.178644 0.8082799 -0.5726466 -0.1369661 0.898007 -0.405806 -0.1700146 0.209501 -0.62756 -0.7498519 0.2226433 -0.661854 -0.7158067 0.2549442 -0.9061564 -0.3374673 0.09954833 -0.8620548 -0.4969425 0.1464033 -0.9867171 -0.07039451 -0.02380299 -0.9774171 -0.2099746 -0.01343518 -0.9838092 -0.1787149 0.833975 -0.5074418 -0.2167688 0.8824146 -0.3217214 -0.3432781 0.6466354 -0.7162495 -0.2623917 0.719682 -0.5102106 -0.4708961 0.5065781 -0.7976978 -0.3271957 0.4721186 -0.5529003 -0.6865897 0.3786563 -0.7180459 -0.5839774 0.196357 -0.1027015 0.9751392 -0.3645791 -0.6566675 0.6602045 0.1481297 0.01378983 0.9888718 -0.3778033 0.608068 0.6982249 -0.3313269 0.4723181 0.8167853 -0.2150795 0.3400138 0.9154953 -0.2161951 0.3738796 0.9019277 -0.01587194 0.2374823 0.9712622 -0.2727701 -0.5789726 0.7683667 -0.4344657 -0.7368343 0.5179912 -0.4266487 -0.7368926 0.5243665 -0.4004288 -0.7477814 0.5296035 -0.4099076 -0.7422626 0.530115 -0.4187056 -0.7386246 0.5283175 -0.5268529 -0.4348177 0.7303148 -0.3662018 -0.6437268 0.6719465 -0.451105 -0.7443182 0.4924376 -0.4425273 -0.7390437 0.5079215 0.2136258 -0.02308541 0.9766428 0.170147 0.08016937 0.9821522 0.1920539 0.03204298 0.9808611 -0.2878432 0.2485458 0.9248629 -0.08393496 0.0457037 0.9954226 -0.3246963 0.08831435 0.9416863 -0.3124449 0.06668353 0.9475926 -0.519705 0.1245953 0.8452116 -0.5329884 -0.4257041 0.7312315 0.02954894 -0.8343843 0.5503907 -0.2891212 -0.5786645 0.7625985 -0.1452638 -0.4937375 0.8573925 -0.1457542 -0.5105476 0.847406 -0.04119682 -0.3181451 0.9471465 0.162197 -0.08840543 0.9827903 -0.1727012 -0.3362969 0.9257855 -0.0614615 -0.1151809 0.9914413 -0.3097611 -0.2773463 0.9094654 -0.2849758 -0.1465737 0.9472618 -0.4849972 -0.4005627 0.777385 -0.5085364 0.04918968 0.8596343 0.7245382 -0.1853734 -0.6638382 0.167555 0.04632979 -0.9847736 0.9224111 0.1330832 -0.3625558 0.5565275 -0.4341098 -0.7083967 0.6411117 -0.009147107 -0.7673931 0.4694899 -0.1091359 -0.8761671 0.9116452 0.01169055 -0.410812 0.9329258 0.05815649 -0.355341 0.1675563 0.04635137 -0.9847723 0.3922636 0.1168525 -0.9124006 0.3922443 0.1168697 -0.9124066 0.3922696 0.1168336 -0.9124004 0.4395856 -0.4254283 -0.7910597 0.6235207 -0.1889813 -0.7586225 0.6100196 -0.08590608 -0.7877159 0.47438 -0.1219853 -0.8718276 0.787265 -0.1312018 -0.6024947 0.9026749 -0.04031735 -0.4284305 0.9322883 -0.04015564 -0.3594804 0.7523815 0.3046869 -0.5840274 0.6170181 0.5223554 -0.5885862 0.6576016 0.3281418 -0.6781469 0.4164124 0.6465736 -0.6391741 0.9115386 0.06405013 -0.4061959 0.7032427 0.315231 -0.6372435 0.8054065 0.1158187 -0.5812972 0.6323745 0.2104536 -0.7455279 0.6453637 0.1715966 -0.7443523 0.4318598 0.2948082 -0.8523997 0.4570408 0.1373997 -0.8787691 0.4315931 0.6873033 -0.5842446 0.6523827 0.2600942 0.7118623 0.7173924 0.6951588 -0.04585134 0.7110288 0.6216477 -0.3286217 0.7338641 -0.4466085 0.5118442 0.9679617 0.04519021 0.2469978 0.9337025 0.1146329 0.3392035 0.9968154 0.005547046 -0.07955098 0.996421 0.08153909 0.02228659 0.8751753 -0.2884309 0.3884276 0.9302799 0.154324 -0.3328115 0.9980835 -0.04357248 -0.04394173 0.9750663 0.1238675 -0.1841269 0.966418 0.2569297 -0.004856169 0.6352303 0.7700808 0.05880475 0.6599157 0.7462105 0.08764231 0.5380579 0.8188468 0.1999592 0.566676 0.7386471 0.3650736 0.4730923 0.8695416 0.141708 0.3584119 0.9320138 -0.05376958 0.1863036 0.9555097 -0.2286751 0.3617725 0.9197295 -0.1523756 0.4285686 0.8777738 -0.2141076 0.2888065 0.9027316 -0.3188519 0.5695497 0.8029102 -0.1759221 0.7432812 0.6504868 -0.1562052 0.7200641 0.6712907 -0.1757172 0.7578909 0.5867059 -0.2852677 0.3472127 0.7803965 -0.5200237 0.4630607 0.738132 -0.4906485 0.6365792 0.06698763 0.7682965 0.6618553 0.3154749 0.6800171 0.7834257 0.0692439 0.6176161 0.7954852 0.4061896 0.4496814 0.8559931 0.03096127 0.5160594 0.872327 0.159925 0.4620277 0.9402627 0.1583786 0.3013675 0.9375935 0.2585482 0.2325322 0.9844021 0.1511916 0.08996474 0.4653107 0.7006665 -0.5408813 0.3356997 0.7415183 -0.58091 0.7170083 0.5256655 -0.4577936 0.6388796 0.5833424 -0.5015421 0.6947737 0.7159793 -0.06828725 0.4472814 0.833841 -0.3234944 0.4785257 0.791417 -0.3803582 0.4127585 0.8124802 -0.4117118 0.5283756 0.7503454 -0.3972417 0.8040814 0.4374129 -0.4026451 0.8987546 0.3013944 -0.3184362 0.8905287 0.4320648 -0.1424039 0.9340174 0.3486562 -0.07778453 0.8874626 0.4565078 0.06333208 0.9062456 0.4118394 0.09543198 0.8483536 0.4900205 0.2004404 0.8643371 0.4460653 0.2322655 0.7716464 0.5309426 0.3502311 0.7860507 0.4863262 0.3815906 0.6308126 0.5749875 0.5210229 0.6562059 0.4653351 0.5940179 0.1751645 0.7125295 0.6794256 0.07421582 0.8014587 0.5934274 0.07449465 0.8123209 0.5784337 0.01077657 0.927466 0.3737521 -0.07112401 0.9445623 0.320536 0.1790059 0.9753819 0.1287906 0.1732667 0.9827141 0.06520485 0.272629 0.9229407 0.271761 0.3480401 0.8437302 0.408641 0.3559878 0.7896794 0.499679 0.4643082 0.6013751 0.6502045 0.4678928 0.5136846 0.7191693 0.5067479 0.2901446 0.8118021 0.5080419 0.2964975 0.808692 0.4974381 0.1012033 0.861576 0.3969156 0.2920616 0.8701484 0.3766216 0.1808705 0.9085384 0.3467173 0.4150786 0.8411284 0.2921611 0.5629914 0.7730994 0.173879 0.716228 0.6758576 0.3159846 0.605685 0.7302736 0.2326686 0.8224821 0.5190266 0.1844359 0.8488492 0.4954174 0.09222358 0.9656768 0.2428233 0.03130662 0.9781211 0.2056679 0.2374433 0.3860046 0.8914152 -0.1937083 0.8681483 0.4569416 0.2931417 0.1573194 0.9430369 -0.2869085 0.6839705 0.670722 -0.2764157 0.7666733 0.5794882 -0.1651693 0.6152825 0.7708091 -0.1505258 0.584259 0.7974857 -0.03988307 0.5226318 0.8516252 -0.07695704 0.589991 0.8037341 0.1402056 0.3660976 0.9199538 0.2873771 0.08985775 0.9535932 0.2279211 0.1280757 0.9652194 -0.1120062 0.8473759 0.519046 -0.06427925 0.7709485 0.6336455 0.03152674 0.6786019 0.7338293 0.03196948 0.6728975 0.7390446 0.1147873 0.5149052 0.8495273 0.1648035 -0.8061972 0.5682308 -0.2110294 -0.7583312 0.6167661 0.5656442 -0.0851897 0.8202374 0.6229755 -0.1784786 0.7616081 0.4472708 -0.4049843 0.7974563 0.3772185 -0.4854556 0.7886946 0.4938744 -0.03002178 0.8690149 0.6543794 0.3955802 0.6444409 0.2726969 -0.1484343 0.9505808 -0.1053078 -0.6856436 0.72028 -0.01104551 -0.6010965 0.7991001 0.07903844 -0.6733105 0.735123 -0.05803328 -0.7761386 0.6278863 0.1892355 -0.6893554 0.6992704 -0.01905393 -0.9267523 0.3751895 -0.01777118 -0.9268424 0.37503 0.2048355 -0.9047604 0.3734315 0.4082854 -0.8423777 0.3517142 0.9953872 -0.08001267 0.0529381 0.8883397 0.444787 -0.1140928 0.964861 -0.2370637 0.1133316 0.9472223 -0.1670691 0.2736018 0.948817 -0.2837004 0.1387821 0.9005425 -0.3934488 0.1849902 0.7607402 -0.5927697 0.2643835 0.7790632 -0.5742927 0.2514926 0.4350357 -0.8286122 0.3523437 0.9111095 -0.1886484 0.3664578 -0.06717759 -0.8827899 0.46494 0.3110762 -0.7769985 0.5472705 0.3389893 -0.7598248 0.5547546 0.643051 -0.5403832 0.5426522 0.6751765 -0.500261 0.5421032 0.8880633 -0.1531969 0.4334448 0.8669865 -0.2168757 0.448664 0.8291723 -0.1675634 0.5332877 0.9370719 -0.2054293 0.2823032 0.7440028 -0.5299336 0.4069771 0.7138518 -0.5676546 0.4101026 0.3958288 -0.7947244 0.4601443 0.3679351 -0.8103492 0.4560241 -0.02354443 -0.9046753 0.4254509 -0.02594101 -0.9049884 0.4246447 -0.004773378 -0.5958129 0.8031091 0.1543875 -0.4361651 0.886524 0.2137771 -0.3574433 0.909139 0.3693711 -0.1493844 0.9171965 0.5426594 -0.2852635 0.7900289 0.8049917 0.2845301 0.5206065 0.8068164 0.3036257 0.5068123 0.6983912 -0.2735683 0.6613699 0.8354784 -0.05508965 0.546755 0.7322771 -0.2860409 0.6180219 0.5859033 -0.4698458 0.6602744 0.5528395 -0.5113466 0.6579462 0.2675062 -0.7231988 0.6367292 0.2408601 -0.7414357 0.6263064 -0.1051964 -0.8577542 0.5031814 -0.1338159 -0.8286947 0.543469 -0.1439091 -0.8325172 0.5349815 -0.177286 -0.8031095 0.5688452 -0.1577088 -0.7927082 0.5888479 -0.2693465 -0.7882907 0.553218 -0.3063403 -0.8091949 0.5013577 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.05991184 -0.2085626 -0.9761723 0.4873585 -0.2084038 -0.8479679 0.8162783 -0.2081369 -0.5388588 -0.7292341 -0.2086337 -0.6516821 -0.3900035 -0.2087948 -0.8968289 0.2367355 -0.9251122 -0.2968567 0.07160425 -0.9974005 0.008067846 0.01634168 -0.9972997 0.07159775 0.01634162 -0.9972998 0.07159745 -0.01634162 -0.9972998 0.07159745 -0.01634168 -0.9972997 0.07159769 -0.04578846 -0.9972997 0.05741697 0.06616532 -0.9972999 0.03186351 0.07160425 -0.9974006 -0.008067846 0.04578816 -0.9972999 -0.05741655 0.04578846 -0.9972997 -0.05741697 0.01634168 -0.9972997 -0.07159781 0.08448946 -0.925113 0.3701723 0.08448994 -0.925112 0.3701748 -0.08449006 -0.925112 0.370175 -0.0844894 -0.925113 0.3701722 -0.2367344 -0.9251128 0.2968558 -0.2367354 -0.9251123 0.2968564 -0.3420913 -0.9251127 0.1647425 0.1704334 -0.6429355 0.7467172 0.1704321 -0.6429425 0.7467114 -0.170432 -0.6429423 0.7467116 -0.1704334 -0.6429353 0.7467172 -0.4775438 -0.642935 0.5988211 -0.4775433 -0.6429359 0.5988203 -0.6900693 -0.6429371 0.3323197 -0.6900671 -0.6429399 0.3323188 -0.7659088 -0.6429492 0 0.06616783 -0.9972996 0.03186476 0.3420929 -0.925112 0.1647433 0.3420936 -0.9251117 0.1647436 0.6900704 -0.6429355 0.3323204 0.7033748 -0.6244265 0.3396403 0.7034359 -0.6248373 -0.3387569 0.342091 -0.9251129 -0.1647424 0.3420954 -0.9251108 -0.1647444 0.06616425 -0.9972999 -0.03186303 0.06616884 -0.9972996 -0.03186523 -0.07343685 -0.9972999 0 -0.06616783 -0.9972996 -0.03186476 -0.3420929 -0.925112 -0.1647433 -0.2367346 -0.9251127 -0.2968557 -0.4869608 -0.6245 -0.61063 -0.1737892 -0.6245383 -0.7614127 -0.1683389 0.6539927 -0.7375335 -0.1807895 -0.2055375 -0.9618054 -0.0661689 -0.9972996 0.03186523 -0.07344245 -0.9972996 0 -0.3796933 -0.9251124 0 -0.3420936 -0.9251117 -0.1647436 -0.7036738 -0.6245072 -0.3388715 -0.4869428 -0.6245398 -0.6106036 -0.398147 0.7695586 -0.4992579 -0.5662412 -0.2061521 -0.7980429 -0.04578799 -0.9972998 0.05741631 -0.06616479 -0.9972999 0.03186327 -0.3420946 -0.9251112 0.1647441 -0.3796927 -0.9251127 0 -0.7659204 -0.6429356 0 -0.6903816 -0.643042 -0.3314669 -0.7252843 0.5912702 -0.3526502 -0.8652276 -0.205504 -0.4573283 -0.9395344 -0.2321186 -0.2517857 -0.9734596 -0.2278094 -0.02189874 -0.9344597 0.356069 0 -0.9529027 -0.2322262 0.1950575 -0.8774999 -0.2267573 0.4225815 -0.8987753 0.1265456 0.4197491 -0.5319733 -0.5215529 0.6670735 -0.6163381 -0.226164 0.7543058 -0.4196152 -0.2322789 0.8774793 -0.2200427 -0.148806 0.9640737 -0.2141038 -0.2268941 0.9500941 0.216724 -0.2267598 0.9495319 0.2167244 -0.2267631 0.949531 0.4416694 -0.232227 0.866602 0.5823832 0.3570901 0.7302852 0.4775426 -0.6429373 0.5988193 0.4775442 -0.642934 0.5988218 0.2367348 -0.9251126 0.296856 0.2367352 -0.9251124 0.2968565 0.04578834 -0.9972997 0.05741673 0.04578816 -0.9972999 0.05741655 0.8378181 0.5435276 0.05136823 0.6241019 -0.2278129 0.7473943 0.7837929 -0.2321197 0.5760116 0.7135699 0.6124293 0.3402181 0.8977748 -0.2055937 0.3895275 0.963312 -0.2086796 0.1687687 0.01096379 -0.9999399 0 0.3796933 -0.9251124 0 0.3796927 -0.9251127 0 0.7809875 -0.6245467 0 0.7807579 -0.6248338 -1.37398e-5 0.512314 0.8587983 5.73474e-5 0.9719645 -0.2080666 -0.1095138 -0.01634162 -0.9972998 -0.07159745 0.01634162 -0.9972998 -0.07159745 0.0844894 -0.925113 -0.3701723 0.2367344 -0.9251128 -0.2968558 0.4869558 -0.6245101 -0.6106236 0.7036524 -0.6245454 -0.3388458 0.4773237 0.8481121 -0.2299304 0.9158417 -0.2075246 -0.343755 -0.04578793 -0.9972999 -0.05741626 -0.01634168 -0.9972997 -0.07159775 -0.08448994 -0.925112 -0.3701748 0.08449006 -0.925112 -0.370175 0.1737942 -0.6245015 -0.7614417 0.48694 -0.62454 -0.6106058 0.3547742 0.8223263 -0.4448764 0.6640771 -0.2066891 -0.7185271 -0.06616532 -0.9972999 -0.03186351 -0.04578852 -0.9972997 -0.05741697 -0.2367352 -0.9251123 -0.2968565 -0.08448946 -0.925113 -0.3701723 -0.1737936 -0.6245056 -0.7614385 0.1737838 -0.6245455 -0.761408 0.1364198 0.7900267 -0.5977018 0.2757614 -0.2063214 -0.9388223 0 1 1.69587e-6 0 1 0 0 1 1.52707e-7 0 1 -8.56224e-7 0 1 -3.06061e-7 0 1 3.01061e-7 0 1 -1.72687e-6 0 1 4.99984e-7 0 1 -1.91363e-6 0 1 3.06525e-7 0 1 -4.22799e-7 0 1 -2.94117e-7 0 1 0 0 1 2.96075e-7 0 1 2.99554e-7 0 1 0 0.9981257 0 0.0611971 0.9849977 0 0.1725679 0.9849977 0 0.1725679 0.9173722 0 0.3980305 0.8058014 0 0.592186 0.805801 0 0.5921866 0.6409559 0 0.7675778 0.6409559 0 0.7675778 0.4540832 0 0.8909593 0.4540832 0 0.8909593 0.2225207 0 0.974928 -0.2198368 0 0.9755368 -0.2198367 0 0.9755367 -0.6305991 0 0.7761089 -0.4307032 -0.05624985 0.900739 -0.6327327 0 0.7743704 -0.9060592 0 0.423151 -0.9060592 0 0.423151 -0.9796855 0 0.20054 -0.9796855 0 0.2005401 -0.9997471 0 -0.02249008 -0.965916 0 -0.2588558 -0.965916 0 -0.2588558 -0.8840977 0 -0.4673023 -0.8840976 0 -0.4673024 -0.7456427 0 -0.666346 -0.7456428 0 -0.6663459 -0.5786715 0 -0.8155608 -0.578671 0 -0.8155611 -0.3987923 0 -0.9170413 -0.3987945 0 -0.9170404 -0.1847337 0 -0.9827886 -0.1847332 0 -0.9827888 0.06125634 0 -0.9981221 0.06125795 0 -0.998122 0.2818246 0 -0.959466 0.2818251 0 -0.9594658 0.4983001 0 -0.8670046 0.4982991 0 -0.8670053 0.6787331 0 -0.7343851 0.6787332 0 -0.734385 0.8345553 0 -0.5509243 0.8345554 0 -0.5509241 0.9362235 0 -0.3514052 0.9937123 0 -0.1119642 -0.06594461 -0.9550866 -0.2888961 -0.1423023 -0.9736055 -0.1784446 -0.5774048 0.06586694 -0.8137968 -0.3979278 0.06676465 -0.9149842 -0.2732416 -0.9529033 -0.1315836 -0.882187 0.06570768 -0.4662925 -0.7440018 0.06675958 -0.6648342 -0.4487093 -0.8936778 -1.078e-4 -0.9975982 0.06553065 -0.02244168 -0.9637612 0.06674963 -0.2582808 0.2767891 -0.8960528 0.3470984 0.4530804 0.06681632 0.8889622 0.2220919 0.06517183 0.9728453 0.2219671 0.06982403 0.9725509 -0.2219773 0.06982851 0.9725483 -0.2158353 -0.1901936 0.9577273 -0.5939746 0.3248406 0.7359843 -0.5667071 0.4386096 0.6974703 -0.8956771 -0.1440663 0.4207227 -0.9040586 0.06639617 0.4222198 -0.9774485 0.06759434 0.2000641 0.2629396 -0.956466 0.1266315 0.8040095 0.06678849 0.5908537 0.6396181 0.06550323 0.7658969 0.1723725 -0.9850319 0 0.3627207 -0.9316327 0.02223581 0.9828026 0.06674712 0.1721745 0.9153949 0.06574583 0.397152 0.161691 -0.9837645 -0.07786917 0.9341737 0.06620275 -0.3506234 0.9915173 0.06644427 -0.1117079 0.1223129 -0.9805691 -0.1533752 0.6772852 0.0661118 -0.7327442 0.8327164 0.06660348 -0.5496795 -0.1843415 0.06570321 -0.9806638 0.06111925 0.06671547 -0.9958984 0.04806065 -0.9763928 -0.2105882 0.2812023 0.06597673 -0.9573779 0.4971997 0.06668621 -0.8650696 0.5819044 0.3590988 -0.7296817 0.5819104 0.3590601 -0.7296959 0.8408851 0.3590601 -0.4049544 0.8408902 0.3590515 -0.4049515 0.9333165 0.3590548 0 0.9333085 0.3590758 0 0.8408852 0.35906 0.4049543 0.8408883 0.3590646 0.4049437 0.5819121 0.359061 0.7296941 0.5819105 0.3590601 0.7296959 0.2076851 0.3590664 0.9099112 0.2071418 0.3634408 0.9082969 -0.2073033 0.3634302 0.9082642 -0.2073097 0.3634398 0.908259 -0.5808554 0.3634285 0.7283728 -0.510426 0.5895112 0.6260526 -0.8702625 0.2588482 0.4190953 -0.8415061 0.3598827 0.4029293 -0.9330085 0.3598545 0 -0.9333078 0.3590775 2.96029e-5 -0.8408822 0.35907 -0.4049518 -0.8408882 0.3590576 -0.4049504 -0.5819121 0.359061 -0.7296941 -0.5819163 0.3590199 -0.7297109 -0.2076874 0.3590271 -0.9099262 -0.2076826 0.3590676 -0.9099112 0.2076795 0.3590622 -0.9099141 0.2076794 0.3590984 -0.9098998 -0.1473023 0.749546 -0.6453548 -0.1472969 0.7495204 -0.6453859 -0.412729 0.749541 -0.5175358 -0.4127278 0.7495391 -0.5175393 -0.5964154 0.7495325 -0.2872104 -0.5964006 0.7495427 -0.2872146 -0.6619592 0.7495399 0 -0.6619622 0.7495374 0 -0.5964079 0.7495371 0.2872138 -0.5964068 0.7495366 0.2872175 -0.4127304 0.7495393 0.517537 -0.4127264 0.7495408 0.517538 -0.1472995 0.749534 0.6453694 -0.1472997 0.7495322 0.6453714 0.1473023 0.749546 0.6453548 0.1472969 0.7495204 0.6453859 0.412729 0.749541 0.5175358 0.4127278 0.7495391 0.5175393 0.5964154 0.7495325 0.2872104 0.5964006 0.7495427 0.2872146 0.6619592 0.7495399 0 0.6619622 0.7495374 0 0.5964079 0.7495371 -0.2872138 0.5964068 0.7495366 -0.2872175 0.4127304 0.7495393 -0.517537 0.4127264 0.7495408 -0.517538 0.1472995 0.749534 -0.6453694 0.1472997 0.7495322 -0.6453714 0.2143607 0.971283 0.103242 0.2321994 0.9723163 0.02616351 0.08693408 0.9962142 0 0.2321994 0.9723163 -0.02616351 0.2143598 0.9712851 -0.103224 0.2143578 0.9712834 -0.1032442 0.1483398 0.9712842 -0.186017 0.1483401 0.9712829 -0.186024 0.05294209 0.9712843 -0.2319573 0.05294215 0.9712862 -0.2319489 -0.05294239 0.9712907 -0.2319298 -0.05294185 0.9712797 -0.231976 -0.1483408 0.9712839 -0.1860183 -0.1483391 0.9712833 -0.1860227 -0.2143567 0.9712859 -0.1032226 -0.2143608 0.9712826 -0.1032456 -0.2379179 0.9712853 0 -0.2379245 0.9712837 0 -0.2143598 0.9712851 0.103224 -0.2143578 0.9712834 0.1032442 -0.1483398 0.9712842 0.186017 -0.1483401 0.9712829 0.186024 -0.05294209 0.9712843 0.2319573 -0.05294215 0.9712862 0.2319489 0.05294239 0.9712907 0.2319298 0.05294185 0.9712797 0.231976 0.1483408 0.9712839 0.1860183 0.1483391 0.9712833 0.1860227 0.2143567 0.9712859 0.1032226 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + 1 0 0 0 0 -4.37114e-8 -1 0 0 1 -4.37114e-8 0 0 0 0 1 + + + + + + + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/robots/mini_quadrotor/urdf/mesh/turnigy_3S_2200mAh.dae b/robots/mini_quadrotor/urdf/mesh/turnigy_3S_2200mAh.dae new file mode 100644 index 000000000..ba339fec8 --- /dev/null +++ b/robots/mini_quadrotor/urdf/mesh/turnigy_3S_2200mAh.dae @@ -0,0 +1,162 @@ + + + + + Blender User + Blender 3.0.1 commit date:2022-01-25, commit time:17:19, hash:dc2d18018171 + + 2022-12-17T18:06:10 + 2022-12-17T18:06:10 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0.00111109 + + + + + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + 0 + 1000 + 29.99998 + 75 + 0.15 + 0 + 1 + 2 + 0.04999995 + 30.002 + 1 + 3 + 2880 + 3 + 1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.001904119 0.004750105 0.8000001 1 + + + 0.5 + + + + + + + + + + + + + + + + + 0.05149996 0.01199996 0.01649999 -0.05149996 0.01199996 0.01649999 0.05149996 -0.01199996 0.01649999 -0.05149996 -0.01199996 0.01649999 0.05149996 0.01199996 -0.01649999 -0.05149996 0.01199996 -0.01649999 0.05149996 -0.01199996 -0.01649999 -0.05149996 -0.01199996 -0.01649999 + + + + + + + + + + 0 0 1 0 1 0 0 0 -1 0 -1 0 -1 0 0 1 0 0 + + + + + + + + + + + + + + +

0 0 1 0 2 0 2 0 1 0 3 0 4 1 5 1 0 1 0 1 5 1 1 1 6 2 7 2 4 2 4 2 7 2 5 2 2 3 3 3 6 3 6 3 3 3 7 3 5 4 7 4 1 4 1 4 7 4 3 4 6 5 4 5 2 5 2 5 4 5 0 5

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/robots/mini_quadrotor/urdf/robot.gazebo.xacro b/robots/mini_quadrotor/urdf/robot.gazebo.xacro new file mode 100644 index 000000000..a5d84d326 --- /dev/null +++ b/robots/mini_quadrotor/urdf/robot.gazebo.xacro @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + 0.1 + 0.1 + + + diff --git a/robots/mini_quadrotor/urdf/robot.urdf.xacro b/robots/mini_quadrotor/urdf/robot.urdf.xacro new file mode 100644 index 000000000..08a74e762 --- /dev/null +++ b/robots/mini_quadrotor/urdf/robot.urdf.xacro @@ -0,0 +1,161 @@ + + + + + + + + + + + + + + + + + + + + + 0.00 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + transmission_interface/SimpleTransmission + + + RotorInterface + + + + RotorInterface + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +