diff --git a/src/ZLAC8015D_python/examples/ZLAC8015D.py b/src/ZLAC8015D_python/examples/ZLAC8015D.py new file mode 100644 index 0000000..274fa36 --- /dev/null +++ b/src/ZLAC8015D_python/examples/ZLAC8015D.py @@ -0,0 +1,331 @@ + +from pymodbus.client.sync import ModbusSerialClient as ModbusClient +import numpy as np + +class Controller: + + def __init__(self, port="/dev/ttyUSB0"): + + self._port = port + + self.client = ModbusClient(method='rtu', port=self._port, baudrate=115200, timeout=1) + + self.client.connect() + + self.ID = 1 + + ###################### + ## Register Address ## + ###################### + ## Common + self.CONTROL_REG = 0x200E + self.OPR_MODE = 0x200D + self.L_ACL_TIME = 0x2080 + self.R_ACL_TIME = 0x2081 + self.L_DCL_TIME = 0x2082 + self.R_DCL_TIME = 0x2083 + + ## Velocity control + self.L_CMD_RPM = 0x2088 + self.R_CMD_RPM = 0x2089 + self.L_FB_RPM = 0x20AB + self.R_FB_RPM = 0x20AC + + ## Position control + self.POS_CONTROL_TYPE = 0x200F + + self.L_MAX_RPM_POS = 0x208E + self.R_MAX_RPM_POS = 0x208F + + self.L_CMD_REL_POS_HI = 0x208A + self.L_CMD_REL_POS_LO = 0x208B + self.R_CMD_REL_POS_HI = 0x208C + self.R_CMD_REL_POS_LO = 0x208D + + self.L_FB_POS_HI = 0x20A7 + self.L_FB_POS_LO = 0x20A8 + self.R_FB_POS_HI = 0x20A9 + self.R_FB_POS_LO = 0x20AA + + ## Troubleshooting + self.L_FAULT = 0x20A5 + self.R_FAULT = 0x20A6 + + ######################## + ## Control CMDs (REG) ## + ######################## + self.EMER_STOP = 0x05 + self.ALRM_CLR = 0x06 + self.DOWN_TIME = 0x07 + self.ENABLE = 0x08 + self.POS_SYNC = 0x10 + self.POS_L_START = 0x11 + self.POS_R_START = 0x12 + + #################### + ## Operation Mode ## + #################### + self.POS_REL_CONTROL = 1 + self.POS_ABS_CONTROL = 2 + self.VEL_CONTROL = 3 + + self.ASYNC = 0 + self.SYNC = 1 + + ################# + ## Fault codes ## + ################# + self.NO_FAULT = 0x0000 + self.OVER_VOLT = 0x0001 + self.UNDER_VOLT = 0x0002 + self.OVER_CURR = 0x0004 + self.OVER_LOAD = 0x0008 + self.CURR_OUT_TOL = 0x0010 + self.ENCOD_OUT_TOL = 0x0020 + self.MOTOR_BAD = 0x0040 + self.REF_VOLT_ERROR = 0x0080 + self.EEPROM_ERROR = 0x0100 + self.WALL_ERROR = 0x0200 + self.HIGH_TEMP = 0x0400 + self.FAULT_LIST = [self.OVER_VOLT, self.UNDER_VOLT, self.OVER_CURR, self.OVER_LOAD, self.CURR_OUT_TOL, self.ENCOD_OUT_TOL, \ + self.MOTOR_BAD, self.REF_VOLT_ERROR, self.EEPROM_ERROR, self.WALL_ERROR, self.HIGH_TEMP] + + ############## + ## Odometry ## + ############## + ## 8 inches wheel + self.travel_in_one_rev = 0.655 + self.cpr = 16385 + self.R_Wheel = 0.105 #meter + print(self.R_Wheel) + + ## Some time if read immediatly after write, it would show ModbusIOException when get data from registers + def modbus_fail_read_handler(self, ADDR, WORD): + + read_success = False + reg = [None]*WORD + while not read_success: + result = self.client.read_holding_registers(ADDR, WORD, unit=self.ID) + try: + for i in range(WORD): + reg[i] = result.registers[i] + read_success = True + except AttributeError as e: + print(e) + pass + + return reg + + def rpm_to_radPerSec(self, rpm): + return rpm*2*np.pi/60.0 + + def rpm_to_linear(self, rpm): + + W_Wheel = self.rpm_to_radPerSec(rpm) + V = W_Wheel*self.R_Wheel + + return V + + def set_mode(self, MODE): + if MODE == 1: + print("Set relative position control") + elif MODE == 2: + print("Set absolute position control") + elif MODE == 3: + print("Set speed rpm control") + else: + print("set_mode ERROR: set only 1, 2, or 3") + return 0 + + result = self.client.write_register(self.OPR_MODE, MODE, unit=self.ID) + return result + + def get_mode(self): + + # result = self.client.read_holding_registers(self.OPR_MODE, 1, unit=self.ID) + registers = self.modbus_fail_read_handler(self.OPR_MODE, 1) + + mode = registers[0] + + return mode + + def enable_motor(self): + result = self.client.write_register(self.CONTROL_REG, self.ENABLE, unit=self.ID) + + def disable_motor(self): + result = self.client.write_register(self.CONTROL_REG, self.DOWN_TIME, unit=self.ID) + + def get_fault_code(self): + + fault_codes = self.client.read_holding_registers(self.L_FAULT, 2, unit=self.ID) + + L_fault_code = fault_codes.registers[0] + R_fault_code = fault_codes.registers[1] + + L_fault_flag = L_fault_code in self.FAULT_LIST + R_fault_flag = R_fault_code in self.FAULT_LIST + + return (L_fault_flag, L_fault_code), (R_fault_flag, R_fault_code) + + def clear_alarm(self): + result = self.client.write_register(self.CONTROL_REG, self.ALRM_CLR, unit=self.ID) + + def set_accel_time(self, L_ms, R_ms): + + if L_ms > 32767: + L_ms = 32767 + elif L_ms < 0: + L_ms = 0 + + if R_ms > 32767: + R_ms = 32767 + elif R_ms < 0: + R_ms = 0 + + result = self.client.write_registers(self.L_ACL_TIME, [int(L_ms),int(R_ms)], unit=self.ID) + + + def set_decel_time(self, L_ms, R_ms): + + if L_ms > 32767: + L_ms = 32767 + elif L_ms < 0: + L_ms = 0 + + if R_ms > 32767: + R_ms = 32767 + elif R_ms < 0: + R_ms = 0 + + result = self.client.write_registers(self.L_DCL_TIME, [int(L_ms), int(R_ms)], unit=self.ID) + + def int16Dec_to_int16Hex(self,int16): + + lo_byte = (int16 & 0x00FF) + hi_byte = (int16 & 0xFF00) >> 8 + + all_bytes = (hi_byte << 8) | lo_byte + + return all_bytes + + + def set_rpm(self, L_rpm, R_rpm): + + if L_rpm > 3000: + L_rpm = 3000 + elif L_rpm < -3000: + L_rpm = -3000 + + if R_rpm > 3000: + R_rpm = 3000 + elif R_rpm < -3000: + R_rpm = -3000 + + left_bytes = self.int16Dec_to_int16Hex(L_rpm) + right_bytes = self.int16Dec_to_int16Hex(R_rpm) + + result = self.client.write_registers(self.L_CMD_RPM, [left_bytes, right_bytes], unit=self.ID) + + def get_rpm(self): + + + # rpms = self.client.read_holding_registers(self.L_FB_RPM, 2, unit=self.ID) + # fb_L_rpm = np.int16(rpms.registers[0])/10.0 + # fb_R_rpm = np.int16(rpms.registers[1])/10.0 + + registers = self.modbus_fail_read_handler(self.L_FB_RPM, 2) + fb_L_rpm = np.int16(registers[0])/10.0 + fb_R_rpm = np.int16(registers[1])/10.0 + + return fb_L_rpm, fb_R_rpm + + def get_linear_velocities(self): + + rpmL, rpmR = self.get_rpm() + + VL = self.rpm_to_linear(rpmL) + VR = self.rpm_to_linear(-rpmR) + + return VL, VR + + def map(self, val, in_min, in_max, out_min, out_max): + + return (val - in_min) * (out_max - out_min) / (in_max - in_min) + out_min + + def set_maxRPM_pos(self, max_L_rpm, max_R_rpm): + + if max_L_rpm > 1000: + max_L_rpm = 1000 + elif max_L_rpm < 1: + max_L_rpm = 1 + + if max_R_rpm > 1000: + max_R_rpm = 1000 + elif max_R_rpm < 1: + max_R_rpm = 1 + + result = self.client.write_registers(self.L_MAX_RPM_POS, [int(max_L_rpm), int(max_R_rpm)], unit=self.ID) + + def set_position_async_control(self): + + result = self.client.write_register(self.POS_CONTROL_TYPE, self.ASYNC, unit=self.ID) + + def move_left_wheel(self): + + result = self.client.write_register(self.CONTROL_REG, self.POS_L_START, unit=self.ID) + + def move_right_wheel(self): + + result = self.client.write_register(self.CONTROL_REG, self.POS_R_START, unit=self.ID) + + def deg_to_32bitArray(self, deg): + + dec = int(self.map(deg, -1440, 1440, -65536, 65536)) + HI_WORD = (dec & 0xFFFF0000) >> 16 + LO_WORD = dec & 0x0000FFFF + + return [HI_WORD, LO_WORD] + + def set_relative_angle(self, ang_L, ang_R): + + L_array = self.deg_to_32bitArray(ang_L) + R_array = self.deg_to_32bitArray(ang_R) + all_cmds_array = L_array + R_array + + result = self.client.write_registers(self.L_CMD_REL_POS_HI, all_cmds_array, unit=self.ID) + + def get_wheels_travelled(self): + + # read_success = False + # while not read_success: + + # result = self.client.read_holding_registers(self.L_FB_POS_HI, 4, unit=self.ID) + # try: + # l_pul_hi = result.registers[0] + # l_pul_lo = result.registers[1] + # r_pul_hi = result.registers[2] + # r_pul_lo = result.registers[3] + + # l_pulse = ((l_pul_hi & 0xFFFF) << 16) | (l_pul_lo & 0xFFFF) + # r_pulse = ((r_pul_hi & 0xFFFF) << 16) | (r_pul_lo & 0xFFFF) + # l_travelled = (float(l_pulse)/self.cpr)*self.travel_in_one_rev # unit in meter + # r_travelled = (float(r_pulse)/self.cpr)*self.travel_in_one_rev # unit in meter + + # read_success = True + + # except AttributeError: + # # print("error") + # pass + + registers = self.modbus_fail_read_handler(self.L_FB_POS_HI, 4) + l_pul_hi = registers[0] + l_pul_lo = registers[1] + r_pul_hi = registers[2] + r_pul_lo = registers[3] + + l_pulse = np.int32(((l_pul_hi & 0xFFFF) << 16) | (l_pul_lo & 0xFFFF)) + r_pulse = np.int32(((r_pul_hi & 0xFFFF) << 16) | (r_pul_lo & 0xFFFF)) + l_travelled = (float(l_pulse)/self.cpr)*self.travel_in_one_rev # unit in meter + r_travelled = (float(r_pulse)/self.cpr)*self.travel_in_one_rev # unit in meter + + return l_travelled, r_travelled diff --git a/src/ZLAC8015D_python/examples/test_speed_control.py b/src/ZLAC8015D_python/examples/test_speed_control.py index fcff88c..de92eb6 100644 --- a/src/ZLAC8015D_python/examples/test_speed_control.py +++ b/src/ZLAC8015D_python/examples/test_speed_control.py @@ -1,23 +1,21 @@ -from zlac8015d import ZLAC8015D -import importlib -importlib.reload(ZLAC8015D) +import ZLAC8015D import time motors = ZLAC8015D.Controller(port="/dev/ZLAC8015D") motors.disable_motor() -motors.set_accel_time(500,500) +motors.set_accel_time(1000,1000) motors.set_decel_time(1000,1000) motors.set_mode(3) motors.enable_motor() -cmds = [-140, 170] +# cmds = [140, 170] #cmds = [100, 50] #cmds = [150, -100] -#cmds = [-50, 30] +cmds = [-50, 30] motors.set_rpm(cmds[0],cmds[1]) @@ -29,13 +27,12 @@ # motors.set_rpm(cmds[0],cmds[1]) rpmL, rpmR = motors.get_rpm() - #print("period: {:.4f} rpmL: {:.1f} | rpmR: {:.1f}".format(period,rpmL,rpmR)) - print("{:.4f},{:.1f},{:.1f}".format(period,rpmL,rpmR)) + print("period: {:.4f} rpmL: {:.1f} | rpmR: {:.1f}".format(period,rpmL,rpmR)) time.sleep(0.01) - + except KeyboardInterrupt: motors.disable_motor() break - #last_time = time.time() + last_time = time.time() diff --git a/src/ZLAC8015D_python/zlac8015d/ZLAC8015D.py b/src/ZLAC8015D_python/zlac8015d/ZLAC8015D.py index 45541fe..cbc8c30 100644 --- a/src/ZLAC8015D_python/zlac8015d/ZLAC8015D.py +++ b/src/ZLAC8015D_python/zlac8015d/ZLAC8015D.py @@ -1,6 +1,7 @@ from pymodbus.client.sync import ModbusSerialClient as ModbusClient import numpy as np +import time class Controller: @@ -110,6 +111,7 @@ reg[i] = result.registers[i] read_success = True except AttributeError as e: + time.sleep(0.5) print(e) pass @@ -131,8 +133,7 @@ elif MODE == 2: print("Set absolute position control") elif MODE == 3: - dummy = 0 - #print("Set speed rpm control") + print("Set speed rpm control") else: print("set_mode ERROR: set only 1, 2, or 3") return 0 diff --git a/src/ira_laser_tools b/src/ira_laser_tools new file mode 160000 index 0000000..958d0ac --- /dev/null +++ b/src/ira_laser_tools @@ -0,0 +1 @@ +Subproject commit 958d0ac8e103822ce9ce04c0bb9c3b499322575d diff --git a/src/junk/tsukuba2022/config/gps_parameters.yaml b/src/junk/tsukuba2022/config/gps_parameters.yaml new file mode 100644 index 0000000..38970f9 --- /dev/null +++ b/src/junk/tsukuba2022/config/gps_parameters.yaml @@ -0,0 +1,37 @@ +# maintainer:kbkn/mori +# +# name of the port that connects to gps device +dev_name: /dev/sensors/rtkgps +# directory of the file where waypoints will be saved +output_file: /home/ubuntu/catkin_ws/src/igvc2022/config/gps_waypoints/gps_waypoints.yaml +#output_file: /home/ubuntu/catkin_ws/src/igvc2022/config/gps_waypoints/qualification_waypoints.yaml +# country_id: 0, then Japan +# country_id: 1, then USA +country_id: 0 +# true north is 0 degrees, clockwise angle +azimuth: 180 +# latitude and longitude information given by the organizer at IGVC +# - - latitude(1) +# - longitude(1) +# - - latitude(2) +# - longitude(2) +# ............ +latitude_longitude: + - - 42.66792770 + - -83.21932764 + - - 42.66807663 + - -83.21935915 + - - 42.66812064 + - -83.21936060 + - - 42.66826972 + - -83.21934030 + + +# - - 42.66826972 +# - -83,21934030 +# - - 42.66812064 +# - -83.21936060 +# - - 42.66807663 +# - -83.21935915 +# - - 42.66792770 +# - -83.21932764 diff --git a/src/junk/tsukuba2022/config/gps_waypoints/gps_waypoints.yaml b/src/junk/tsukuba2022/config/gps_waypoints/gps_waypoints.yaml new file mode 100644 index 0000000..1de4c59 --- /dev/null +++ b/src/junk/tsukuba2022/config/gps_waypoints/gps_waypoints.yaml @@ -0,0 +1,17 @@ +waypoints: + - point: + x: 23.832395277342513 + y: -39.51859423889264 + z: 0 + - point: + x: 7.288423107180874 + y: -42.101774823056566 + z: 0 + - point: + x: 2.399529025831852 + y: -42.22065671153237 + z: 0 + - point: + x: -14.161232871434652 + y: -40.556537994560074 + z: 0 diff --git a/src/junk/tsukuba2022/config/gps_waypoints/gps_waypoints_north.yaml b/src/junk/tsukuba2022/config/gps_waypoints/gps_waypoints_north.yaml new file mode 100644 index 0000000..ff46ecf --- /dev/null +++ b/src/junk/tsukuba2022/config/gps_waypoints/gps_waypoints_north.yaml @@ -0,0 +1,17 @@ +waypoints: + - point: + x: 18.6965 + y: 41.0993 + z: 0 + - point: + x: 4.5435 + y: 41.0993 + z: 0 + - point: + x: -5.1435 + y: 41.0993 + z: 0 + - point: + x: -19.2965 + y: 41.0993 + z: 0 diff --git a/src/junk/tsukuba2022/config/gps_waypoints/gps_waypoints_simulation.yaml b/src/junk/tsukuba2022/config/gps_waypoints/gps_waypoints_simulation.yaml new file mode 100644 index 0000000..01d3b85 --- /dev/null +++ b/src/junk/tsukuba2022/config/gps_waypoints/gps_waypoints_simulation.yaml @@ -0,0 +1,17 @@ +waypoints: + - point: + x: 15.799 + y: 30.600 + z: 0 + - point: + x: 4.700 + y: 30.142 + z: 0 + - point: + x: -4.420 + y: 30.514 + z: 0 + - point: + x: -15.912 + y: 30.702 + z: 0 diff --git a/src/junk/tsukuba2022/config/gps_waypoints/gps_waypoints_simulation_reverse.yaml b/src/junk/tsukuba2022/config/gps_waypoints/gps_waypoints_simulation_reverse.yaml new file mode 100644 index 0000000..9897947 --- /dev/null +++ b/src/junk/tsukuba2022/config/gps_waypoints/gps_waypoints_simulation_reverse.yaml @@ -0,0 +1,17 @@ +waypoints: + - point: + x: -15.799 + y: -30.600 + z: 0 + - point: + x: -4.700 + y: -30.142 + z: 0 + - point: + x: 4.420 + y: -30.514 + z: 0 + - point: + x: 15.912 + y: -30.702 + z: 0 diff --git a/src/junk/tsukuba2022/config/gps_waypoints/gps_waypoints_south.yaml b/src/junk/tsukuba2022/config/gps_waypoints/gps_waypoints_south.yaml new file mode 100644 index 0000000..f08bc57 --- /dev/null +++ b/src/junk/tsukuba2022/config/gps_waypoints/gps_waypoints_south.yaml @@ -0,0 +1,17 @@ +waypoints: + - point: + x: 19.2965 + y: -41.0993 + z: 0 + - point: + x: 5.1435 + y: -41.0993 + z: 0 + - point: + x: -4.5435 + y: -41.0993 + z: 0 + - point: + x: -18.6965 + y: -41.0993 + z: 0 diff --git a/src/junk/tsukuba2022/config/gps_waypoints/qualification_waypoints.yaml b/src/junk/tsukuba2022/config/gps_waypoints/qualification_waypoints.yaml new file mode 100644 index 0000000..de097ab --- /dev/null +++ b/src/junk/tsukuba2022/config/gps_waypoints/qualification_waypoints.yaml @@ -0,0 +1,17 @@ +waypoints: + - point: + x: 7.058685 + y: 0.5 + z: 0 + - point: + x: 14.117370781974484 + y: 1 + z: 0 + - point: + x: 14.117370781974484 + y: -2.1647149478696024 + z: 0 + - point: + x: -258532440.12709326 + y: 18422863.225660857 + z: 0 diff --git a/src/junk/tsukuba2022/config/igvc_robot_control.yaml b/src/junk/tsukuba2022/config/igvc_robot_control.yaml new file mode 100644 index 0000000..bb3afc4 --- /dev/null +++ b/src/junk/tsukuba2022/config/igvc_robot_control.yaml @@ -0,0 +1,43 @@ +joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 100 + +igvc_robot: + type : "diff_drive_controller/DiffDriveController" + left_wheel : 'right_wheel_hinge' + right_wheel : 'left_wheel_hinge' + publish_rate: 100 + + enable_odom_tf: false + + pose_covariance_diagonal : [0.00001, 0.00001, 1000000000000.0, 1000000000000.0, 1000000000000.0, 0.001] + twist_covariance_diagonal: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] + + # Wheel separation and radius multipliers + wheel_separation_multiplier: 1.0 # default: 1.0 + wheel_radius_multiplier : 1.0 # default: 1.0 + + # Velocity commands timeout [s], default 0.5 + cmd_vel_timeout: 1.0 + + # Base frame_id + base_frame_id: base_link + + # Velocity and acceleration limits + # Whenever a min_* is unspecified, default to -max_* + linear: + x: + has_velocity_limits : true + max_velocity : 0.8 # m/s + min_velocity : -0.8 # m/s + has_acceleration_limits: true + max_acceleration : 0.8 # m/s^2 + min_acceleration : -0.8 # m/s^2 + angular: + z: + has_velocity_limits : true + max_velocity : 0.4 # rad/s + min_velocity : -0.4 # rad/s + has_acceleration_limits: true + max_acceleration : 0.3 # rad/s^2 + min_acceleration : -0.3 # rad/s^2 diff --git a/src/junk/tsukuba2022/config/igvc_robot_control_sim.yaml b/src/junk/tsukuba2022/config/igvc_robot_control_sim.yaml new file mode 100644 index 0000000..cb6b6b3 --- /dev/null +++ b/src/junk/tsukuba2022/config/igvc_robot_control_sim.yaml @@ -0,0 +1,45 @@ +joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 100 + +igvc_robot: + #type: "icart_mini_controller/ICartMiniController" + type : "diff_drive_controller/DiffDriveController" + left_wheel : 'left_wheel_hinge' + right_wheel : 'right_wheel_hinge' + publish_rate: 100 + + enable_odom_tf: false + + #pose_covariance_diagonal : [0.00001, 0.00001, 1000000000000.0, 1000000000000.0, 1000000000000.0, 0.001] + #twist_covariance_diagonal: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] + pose_covariance_diagonal : [0.01, 0.01, 10000.0, 10000.0, 10000.0, 10.0] + twist_covariance_diagonal: [0.01, 0.01, 10000.0, 10000.0, 10000.0, 10.0] + + # Wheel separation and radius multipliers + wheel_separation_multiplier: 1.0 # default: 1.0 + wheel_radius_multiplier : 1.0 # default: 1.0 + + # Velocity commands timeout [s], default 0.5 + cmd_vel_timeout: 1.0 + + # Base frame_id + base_frame_id: base_link + + # Velocity and acceleration limits + # Whenever a min_* is unspecified, default to -max_* + linear: + x: + has_velocity_limits : false + #max_velocity : 0.9 # m/s + #min_velocity : -0.9 # m/s + has_acceleration_limits: true + max_acceleration : 1.5 # m/s^2 + min_acceleration : -1.5 # m/s^2 + angular: + z: + has_velocity_limits : false + #max_velocity : 0.5 # rad/s + has_acceleration_limits: false + #max_acceleration : 1.5 # rad/s^2 + diff --git a/src/junk/tsukuba2022/urdf/igvc_robot.gazebo b/src/junk/tsukuba2022/urdf/igvc_robot.gazebo new file mode 100644 index 0000000..f32242a --- /dev/null +++ b/src/junk/tsukuba2022/urdf/igvc_robot.gazebo @@ -0,0 +1,76 @@ + + + + + + + + + igvc_robot/cmd_vel + igvc_robot/odom + base_link + odom + world + + true + false + false + + true + + true + + 30 + left_wheel_hinge + right_wheel_hinge + 0.670 + 0.192 + 1 + 10 + na + false + + + + + + + Gazebo/Black + + + + + 5.0 + 5.0 + 1000000.0 + 100.0 + 0.001 + 1.0 + + + + + 5.0 + 5.0 + 1000000.0 + 100.0 + 0.001 + 1.0 + + + + + 0.0 + 0.0 + + + + 0.0 + 0.0 + + + diff --git a/src/junk/tsukuba2022/urdf/igvc_robot.xacro b/src/junk/tsukuba2022/urdf/igvc_robot.xacro new file mode 100644 index 0000000..513d453 --- /dev/null +++ b/src/junk/tsukuba2022/urdf/igvc_robot.xacro @@ -0,0 +1,221 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + left_wheel + base_link + + + + + + + + + + + + + + + + + + + + + + + + + + + + right_wheel + base_link + + + + + + + transmission_interface/SimpleTransmission + + VelocityJointInterface + + + VelocityJointInterface + 1 + + + + + transmission_interface/SimpleTransmission + + VelocityJointInterface + + + VelocityJointInterface + 1 + + + + diff --git a/src/junk/tsukuba2022/urdf/igvc_robot_cp.urdf b/src/junk/tsukuba2022/urdf/igvc_robot_cp.urdf new file mode 100644 index 0000000..3ecfca1 --- /dev/null +++ b/src/junk/tsukuba2022/urdf/igvc_robot_cp.urdf @@ -0,0 +1,220 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + left_wheel + base_link + + + + + + + + + + + + + + + + + + + + + + + + + + + + right_wheel + base_link + + + + + + + transmission_interface/SimpleTransmission + + VelocityJointInterface + + + VelocityJointInterface + 1 + + + + + transmission_interface/SimpleTransmission + + VelocityJointInterface + + + VelocityJointInterface + 1 + + + diff --git a/src/junk/tsukuba2022/urdf/sensors/camera.urdf.xacro b/src/junk/tsukuba2022/urdf/sensors/camera.urdf.xacro new file mode 100644 index 0000000..9326083 --- /dev/null +++ b/src/junk/tsukuba2022/urdf/sensors/camera.urdf.xacro @@ -0,0 +1,76 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 30.0 + + 0 0 0 0 ${PI/2} 0 + 3.1415 + + R8G8B8 + 800 + 800 + + + 0.01 + 100 + + + stereographic + 1 + 1.5707 + 512 + + + + + true + 0.0 + cv_camera + image_raw + camera_info + camera_link + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + + + Gazebo/DarkGray + + + + + + diff --git a/src/tsukuba2022/config/elecom_joy.yaml b/src/tsukuba2022/config/elecom_joy.yaml index ed40e4b..de1c032 100644 --- a/src/tsukuba2022/config/elecom_joy.yaml +++ b/src/tsukuba2022/config/elecom_joy.yaml @@ -1,6 +1,6 @@ axis_linear: 1 scale_linear: 0.4 #0.4 -scale_linear_turbo: 1.0 #0.8 +scale_linear_turbo: 0.8 #0.8 axis_angular: 0 scale_angular: 0.5 #0.9 diff --git a/src/tsukuba2022/config/orange2022_control.yaml b/src/tsukuba2022/config/orange2022_control.yaml new file mode 100644 index 0000000..60740d6 --- /dev/null +++ b/src/tsukuba2022/config/orange2022_control.yaml @@ -0,0 +1,43 @@ +joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 100 + +diff_drive_controller: + type : "diff_drive_controller/DiffDriveController" + left_wheel : 'left_wheel_hinge' + right_wheel : 'right_wheel_hinge' + publish_rate: 100 + + enable_odom_tf: false + + pose_covariance_diagonal : [0.00001, 0.00001, 1000000000000.0, 1000000000000.0, 1000000000000.0, 0.001] + twist_covariance_diagonal: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] + + # Wheel separation and radius multipliers + wheel_separation_multiplier: 1.0 # default: 1.0 + wheel_radius_multiplier : 1.0 # default: 1.0 + + # Velocity commands timeout [s], default 0.5 + cmd_vel_timeout: 1.0 + + # Base frame_id + base_frame_id: base_link + + # Velocity and acceleration limits + # Whenever a min_* is unspecified, default to -max_* + linear: + x: + has_velocity_limits : true + max_velocity : 0.8 # m/s + min_velocity : -0.8 # m/s + has_acceleration_limits: true + max_acceleration : 0.8 # m/s^2 + min_acceleration : -0.8 # m/s^2 + angular: + z: + has_velocity_limits : true + max_velocity : 0.4 # rad/s + min_velocity : -0.4 # rad/s + has_acceleration_limits: true + max_acceleration : 0.3 # rad/s^2 + min_acceleration : -0.3 # rad/s^2 diff --git a/src/tsukuba2022/config/orange2022_control_sim.yaml b/src/tsukuba2022/config/orange2022_control_sim.yaml new file mode 100644 index 0000000..edc0632 --- /dev/null +++ b/src/tsukuba2022/config/orange2022_control_sim.yaml @@ -0,0 +1,41 @@ +joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 100 + +diff_drive_controller: + type : "diff_drive_controller/DiffDriveController" + left_wheel : 'left_wheel_hinge' + right_wheel : 'right_wheel_hinge' + publish_rate: 100 + + enable_odom_tf: false + + pose_covariance_diagonal : [0.01, 0.01, 10000.0, 10000.0, 10000.0, 10.0] + twist_covariance_diagonal: [0.01, 0.01, 10000.0, 10000.0, 10000.0, 10.0] + + # Wheel separation and radius multipliers + wheel_separation_multiplier: 1.0 # default: 1.0 + wheel_radius_multiplier : 1.0 # default: 1.0 + + # Velocity commands timeout [s], default 0.5 + cmd_vel_timeout: 1.0 + + # Base frame_id + base_frame_id: base_link + + # Velocity and acceleration limits + # Whenever a min_* is unspecified, default to -max_* + linear: + x: + has_velocity_limits : false + #max_velocity : 0.9 # m/s + #min_velocity : -0.9 # m/s + has_acceleration_limits: true + max_acceleration : 1.5 # m/s^2 + min_acceleration : -1.5 # m/s^2 + angular: + z: + has_velocity_limits : false + #max_velocity : 0.5 # rad/s + has_acceleration_limits: false + #max_acceleration : 1.5 # rad/s^2 diff --git a/src/tsukuba2022/config/waypoints/waypoints.yaml b/src/tsukuba2022/config/waypoints/waypoints.yaml index ebd8cfe..ddac05b 100644 --- a/src/tsukuba2022/config/waypoints/waypoints.yaml +++ b/src/tsukuba2022/config/waypoints/waypoints.yaml @@ -1,28 +1,19 @@ waypoints: - - point: - x: 22.5481 - y: -1.70773 - z: 0 - - point: - x: 28.3916 - y: -0.557724 - z: 0 - - point: - x: 34.159 - y: -1.72355 - z: 0 +- point: {x: 3.82361, y: 0.164189, z: 0.00511169, vel: 1, rad: 1, stop: false} +- point: {x: 11.1774, y: 0.0853908, z: -0.00192642, vel: 1, rad: 1, stop: false} +- point: {x: 15.6239, y: 0.174851, z: 0.00251579, vel: 1, rad: 1, stop: false} +- point: {x: 15.7556, y: 8.48258, z: 0.00242996, vel: 1, rad: 1, stop: false} +- point: {x: 15.8543, y: 16.8748, z: 0.0023098, vel: 1, rad: 1, stop: false} +- point: {x: 9.36751, y: 17.0985, z: 0.00177956, vel: 1, rad: 1, stop: false} +- point: {x: 2.68957, y: 17.1423, z: 0.000879288, vel: 1, rad: 1, stop: false} +- point: {x: 4.72936, y: 13.403, z: 0.00301743, vel: 1, rad: 1, stop: false} +- point: {x: 6.72777, y: 10.9204, z: 0.00507927, vel: 1, rad: 1, stop: false} +- point: {x: 7.85304, y: 8.43392, z: 0.00030899, vel: 1, rad: 1, stop: false} +- point: {x: 9.32663, y: 6.47157, z: 0.00183296, vel: 1, rad: 1, stop: false} +- point: {x: 11.2611, y: 3.52007, z: 0.00384521, vel: 1, rad: 1, stop: false} +- point: {x: 11.2283, y: 0.737249, z: 0.00480747, vel: 1, rad: 1, stop: false} finish_pose: - header: - seq: 0 - stamp: 1651810719.399999678 - frame_id: map - pose: - position: - x: 38.532 - y: -1.92273 - z: 0 - orientation: - x: 0 - y: 0 - z: 0.00701728 - w: 0.999975 + header: {seq: 0, stamp: 113.132000000, frame_id: map} + pose: + position: {x: 9.27349, y: 0.143879, z: 0} + orientation: {x: 0, y: 0, z: 0.999983, w: 0.00578372} diff --git a/src/tsukuba2022/config/waypoints/waypoints_nakaniwa.yaml b/src/tsukuba2022/config/waypoints/waypoints_nakaniwa.yaml new file mode 100644 index 0000000..03e07a4 --- /dev/null +++ b/src/tsukuba2022/config/waypoints/waypoints_nakaniwa.yaml @@ -0,0 +1,33 @@ +waypoints: +- point: {x: 4.8992, y: 0.0763934, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 17.334, y: -0.0478781, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 25.9562, y: -0.150485, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 34.8965, y: -2.35386, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 43.2493, y: -4.61744, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 52.0631, y: -4.78826, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 53.2674, y: 7.98859, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 53.0977, y: 20.0885, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 52.5512, y: 29.5179, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 52.225629, y: 42.300035, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 51.282771, y: 54.557184, z: 0, vel: 1, rad: 0.6, stop: false} +- point: {x: 37.976717, y: 54.326666, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 27.652743, y: 54.28618, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 16.033212, y: 54.367152, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 5.061459, y: 53.516942, z: 0, vel: 1, rad: 0.5, stop: true} +- point: {x: 6.397503, y: 50.520966, z: 0, vel: 0.3, rad: 0.3, stop: false} +- point: {x: 9.777492, y: 43.91924, z: 0, vel: 0.3, rad: 0.3, stop: false} +- point: {x: 12.326369, y: 38.156927, z: 0.0, vel: 1.0, rad: 0.4, stop: false} +- point: {x: 14.7664, y: 33.8169, z: 0, vel: 0.3, rad: 0.3, stop: false} +- point: {x: 18.112117, y: 26.331971, z: 0, vel: 0.3, rad: 0.3, stop: false} +- point: {x: 20.711327, y: 20.328163, z: 0, vel: 0.3, rad: 0.3, stop: false} +- point: {x: 22.614973, y: 15.935132, z: 0, vel: 0.3, rad: 0.3, stop: false} +- point: {x: 24.408794, y: 12.164447, z: 0, vel: 0.3, rad: 0.3, stop: false} +- point: {x: 29.131302, y: 2.572996, z: 0, vel: 0.3, rad: 0.3, stop: false} +- point: {x: 28.801589, y: 0.126455, z: 0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 19.9255, y: 0.305246, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 9.62386, y: 1.54376, z: 0, vel: 1, rad: 1.0, stop: false} +finish_pose: + header: {seq: 0, stamp: 1663209268.6905353, frame_id: map} + pose: + position: {x: -0.0241434, y: 1.60681, z: 0} + orientation: {x: 0, y: 0, z: 0.999995, w: 0.00303693} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/waypoints_sim_nakaniwa.yaml b/src/tsukuba2022/config/waypoints/waypoints_sim_nakaniwa.yaml new file mode 100644 index 0000000..ddac05b --- /dev/null +++ b/src/tsukuba2022/config/waypoints/waypoints_sim_nakaniwa.yaml @@ -0,0 +1,19 @@ +waypoints: +- point: {x: 3.82361, y: 0.164189, z: 0.00511169, vel: 1, rad: 1, stop: false} +- point: {x: 11.1774, y: 0.0853908, z: -0.00192642, vel: 1, rad: 1, stop: false} +- point: {x: 15.6239, y: 0.174851, z: 0.00251579, vel: 1, rad: 1, stop: false} +- point: {x: 15.7556, y: 8.48258, z: 0.00242996, vel: 1, rad: 1, stop: false} +- point: {x: 15.8543, y: 16.8748, z: 0.0023098, vel: 1, rad: 1, stop: false} +- point: {x: 9.36751, y: 17.0985, z: 0.00177956, vel: 1, rad: 1, stop: false} +- point: {x: 2.68957, y: 17.1423, z: 0.000879288, vel: 1, rad: 1, stop: false} +- point: {x: 4.72936, y: 13.403, z: 0.00301743, vel: 1, rad: 1, stop: false} +- point: {x: 6.72777, y: 10.9204, z: 0.00507927, vel: 1, rad: 1, stop: false} +- point: {x: 7.85304, y: 8.43392, z: 0.00030899, vel: 1, rad: 1, stop: false} +- point: {x: 9.32663, y: 6.47157, z: 0.00183296, vel: 1, rad: 1, stop: false} +- point: {x: 11.2611, y: 3.52007, z: 0.00384521, vel: 1, rad: 1, stop: false} +- point: {x: 11.2283, y: 0.737249, z: 0.00480747, vel: 1, rad: 1, stop: false} +finish_pose: + header: {seq: 0, stamp: 113.132000000, frame_id: map} + pose: + position: {x: 9.27349, y: 0.143879, z: 0} + orientation: {x: 0, y: 0, z: 0.999983, w: 0.00578372} diff --git a/src/tsukuba2022/launch/buildmap_from_bag.launch b/src/tsukuba2022/launch/buildmap_from_bag.launch new file mode 100644 index 0000000..bd635a5 --- /dev/null +++ b/src/tsukuba2022/launch/buildmap_from_bag.launch @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/src/tsukuba2022/launch/buildmap_teleop_joy.launch b/src/tsukuba2022/launch/buildmap_teleop_joy.launch new file mode 100644 index 0000000..acdc48d --- /dev/null +++ b/src/tsukuba2022/launch/buildmap_teleop_joy.launch @@ -0,0 +1,45 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/tsukuba2022/launch/motor.launch b/src/tsukuba2022/launch/motor.launch new file mode 100644 index 0000000..e41ec65 --- /dev/null +++ b/src/tsukuba2022/launch/motor.launch @@ -0,0 +1,39 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/tsukuba2022/launch/segmentaion.launch b/src/tsukuba2022/launch/segmentaion.launch new file mode 100644 index 0000000..6141ea3 --- /dev/null +++ b/src/tsukuba2022/launch/segmentaion.launch @@ -0,0 +1,33 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/tsukuba2022/launch/start.launch b/src/tsukuba2022/launch/start.launch new file mode 100644 index 0000000..6c5fd1e --- /dev/null +++ b/src/tsukuba2022/launch/start.launch @@ -0,0 +1,140 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/tsukuba2022/launch/start_sim.launch b/src/tsukuba2022/launch/start_sim.launch index 287dc1b..dedba07 100644 --- a/src/tsukuba2022/launch/start_sim.launch +++ b/src/tsukuba2022/launch/start_sim.launch @@ -1,47 +1,40 @@ - - - + - - - - + + + + - - + - - + + - - - + + + - - + args="-urdf -model orange2022 -param robot_description -x $(arg x) -y $(arg y) -z $(arg z) -R $(arg roll) -P $(arg pitch) -Y $(arg yaw)"/> - - - + + + - @@ -49,33 +42,30 @@ - - - - - - - - - - + + + + + + + + - - + !-----> - - - - - - + - + + + + + + + diff --git a/src/tsukuba2022/launch/teb_local_planner_test.launch b/src/tsukuba2022/launch/teb_local_planner_test.launch new file mode 100644 index 0000000..27664e6 --- /dev/null +++ b/src/tsukuba2022/launch/teb_local_planner_test.launch @@ -0,0 +1,47 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/tsukuba2022/launch/teleop_joy.launch b/src/tsukuba2022/launch/teleop_joy.launch new file mode 100644 index 0000000..8b8fe08 --- /dev/null +++ b/src/tsukuba2022/launch/teleop_joy.launch @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/tsukuba2022/launch/waypoint_navigation.launch b/src/tsukuba2022/launch/waypoint_navigation.launch new file mode 100644 index 0000000..a896ca9 --- /dev/null +++ b/src/tsukuba2022/launch/waypoint_navigation.launch @@ -0,0 +1,47 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/tsukuba2022/maps/mymap.pgm b/src/tsukuba2022/maps/mymap.pgm new file mode 100644 index 0000000..7bedc78 --- /dev/null +++ b/src/tsukuba2022/maps/mymap.pgm Binary files differ diff --git a/src/tsukuba2022/maps/mymap.yaml b/src/tsukuba2022/maps/mymap.yaml new file mode 100644 index 0000000..ca6f07f --- /dev/null +++ b/src/tsukuba2022/maps/mymap.yaml @@ -0,0 +1,7 @@ +image: /home/ubuntu/catkin_ws/src/tsukuba2022/maps/mymap.pgm +resolution: 0.050000 +origin: [-60.000000, -60.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/mymap_nakaniwa.pgm b/src/tsukuba2022/maps/mymap_nakaniwa.pgm new file mode 100644 index 0000000..86ebccd --- /dev/null +++ b/src/tsukuba2022/maps/mymap_nakaniwa.pgm Binary files differ diff --git a/src/tsukuba2022/maps/mymap_nakaniwa.yaml b/src/tsukuba2022/maps/mymap_nakaniwa.yaml new file mode 100644 index 0000000..deebdb7 --- /dev/null +++ b/src/tsukuba2022/maps/mymap_nakaniwa.yaml @@ -0,0 +1,7 @@ +image: /home/ubuntu/catkin_ws/src/tsukuba2022/maps/mymap_nakaniwa.pgm +resolution: 0.050000 +origin: [-60.000000, -60.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/mymap_sim_nakaniwa.pgm b/src/tsukuba2022/maps/mymap_sim_nakaniwa.pgm new file mode 100644 index 0000000..7bedc78 --- /dev/null +++ b/src/tsukuba2022/maps/mymap_sim_nakaniwa.pgm Binary files differ diff --git a/src/tsukuba2022/maps/mymap_sim_nakaniwa.yaml b/src/tsukuba2022/maps/mymap_sim_nakaniwa.yaml new file mode 100644 index 0000000..e95a921 --- /dev/null +++ b/src/tsukuba2022/maps/mymap_sim_nakaniwa.yaml @@ -0,0 +1,7 @@ +image: /home/ubuntu/catkin_ws/src/tsukuba2022/maps/mymap_sim_nakaniwa.pgm +resolution: 0.050000 +origin: [-60.000000, -60.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/meshes/chassis.dae b/src/tsukuba2022/meshes/chassis.dae index 5a23062..e6494a9 100644 --- a/src/tsukuba2022/meshes/chassis.dae +++ b/src/tsukuba2022/meshes/chassis.dae @@ -2,9 +2,9 @@ - 2022-05-02T17:34:38 - 2022-05-02T17:34:38 - + 2022-09-07T15:25:12 + 2022-09-07T15:25:12 + Z_UP @@ -12,9 +12,6 @@ - - - @@ -23,29 +20,7 @@ - 0.913725 0.913725 0.913725 1 - - - 1 1 1 1 - - - 1 - - - - - - 1 - - - - - - - - - - 0.301961 0.301961 0.301961 1 + 0.647059 0.647059 0.647059 1 1 1 1 1 @@ -68,9 +43,9 @@ - 0.557468 0.671506 -0.2 0.529468 0.671506 0.2 0.557468 0.671506 0.2 0.529468 0.671506 -0.2 0.529468 0.671506 0.2 0.529468 0.643506 -0.2 0.529468 0.643506 0.2 0.529468 0.671506 -0.2 0.557468 0.643506 -0.2 0.557468 0.643506 0.2 0.529468 0.643506 0.2 0.529468 0.643506 -0.2 0.557468 0.643506 -0.2 0.557468 0.671506 -0.2 0.557468 0.671506 0.2 0.557468 0.643506 0.2 0.529468 0.671506 0.2 0.529468 0.643506 0.2 0.557468 0.643506 0.2 0.557468 0.671506 0.2 0.529468 0.671506 -0.2 0.557468 0.671506 -0.2 0.557468 0.643506 -0.2 0.529468 0.643506 -0.2 + -0.16375 -0.543 -0.544 -0.16375 -0.543 -0.572 0 -0.543 -0.572 0.028 -0.543 -0.679 0.028 -0.543 0.028 1.77636e-18 -0.543 -0.285 -0.4715 -0.543 -0.679 -0.4435 -0.543 -0.679 -0.4435 -0.543 -0.572 -0.4435 -0.543 -0.257 -0.4715 -0.543 0.028 -0.4435 -0.543 -0.285 0 -0.543 -0.544 0 -0.543 -0.257 0 -0.543 -0.679 -0.4435 -0.543 -0.544 -0.27975 -0.543 -0.572 -0.27975 -0.543 -0.544 -0.4435 -0.543 0 1.77636e-18 -0.543 0 -0.19175 -0.543 -0.572 -0.19175 -0.543 -0.544 -0.25175 -0.543 -0.544 -0.25175 -0.543 -0.572 -0.4715 -0.362 -0.101 -0.25975 -0.39 -0.101 -0.25975 -0.362 -0.101 -0.4715 -0.39 -0.101 -0.18375 -0.362 -0.101 -0.18375 -0.39 -0.101 0.028 -0.39 -0.101 0.028 -0.362 -0.101 -0.4435 -0.362 -0.129 -0.4435 -0.39 -0.129 -0.4435 -0.39 -0.257 -0.4435 -0.362 -0.257 -0.4435 -0.515 -0.285 -0.4435 -0.028 -0.285 -0.4435 -0.028 -0.257 -0.4435 -0.515 -0.257 3.46945e-18 -0.515 -0.285 3.46945e-18 -0.362 -0.257 3.46945e-18 -0.028 -0.285 3.46945e-18 -0.39 -0.257 3.46945e-18 -0.515 -0.257 3.46945e-18 -0.362 -0.129 3.46945e-18 -0.028 -0.257 3.46945e-18 -0.39 -0.129 -0.4715 -0.362 -0.257 -0.4435 -0.028 -0.257 -0.4715 -0.028 -0.257 -0.4435 -0.362 -0.257 0.028 -0.515 -0.257 0.028 -0.39 -0.257 3.46945e-18 -0.39 -0.257 3.46945e-18 -0.515 -0.257 -0.20775 -0.515 -0.285 3.46945e-18 -0.515 -0.257 3.46945e-18 -0.515 -0.285 -0.20775 -0.515 -0.257 3.46945e-18 -0.028 -0.257 -0.20775 -0.028 -0.285 3.46945e-18 -0.028 -0.285 -0.20775 -0.028 -0.257 0.028 -0.515 0 3.46945e-18 -0.515 -0.257 0 -0.515 0 0.028 -0.515 -0.257 -0.23575 -0.515 -0.257 -0.23575 -0.515 -0.285 -0.4435 -0.515 -0.285 -0.4435 -0.515 -0.257 0.028 -0.028 0 3.46945e-18 -0.028 -0.257 0.028 -0.028 -0.257 0 -0.028 0 0.028 -0.028 -0.544 0 -0.028 -0.46 0 -0.028 -0.488 -0.4435 -0.028 -0.285 -0.4715 -0.028 -0.285 -0.4435 -0.028 -0.46 3.46945e-18 -0.028 -0.285 0.028 -0.028 -0.285 -0.4435 -0.028 -0.544 -0.4435 -0.028 -0.488 -0.4715 -0.028 -0.544 0 -0.028 -0.544 0 -0.515 -0.544 0.028 -0.515 -0.285 0.028 -0.515 -0.544 3.46945e-18 -0.515 -0.285 -0.4435 -0.515 -0.285 -0.4435 -0.515 -0.544 -0.4715 -0.515 -0.544 -0.4715 -0.515 -0.285 -0.23575 -0.028 -0.257 -0.4435 -0.028 -0.257 -0.4435 -0.028 -0.285 -0.23575 -0.028 -0.285 -0.4435 0 -0.285 -0.4435 -0.028 -0.285 -0.4435 -0.028 -0.46 -0.4435 0 -0.46 1.73472e-18 0 -0.285 1.73472e-18 0 -0.46 0 -0.028 -0.46 3.46945e-18 -0.028 -0.285 -0.4435 -0.515 -0.285 -0.4435 -0.543 -0.285 -0.4435 -0.543 -0.544 -0.4435 -0.515 -0.544 3.46945e-18 -0.515 -0.285 0 -0.515 -0.544 0 -0.543 -0.544 1.77636e-18 -0.543 -0.285 -0.4435 0 -0.488 -0.4435 -0.028 -0.488 -0.4435 -0.028 -0.544 -0.4435 0 -0.544 1.73472e-18 0 -0.488 1.73472e-18 0 -0.544 0 -0.028 -0.544 0 -0.028 -0.488 0.028 -0.515 -0.572 0 -0.515 -0.651 0 -0.515 -0.572 0.028 -0.515 -0.651 0.028 -0.399 -0.572 1.77636e-18 -0.399 -0.651 0.028 -0.399 -0.651 1.77636e-18 -0.399 -0.572 -0.4435 -0.515 -0.572 -0.4715 -0.515 -0.651 -0.4715 -0.515 -0.572 -0.4435 -0.515 -0.651 -0.4435 -0.399 -0.572 -0.4715 -0.399 -0.651 -0.4435 -0.399 -0.651 -0.4715 -0.399 -0.572 0 -0.515 -0.572 0.028 -0.399 -0.572 0.028 -0.515 -0.572 1.77636e-18 -0.399 -0.572 -0.16375 -0.543 -0.572 0 -0.515 -0.572 0 -0.543 -0.572 -0.16375 -0.606 -0.572 -0.19175 -0.606 -0.572 -0.19175 -0.543 -0.572 -0.27975 -0.606 -0.572 -0.25175 -0.543 -0.572 -0.25175 -0.606 -0.572 -0.4435 -0.515 -0.572 -0.27975 -0.543 -0.572 -0.4435 -0.543 -0.572 -0.4715 -0.515 -0.572 -0.4435 -0.399 -0.572 -0.4435 -0.515 -0.572 -0.4715 -0.399 -0.572 0.028 -0.371 -0.572 0 -0.371 -0.572 0 -0.028 -0.572 -0.4435 -0.371 -0.572 -0.4715 -0.371 -0.572 -0.4435 -0.028 -0.572 -0.4715 0 -0.572 0.028 0 -0.572 -0.4435 -0.515 -0.544 -0.4435 -0.371 -0.572 -0.4435 -0.028 -0.544 -0.4435 -0.399 -0.651 -0.4435 -0.371 -0.679 -0.4435 -0.515 -0.572 -0.4435 -0.399 -0.572 -0.4435 -0.028 -0.572 -0.4435 -0.543 -0.572 -0.4435 -0.515 -0.651 -0.4435 -0.543 -0.679 1.77636e-18 -0.399 -0.572 0 -0.515 -0.544 0 -0.371 -0.572 0 -0.515 -0.572 0 -0.543 -0.679 1.77636e-18 -0.399 -0.651 1.73472e-18 -0.371 -0.679 0 -0.543 -0.572 0 -0.515 -0.651 0 -0.028 -0.544 0 -0.028 -0.572 -0.4435 -0.543 -0.257 -0.4435 -0.515 -0.257 -0.4435 -0.515 0 -0.4435 -0.543 0 0 -0.515 0 3.46945e-18 -0.515 -0.257 0 -0.543 -0.257 1.77636e-18 -0.543 0 -0.4435 -0.515 0 -0.4435 -0.515 -0.257 -0.4715 -0.515 -0.257 -0.4715 -0.515 0 -0.4715 -0.028 -0.257 -0.4435 -0.028 -0.257 -0.4435 -0.028 0 -0.4715 -0.028 0 -0.4435 0 0 0 -0.028 0 -0.4435 -0.028 0 3.55271e-18 0 0 0 -0.028 0 0.028 -0.028 0 0.028 -0.515 0 0 -0.515 0 -0.4435 -0.515 0 1.77636e-18 -0.543 0 -0.4435 -0.543 0 0 -0.515 0 -0.4435 -0.028 0.028 -0.4435 -0.515 0 -0.4435 -0.028 0 -0.4435 -0.515 0.028 0 -0.028 0.028 -0.4435 -0.028 0 0 -0.028 0 -0.4435 -0.028 0.028 0 -0.028 0 0 -0.515 0.028 0 -0.028 0.028 0 -0.515 0 -0.4715 -0.028 0 -0.4435 -0.028 0 -0.4435 -0.515 0 -0.4715 -0.515 0 0.028 -0.028 -0.285 0.028 -0.028 -0.544 0.028 0 -0.572 0.028 -0.515 -0.544 0.028 -0.515 -0.572 0.028 -0.399 -0.572 0.028 -0.362 -0.257 0.028 -0.362 -0.101 0.028 -0.39 -0.101 0.028 -0.543 0.028 0.028 -0.028 0 0.028 0 0.028 0.028 -0.371 -0.572 0.028 -0.543 -0.679 0.028 -0.515 -0.285 0.028 -0.399 -0.651 0.028 -0.371 -0.679 0.028 -0.515 -0.651 0.028 -0.39 -0.257 0.028 -0.515 0 0.028 -0.515 -0.257 0.028 -0.028 -0.257 0.028 -0.543 0.028 0 -0.515 0.028 -0.4435 -0.515 0.028 -0.4715 -0.543 0.028 0.028 0 0.028 0 -0.028 0.028 -0.4715 0 0.028 -0.4435 -0.028 0.028 0.028 0 -0.572 -0.4435 0 -0.544 1.73472e-18 0 -0.544 1.73472e-18 0 -0.488 -0.4435 0 -0.488 -0.4435 0 -0.46 -0.4715 0 -0.572 0 0 -0.257 0.028 0 0.028 1.73472e-18 0 -0.285 1.73472e-18 0 -0.46 3.55271e-18 0 0 -0.4715 0 0.028 -0.4435 0 0 -0.4435 0 -0.257 -0.4435 0 -0.285 -0.4715 -0.515 -0.285 -0.4715 -0.543 -0.679 -0.4715 -0.543 0.028 -0.4715 -0.515 -0.544 -0.4715 -0.028 -0.544 -0.4715 -0.371 -0.572 -0.4715 -0.515 -0.572 -0.4715 -0.515 -0.257 -0.4715 -0.39 -0.257 -0.4715 -0.515 -0.651 -0.4715 0 -0.572 -0.4715 -0.028 -0.285 -0.4715 0 0.028 -0.4715 -0.399 -0.572 -0.4715 -0.399 -0.651 -0.4715 -0.371 -0.679 -0.4715 -0.515 0 -0.4715 -0.362 -0.101 -0.4715 -0.39 -0.101 -0.4715 -0.362 -0.257 -0.4715 -0.028 0 -0.4715 -0.028 -0.257 0 -0.515 0.028 0 -0.515 0 -0.4435 -0.515 0 -0.4435 -0.515 0.028 -0.4435 -0.028 -0.257 -0.4435 0 -0.257 -0.4435 0 0 -0.4435 -0.028 0 3.55271e-18 0 0 0 0 -0.257 3.46945e-18 -0.028 -0.257 0 -0.028 0 -0.4715 -0.028 -0.544 -0.4715 -0.515 -0.544 -0.4435 -0.515 -0.544 -0.4435 -0.028 -0.544 0 -0.028 -0.544 0 -0.515 -0.544 0.028 -0.515 -0.544 0.028 -0.028 -0.544 -0.4435 -0.515 -0.544 -0.27975 -0.543 -0.544 -0.25175 -0.543 -0.544 -0.4435 -0.543 -0.544 -0.25175 -0.606 -0.544 -0.16375 -0.606 -0.544 -0.16375 -0.543 -0.544 -0.19175 -0.543 -0.544 -0.27975 -0.606 -0.544 0 -0.515 -0.544 -0.19175 -0.606 -0.544 0 -0.543 -0.544 -0.4435 -0.515 -0.572 0 -0.515 -0.544 0 -0.515 -0.572 -0.4435 -0.515 -0.544 1.73472e-18 0 -0.544 -0.4435 -0.028 -0.544 0 -0.028 -0.544 -0.4435 0 -0.544 0 -0.028 -0.544 -0.4435 -0.028 -0.572 0 -0.028 -0.572 -0.4435 -0.028 -0.544 -0.4715 -0.543 -0.679 -0.4435 -0.371 -0.679 -0.4435 -0.543 -0.679 -0.4715 -0.371 -0.679 -0.4435 -0.371 -0.572 -0.4435 -0.371 -0.679 -0.4715 -0.371 -0.679 -0.4715 -0.371 -0.572 0 -0.543 -0.679 0.028 -0.371 -0.679 0.028 -0.543 -0.679 1.73472e-18 -0.371 -0.679 0.028 -0.371 -0.572 0.028 -0.371 -0.679 1.73472e-18 -0.371 -0.679 0 -0.371 -0.572 -0.4715 -0.399 -0.651 -0.4715 -0.515 -0.651 -0.4435 -0.515 -0.651 -0.4435 -0.399 -0.651 1.77636e-18 -0.399 -0.651 0 -0.515 -0.651 0.028 -0.515 -0.651 0.028 -0.399 -0.651 0 -0.028 -0.46 1.73472e-18 0 -0.46 -0.4435 0 -0.46 -0.4435 -0.028 -0.46 -0.4435 0 -0.488 0 -0.028 -0.488 -0.4435 -0.028 -0.488 1.73472e-18 0 -0.488 0 -0.543 -0.257 -0.20775 -0.515 -0.257 -0.23575 -0.515 -0.257 -0.20775 -0.028 -0.257 -0.4435 0 -0.257 -0.23575 -0.028 -0.257 3.46945e-18 -0.515 -0.257 3.46945e-18 -0.028 -0.257 0 0 -0.257 -0.4435 -0.515 -0.257 -0.4435 -0.543 -0.257 -0.4435 -0.028 -0.257 -0.23575 -0.515 -0.285 -0.20775 -0.515 -0.285 1.77636e-18 -0.543 -0.285 -0.20775 -0.028 -0.285 1.73472e-18 0 -0.285 3.46945e-18 -0.028 -0.285 -0.23575 -0.028 -0.285 -0.4435 0 -0.285 -0.4435 -0.543 -0.285 -0.4435 -0.028 -0.285 -0.4435 -0.515 -0.285 3.46945e-18 -0.515 -0.285 -0.4435 -0.39 -0.257 -0.4715 -0.39 -0.257 -0.4715 -0.515 -0.257 -0.4435 -0.515 -0.257 -0.4435 -0.028 -0.285 -0.4435 -0.515 -0.285 -0.4715 -0.515 -0.285 -0.4715 -0.028 -0.285 3.46945e-18 -0.028 -0.257 0.028 -0.362 -0.257 0.028 -0.028 -0.257 3.46945e-18 -0.362 -0.257 3.46945e-18 -0.028 -0.285 0.028 -0.028 -0.285 0.028 -0.515 -0.285 3.46945e-18 -0.515 -0.285 -0.23575 -0.028 -0.257 -0.23575 -0.028 -0.285 -0.23575 -0.515 -0.285 -0.23575 -0.515 -0.257 -0.20775 -0.028 -0.257 -0.20775 -0.515 -0.257 -0.20775 -0.515 -0.285 -0.20775 -0.028 -0.285 -0.18375 -0.362 -0.101 3.46945e-18 -0.362 -0.129 -0.21175 -0.362 -0.101 -0.21175 -0.362 0.418 -0.18375 -0.362 0.418 -0.4435 -0.362 -0.129 -0.25975 -0.362 -0.101 -0.25975 -0.362 0.418 -0.23175 -0.362 0.418 -0.23175 -0.362 -0.101 -0.4715 -0.362 -0.257 -0.4715 -0.362 -0.101 -0.4435 -0.362 -0.257 0.028 -0.362 -0.257 0.028 -0.362 -0.101 3.46945e-18 -0.362 -0.257 -0.18375 -0.39 -0.101 -0.21175 -0.39 -0.101 3.46945e-18 -0.39 -0.129 0.028 -0.39 -0.257 0.028 -0.39 -0.101 -0.18375 -0.39 0.418 -0.21175 -0.39 0.418 -0.4435 -0.39 -0.129 -0.25975 -0.39 -0.101 -0.23175 -0.39 0.418 -0.25975 -0.39 0.418 -0.23175 -0.39 -0.101 -0.4715 -0.39 -0.101 -0.4715 -0.39 -0.257 -0.4435 -0.39 -0.257 3.46945e-18 -0.39 -0.257 -0.23175 -0.362 -0.101 -0.21175 -0.39 -0.101 -0.21175 -0.362 -0.101 -0.23175 -0.39 -0.101 -0.4435 -0.362 -0.129 3.46945e-18 -0.39 -0.129 -0.4435 -0.39 -0.129 3.46945e-18 -0.362 -0.129 -0.21175 -0.362 0.418 -0.21175 -0.39 -0.101 -0.21175 -0.39 0.418 -0.21175 -0.362 -0.101 -0.18375 -0.39 -0.101 -0.18375 -0.362 -0.101 -0.18375 -0.362 0.418 -0.18375 -0.39 0.418 -0.21175 -0.362 0.418 -0.21175 -0.39 0.418 -0.18375 -0.39 0.418 -0.18375 -0.362 0.418 -0.23175 -0.362 -0.101 -0.23175 -0.362 0.418 -0.23175 -0.39 0.418 -0.23175 -0.39 -0.101 -0.25975 -0.362 -0.101 -0.25975 -0.39 0.418 -0.25975 -0.362 0.418 -0.25975 -0.39 -0.101 -0.25975 -0.362 0.418 -0.23175 -0.39 0.418 -0.23175 -0.362 0.418 -0.25975 -0.39 0.418 -0.27975 -0.543 -0.544 -0.27975 -0.543 -0.572 -0.27975 -0.606 -0.572 -0.27975 -0.606 -0.544 -0.25175 -0.543 -0.544 -0.25175 -0.606 -0.544 -0.25175 -0.606 -0.572 -0.25175 -0.543 -0.572 -0.27975 -0.606 -0.544 -0.27975 -0.606 -0.572 -0.25175 -0.606 -0.572 -0.25175 -0.606 -0.544 -0.19175 -0.543 -0.544 -0.19175 -0.543 -0.572 -0.19175 -0.606 -0.572 -0.19175 -0.606 -0.544 -0.16375 -0.543 -0.544 -0.16375 -0.606 -0.544 -0.16375 -0.606 -0.572 -0.16375 -0.543 -0.572 -0.19175 -0.606 -0.544 -0.19175 -0.606 -0.572 -0.16375 -0.606 -0.572 -0.16375 -0.606 -0.544 - + @@ -78,9 +53,9 @@ - 0 1 0 0 1 0 0 1 0 0 1 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 + 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 1 0 0 1 0 0 1 0 0 1 0 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 1 0 0 1 0 0 1 0 0 1 0 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 1 0 0 1 0 0 1 0 0 1 0 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 - + @@ -91,905 +66,9 @@ - + -

0 1 2 1 0 3 4 5 6 4 7 5 8 9 10 10 11 8 12 13 14 12 14 15 16 17 18 16 18 19 20 21 22 22 23 20

-
-
-
- - - - 0.0211458 0 0.0882574 0.0215681 0 0.0885521 0.0192195 0 0.091452 0.0185 0 0.095 0.00545791 -0.0176766 0.095 0.0138147 0 0.0942458 0.0234826 0 0.0920843 0.0192195 0 0.093443 0.0135897 0 0.093443 0.0192197 0 0.0875521 0.0197243 0 0.0876522 0.0202177 0 0.0878044 0.0206928 0 0.0880066 0.0136111 0 0.091452 0.0137405 0 0.0909682 0.0139165 0 0.0905022 0.0141392 0 0.090054 0.0144048 0 0.0896315 0.014712 0 0.0892364 0.0150569 0 0.0888745 0.0154358 0 0.0885491 0.0158461 0 0.0882624 0.0167407 0 0.0878198 0.0162823 0 0.0880188 0.0177058 0 0.0875636 0.0172175 0 0.0876673 0.0182031 0 0.0875089 0.018704 0 0.0875042 0.0223133 0 0.0892662 0.0219598 0 0.0888903 0.0228966 0 0.0901188 0.0226265 0 0.0896767 0.0232914 0 0.091071 0.023118 0 0.0905836 0.0234131 0 0.0915726 0.0234618 0 0.0931156 0.023499 0 0.092602 0.0233718 0 0.0936251 0.0232297 0 0.0941213 0.0230373 0 0.0946004 0.0227957 0 0.0950586 0.0225097 0 0.0954868 0.0221797 0 0.0958852 0.021811 0 0.0962465 0.021407 0 0.096568 0.0209707 0 0.0968469 0.0205104 0 0.0970779 0.0200265 0 0.0972613 0.0195278 0 0.0973931 0.0185 0 0.0975 0.0190177 0 0.097473 0.0230872 0 -0.094489 0.0228607 0 -0.0949462 0.0185 2.46519e-32 -0.095 0.0211301 0 -0.0882477 0.0206838 0 -0.0880022 0.0192127 0 -0.0974488 0.018704 2.46519e-32 -0.0974958 0.0197119 0 -0.0973508 0.0185 2.46519e-32 -0.0975 0.0206685 0 -0.0970051 0.0201986 0 -0.0972026 0.0215351 0 -0.0964733 0.0211143 0 -0.0967621 0.022276 0 -0.0957774 0.0219229 0 -0.0961446 0.0225898 0 -0.0953761 0.0232654 0 -0.0940134 0.0233948 0 -0.0935201 0.0234731 0 -0.093017 0.0235 0 -0.0925093 0.0234748 0 -0.0919999 0.0232708 0 -0.0910039 0.0233986 0 -0.0914982 0.0228698 0 -0.09007 0.0230941 0 -0.0905268 0.0222882 0 -0.0892366 0.0225995 0 -0.0896377 0.0215492 0 -0.0885375 0.0219358 0 -0.0888676 0.0202162 0 -0.0878038 0.0197284 0 -0.0876534 0.0192304 0 -0.0875537 0.0187232 0 -0.087505 0.0182139 0 -0.0875083 0.0177079 0 -0.0875632 0.017209 0 -0.0876697 0.0167259 0 -0.0878253 0.0162586 0 -0.0880306 0.015816 0 -0.0882816 0.0154011 0 -0.0885762 0.0150177 0 -0.0889122 0.0143638 0 -0.0896909 0.0146717 0 -0.0892838 0.0138811 0 -0.0905854 0.0141 0 -0.0901254 0.0135894 0 -0.0915588 0.0137104 0 -0.0910654 0.0135006 0 -0.0925718 0.0135191 0 -0.0920642 0.0136188 0 -0.0935827 0.0135339 0 -0.0930807 0.0139375 0 -0.0945453 0.0137538 0 -0.0940728 0.0184635 0.00116162 -0.0973816 0.0184266 -0.00164718 0.0973312 0.017826 -0.00494677 0.0969743 0.0182026 -0.00330214 0.0971554 0.0185 0 0.0975 0.0226265 0 0.0896767 0.0228607 0 -0.0949462 0.0228966 0 0.0901188 0.0166233 -0.00811875 0.0966051 0.0172979 -0.00655921 0.0967901 0.0187232 0 -0.087505 0.0138237 -0.0122951 0.0960684 0.0158108 -0.00960582 0.0964217 0.0114214 -0.014553 0.09573 0.00545791 -0.0176766 0.095 0.0148727 -0.0110029 0.0962421 0.0126752 -0.0134756 0.0959002 0.010056 -0.015528 0.0955521 0.00705641 -0.0171014 0.0951848 0.00859545 -0.0163819 0.0953696 0.0182139 0 -0.0875083 0.0167231 -0.00837677 0.0742557 0.0180874 -0.00476317 0.0746715 0.0175453 0.0064807 0.0758634 -0.00593515 -0.0177374 0.0714571 -0.00219308 -0.0185753 0.071864 0.00888973 -0.0164564 0.0730646 -0.0176752 0.00611774 0.0806864 -0.0186531 -0.00137519 0.0814769 -0.0160425 0.00961647 0.080271 0.0158421 0.00994348 0.0762781 0.0106397 0.0153825 0.0770587 -0.008549 -0.0166357 0.083485 -0.00118768 -0.0186666 0.0843011 -0.0117584 -0.0145455 0.0830795 0.00629953 -0.0176112 0.0850926 0.00978049 -0.0159432 0.0855077 0.00256843 -0.0185265 0.0846837 0.0178758 0.00550385 0.0634192 0.0184635 0.00116162 -0.0973816 0.0162365 -0.00928475 0.061812 -0.0179857 -0.00513246 0.0818778 -0.0144262 -0.0119049 0.0826983 -0.0137663 0.0126623 0.0798747 0.00796903 -0.0169214 0.0606205 -0.00394945 0.018282 0.0786645 0.00726267 0.0172363 0.0774711 -0.00690446 -0.0173829 0.0590128 0.0186775 -0.000998982 0.0750703 0.0184995 0.00275759 0.0754536 0.0135095 0.0129363 0.0766721 -0.0123358 0.0140599 0.0550062 0.0018143 0.0186158 0.0534033 -0.0181819 0.00438874 0.0562127 0.0122412 0.0141415 0.052182 0.00156373 -0.0186383 0.0722462 -0.00666144 0.0174774 0.0666342 -0.0130705 0.0133796 0.0674408 -0.00294553 0.0184703 0.0662235 -0.0183949 0.00338734 0.0686544 -0.0187003 -0.000376571 0.0690427 -0.0150506 -0.0111051 0.0702596 0.00282152 0.0184901 0.0409646 -0.00831663 0.0167533 0.042162 0.0163641 0.00905853 0.0638352 0.0114608 0.0147808 0.0646189 0.00911677 0.0163313 0.0525826 0.00556685 0.0178563 0.0529987 -0.0031994 -0.0184286 0.0594245 -0.0127078 -0.0137244 0.0212853 -0.00244428 -0.0185438 0.0225044 -0.0185822 -0.00212751 0.0445542 -0.0177584 -0.00587113 0.0449606 -0.0186334 0.00162638 0.0441728 0.0182116 0.00426197 0.00161517 0.0184176 -0.0032621 0.000834461 0.0186975 0.000501384 0.00122198 0.0177169 -0.00599611 0.0128669 0.00866271 0.0163465 -0.0953778 0.0139705 0.0121275 -0.0960913 0.0185 2.46519e-32 -0.0975 0.018644 -0.00150117 -0.0236477 0.0138498 0.0125708 -0.0220451 -0.0156343 -0.010267 0.0578188 0.0104278 0.0155274 -0.0585809 0.00702386 0.0173351 -0.0581678 -0.00419939 0.0182261 -0.056975 -0.018552 0.00238155 0.0810943 -0.00761589 0.0170832 0.0790787 -0.0165476 -0.00871863 0.0822938 -0.00494956 -0.0180373 0.0839009 0.000810518 0.0186865 0.0658395 0.0183215 -0.00376384 0.0871139 0.0128006 -0.013638 0.0859034 0.0171598 -0.00744136 0.0867001 0.0152727 -0.0107967 0.0862885 -0.0109503 0.0151637 0.0794896 0.00357487 0.0183592 0.0778843 -0.000188624 0.0187031 0.0782736 0.0120498 -0.0143056 0.0734677 0.0146636 -0.0116105 0.0738491 -0.00945127 -0.0161402 0.0710415 -0.0125242 -0.0138917 0.0706431 0.00531864 -0.0179317 0.0726485 0.0186891 0.000749768 0.05058 -0.0182404 -0.00413686 0.0694349 -0.0170033 -0.00779252 0.0698496 0.0157027 -0.0101615 0.0493695 -0.0154913 0.010481 0.0678289 -0.0173108 0.00708341 0.068242 -0.0101056 0.0157392 0.0670485 0.00332216 -0.0184061 0.0477636 0.00457565 0.0181357 0.0654422 0.00820309 0.0168089 0.0650266 -0.00785305 -0.0169755 0.0465683 -0.0179132 0.00538115 0.0437695 0.0141835 0.0121934 0.064237 0.0185965 -0.00200406 0.0626337 0.0186218 0.00175169 0.0630153 0.0177977 -0.00575158 0.0622279 0.0112581 -0.0149365 0.0610296 0.0140172 -0.0123835 0.0614125 0.0043246 -0.0181969 0.0602053 0.000563633 -0.0186957 0.0598115 -0.0103217 -0.015598 0.0585992 -0.0132479 -0.0132036 0.0582094 0.0154204 0.0105857 0.0393594 0.0187027 -0.000249682 0.038146 -0.0186939 0.000623273 0.0566085 -0.0184392 -0.00313366 0.0569935 -0.0174075 -0.00684192 0.057405 -0.0168935 0.00802784 0.0557975 -0.0148971 0.0113094 0.0553888 0.0151247 -0.0110034 0.0369285 0.0126171 -0.0138076 0.0365447 -0.00193939 0.018603 0.0537846 -0.00568759 0.0178181 0.0541899 -0.0092265 0.01627 0.0546058 0.00231613 -0.0185596 0.0353239 0.0168382 0.00814346 0.0513913 0.0148216 0.0114092 0.0517993 -0.00877666 -0.0165169 0.0341241 0.0181514 0.00451286 0.0509759 -0.0119531 -0.0143861 0.0337205 0.0174533 -0.00672449 0.0497836 0.0184603 -0.00301085 0.0501946 0.0104277 -0.0155275 0.0485892 0.0133365 -0.0131141 0.0489787 -0.0180546 -0.00488464 0.0325169 0.00702233 -0.0173356 0.0481759 -0.0175891 0.00636082 0.0313253 -0.00420212 -0.018226 0.046983 -0.000436429 -0.0186993 0.0473774 -0.0159082 0.00983653 0.0309103 -0.016174 -0.00939381 0.0453764 -0.0139344 -0.0124771 0.0457755 -0.0111567 -0.0150122 0.0461586 -0.00737986 0.0171865 0.0297176 0.00382675 0.0183084 0.0285238 -0.016425 0.0089472 0.0433534 -0.0142646 0.0120976 0.0429514 -0.0115591 0.014705 0.042569 -0.000935645 0.0186805 0.0413483 -0.00469884 0.018104 0.0417464 0.00750061 0.017134 0.0281099 0.0159765 0.00972594 0.0269176 0.00654333 0.017522 0.0405544 0.00999979 0.015806 0.0401398 0.0129794 0.0134677 0.0397479 0.0183712 0.00351121 0.0385339 0.0172617 0.00720223 0.0389469 0.0180202 -0.00501148 0.0253107 0.0186625 -0.00125046 0.0257114 0.0118559 -0.0144665 0.0241084 0.0182682 -0.00401486 0.0377534 0.0170556 -0.00767743 0.037339 0.00605466 -0.0176967 0.0357314 0.00956063 -0.0160759 0.036147 0.00131231 -0.0186576 0.022887 -0.00143854 -0.0186489 0.0349421 -0.00519666 -0.0179677 0.0345401 -0.0182954 -0.00388702 0.0200744 -0.0166665 -0.00848919 0.0329328 -0.0145867 -0.0117079 0.0333387 -0.01867 -0.00112378 0.0321176 -0.0185179 0.00263231 0.0317346 -0.0187036 -0.000125809 0.0196838 -0.015346 0.0106922 0.0184686 -0.00642037 0.0175675 0.0172731 -0.0107426 0.0153116 0.0301295 -0.0135971 0.012844 0.0305168 -0.00369976 0.0183343 0.0293042 6.2562e-05 0.018704 0.0289146 0.00482541 0.0180709 0.0160813 0.00843433 0.0166941 0.0156655 0.0164868 0.0088332 0.0144744 0.0136806 0.012755 0.0273137 0.0108486 0.0152359 0.0276985 0.0176329 0.00623836 0.0265023 0.0185351 0.00250528 0.0260938 0.00709159 0.0170868 -0.0951889 0.0185677 -0.00225595 0.0132741 0.0145058 -0.0118074 0.0244897 0.0166063 -0.00860612 0.0248948 0.00866132 -0.0165777 0.0237036 0.00507048 -0.0180033 0.0232875 0.0101511 0.0154663 -0.0955642 0.0115389 0.0144604 -0.0957457 0.0128117 0.0133458 -0.0959202 -0.00967157 -0.0160093 0.0216808 -0.00617842 -0.0176541 0.0220962 -0.015201 -0.0108985 0.0208995 -0.0171093 -0.00755695 0.0204884 -0.0172109 0.0073224 0.0188808 -0.0183469 0.00363763 0.0192942 0.0150276 0.0107899 -0.0962699 0.0159663 0.00934483 -0.0964544 0.0167713 0.00780865 -0.0966425 -0.00988925 0.015876 0.017688 -0.0128913 0.0135525 0.0180826 0.00106195 0.0186741 0.0164806 -0.00269482 0.0185088 0.0168637 0.0182784 0.00285459 -0.0972036 0.01743 0.00620053 -0.0968317 0.0179338 0.00454173 -0.0970195 0.014346 0.0120016 0.0148779 0.01166 0.0146243 0.0152593 0.0186435 0.00150092 0.0136565 0.0179499 0.00525654 0.0140582 0.0110536 -0.0150885 0.0116696 0.0138497 -0.0125708 0.0120534 0.0161078 -0.00950648 0.0124513 0.000314013 -0.0187015 0.010453 0.00407436 -0.0182545 0.0108447 0.00773367 -0.0170302 0.0112593 -0.00344989 -0.0183832 0.0100644 -0.0134231 -0.0130259 0.00885124 -0.0105341 -0.0154551 0.00923884 -0.00714286 -0.0172864 0.00965173 -0.0184803 -0.00288287 0.00763355 -0.0175003 -0.00660123 0.00804389 -0.0157737 -0.0100516 0.00845835 -0.0186836 0.00087305 0.00724981 -0.0147418 0.0115109 0.00602897 -0.0167805 0.00826116 0.00643628 -0.0181198 0.00463829 0.00685193 -0.00544253 0.0178946 0.00482902 -0.00900236 0.0163951 0.00524501 -0.0121457 0.0142244 0.00564722 -0.00168914 0.0186275 0.00442567 0.00934041 0.0162045 0.00322183 0.00581289 0.0177778 0.00363764 0.00206714 0.0185897 0.00404378 0.0169489 0.0079102 0.00203019 0.0149744 0.0112075 0.00243962 0.0124306 0.0139755 0.0028227 0.0173591 -0.00696421 0.000422499 0.0155629 -0.0103747 9.13966e-06 0.0131594 -0.013292 -0.000380158 0.00678177 -0.017431 -0.00118529 0.0102132 -0.0156695 -0.000771279 -0.000685633 -0.0186917 -0.0019811 -0.00445084 -0.0181668 -0.00237748 0.00307092 -0.0184498 -0.00159649 -0.0113601 -0.0148584 -0.0032012 -0.00808644 -0.0168655 -0.00279283 -0.0163016 -0.00917059 -0.0039844 -0.0141013 -0.0122885 -0.0035835 -0.0186095 -0.00187676 -0.00480521 -0.0186096 0.00187765 -0.00518654 -0.0178376 -0.00562637 -0.00440033 -0.0162999 0.00917293 -0.00600758 -0.017837 0.00562856 -0.00559158 -0.011359 0.01486 -0.00679059 -0.0141002 0.0122888 -0.00640787 -0.00445004 0.0181668 -0.00761427 -0.000687822 0.0186915 -0.00800947 -0.00808558 0.016866 -0.00719895 0.0067846 0.01743 -0.00880671 0.00307378 0.0184499 -0.00839547 0.0131588 0.0132923 -0.00961111 0.010215 0.015668 -0.00922064 0.0173598 0.00696219 -0.0104144 0.0184174 0.00325928 -0.0108264 0.0155633 0.0103742 -0.0100009 0.0182115 -0.00426439 -0.0116071 0.0186977 -0.000498681 -0.0112122 0.0149741 -0.0112077 -0.0124313 0.0169484 -0.00791134 -0.012022 0.0093381 -0.0162062 -0.0132138 0.00580996 -0.0177785 -0.0136296 0.0124301 -0.0139764 -0.0128143 -0.00168897 -0.0186277 -0.014417 0.00206476 -0.0185894 -0.0140357 -0.00900391 -0.0163939 -0.0152369 -0.00544296 -0.0178945 -0.0148207 -0.0147441 -0.0115092 -0.0160209 -0.0167818 -0.00825898 -0.0164282 -0.0121456 -0.0142238 -0.0156384 -0.0186836 -0.000873397 -0.0172413 -0.01812 -0.00463688 -0.0168438 -0.0184803 0.00288473 -0.0176254 -0.0174993 0.00660386 -0.0180359 -0.0134242 0.0130244 -0.0188418 -0.0105332 0.0154563 -0.0192307 -0.0157717 0.0100539 -0.0184503 -0.00344813 0.0183831 -0.0200562 -0.00714266 0.0172864 -0.0196434 0.000311946 0.0187018 -0.0204435 0.00407736 0.0182543 -0.0208367 0.0110547 0.0150874 -0.0216614 0.0077361 0.0170291 -0.0212512 0.0177175 0.00599347 -0.0228589 0.0161088 0.00950507 -0.0224432 0.0185673 0.0022532 -0.023266 0.0164868 -0.00883325 -0.0244661 0.0179497 -0.00525823 -0.0240501 0.0143459 -0.0120013 -0.0248692 0.00482271 -0.0180713 -0.0260733 0.00843172 -0.0166957 -0.0256575 0.0116584 -0.0146264 -0.0252512 0.00106101 -0.0186737 -0.0264722 -0.00642182 -0.0175669 -0.027265 -0.00269495 -0.0185088 -0.0268553 -0.00989114 -0.0158742 -0.0276799 -0.0172118 -0.00732072 -0.0288726 -0.015348 -0.0106904 -0.0284606 -0.0128892 -0.0135542 -0.0280728 -0.0183469 -0.00363733 -0.0292859 -0.0182952 0.00388956 -0.0300663 -0.0187038 0.000125013 -0.0296749 -0.017108 0.00755969 -0.0304804 -0.00967127 0.0160096 -0.0316725 -0.0127093 0.013723 -0.0312759 -0.015199 0.0109004 -0.0308915 -0.00617709 0.0176544 -0.032088 -0.00244218 0.0185434 -0.0324962 0.00131319 0.0186582 -0.0328784 0.0050733 0.0180029 -0.0332795 0.0145068 0.0118067 -0.0344815 0.0118562 0.0144661 -0.0341001 0.0086631 0.0165767 -0.0336954 0.0166075 0.00860398 -0.0348867 0.0180206 0.00500851 -0.0353027 0.018662 0.00124944 -0.0357028 0.0185354 -0.00250698 -0.0360855 0.0136821 -0.0127533 -0.0373042 0.0159757 -0.00972676 -0.0369094 0.0176328 -0.00623902 -0.0364941 0.0108466 -0.0152381 -0.0376905 0.00749797 -0.0171353 -0.0381018 0.0038246 -0.0183086 -0.0385157 6.29299e-05 -0.0187039 -0.038906 -0.0107445 -0.0153094 -0.0401214 -0.00738196 -0.0171855 -0.0397096 -0.0037008 -0.0183343 -0.039296 -0.0135953 -0.012846 -0.040507 -0.0159097 -0.00983493 -0.0409021 -0.0175895 -0.00635998 -0.0413171 -0.0185178 -0.00263161 -0.0417263 -0.016665 0.00849174 -0.0429248 -0.0180542 0.00488755 -0.0425089 -0.0186704 0.00112485 -0.0421091 -0.014585 0.0117093 -0.0433306 -0.0119533 0.0143861 -0.0437119 -0.00877593 0.0165173 -0.0441159 -0.00519448 0.0179679 -0.044532 0.00605698 0.0176961 -0.0457233 0.00231877 0.01856 -0.0453158 -0.00143807 0.0186484 -0.0449333 0.00956155 0.0160753 -0.0461388 0.0126166 0.0138081 -0.046536 0.0151262 0.011002 -0.0469204 0.0170568 0.00767479 -0.047331 0.0183713 -0.0035124 -0.0485257 0.0187024 0.000251362 -0.0481367 0.0182683 0.00401189 -0.0477454 0.0172615 -0.00720276 -0.0489386 0.0154188 -0.010587 -0.0493512 0.0129812 -0.0134664 -0.0497383 0.0099976 -0.015808 -0.0501318 0.00282022 -0.01849 -0.0509564 0.00654099 -0.0175229 -0.0505464 -0.000935941 -0.0186806 -0.0513399 -0.0115607 -0.0147028 -0.0525609 -0.00831905 -0.0167518 -0.052154 -0.00470079 -0.0181037 -0.0517383 -0.0142651 -0.0120978 -0.0529426 -0.0179132 -0.0053808 -0.0537612 -0.0164258 -0.0089461 -0.0533452 -0.018633 -0.00162648 -0.054164 -0.0161725 0.00939592 -0.0553683 -0.0177577 0.00587408 -0.0549526 -0.0185826 0.00213014 -0.0545461 -0.0139336 0.0124775 -0.0557671 -0.00785136 0.0169762 -0.0565601 -0.0111565 0.0150124 -0.0561503 0.00332475 0.0184063 -0.0577556 -0.000439029 0.018699 -0.0573676 0.0157045 0.0101594 -0.0593614 0.0133359 0.013115 -0.0589697 0.0174543 0.00672161 -0.0597756 0.0186892 -0.000748046 -0.0605708 0.0184602 0.00300821 -0.0601865 0.0168373 -0.00814486 -0.0613831 0.0181514 -0.00451289 -0.0609676 0.012241 -0.0141425 -0.0621733 0.0148197 -0.0114105 -0.0617911 0.0091146 -0.016333 -0.0625746 0.00181415 -0.0186158 -0.063395 0.00556513 -0.0178568 -0.0629906 -0.00569014 -0.0178174 -0.0641818 -0.0019409 -0.0186032 -0.0637764 -0.0123362 -0.0140587 -0.0649977 -0.00922892 -0.0162682 -0.0645978 -0.0148983 -0.0113086 -0.0653805 -0.0181819 -0.00438729 -0.0662045 -0.0168937 -0.0080276 -0.0657892 -0.0184393 0.00313663 -0.0669855 -0.0186937 -0.000625779 -0.0665989 -0.0156331 0.0102684 -0.0678107 -0.0174066 0.00684459 -0.067397 -0.013248 0.0132035 -0.0682009 -0.00690205 0.0173838 -0.0690047 -0.0103206 0.0155989 -0.068591 0.000560958 0.0186959 -0.0698018 -0.00319644 0.0184284 -0.0694164 0.00796952 0.0169212 -0.0706122 0.0043266 0.0181968 -0.0701972 0.0112587 0.0149356 -0.0710213 0.0162382 0.00928234 -0.071804 0.0140183 0.012383 -0.071404 0.0185963 0.00200205 -0.0726255 0.0177984 0.00574878 -0.0722199 0.0178755 -0.00550498 -0.073411 0.0186219 -0.00175156 -0.0730068 0.0163627 -0.00906043 -0.0738271 0.0114593 -0.0147829 -0.0746108 0.0141827 -0.0121935 -0.0742282 0.0045749 -0.0181358 -0.0754339 0.00820126 -0.0168101 -0.0750185 -0.00294784 -0.0184704 -0.0762154 0.000811624 -0.0186865 -0.0758307 -0.00666424 -0.0174764 -0.0766262 -0.0130693 -0.0133804 -0.0774316 -0.0101077 -0.0157373 -0.0770404 -0.015492 -0.0104805 -0.0778207 -0.0187007 0.000374189 -0.0790331 -0.0183947 -0.00338511 -0.0786463 -0.0173111 -0.00708248 -0.0782338 -0.0182403 0.00413978 -0.0794268 -0.0150499 0.0111058 -0.0802514 -0.0170024 0.00779463 -0.0798415 -0.012524 0.0138922 -0.0806348 -0.00219033 0.0185749 -0.0818559 -0.0059323 0.017738 -0.0814491 -0.00944946 0.0161415 -0.0810334 0.00156378 0.0186388 -0.0822375 0.0088903 0.0164559 -0.0830564 0.00531972 0.0179316 -0.0826403 0.0120495 0.0143053 -0.0834589 0.0180878 0.00476078 -0.0846634 0.0167246 0.00837421 -0.0842477 0.0146658 0.0116088 -0.0838411 0.0186772 0.0009983 -0.085062 0.0175446 -0.00648265 -0.0858553 0.0184996 -0.0027582 -0.0854454 0.0158402 -0.00994556 -0.0862701 0.00726151 -0.0172369 -0.0874629 0.0106381 -0.0153843 -0.0870506 0.0135111 -0.0129343 -0.0866624 0.00357438 -0.0183592 -0.087876 -0.00395226 -0.0182818 -0.0886565 -0.000187379 -0.0187034 -0.0882645 -0.00761863 -0.0170819 -0.0890707 -0.0160427 -0.00961616 -0.0902627 -0.0137654 -0.0126633 -0.0898656 -0.010952 -0.0151619 -0.0894815 -0.0176756 -0.00611586 -0.0906783 -0.0186537 0.00137589 -0.0914681 -0.0185516 -0.00237913 -0.0910861 -0.0179854 0.00513502 -0.0918697 -0.0117573 0.0145469 -0.0930714 -0.0144262 0.0119048 -0.0926899 -0.0165469 0.00871994 -0.0922857 -0.0085466 0.0166371 -0.093477 -0.00118659 0.0186661 -0.0942926 -0.00494657 0.0180377 -0.0938929 0.00256965 0.0185268 -0.0946755 0.0127987 0.0136397 -0.0958937 0.00978174 0.015942 -0.0954996 0.00629966 0.0176112 -0.0950843 0.0152749 0.0107947 -0.0962805 0.0183216 0.00376218 -0.0971058 0.017161 0.00743894 -0.0966921 0.018704 2.46519e-32 -0.0974958 0.00557861 0.0170224 -0.095 0.0182031 0 0.0875089 0.0177058 0 0.0875636 0.0172175 0 0.0876673 0.00597393 0.0164672 -0.095 0.00643452 0.0159661 -0.0949999 0.0167407 0 0.0878198 0.00691735 0.0154865 -0.095 0.00789457 0.0145395 -0.0949998 0.00740662 0.0150136 -0.095 0.0162823 0 0.0880188 0.00837749 0.0140602 -0.095 0.00885253 0.0135715 -0.095 0.0158461 0 0.0882624 0.00931915 0.0130698 -0.095 0.01021 0.0120336 -0.095 0.00977209 0.0125574 -0.095 0.0154358 0 0.0885491 0.0106339 0.0114949 -0.095 0.011039 0.0109455 -0.095 0.0117889 0.00980152 -0.0949999 0.0114241 0.0103819 -0.0949999 0.0121313 0.00920631 -0.0949999 0.0150569 0 0.0888745 0.0124497 0.00859864 -0.095 0.0127427 0.00798103 -0.095 0.0130099 0.00735415 -0.095 0.014712 0 0.0892364 0.0132527 0.00671459 -0.095 0.0136594 0.00540841 -0.095 0.0134696 0.00606494 -0.095 0.013957 0.00407613 -0.095 0.0138216 0.00474662 -0.095 0.0144048 0 0.0896315 0.0141432 0.00272057 -0.095 0.0140644 0.00339963 -0.095 0.0142145 0.00136084 -0.095 0.0141932 0.00204155 -0.095 0.0142067 0.000679707 -0.095 0.0141392 0 0.090054 0.0139165 0 0.0905022 0.0139375 0 -0.0945453 0.0137405 0 0.0909682 0.0137538 0 -0.0940728 0.0136188 0 -0.0935827 0.0136111 0 0.091452 0.0135003 0 0.0924457 0.0135339 0 -0.0930807 0.018704 0 0.0875042 0.0135191 0 -0.0920642 0.0135006 0 -0.0925718 0.0135897 0 0.093443 0.0135894 0 -0.0915588 0.0138147 0 0.0942458 0.0137104 0 -0.0910654 0.0141 0 -0.0901254 0.0138811 0 -0.0905854 0.0142067 -0.000679707 0.095 0.0142145 -0.00136084 0.095 0.0143638 0 -0.0896909 0.0141932 -0.00204155 0.095 0.0141432 -0.00272057 0.095 0.0140644 -0.00339963 0.095 0.0146717 0 -0.0892838 0.013957 -0.00407613 0.095 0.0138216 -0.00474662 0.095 0.0134696 -0.00606494 0.095 0.0136594 -0.00540841 0.095 0.0132527 -0.00671459 0.095 0.0150177 0 -0.0889122 0.0127427 -0.00798103 0.095 0.0130099 -0.00735415 0.095 0.0124497 -0.00859864 0.095 0.0121313 -0.00920631 0.0949999 0.0117889 -0.00980152 0.0949999 0.0154011 0 -0.0885762 0.0114241 -0.0103819 0.0949999 0.011039 -0.0109455 0.095 0.0106339 -0.0114949 0.095 0.015816 0 -0.0882816 0.01021 -0.0120336 0.095 0.00977209 -0.0125574 0.095 0.0162586 0 -0.0880306 0.00931915 -0.0130698 0.095 0.00885253 -0.0135715 0.095 0.00837749 -0.0140602 0.095 0.0167259 0 -0.0878253 0.00789457 -0.0145395 0.0949998 0.00740662 -0.0150136 0.095 0.00691735 -0.0154865 0.095 0.00643452 -0.0159661 0.0949999 0.017209 0 -0.0876697 0.00597393 -0.0164672 0.095 0.0177079 0 -0.0875632 0.00557861 -0.0170224 0.095 0.0202162 0 -0.0878038 0.0197284 0 -0.0876534 0.0200265 0 0.0972613 0.0192304 0 -0.0875537 0.0190177 0 0.097473 0.021407 0 0.096568 0.0215492 0 -0.0885375 0.0211301 0 -0.0882477 0.0205104 0 0.0970779 0.0209707 0 0.0968469 0.0206838 0 -0.0880022 0.0228698 0 -0.09007 0.0225995 0 -0.0896377 0.0227957 0 0.0950586 0.0222882 0 -0.0892366 0.0219358 0 -0.0888676 0.0221797 0 0.0958852 0.0233718 0 0.0936251 0.0233986 0 -0.0914982 0.0232708 0 -0.0910039 0.0230373 0 0.0946004 0.0232297 0 0.0941213 0.0230941 0 -0.0905268 0.0235 0 -0.0925093 0.0234826 0 0.0920843 0.0234731 0 -0.093017 0.0234748 0 -0.0919999 0.0234618 0 0.0931156 0.023499 0 0.092602 0.0230872 0 -0.094489 0.0232654 0 -0.0940134 0.023118 0 0.0905836 0.0232914 0 0.091071 0.0233948 0 -0.0935201 0.0234131 0 0.0915726 0.0225898 0 -0.0953761 0.0192197 0 0.0875521 0.0223133 0 0.0892662 0.022276 0 -0.0957774 0.0197243 0 0.0876522 0.0192127 0 -0.0974488 0.0197119 0 -0.0973508 0.0202177 0 0.0878044 0.0201986 0 -0.0972026 0.0206928 0 0.0880066 0.0206685 0 -0.0970051 0.0211143 0 -0.0967621 0.0215351 0 -0.0964733 0.0211458 0 0.0882574 0.0219229 0 -0.0961446 0.0215681 0 0.0885521 0.0219598 0 0.0888903 0.0225097 0 0.0954868 0.021811 0 0.0962465 0.0195278 0 0.0973931 0.0121076 0.00310754 0.093443 0.0116228 0.0046 0.093443 0.0192195 0.0046 0.093443 0.0192195 0 0.093443 0.0124015 0.00156611 0.093443 0.0125 0 0.093443 0.0135897 0 0.093443 0.0192195 0 0.093443 0.0192195 0.0046 0.093443 0.0192195 0.0046 0.091452 0.0192195 0 0.091452 0.0192195 0.0046 0.091452 0.0124015 0.00156611 0.091452 0.0192195 0 0.091452 0.0116228 0.0046 0.091452 0.0121076 0.00310754 0.091452 0.0125 0 0.091452 0.0136111 0 0.091452 0.0192195 0.0046 0.093443 0.0116228 0.0046 0.091452 0.0192195 0.0046 0.091452 0.0116228 0.0046 0.093443 0.0135003 0 0.0924457 0.0125 0 0.091452 0.0125 0 0.093443 0.0135897 0 0.093443 0.0136111 0 0.091452 -9.96478e-07 -0.0185 0.1 0.000350326 -0.0184967 0.095 -0.00137838 -0.0184486 0.095 0.0185 0 0.0975 0.0184211 0.00170704 0.1 0.0184211 0.00170704 0.095 -0.00309504 -0.0182393 0.095 -0.00170797 -0.0184209 0.1 -0.00478465 -0.0178706 0.095 -0.00340036 -0.0181848 0.1 -0.00506374 -0.0177935 0.1 -0.00643246 -0.0173457 0.095 -0.00802405 -0.0166693 0.095 -0.0066839 -0.0172503 0.1 -0.00954553 -0.0158472 0.095 -0.00824703 -0.01656 0.1 -0.0097398 -0.0157285 0.1 -0.0109836 -0.0148866 0.095 -0.0123257 -0.0137959 0.095 -0.0111495 -0.0147627 0.1 -0.0135601 -0.0125847 0.095 -0.012464 -0.013671 0.1 -0.0136722 -0.0124627 0.1 -0.0146759 -0.0112635 0.095 -0.0156636 -0.00984391 0.095 -0.0147638 -0.0111481 0.1 -0.0165143 -0.00833827 0.095 -0.0157294 -0.00973837 0.1 -0.0165608 -0.00824559 0.1 -0.0172208 -0.00675977 0.095 -0.0177768 -0.0051222 0.095 -0.0172509 -0.00668248 0.1 -0.0181774 -0.00343987 0.095 -0.0177939 -0.00506237 0.1 -0.018185 -0.00339908 0.1 -0.0184192 -0.00172748 0.095 -0.0185 1.37983e-17 0.095 -0.0184211 -0.00170704 0.1 -0.0185 1.37983e-17 0.1 0.00170599 -0.0184211 0.1 0.00339843 -0.0181851 0.1 0.00207597 -0.0183832 0.095 0.00378347 -0.018109 0.095 0.00506188 -0.017794 0.1 0.00668215 -0.017251 0.1 0.00545791 -0.0176766 0.095 0.00824542 -0.0165609 0.1 0.00705641 -0.0171014 0.0951848 0.00859545 -0.0163819 0.0953696 0.00973833 -0.0157294 0.1 0.0111482 -0.0147637 0.1 0.010056 -0.015528 0.0955521 0.0124629 -0.0136721 0.1 0.0114214 -0.014553 0.09573 0.0126752 -0.0134756 0.0959002 0.0136713 -0.0124638 0.1 0.014763 -0.0111492 0.1 0.0138237 -0.0122951 0.0960684 0.0157288 -0.00973938 0.1 0.0148727 -0.0110029 0.0962421 0.0158108 -0.00960582 0.0964217 0.0165603 -0.0082465 0.1 0.0172506 -0.00668326 0.1 0.0166233 -0.00811875 0.0966051 0.0177937 -0.00506299 0.1 0.0172979 -0.00655921 0.0967901 0.017826 -0.00494677 0.0969743 0.018185 -0.00339952 0.1 0.0184211 -0.00170704 0.1 0.0182026 -0.00330214 0.0971554 0.0185 -4.05185e-18 0.1 0.0184266 -0.00164718 0.0973312 0.0185 0 0.095 0.0172509 0.00668248 0.095 0.0177939 0.00506237 0.095 0.0177939 0.00506237 0.1 0.018185 0.00339908 0.1 0.018185 0.00339908 0.095 0.0157294 0.00973837 0.1 0.0147638 0.0111481 0.095 0.0157294 0.00973837 0.095 0.0172509 0.00668248 0.1 0.0165608 0.00824559 0.1 0.0165608 0.00824559 0.095 0.012464 0.013671 0.095 0.012464 0.013671 0.1 0.0111495 0.0147627 0.095 0.0136722 0.0124627 0.095 0.0147638 0.0111481 0.1 0.0136722 0.0124627 0.1 0.0066839 0.0172503 0.095 0.00824703 0.01656 0.095 0.00824703 0.01656 0.1 0.0097398 0.0157285 0.1 0.0097398 0.0157285 0.095 0.0111495 0.0147627 0.1 0.00340036 0.0181848 0.1 0.00170797 0.0184209 0.095 0.00340036 0.0181848 0.095 0.0066839 0.0172503 0.1 0.00506374 0.0177935 0.1 0.00506374 0.0177935 0.095 -0.00170599 0.0184211 0.095 -0.00170599 0.0184211 0.1 -0.00339843 0.0181851 0.095 9.96478e-07 0.0185 0.095 0.00170797 0.0184209 0.1 9.96478e-07 0.0185 0.1 -0.00824542 0.0165609 0.095 -0.00668215 0.017251 0.095 -0.00668215 0.017251 0.1 -0.00506188 0.017794 0.1 -0.00506188 0.017794 0.095 -0.00339843 0.0181851 0.1 -0.0111482 0.0147637 0.1 -0.0124629 0.0136721 0.095 -0.0111482 0.0147637 0.095 -0.00824542 0.0165609 0.1 -0.00973833 0.0157294 0.1 -0.00973833 0.0157294 0.095 -0.0136713 0.0124638 0.1 -0.014763 0.0111492 0.095 -0.0136713 0.0124638 0.095 -0.0124629 0.0136721 0.1 -0.0157288 0.00973938 0.095 -0.014763 0.0111492 0.1 -0.0157288 0.00973938 0.1 -0.0165603 0.0082465 0.095 -0.0165603 0.0082465 0.1 -0.0172506 0.00668326 0.095 -0.0177937 0.00506299 0.095 -0.0172506 0.00668326 0.1 -0.0177937 0.00506299 0.1 -0.018185 0.00339952 0.095 -0.018185 0.00339952 0.1 -0.0184211 0.00170704 0.095 -0.0184211 0.00170704 0.1 0.0121313 -0.00920631 0.0949999 0.0117889 -0.00980152 0.0949999 0.00883954 -0.00883803 0.095 -0.00779447 0.00977212 0.095 -0.00665138 0.0105834 0.095 -0.0111482 0.0147637 0.095 -0.0124629 0.0136721 0.095 -0.00883954 0.00883803 0.095 0.0124214 -0.00139967 0.095 0.00643452 -0.0159661 0.0949999 0.00597393 -0.0164672 0.095 -0.0124214 -0.00139967 0.095 -0.0125 7.65404e-19 0.095 -0.0184192 -0.00172748 0.095 0.0121867 -0.0027811 0.095 0.00545791 -0.0176766 0.095 0.0125 -3.2549e-18 0.095 0.00557861 -0.0170224 0.095 -0.0165143 -0.00833827 0.095 -0.0112619 -0.00542396 0.095 -0.0172208 -0.00675977 0.095 -0.00977247 -0.00779414 0.095 -0.0105837 -0.00665088 0.095 -0.0146759 -0.0112635 0.095 -0.0181774 -0.00343987 0.095 -0.0121865 -0.00278174 0.095 -0.0177768 -0.0051222 0.095 -0.0117984 -0.00412882 0.095 -0.0184211 0.00170704 0.095 -0.0185 1.37983e-17 0.095 -0.0121867 0.0027811 0.095 -0.0177937 0.00506299 0.095 -0.018185 0.00339952 0.095 -0.0124214 0.00139967 0.095 -0.0135601 -0.0125847 0.095 -0.00883828 -0.00883937 0.095 -0.0117987 0.00412791 0.095 -0.0105845 0.00664963 0.095 -0.014763 0.0111492 0.095 -0.0157288 0.00973938 0.095 -0.0112624 0.00542285 0.095 -0.0172506 0.00668326 0.095 -0.00824542 0.0165609 0.095 -0.00973833 0.0157294 0.095 -0.0136713 0.0124638 0.095 -0.00977345 0.00779281 0.095 -0.00506188 0.017794 0.095 -0.00412965 0.0117981 0.095 -0.00278273 0.0121863 0.095 -0.00668215 0.017251 0.095 -1.22861e-06 0.0124999 0.095 0.00170797 0.0184209 0.095 9.96478e-07 0.0185 0.095 -0.00140079 0.0124212 0.095 -0.00339843 0.0181851 0.095 0.00542261 0.0112625 0.095 0.00824703 0.01656 0.095 0.0066839 0.0172503 0.095 0.00278038 0.0121868 0.095 0.00506374 0.0177935 0.095 0.00340036 0.0181848 0.095 0.00883828 0.00883937 0.095 0.012464 0.013671 0.095 0.00779294 0.00977341 0.095 0.0177939 0.00506237 0.095 0.0117984 0.00412882 0.095 0.0121865 0.00278174 0.095 0.0147638 0.0111481 0.095 0.0105837 0.00665088 0.095 0.0157294 0.00973837 0.095 0.018185 0.00339908 0.095 0.0184211 0.00170704 0.095 0.0185 0 0.095 0.0172509 0.00668248 0.095 0.0165608 0.00824559 0.095 0.0112619 0.00542396 0.095 0.0097398 0.0157285 0.095 0.00664959 0.0105845 0.095 0.0111495 0.0147627 0.095 0.0136722 0.0124627 0.095 0.00977247 0.00779414 0.095 0.00139836 0.0124215 0.095 0.00412745 0.0117989 0.095 -0.00542463 0.0112615 0.095 -0.00170599 0.0184211 0.095 -0.0165603 0.0082465 0.095 0.00691735 -0.0154865 0.095 -0.0123257 -0.0137959 0.095 -0.00779294 -0.00977341 0.095 0.00740662 -0.0150136 0.095 -0.0109836 -0.0148866 0.095 0.0117987 -0.00412791 0.095 0.00789457 -0.0145395 0.0949998 0.00885253 -0.0135715 0.095 0.00837749 -0.0140602 0.095 0.0112624 -0.00542285 0.095 0.00931915 -0.0130698 0.095 0.00977209 -0.0125574 0.095 -0.00954553 -0.0158472 0.095 -0.00664959 -0.0105845 0.095 -0.00542261 -0.0112625 0.095 -0.00802405 -0.0166693 0.095 0.0106339 -0.0114949 0.095 0.01021 -0.0120336 0.095 0.0105845 -0.00664963 0.095 0.00977345 -0.00779281 0.095 0.011039 -0.0109455 0.095 0.0114241 -0.0103819 0.0949999 -0.00643246 -0.0173457 0.095 -0.00412745 -0.0117989 0.095 -0.00478465 -0.0178706 0.095 -0.00278038 -0.0121868 0.095 -0.00139836 -0.0124215 0.095 -0.00309504 -0.0182393 0.095 -0.00137838 -0.0184486 0.095 0.000350326 -0.0184967 0.095 1.22861e-06 -0.0124999 0.095 0.0124497 -0.00859864 0.095 0.00207597 -0.0183832 0.095 0.00140079 -0.0124212 0.095 0.00779447 -0.00977212 0.095 0.0127427 -0.00798103 0.095 0.0132527 -0.00671459 0.095 0.0130099 -0.00735415 0.095 0.00665138 -0.0105834 0.095 0.0134696 -0.00606494 0.095 0.0138216 -0.00474662 0.095 0.0136594 -0.00540841 0.095 0.0140644 -0.00339963 0.095 0.013957 -0.00407613 0.095 0.00542463 -0.0112615 0.095 0.00412965 -0.0117981 0.095 0.0141432 -0.00272057 0.095 0.0141932 -0.00204155 0.095 0.0142145 -0.00136084 0.095 0.0142067 -0.000679707 0.095 0.00378347 -0.018109 0.095 0.00278273 -0.0121863 0.095 -0.0156636 -0.00984391 0.095 0.0124214 0.00139967 0.095 -0.00139836 -0.0124215 0.095 1.22861e-06 -0.0124999 0.095 -1.22861e-06 -0.0124999 -0.095 0.0125 0 0.091452 0.0124214 0.00139967 -0.095 0.0125 2.29621e-18 -0.095 -0.00140079 -0.0124212 -0.095 -0.00278038 -0.0121868 0.095 -0.00278273 -0.0121863 -0.095 -0.00412745 -0.0117989 0.095 -0.00542261 -0.0112625 0.095 -0.00412965 -0.0117981 -0.095 -0.00542463 -0.0112615 -0.095 -0.00664959 -0.0105845 0.095 -0.00665138 -0.0105834 -0.095 -0.00779294 -0.00977341 0.095 -0.00883828 -0.00883937 0.095 -0.00779447 -0.00977212 -0.095 -0.00883954 -0.00883803 -0.095 -0.00977247 -0.00779414 0.095 -0.00977345 -0.00779281 -0.095 -0.0105837 -0.00665088 0.095 -0.0112619 -0.00542396 0.095 -0.0105845 -0.00664963 -0.095 -0.0112624 -0.00542285 -0.095 -0.0117984 -0.00412882 0.095 -0.0117987 -0.00412791 -0.095 -0.0121865 -0.00278174 0.095 -0.0124214 -0.00139967 0.095 -0.0121867 -0.0027811 -0.095 -0.0124214 -0.00139967 -0.095 -0.0125 7.65404e-19 0.095 -0.0125 -2.29621e-18 -0.095 0.00139836 -0.0124215 -0.095 0.00140079 -0.0124212 0.095 0.00278038 -0.0121868 -0.095 0.00412745 -0.0117989 -0.095 0.00278273 -0.0121863 0.095 0.00412965 -0.0117981 0.095 0.00542261 -0.0112625 -0.095 0.00542463 -0.0112615 0.095 0.00664959 -0.0105845 -0.095 0.00779294 -0.00977341 -0.095 0.00665138 -0.0105834 0.095 0.00779447 -0.00977212 0.095 0.00883828 -0.00883937 -0.095 0.00883954 -0.00883803 0.095 0.00977247 -0.00779414 -0.095 0.0105837 -0.00665088 -0.095 0.00977345 -0.00779281 0.095 0.0105845 -0.00664963 0.095 0.0112619 -0.00542396 -0.095 0.0112624 -0.00542285 0.095 0.0117984 -0.00412882 -0.095 0.0121865 -0.00278174 -0.095 0.0117987 -0.00412791 0.095 0.0121867 -0.0027811 0.095 0.0124214 -0.00139967 -0.095 0.0124214 -0.00139967 0.095 0.0124015 0.00156611 0.091452 0.0121076 0.00310754 0.091452 0.0121867 0.0027811 -0.095 0.0105837 0.00665088 0.095 0.0105845 0.00664963 -0.095 0.0112619 0.00542396 0.095 0.0117987 0.00412791 -0.095 0.0116228 0.0046 0.091452 0.0112624 0.00542285 -0.095 0.00883828 0.00883937 0.095 0.00779294 0.00977341 0.095 0.00779447 0.00977212 -0.095 0.00977345 0.00779281 -0.095 0.00977247 0.00779414 0.095 0.00883954 0.00883803 -0.095 0.00412965 0.0117981 -0.095 0.00542261 0.0112625 0.095 0.00412745 0.0117989 0.095 0.00542463 0.0112615 -0.095 0.00665138 0.0105834 -0.095 0.00664959 0.0105845 0.095 -1.22861e-06 0.0124999 0.095 1.22861e-06 0.0124999 -0.095 0.00139836 0.0124215 0.095 0.00278038 0.0121868 0.095 0.00140079 0.0124212 -0.095 0.00278273 0.0121863 -0.095 -0.00278273 0.0121863 0.095 -0.00412965 0.0117981 0.095 -0.00412745 0.0117989 -0.095 -0.00139836 0.0124215 -0.095 -0.00140079 0.0124212 0.095 -0.00278038 0.0121868 -0.095 -0.00779294 0.00977341 -0.095 -0.00665138 0.0105834 0.095 -0.00779447 0.00977212 0.095 -0.00664959 0.0105845 -0.095 -0.00542261 0.0112625 -0.095 -0.00542463 0.0112615 0.095 -0.00977247 0.00779414 -0.095 -0.00883954 0.00883803 0.095 -0.00977345 0.00779281 0.095 -0.00883828 0.00883937 -0.095 -0.0105845 0.00664963 0.095 -0.0105837 0.00665088 -0.095 -0.0112624 0.00542285 0.095 -0.0112619 0.00542396 -0.095 -0.0117984 0.00412882 -0.095 -0.0117987 0.00412791 0.095 -0.0121867 0.0027811 0.095 -0.0121865 0.00278174 -0.095 -0.0124214 0.00139967 0.095 -0.0124214 0.00139967 -0.095 0.0125 -3.2549e-18 0.095 0.0124214 0.00139967 0.095 0.0125 0 0.093443 0.0116228 0.0046 0.093443 0.0121865 0.00278174 0.095 0.0121076 0.00310754 0.093443 0.0124015 0.00156611 0.093443 0.0117984 0.00412882 0.095 0.0177875 -0.00508453 -0.095 0.0181822 -0.00341419 -0.095 0.0180545 -0.00403565 -0.1 0.0185 2.46519e-32 -0.095 0.0184909 -0.000581099 -0.1 0.0184204 -0.00171461 -0.095 0.0184635 0.00116162 -0.1 0.0185 2.46519e-32 -0.0975 0.0184635 0.00116162 -0.0973816 0.0165436 -0.00827992 -0.095 0.0162117 -0.00891244 -0.1 0.0157051 -0.00977747 -0.095 0.0169785 -0.00734724 -0.1 0.0172398 -0.0067111 -0.095 0.0175945 -0.00571681 -0.1 0.0117923 -0.0142545 -0.1 0.012413 -0.0137174 -0.095 0.0130815 -0.0130815 -0.1 0.0142545 -0.0117923 -0.1 0.0136308 -0.012508 -0.095 0.0147314 -0.0111909 -0.095 0.00816477 -0.0166008 -0.095 0.00734724 -0.0169785 -0.1 0.00659111 -0.017286 -0.095 0.00966813 -0.0157726 -0.095 0.0103985 -0.015301 -0.1 0.00891244 -0.0162117 -0.1 0.000581099 -0.0184909 -0.1 0.00158624 -0.0184318 -0.095 0.00231866 -0.0183541 -0.1 0.00403565 -0.0180545 -0.1 0.00496073 -0.0178224 -0.095 0.00571681 -0.0175945 -0.1 -0.00289404 -0.0182722 -0.1 -0.00460076 -0.0179188 -0.1 -0.00354085 -0.0181579 -0.095 -0.000128811 -0.0184995 -0.095 -0.00116162 -0.0184635 -0.1 -0.00184276 -0.0184079 -0.095 -0.00988695 -0.0156364 -0.095 -0.00839522 -0.0164854 -0.095 -0.00941727 -0.0159237 -0.1 -0.00787692 -0.0167393 -0.1 -0.00683124 -0.0171925 -0.095 -0.00626665 -0.0174063 -0.1 -0.0134859 -0.0126641 -0.1 -0.0146179 -0.0113388 -0.1 -0.0138039 -0.0123167 -0.095 -0.0112936 -0.0146528 -0.095 -0.0122343 -0.0138771 -0.1 -0.012603 -0.013543 -0.095 -0.0173318 -0.0064698 -0.095 -0.0166576 -0.00804827 -0.095 -0.0172009 -0.0068103 -0.1 -0.0158399 -0.00955745 -0.095 -0.014886 -0.0109844 -0.095 -0.0156201 -0.0099128 -0.1 -0.0184179 -0.001741 -0.1 -0.0185 -5.55112e-18 -0.1 -0.0184425 -0.00145686 -0.095 -0.0177654 -0.00516134 -0.1 -0.0181723 -0.00346655 -0.1 -0.0178568 -0.00483564 -0.095 -0.0181326 0.00366832 -0.095 -0.0181789 0.00343195 -0.1 -0.0177801 0.00511058 -0.1 -0.0183946 0.00197199 -0.095 -0.0184982 0.000258675 -0.095 -0.0184195 0.00172347 -0.1 -0.0156764 0.00982341 -0.1 -0.0155665 0.0099967 -0.095 -0.016426 0.00851095 -0.095 -0.0172267 0.00674475 -0.1 -0.0165234 0.00832027 -0.1 -0.0171441 0.00695194 -0.095 -0.0122192 0.0138903 -0.095 -0.0123527 0.0137717 -0.1 -0.011016 0.0148626 -0.1 -0.013454 0.012698 -0.095 -0.014573 0.0113964 -0.095 -0.013582 0.012561 -0.1 -0.00648159 0.0173274 -0.1 -0.00634753 0.017377 -0.095 -0.00793073 0.0167139 -0.095 -0.0095835 0.0158242 -0.1 -0.00944566 0.0159069 -0.095 -0.0108793 0.014963 -0.095 -0.00315466 0.018229 -0.1 -0.00470968 0.0178905 -0.095 -0.00483917 0.0178559 -0.1 -0.00303129 0.01825 -0.095 -0.00144271 0.0184437 -0.1 0.00028178 0.0184979 -0.1 -0.00132681 0.0184524 -0.095 0.0053808 0.0177002 -0.1 0.00700636 0.0171219 -0.1 0.00370844 0.0181245 -0.1 0.00379613 0.0181063 -0.095 0.00210166 0.0183802 -0.095 0.00857098 0.0163948 -0.1 0.0179338 0.00454173 -0.0970195 0.0182784 0.00285459 -0.0972036 0.010061 0.015525 -0.1 0.01743 0.00620053 -0.0968317 0.0174241 0.00621691 -0.1 0.0179275 0.00456664 -0.1 0.0101511 0.0154663 -0.0955642 0.0114636 0.0145202 -0.1 0.0167713 0.00780865 -0.0966425 0.0167692 0.00781312 -0.1 0.0115389 0.0144604 -0.0957457 0.0159684 0.00934136 -0.1 0.0159663 0.00934483 -0.0964544 0.0127665 0.0133891 -0.1 0.0128117 0.0133458 -0.0959202 0.0139583 0.0121415 -0.1 0.0150287 0.0107884 -0.1 0.0150276 0.0107899 -0.0962699 0.0139705 0.0121275 -0.0960913 0.00866271 0.0163465 -0.0953778 0.00709159 0.0170868 -0.0951889 0.018275 0.00287664 -0.1 0.00200382 0.0183912 -0.1 0.000389101 0.0184959 -0.095 -0.00806763 0.0166482 -0.1 -0.0146931 0.0112411 -0.1 -0.0177146 0.00533309 -0.095 -0.0182281 -0.00315985 -0.095 -0.0164836 -0.00839882 -0.1 -0.010874 -0.0149668 -0.1 -0.00520846 -0.0177516 -0.095 0.00328764 -0.0182055 -0.095 0.0110883 -0.0148087 -0.095 0.015301 -0.0103985 -0.1 0.0183541 -0.00231866 -0.1 -0.0146931 0.0112411 -0.1 -0.0123527 0.0137717 -0.1 -0.013582 0.012561 -0.1 -0.00787692 -0.0167393 -0.1 -0.00626665 -0.0174063 -0.1 0.0174241 0.00621691 -0.1 -0.011016 0.0148626 -0.1 -0.0156764 0.00982341 -0.1 -0.0165234 0.00832027 -0.1 -0.0095835 0.0158242 -0.1 -0.0172267 0.00674475 -0.1 -0.00806763 0.0166482 -0.1 -0.00648159 0.0173274 -0.1 -0.0177801 0.00511058 -0.1 -0.00483917 0.0178559 -0.1 -0.00315466 0.018229 -0.1 -0.0181789 0.00343195 -0.1 -0.0184195 0.00172347 -0.1 -0.00144271 0.0184437 -0.1 -0.0185 -5.55112e-18 -0.1 0.00028178 0.0184979 -0.1 0.00370844 0.0181245 -0.1 -0.0181723 -0.00346655 -0.1 -0.0177654 -0.00516134 -0.1 0.00200382 0.0183912 -0.1 -0.0184179 -0.001741 -0.1 -0.0164836 -0.00839882 -0.1 0.010061 0.015525 -0.1 0.00857098 0.0163948 -0.1 -0.0172009 -0.0068103 -0.1 0.00700636 0.0171219 -0.1 0.0053808 0.0177002 -0.1 -0.0146179 -0.0113388 -0.1 -0.0134859 -0.0126641 -0.1 0.0127665 0.0133891 -0.1 0.0114636 0.0145202 -0.1 -0.0156201 -0.0099128 -0.1 0.0159684 0.00934136 -0.1 -0.010874 -0.0149668 -0.1 -0.00941727 -0.0159237 -0.1 0.0150287 0.0107884 -0.1 0.0139583 0.0121415 -0.1 -0.0122343 -0.0138771 -0.1 -0.00460076 -0.0179188 -0.1 0.0179275 0.00456664 -0.1 0.0167692 0.00781312 -0.1 -0.00116162 -0.0184635 -0.1 0.000581099 -0.0184909 -0.1 0.0184909 -0.000581099 -0.1 0.018275 0.00287664 -0.1 -0.00289404 -0.0182722 -0.1 0.0184635 0.00116162 -0.1 0.0175945 -0.00571681 -0.1 0.00403565 -0.0180545 -0.1 0.00571681 -0.0175945 -0.1 0.0180545 -0.00403565 -0.1 0.0183541 -0.00231866 -0.1 0.00231866 -0.0183541 -0.1 0.0103985 -0.015301 -0.1 0.015301 -0.0103985 -0.1 0.00891244 -0.0162117 -0.1 0.00734724 -0.0169785 -0.1 0.0162117 -0.00891244 -0.1 0.0169785 -0.00734724 -0.1 0.0130815 -0.0130815 -0.1 0.0142545 -0.0117923 -0.1 0.0117923 -0.0142545 -0.1 0.00885253 0.0135715 -0.095 0.0117987 0.00412791 -0.095 0.00837749 0.0140602 -0.095 -0.00779294 0.00977341 -0.095 -0.0122192 0.0138903 -0.095 -0.00883828 0.00883937 -0.095 0.00691735 0.0154865 -0.095 0.0121867 0.0027811 -0.095 0.00643452 0.0159661 -0.0949999 -0.00977247 0.00779414 -0.095 -0.013454 0.012698 -0.095 0.0124214 0.00139967 -0.095 0.00597393 0.0164672 -0.095 -0.014573 0.0113964 -0.095 -0.0155665 0.0099967 -0.095 0.00557861 0.0170224 -0.095 -0.0105837 0.00665088 -0.095 -0.016426 0.00851095 -0.095 0.0125 2.29621e-18 -0.095 -0.0112619 0.00542396 -0.095 -0.0171441 0.00695194 -0.095 0.0184635 0.00116162 -0.0973816 -0.0121865 0.00278174 -0.095 -0.0117984 0.00412882 -0.095 -0.0177146 0.00533309 -0.095 -0.0181326 0.00366832 -0.095 -0.0124214 0.00139967 -0.095 0.00740662 0.0150136 -0.095 -0.0183946 0.00197199 -0.095 -0.0184982 0.000258675 -0.095 0.00789457 0.0145395 -0.0949998 -0.0108793 0.014963 -0.095 0.0112624 0.00542285 -0.095 -0.00664959 0.0105845 -0.095 -0.00944566 0.0159069 -0.095 0.00931915 0.0130698 -0.095 0.00278038 -0.0121868 -0.095 0.00496073 -0.0178224 -0.095 0.00412745 -0.0117989 -0.095 0.0114241 0.0103819 -0.0949999 0.0117889 0.00980152 -0.0949999 0.00977345 0.00779281 -0.095 0.011039 0.0109455 -0.095 0.0105845 0.00664963 -0.095 0.0106339 0.0114949 -0.095 -0.00278038 0.0121868 -0.095 -0.00139836 0.0124215 -0.095 -0.00303129 0.01825 -0.095 0.00278273 0.0121863 -0.095 0.00412965 0.0117981 -0.095 0.0142145 0.00136084 -0.095 0.0124497 0.00859864 -0.095 0.00883954 0.00883803 -0.095 0.0121313 0.00920631 -0.0949999 0.0141432 0.00272057 -0.095 0.0140644 0.00339963 -0.095 0.000389101 0.0184959 -0.095 0.00140079 0.0124212 -0.095 0.00210166 0.0183802 -0.095 0.00665138 0.0105834 -0.095 0.0134696 0.00606494 -0.095 0.0136594 0.00540841 -0.095 0.0132527 0.00671459 -0.095 0.00779447 0.00977212 -0.095 0.0130099 0.00735415 -0.095 0.0127427 0.00798103 -0.095 0.0138216 0.00474662 -0.095 0.00542463 0.0112615 -0.095 0.013957 0.00407613 -0.095 -0.00132681 0.0184524 -0.095 1.22861e-06 0.0124999 -0.095 0.0141932 0.00204155 -0.095 -0.00412745 0.0117989 -0.095 -0.00470968 0.0178905 -0.095 -0.00542261 0.0112625 -0.095 -0.00634753 0.017377 -0.095 0.0142067 0.000679707 -0.095 0.00379613 0.0181063 -0.095 -0.00793073 0.0167139 -0.095 0.01021 0.0120336 -0.095 -0.0158399 -0.00955745 -0.095 -0.0112624 -0.00542285 -0.095 -0.0166576 -0.00804827 -0.095 0.00977209 0.0125574 -0.095 -0.0182281 -0.00315985 -0.095 -0.0121867 -0.0027811 -0.095 -0.0124214 -0.00139967 -0.095 -0.0125 -2.29621e-18 -0.095 -0.0184425 -0.00145686 -0.095 -0.0117987 -0.00412791 -0.095 -0.0173318 -0.0064698 -0.095 -0.0178568 -0.00483564 -0.095 -0.00977345 -0.00779281 -0.095 -0.014886 -0.0109844 -0.095 -0.0138039 -0.0123167 -0.095 -0.0105845 -0.00664963 -0.095 -0.012603 -0.013543 -0.095 -0.00779447 -0.00977212 -0.095 -0.00883954 -0.00883803 -0.095 -0.00665138 -0.0105834 -0.095 -0.00988695 -0.0156364 -0.095 -0.00839522 -0.0164854 -0.095 -0.0112936 -0.0146528 -0.095 -0.00542463 -0.0112615 -0.095 -0.00683124 -0.0171925 -0.095 0.0185 2.46519e-32 -0.095 0.0184204 -0.00171461 -0.095 -0.00412965 -0.0117981 -0.095 -0.00520846 -0.0177516 -0.095 0.0181822 -0.00341419 -0.095 -0.00278273 -0.0121863 -0.095 0.0177875 -0.00508453 -0.095 0.0121865 -0.00278174 -0.095 0.0117984 -0.00412882 -0.095 -0.00354085 -0.0181579 -0.095 -0.00140079 -0.0124212 -0.095 0.0172398 -0.0067111 -0.095 0.0112619 -0.00542396 -0.095 0.0165436 -0.00827992 -0.095 -1.22861e-06 -0.0124999 -0.095 -0.00184276 -0.0184079 -0.095 0.0105837 -0.00665088 -0.095 0.0147314 -0.0111909 -0.095 0.0157051 -0.00977747 -0.095 -0.000128811 -0.0184995 -0.095 0.00158624 -0.0184318 -0.095 0.0136308 -0.012508 -0.095 0.00977247 -0.00779414 -0.095 0.00883828 -0.00883937 -0.095 0.00139836 -0.0124215 -0.095 0.00328764 -0.0182055 -0.095 0.00779294 -0.00977341 -0.095 0.012413 -0.0137174 -0.095 0.0110883 -0.0148087 -0.095 0.00664959 -0.0105845 -0.095 0.00966813 -0.0157726 -0.095 0.00659111 -0.017286 -0.095 0.00816477 -0.0166008 -0.095 0.00542261 -0.0112625 -0.095 0.0124214 -0.00139967 -0.095 -0.00824542 0.0165609 0.1 -0.00668215 0.017251 0.1 0.0177937 -0.00506299 0.1 0.0097398 0.0157285 0.1 0.0111495 0.0147627 0.1 0.0136722 0.0124627 0.1 0.012464 0.013671 0.1 0.0147638 0.0111481 0.1 0.00824703 0.01656 0.1 0.0157294 0.00973837 0.1 0.0066839 0.0172503 0.1 0.00506374 0.0177935 0.1 0.0165608 0.00824559 0.1 0.0172509 0.00668248 0.1 0.00340036 0.0181848 0.1 0.0177939 0.00506237 0.1 0.00170797 0.0184209 0.1 9.96478e-07 0.0185 0.1 0.018185 0.00339908 0.1 0.0184211 0.00170704 0.1 -0.00170599 0.0184211 0.1 0.0185 -4.05185e-18 0.1 -0.00339843 0.0181851 0.1 -0.00973833 0.0157294 0.1 0.0172506 -0.00668326 0.1 0.0165603 -0.0082465 0.1 0.018185 -0.00339952 0.1 -0.00506188 0.017794 0.1 0.0184211 -0.00170704 0.1 -0.0136713 0.0124638 0.1 0.014763 -0.0111492 0.1 0.0136713 -0.0124638 0.1 -0.0124629 0.0136721 0.1 -0.0111482 0.0147637 0.1 0.0157288 -0.00973938 0.1 0.0124629 -0.0136721 0.1 -0.0157288 0.00973938 0.1 -0.014763 0.0111492 0.1 -0.0177937 0.00506299 0.1 -0.0172506 0.00668326 0.1 0.00824542 -0.0165609 0.1 0.00973833 -0.0157294 0.1 -0.0165603 0.0082465 0.1 0.0111482 -0.0147637 0.1 0.00339843 -0.0181851 0.1 -0.0185 1.37983e-17 0.1 -0.0184211 0.00170704 0.1 0.00668215 -0.017251 0.1 0.00506188 -0.017794 0.1 -0.018185 0.00339952 0.1 -0.018185 -0.00339908 0.1 -0.00170797 -0.0184209 0.1 -0.0177939 -0.00506237 0.1 -0.0184211 -0.00170704 0.1 0.00170599 -0.0184211 0.1 -9.96478e-07 -0.0185 0.1 -0.0157294 -0.00973837 0.1 -0.0165608 -0.00824559 0.1 -0.0066839 -0.0172503 0.1 -0.00506374 -0.0177935 0.1 -0.0172509 -0.00668248 0.1 -0.00340036 -0.0181848 0.1 -0.00824703 -0.01656 0.1 -0.0097398 -0.0157285 0.1 -0.0147638 -0.0111481 0.1 -0.0136722 -0.0124627 0.1 -0.0111495 -0.0147627 0.1 -0.012464 -0.013671 0.1 - - - - - - - - - - 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.00920026 0.102935 -0.994645 0.0287382 0.103532 -0.994211 0.0188937 0.104117 -0.994386 -2.27733e-07 -0.100087 0.994979 0.824699 0.046357 -0.563668 0.871375 0.0398073 -0.489001 0.878656 0.0386784 -0.475886 0.0474212 0.0970732 -0.994147 0.0383688 0.10116 -0.99413 0.0411856 -0.0989068 0.994244 0.0680014 0.0764435 -0.994752 0.0555585 0.0914279 -0.994261 0.0820418 0.06438 -0.994547 -0.102979 -0.0317964 0.994175 0.0624922 0.0844552 -0.994466 0.07377 0.0694097 -0.994857 0.0893732 0.0578724 -0.994315 0.100058 0.0412842 -0.994125 0.0954623 0.0500842 -0.994172 0.056244 0.101463 -0.993248 -0.0840578 -0.0772522 0.993462 0.0662238 0.0921973 -0.993536 0.0010058 0.114339 -0.993441 -0.0883445 0.07233 0.99346 -0.097537 0.0523715 0.993853 -0.112921 -0.014893 0.993492 0.0732628 0.0876585 0.993453 0.0330092 0.104348 0.993993 0.0892134 0.0699214 0.993555 0.0217291 -0.110922 0.993591 0.0629588 -0.0928741 0.993685 -0.0763042 0.0848141 0.993471 -0.0985217 0.0469325 0.994028 -0.0543208 0.0960939 0.993889 -0.114277 0.00220562 0.993446 -0.11129 -0.0206798 0.993573 -0.108158 0.0259701 0.993794 0.00742421 0.11374 -0.993483 -0.102979 0.031796 -0.994175 -0.0878999 -0.0720046 0.993523 0.00983506 0.113344 0.993507 -0.0338384 0.104769 0.993921 0.0979362 0.0465022 0.994106 -0.113965 -0.00883416 0.993446 0.111473 -0.0174198 0.993615 0.0828411 -0.0789201 0.993433 -0.0844489 0.0771841 0.993434 0.0459209 0.0986397 -0.994063 0.0248257 0.108681 -0.993767 0.0396925 -0.100142 0.994181 0.102956 0.0363443 0.994022 0.0979772 -0.0503255 0.993915 0.0642376 0.0932342 0.99357 0.0502383 -0.0971745 0.993999 -0.105006 0.0319244 0.993959 0.114378 0.000191216 0.993437 0.0994631 0.0404182 0.99422 0.109182 -0.0236736 0.99374 0.0588513 0.0955712 0.993681 0.0385976 0.100505 0.994188 -0.0290253 0.107678 0.993762 0.0966115 -0.0557861 0.993758 0.113645 0.0111336 0.993459 0.0160009 -0.112658 0.993505 0.056728 -0.095329 0.993828 0.0730235 -0.0872163 0.993509 0.0896536 -0.0704364 0.993479 -0.0959399 0.0578314 0.993706 -0.0460841 0.0980084 0.994118 -0.0971957 0.0537374 0.993814 0.0286081 0.106853 0.993863 0.0050132 0.114042 0.993463 0.0493048 0.0981652 0.993948 0.015436 0.112056 -0.993582 0.0581715 0.0958195 -0.993697 0.0379183 0.101016 -0.994162 0.0726419 0.0881182 -0.993458 -0.0952181 0.0504597 -0.994177 0.0673439 -0.077579 0.994709 -1.51822e-07 0.100087 -0.994979 0.0486256 0.0982787 -0.99397 -0.0376706 0.101899 -0.994081 -0.0237906 0.110131 0.993632 0.0644675 -0.0921688 0.993654 0.0839217 -0.0777682 0.993433 0.111945 -0.0158334 0.993588 0.0533959 0.0972847 0.993823 0.114197 0.00650637 0.993437 -0.0137757 0.113162 0.993481 -0.0916462 0.0672078 0.993521 0.098737 -0.044913 0.994099 -0.0608834 -0.094768 0.993636 -0.10081 -0.038949 0.994143 -0.0797688 -0.0820081 0.993434 -0.0933795 -0.0618137 0.99371 0.108174 0.0280745 0.993735 0.0951806 -0.0598688 0.993658 0.0997242 -0.0396052 0.994227 -0.104178 -0.0346903 0.993954 -0.0957223 -0.0555287 0.993858 -0.0709705 0.0885657 0.993539 -0.0477532 0.0977047 0.994069 -0.113554 0.00862991 0.993494 0.0365429 0.102011 -0.994112 0.0162307 0.111831 0.993595 -0.00767357 0.114092 0.993441 0.0912373 0.0663224 -0.993618 0.0923485 0.0640922 0.993662 0.0780583 0.0836548 0.993433 0.110536 0.0227662 0.993611 -0.110117 0.0213482 0.993689 0.0927266 -0.0652336 0.993552 0.078183 -0.0832858 0.993454 -0.0799912 0.0816962 0.993442 0.0694768 0.0902764 0.99349 0.0355257 -0.103573 0.993987 0.0513479 0.0977678 -0.993884 0.0308289 0.105643 -0.993926 0.0713876 0.0890096 -0.993469 -0.107165 -0.0299612 0.99379 -0.0974508 -0.0489988 0.994033 -0.112165 0.0150377 0.993576 -0.101268 0.0375767 0.994149 -0.0652136 0.0918028 0.993639 -0.0411261 0.0987741 0.99426 0.0257998 -0.109268 0.993677 0.041916 0.0989069 -0.994214 0.0439093 0.0988138 0.994137 0.0225143 0.109661 0.993714 -0.00138486 0.114393 0.993435 0.0824984 0.0790961 0.993447 0.0949143 0.0579183 0.993799 -0.0940212 -0.0602696 0.993744 -0.101684 -0.0379302 0.994093 0.106259 -0.0297233 0.993894 0.113903 -0.00621837 0.993472 0.112376 0.0170986 0.993519 -0.107427 0.027483 0.993833 -0.00998776 0.113816 -0.993452 0.0308821 -0.106637 0.993818 -0.0750137 0.0857974 0.993485 0.0138412 0.112476 -0.993558 -0.0526975 0.0965555 0.993932 -0.0762978 -0.0852233 0.993436 0.0568095 0.0962866 -0.993731 -0.109709 -0.024802 0.993654 -0.0985452 -0.0422994 0.994233 0.0114402 0.113028 0.993526 -0.114386 -0.00257457 0.993433 0.0744911 0.0867116 0.993445 -0.09372 0.0632365 0.993588 -0.0988704 0.0429103 0.994175 0.0900483 0.0685002 0.993579 -0.0181859 0.112073 0.993534 -0.0371459 0.102326 0.994057 -0.059099 0.0944783 0.993771 0.114303 0.00494071 0.993434 0.0946256 -0.0612209 0.993629 0.0865154 0.0740266 0.993496 0.0968761 0.0514715 0.993965 0.106093 0.0317875 0.993848 0.102735 -0.0354966 0.994075 0.112763 -0.0126419 0.993541 0.0817262 -0.0800488 0.993435 -0.0203273 0.111408 -0.993567 0.0859775 -0.0754 0.99344 0.0674181 -0.0906524 0.993598 0.043565 -0.0983889 0.994194 0.020176 0.11055 -0.993666 -0.00376008 0.114356 -0.993433 0.0675343 0.0914577 -0.993516 0.0472705 0.0984778 -0.994016 -0.104963 -0.0335508 0.99391 0.0622308 0.0941837 -0.993608 0.0808794 0.0808681 -0.993438 -0.114159 0.00380888 0.993455 -0.11175 -0.0192622 0.99355 -0.104124 0.0333684 0.994004 -0.098332 0.0482864 0.993982 -0.0908777 0.0685093 0.993503 0.0178152 0.111349 0.993622 -0.0122717 0.113452 0.993468 -0.0326771 0.105535 0.993879 0.0344384 0.10344 0.994039 0.0547621 0.0969145 0.993785 0.0399381 0.0994597 0.99424 0.0930448 0.0625784 0.993693 0.114321 -0.00140544 0.993443 0.108811 0.0267841 0.993702 0.0982099 0.0448265 0.994156 0.110961 -0.0189983 0.993643 0.0989235 -0.0409275 0.994253 0.092016 -0.0665524 0.993531 0.0769381 -0.0843116 0.993465 -0.0145217 0.113004 -0.993488 0.0386972 -0.101031 0.99413 0.0614294 -0.0935434 0.993718 0.00260611 0.114251 -0.993448 0.0263499 0.107979 -0.993804 0.0999726 -0.0414909 0.994125 0.0527129 0.0974553 -0.993843 -0.096213 -0.0539162 0.993899 0.0850626 0.0759843 -0.993474 -0.113238 -0.0134012 0.993477 -0.113269 0.0102366 0.993512 0.0889131 -0.0583558 0.994328 0.0813291 -0.0648969 0.994572 0.0727924 -0.0698783 0.994896 -0.0695685 0.0894252 0.993561 -0.0874252 0.0735716 0.993451 -0.0277543 0.108336 0.993727 -0.00611594 0.114227 0.993436 0.0792044 0.0825656 0.993433 0.0602074 0.0950456 0.993651 0.061486 -0.0856347 0.994428 0.0541695 -0.0925539 0.994233 0.0456449 -0.0980363 0.994135 0.111047 0.0213807 0.993585 0.100366 0.0394467 0.994168 0.0986027 -0.0462577 0.994051 0.108509 -0.025208 0.993776 0.0162363 -0.103969 0.994448 0.0362311 -0.101849 0.99414 0.0262983 -0.103845 0.994246 0.0344082 -0.104376 0.993942 0.055127 -0.0958486 0.993868 0.0322872 0.104789 -0.99397 0.00903167 0.113486 -0.993499 -0.107845 -0.02871 0.993753 0.0977844 0.0473368 -0.994081 -0.0887836 -0.0706225 0.993544 -0.100247 0.0389349 0.9942 -0.111714 0.0166275 0.993601 -0.11413 -0.00728527 0.993439 -0.0954435 0.0591907 0.993674 -0.0401782 0.0996906 0.994207 -0.0637159 0.0925259 0.99367 -0.0833857 0.0783469 0.993433 0.0240584 0.109018 0.993749 0.000207388 0.114367 0.993439 -0.0224219 0.110667 0.993605 0.0452488 0.0987068 0.994087 0.0954626 0.056329 0.993838 0.0835448 0.0778747 0.993456 0.0655642 0.0925527 0.993547 0.113681 -0.00782601 0.993487 0.112748 0.0156328 0.993501 0.103776 0.0352492 0.993976 0.105432 -0.0311955 0.993937 0.0716617 -0.0881238 0.993528 0.0887902 -0.0717027 0.993466 0.0976933 -0.0516889 0.993873 -0.00844783 0.11401 -0.993444 -0.0296507 0.107338 -0.99378 0.0485843 -0.0975379 0.994045 0.0774768 0.0841864 -0.993433 -0.0919868 -0.0648413 0.993647 0.0990049 0.040892 -0.994246 -0.114391 -0.000987151 0.993435 -0.110268 -0.0234503 0.993625 -0.0987905 0.0442433 0.994124 -0.0930675 0.06457 0.993564 -0.109504 0.0229013 0.993723 -0.0575224 0.095055 0.993809 -0.0787938 0.0827625 0.99345 -0.0167336 0.112472 0.993514 -0.0360732 0.103163 0.99401 0.0300928 0.106056 0.993905 0.050666 0.0979098 0.993905 0.00662012 0.113851 0.993476 0.0874463 0.0726855 0.993514 0.0707544 0.0894413 0.993476 0.106815 0.0305767 0.993809 0.0972692 0.0498256 0.99401 0.112375 -0.0142402 0.993564 0.101766 -0.0368887 0.994124 0.113868 0.0096042 0.99345 0.0849672 -0.0765947 0.993435 0.0961735 -0.0571501 0.993723 0.0418766 -0.0985924 0.994246 0.065954 -0.0914281 0.993625 -0.00217874 0.114391 -0.993433 0.0217375 0.109967 -0.993697 -0.0244664 0.109852 -0.993647 0.0635709 0.0935604 -0.993582 0.0432425 0.0988538 -0.994162 -0.0946261 -0.0587063 0.99378 0.0819653 0.0796947 -0.993444 -0.112176 -0.0178248 0.993528 -0.113999 0.00541455 0.993466 0.102537 0.0368807 -0.994045 -0.0981048 0.049645 0.993937 -0.106658 0.0289806 0.993873 -0.0736939 0.086751 0.993501 -0.090071 0.0697977 0.993487 -0.0314873 0.106276 0.993838 -0.0107525 0.113704 0.993456 -0.0510609 0.0969781 0.993976 0.0358469 0.102496 0.994087 0.0130413 0.11267 0.993547 0.0561275 0.0965056 0.993749 0.0757006 0.0857283 0.993439 0.0984435 0.0431433 0.994207 0.109417 0.0254687 0.99367 0.0908496 0.0670541 0.993605 0.110408 -0.0205676 0.993674 0.114368 0.00336613 0.993433 0.0988969 -0.042247 0.9942 0.0940316 -0.0625666 0.993601 0.0598803 -0.094176 0.993753 0.0805777 -0.0811534 0.993439 0.00421019 0.114122 -0.993458 -0.0189046 0.11186 -0.993544 0.0278593 0.107238 -0.993843 0.0860386 0.0746865 -0.993488 0.0688327 0.0906796 -0.993499 0.0966648 0.0522895 -0.993942 -0.112942 0.011841 0.993531 -0.113519 -0.0118932 0.993465 -0.105723 -0.0323823 0.993868 -0.103207 0.0347925 0.994051 -0.0864691 0.0747953 0.993443 -0.0968159 0.0551035 0.993776 -0.0681409 0.0902518 0.993585 -0.00454773 0.114323 0.993433 -0.0264576 0.108965 0.993693 -0.0444064 0.0982721 0.994168 0.0193915 0.110827 0.993651 0.061558 0.0944808 0.993622 0.0412564 0.0989201 0.99424 0.0803272 0.0814422 0.993436 0.111524 0.0199736 0.993561 0.10125 0.0384435 0.994118 0.093705 0.0610439 0.993727 0.114223 -0.00300685 0.993451 0.107797 -0.0267287 0.993814 0.0984315 -0.0476088 0.994004 0.0912667 -0.0678601 0.993512 -0.0332613 0.105155 -0.993899 0.0535108 -0.0963296 0.99391 0.0756626 -0.0853094 0.993477 -0.0130256 0.113312 -0.993474 0.010638 0.113191 -0.993516 0.0337263 0.103899 -0.994016 0.054079 0.0971044 -0.993804 0.0980781 0.0456654 -0.99413 0.089635 0.069214 -0.993567 0.0738792 0.0871896 -0.993448 -0.108496 -0.0274325 0.993718 -0.114255 -0.00572481 0.993435 -0.111222 0.0182101 0.993629 -0.0991932 0.0402694 0.994253 -0.0621966 0.0932133 0.993702 -0.0822879 0.0794873 0.993434 -0.094908 0.0605456 0.993643 -0.0391988 0.100589 0.994156 -0.0210309 0.11117 0.993579 0.00180542 0.1143 0.993445 0.0255896 0.108335 0.993785 0.0845638 0.0766221 0.993468 0.0668805 0.0918323 0.993526 0.0465949 0.0985633 0.994039 0.0959725 0.0547243 0.993879 0.104573 0.0341242 0.993932 0.113084 0.0141492 0.993485 0.113416 -0.00943343 0.993503 0.0878895 -0.0729529 0.993455 0.0973712 -0.0530544 0.993833 0.10457 -0.0326488 0.993982 0.0702728 -0.0889996 0.99355 0.0469198 -0.0978615 0.994093 -0.0283931 0.10801 -0.993744 -0.00689616 0.114165 -0.993438 0.0595299 0.0953133 -0.993666 0.0392708 0.0999867 -0.994214 0.0170239 0.111595 -0.993608 0.0786342 0.0831145 -0.993433 0.0927011 0.063338 -0.993677 0.0999167 0.0399364 -0.994194 -0.110796 -0.0220762 0.993598 -0.108851 0.0244424 0.993758 -0.114354 0.000606432 0.99344 -0.0986744 0.0455845 0.994075 -0.0559296 0.0955936 0.993848 -0.0775645 0.0838022 0.993459 -0.0923762 0.0658943 0.993541 -0.0349707 0.103978 0.993965 0.00822796 0.113618 0.99349 -0.0152635 0.112836 0.993496 0.0315604 0.10522 0.993948 0.0883458 0.071317 0.993534 0.0720168 0.0885685 0.993463 0.0520301 0.0976164 0.993863 0.0976225 0.048169 0.994057 0.114052 0.00806127 0.993442 0.107508 0.029339 0.993771 0.0956966 -0.0585115 0.993689 0.100762 -0.0382586 0.994175 -0.0231091 0.110403 -0.993618 -0.0406563 0.0992344 -0.994233 -0.000589578 0.114385 -0.993436 0.0445779 0.0987649 -0.994112 0.0232878 0.109344 -0.993731 0.0830249 0.0784894 -0.993452 0.0649021 0.0928983 -0.993558 0.103369 0.0358005 -0.993999 -0.0951931 -0.057126 0.993818 -0.112566 -0.016368 0.993509 -0.10585 0.0304614 0.993915 -0.113797 0.00702209 0.993479 -0.0892266 0.0710715 0.993472 -0.09784 0.0510068 0.993894 -0.0494127 0.0973612 0.994022 -0.0723461 0.0876739 0.993519 -0.03027 0.106991 0.993799 0.0146391 0.112271 0.99357 -0.00921964 0.113917 0.993447 0.0574914 0.0960577 0.993714 0.0372334 0.101518 0.994137 0.0916164 0.0655847 0.993632 0.0768899 0.0847093 0.993435 0.0986369 0.0414541 0.99426 0.114393 0.00178209 0.993434 0.109992 0.0241293 0.993639 0.0988349 -0.0435762 0.994149 0.109815 -0.0221262 0.993706 0.0793966 -0.0822325 0.993446 0.0933986 -0.0639043 0.993576 0.0583131 -0.0947713 0.99379 -0.0174624 0.112277 -0.993523 -0.0366135 0.102747 -0.994033 0.0293531 0.106459 -0.993884 0.00581636 0.113952 -0.993469 0.0701173 0.0898636 -0.993483 0.0499855 0.0980421 -0.993926 0.0869845 0.0733598 -0.993505 -0.106457 -0.0311857 0.993828 0.0970775 0.0506502 -0.993987 -0.112574 0.0134423 0.993552 -0.113761 -0.0103708 0.993454 -0.0963974 0.0564683 0.99374 -0.102255 0.036196 0.994099 -0.085477 0.0759996 0.993437 -0.0427218 0.0984956 0.99422 -0.0666892 0.0910444 0.993611 -0.0251363 0.109564 0.993662 0.0425781 0.0988848 0.994188 0.0209587 0.110264 0.993681 -0.00296985 0.114378 0.993433 0.0629016 0.0938771 0.993595 0.0943282 0.0594905 0.993762 0.0814254 0.0802857 0.993441 0.102113 0.0374094 0.994069 0.107047 -0.0282339 0.993853 0.114084 -0.00461202 0.99346 0.111968 0.0185461 0.993539 0.0982232 -0.0489649 0.993959 0.0743577 -0.0862778 0.993492 0.0904789 -0.0691556 0.993494 -0.0518804 0.0967718 -0.993954 0.0122413 0.112854 -0.993536 -0.0115135 0.113583 -0.993462 -0.0320859 0.105909 -0.993858 0.035145 0.102973 -0.994063 0.075098 0.0862247 -0.993441 0.0554453 0.0967148 -0.993767 0.0904534 0.0677798 -0.993591 -0.114341 -0.00415452 0.993433 0.109118 0.0261291 -0.993685 -0.0983317 -0.0439862 0.994181 -0.11069 0.0197838 0.993658 -0.0943336 0.0618943 0.993615 -0.0989146 0.0415863 0.994227 -0.0811558 0.0806044 0.993437 -0.0196188 0.111638 0.993555 -0.0381875 0.101468 0.994106 -0.0606576 0.0938642 0.993735 0.00340743 0.114192 0.993453 0.0479471 0.0983829 0.993993 0.0271069 0.107613 0.993823 0.0681854 0.0910732 0.993507 0.105346 0.0329703 0.993889 0.0964439 0.0531042 0.993921 0.0855541 0.0753394 0.993481 0.113383 0.0126494 0.993471 0.103671 -0.0340827 0.994028 0.113111 -0.0110396 0.993521 0.0970106 -0.0544209 0.993794 -0.0452466 0.0981452 -0.994143 0.0688575 -0.0898429 0.993573 0.0869519 -0.0741855 0.993446 -0.0271094 0.108654 -0.99371 0.0186041 0.111093 -0.993636 -0.00533269 0.11428 -0.993434 0.0405992 0.0989246 -0.994266 -0.141489 -0.0763882 -0.986988 -0.0589873 0.101523 -0.993083 -0.157491 0.10321 -0.982112 -0.25502 0.103903 -0.961337 -0.171821 -0.145426 -0.974335 -0.199747 -0.195055 -0.960237 -0.349543 0.103501 -0.931186 -0.227201 -0.23345 -0.945453 0.282799 0.288728 0.914692 -0.254813 -0.26408 -0.930232 -0.44092 0.10191 -0.891742 -0.311119 -0.308269 -0.898986 -0.339838 -0.323496 -0.883097 -0.52802 0.0990479 -0.843436 -0.368966 -0.334853 -0.867028 -0.427324 -0.346822 -0.834931 -0.398165 -0.342535 -0.850961 -0.609757 0.0948586 -0.786891 -0.45647 -0.347918 -0.818894 -0.485454 -0.345735 -0.802995 -0.546799 -0.328983 -0.769923 -0.516234 -0.338605 -0.786669 -0.576916 -0.316905 -0.752821 -0.685706 0.0892779 -0.722383 -0.60635 -0.302462 -0.73543 -0.634883 -0.285754 -0.717822 -0.662391 -0.266848 -0.700022 -0.75489 0.0823005 -0.650667 -0.688903 -0.245688 -0.681946 -0.738063 -0.197087 -0.645306 -0.714202 -0.222379 -0.663674 -0.781053 -0.140822 -0.608379 -0.760339 -0.169932 -0.626903 -0.816591 0.0739509 -0.57246 -0.817061 -0.077464 -0.571324 -0.80002 -0.109928 -0.589817 -0.844952 -0.00843432 -0.534775 -0.832046 -0.0436412 -0.552988 0.855688 -0.0280137 0.516733 -0.870309 0.0642668 -0.488295 -0.915294 0.0533847 -0.399233 -0.910958 0.0545894 -0.40887 -0.951189 0.04142 -0.305815 -0.948449 0.0424959 -0.314067 -0.97594 0.0295211 -0.216031 -0.977388 0.0286443 -0.209505 0.99994 -0.00149147 0.0108199 -0.993154 0.0159124 -0.115721 0.0405992 0.0989246 -0.994266 -0.996079 -0.0120648 0.0876469 -0.999897 0.0019598 -0.0142176 -0.981727 -0.0258175 0.188534 -0.981769 -0.0257888 0.188321 -0.936031 -0.0469818 0.348766 -0.95709 -0.0389752 0.287156 -0.878172 -0.0625883 0.474233 -0.922425 -0.0513106 0.382751 -0.855688 -0.0280105 0.516733 -0.844952 0.00843504 0.534775 -0.824776 -0.0726461 0.560774 -0.832046 0.0436384 0.552988 -0.817061 0.0774659 0.571324 -0.80002 0.109927 0.589817 -0.763066 -0.081326 0.641183 -0.781053 0.140822 0.608379 -0.76034 0.169929 0.626903 -0.714202 0.222381 0.663674 -0.738063 0.197086 0.645306 -0.688902 0.24569 0.681946 -0.693343 -0.0886071 0.715139 -0.634884 0.28575 0.717822 -0.662389 0.266851 0.700022 -0.606352 0.302458 0.73543 0.576916 -0.316905 -0.752821 -0.5468 0.32898 0.769923 -0.61675 -0.0944198 0.781476 -0.516234 0.338605 0.786669 0.485455 -0.345735 -0.802995 -0.45647 0.34792 0.818894 -0.533833 -0.0988024 0.839798 -0.427322 0.346823 0.834931 -0.398164 0.342536 0.850961 -0.445446 -0.101796 0.889503 -0.368966 0.334853 0.867028 -0.339838 0.323496 0.883097 -0.31112 0.308268 0.898986 -0.352914 -0.103464 0.929918 -0.282798 0.288729 0.914692 -0.254813 0.264081 0.930232 0.227201 -0.23345 -0.945453 -0.199747 0.195056 0.960237 -0.256116 -0.103905 0.961045 -0.17182 0.145427 0.974335 -0.157201 -0.103206 0.982159 -0.141488 0.076389 0.986988 0.342184 -0.0861269 0.935677 0.245458 -0.0910206 0.965125 0.303765 -0.0881615 0.948659 0.144598 -0.0953295 0.984888 0.102331 -0.0968958 0.99002 0.579534 -0.0705858 0.811886 0.608695 -0.0682588 0.790463 0.524948 -0.0746646 0.847853 0.400109 -0.0828249 0.912717 0.492676 -0.0769211 0.866807 0.435979 -0.0806324 0.896337 0.873432 -0.0394919 0.485343 0.819339 -0.0470464 0.571376 0.858398 -0.0417392 0.511283 0.756572 -0.0544084 0.651643 0.686294 -0.0614767 0.724721 0.73457 -0.0567344 0.676157 0.974143 -0.0179331 0.225219 0.979599 -0.0159328 0.20033 0.954045 -0.0238869 0.298709 0.906771 -0.0339494 0.420255 0.945527 -0.0259969 0.324504 0.918516 -0.0317565 0.394106 -0.999998 -0.00016467 0.00207944 0.996552 0.00655444 -0.0827086 0.994562 0.00823069 -0.103817 0.995005 -0.00788897 0.099516 0.992283 -0.00980408 0.123603 0.999791 -0.00161575 0.0204026 0.91679 0.0320885 -0.398077 0.952769 0.024215 -0.30273 0.923393 0.0307986 -0.382619 0.958113 0.0228091 -0.28548 0.978754 0.0162589 -0.204394 0.982612 0.0147109 -0.185085 0.816792 0.04737 -0.574984 0.1426 0.0954067 -0.985171 0.761865 0.0538313 -0.645495 0.753822 0.0547054 -0.654798 0.244237 0.0910775 -0.965429 0.141173 0.0954617 -0.985372 0.2409 0.0912326 -0.966252 0.342849 0.0860907 -0.935437 0.338052 0.0863516 -0.937157 0.437716 0.0805233 -0.8955 0.431725 0.0808986 -0.89837 0.521314 0.0749241 -0.850069 0.605162 0.0685466 -0.793146 0.527689 0.0744678 -0.846167 0.683077 0.061777 -0.727729 0.612721 0.0679287 -0.787375 0.690878 0.0610456 -0.72039 0.800671 -0.0493648 0.597067 0.660554 -0.0638303 0.74806 0.204143 -0.0928827 0.974525 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 1 0 0 1 0 0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1.19249e-08 -1 0 0.0189364 -0.999821 0 -0.0745068 -0.997221 0 1 1.50996e-07 0 0.995734 0.0922686 0 0.995734 0.0922683 0 -0.167299 -0.985906 0 -0.0922687 -0.995734 0 -0.25863 -0.965976 0 -0.18375 -0.982973 0 -0.273663 -0.961826 0 -0.3477 -0.937606 0 -0.433732 -0.901042 0 -0.361241 -0.932472 0 -0.515975 -0.856604 0 -0.445738 -0.895163 0 -0.526432 -0.850217 0 -0.593708 -0.804681 0 -0.666253 -0.745726 0 -0.602634 -0.798017 0 -0.732976 -0.680255 0 -0.673696 -0.739009 0 -0.739009 -0.673695 0 -0.793294 -0.608839 0 -0.84668 -0.532103 0 -0.798017 -0.602635 0 -0.892667 -0.450718 0 -0.850217 -0.526432 0 -0.895163 -0.445738 0 -0.930853 -0.365393 0 -0.960906 -0.276876 0 -0.932472 -0.361242 0 -0.982561 -0.185939 0 -0.961826 -0.273663 0 -0.982973 -0.18375 0 -0.995631 -0.0933776 0 -1 -3.01992e-07 0 -0.995734 -0.0922685 0 -1 1.74846e-07 0 0.0922686 -0.995734 0 0.18375 -0.982973 0 0.112214 -0.993684 0 0.204512 -0.978864 0 0.273663 -0.961826 0 0.361242 -0.932472 0 0.295022 -0.95549 0 0.445738 -0.895163 0 0.381417 -0.924403 0 0.464575 -0.885534 0 0.526432 -0.850217 0 0.602634 -0.798017 0 0.543514 -0.8394 0 0.673696 -0.739009 0 0.617316 -0.786715 0 0.685237 -0.72832 0 0.739009 -0.673696 0 0.798017 -0.602635 0 0.747283 -0.664506 0 0.850217 -0.526432 0 0.803858 -0.594822 0 0.854581 -0.519318 0 0.895163 -0.445738 0 0.932472 -0.361242 0 0.898511 -0.438952 0 0.961826 -0.273663 0 0.934997 -0.354656 0 0.96356 -0.267491 0 0.982973 -0.18375 0 0.995734 -0.0922685 0 0.983926 -0.178575 0 1 -8.74228e-08 0 0.996028 -0.0890358 0 1 -8.74228e-08 0 0.932472 0.361242 0 0.961826 0.273663 0 0.961826 0.273663 0 0.982973 0.18375 0 0.982973 0.18375 0 0.850217 0.526432 0 0.798017 0.602635 0 0.850217 0.526432 0 0.932472 0.361242 0 0.895163 0.445738 0 0.895163 0.445738 0 0.673696 0.739009 0 0.673696 0.739009 0 0.602635 0.798017 0 0.739009 0.673696 0 0.798017 0.602635 0 0.739009 0.673696 0 0.361242 0.932472 0 0.445738 0.895163 0 0.445739 0.895163 0 0.526432 0.850217 0 0.526432 0.850217 0 0.602635 0.798017 0 0.18375 0.982973 0 0.0922683 0.995734 0 0.18375 0.982973 0 0.361242 0.932472 0 0.273663 0.961826 0 0.273663 0.961826 0 -0.0922684 0.995734 0 -0.0922684 0.995734 0 -0.18375 0.982973 0 4.37114e-08 1 0 0.0922685 0.995734 0 4.37114e-08 1 0 -0.445738 0.895163 0 -0.361242 0.932472 0 -0.361242 0.932472 0 -0.273663 0.961826 0 -0.273663 0.961826 0 -0.183749 0.982973 0 -0.602635 0.798017 0 -0.673696 0.739009 0 -0.602635 0.798017 0 -0.445738 0.895163 0 -0.526432 0.850217 0 -0.526432 0.850217 0 -0.739009 0.673696 0 -0.798017 0.602635 0 -0.739009 0.673696 0 -0.673696 0.739009 0 -0.850217 0.526432 0 -0.798017 0.602635 0 -0.850217 0.526432 0 -0.895163 0.445738 0 -0.895163 0.445738 0 -0.932472 0.361242 0 -0.961826 0.273663 0 -0.932472 0.361242 0 -0.961826 0.273663 0 -0.982973 0.18375 0 -0.982973 0.18375 0 -0.995734 0.0922684 0 -0.995734 0.0922684 0 0 0 1 -0 -0 -1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 0 0 1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 0 0 1 -0 -0 -1 -0 -0 -1 0 0 1 -0 -0 -1 -0 -0 -1 0 0 1 -0 -0 -1 0 0 1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 0 0 1 0 0 1 -0 -0 -1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 0 0 1 -0 -0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 0 0 1 -0.111965 -0.993712 0 -1.19249e-08 -1 0 -1.19249e-08 -1 0 1 1.50996e-07 0 0.993712 0.111964 0 1 -8.74228e-08 0 -0.111965 -0.993712 0 -0.222521 -0.974928 0 -0.222521 -0.974928 0 -0.330279 -0.943883 0 -0.433884 -0.900969 0 -0.330279 -0.943883 0 -0.433884 -0.900969 0 -0.532032 -0.846724 0 -0.532032 -0.846724 0 -0.62349 -0.781831 0 -0.707107 -0.707107 0 -0.62349 -0.781832 0 -0.707107 -0.707107 0 -0.781831 -0.62349 0 -0.781831 -0.62349 0 -0.846724 -0.532032 0 -0.900969 -0.433884 0 -0.846724 -0.532032 0 -0.900969 -0.433884 0 -0.943883 -0.330279 0 -0.943883 -0.330279 0 -0.974928 -0.222521 0 -0.993712 -0.111964 0 -0.974928 -0.222521 0 -0.993712 -0.111964 0 -1 1.74846e-07 0 -1 1.74846e-07 0 0.111965 -0.993712 0 0.111965 -0.993712 0 0.222521 -0.974928 0 0.330279 -0.943883 0 0.222521 -0.974928 0 0.330279 -0.943883 0 0.433883 -0.900969 0 0.433884 -0.900969 0 0.532032 -0.846724 0 0.62349 -0.781831 0 0.532032 -0.846724 0 0.62349 -0.781831 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.781831 -0.62349 0 0.846724 -0.532032 0 0.781831 -0.62349 0 0.846724 -0.532032 0 0.900969 -0.433884 0 0.900969 -0.433884 0 0.943883 -0.330279 0 0.974928 -0.222521 0 0.943883 -0.330279 0 0.974928 -0.222521 0 0.993712 -0.111964 0 0.993712 -0.111964 0 0.99212 0.125289 0 0.968605 0.248604 0 0.974928 0.222521 0 0.846724 0.532032 0 0.846724 0.532032 0 0.900969 0.433884 0 0.943883 0.330279 0 0.929826 0.368 0 0.900969 0.433884 0 0.707107 0.707107 0 0.62349 0.781832 0 0.62349 0.781832 0 0.781831 0.62349 0 0.781832 0.62349 0 0.707107 0.707107 0 0.330279 0.943883 0 0.433884 0.900969 0 0.330279 0.943883 0 0.433884 0.900969 0 0.532032 0.846724 0 0.532032 0.846724 0 4.37114e-08 1 0 -7.54979e-08 1 0 0.111964 0.993712 0 0.222521 0.974928 0 0.111964 0.993712 0 0.222521 0.974928 0 -0.222521 0.974928 0 -0.330279 0.943883 0 -0.330279 0.943883 0 -0.111964 0.993712 0 -0.111964 0.993712 0 -0.222521 0.974928 0 -0.62349 0.781832 0 -0.532032 0.846724 0 -0.62349 0.781832 0 -0.532032 0.846724 0 -0.433884 0.900969 0 -0.433884 0.900969 0 -0.781831 0.62349 0 -0.707107 0.707107 0 -0.781831 0.62349 0 -0.707107 0.707107 0 -0.846724 0.532032 0 -0.846724 0.532032 0 -0.900969 0.433884 0 -0.900969 0.433884 0 -0.943883 0.330279 0 -0.943883 0.330279 0 -0.974928 0.222521 0 -0.974928 0.222521 0 -0.993712 0.111964 0 -0.993712 0.111964 0 1 -8.74228e-08 0 0.993712 0.111964 0 1 -8.74228e-08 0 0.929826 0.368 0 0.974928 0.222521 0 0.968605 0.248603 0 0.99212 0.125289 0 0.943883 0.330279 0 0.961486 -0.274854 0 0.982821 -0.18456 0 0.975917 -0.218143 0 1 1.49255e-07 0 0.999507 -0.0314106 0 0.995696 -0.0926792 0 0.998027 0.0627907 0 1 -3.27582e-07 0 0.998027 0.0627902 0 0.894242 -0.447584 0 0.876307 -0.481754 0 0.848911 -0.528535 0 0.917755 -0.397148 0 0.931875 -0.36278 0 0.951057 -0.309017 0 0.637424 -0.770513 0 0.670947 -0.741505 0 0.707107 -0.707107 0 0.770513 -0.637424 0 0.736781 -0.676131 0 0.796274 -0.604937 0 0.441301 -0.897359 0 0.397148 -0.917755 0 0.356235 -0.934396 0 0.522568 -0.852597 0 0.562083 -0.827081 0 0.481754 -0.876307 0 0.0314108 -0.999507 0 0.0856935 -0.996322 0 0.125333 -0.992115 0 0.218143 -0.975917 0 0.268102 -0.96339 0 0.309017 -0.951056 0 -0.156435 -0.987688 0 -0.24869 -0.968583 0 -0.19145 -0.981502 0 -0.00701375 -0.999975 0 -0.0627906 -0.998027 0 -0.0996606 -0.995021 0 -0.534476 -0.845183 0 -0.453845 -0.891081 0 -0.509042 -0.860742 0 -0.425779 -0.904827 0 -0.369307 -0.929307 0 -0.338738 -0.940881 0 -0.728969 -0.684547 0 -0.790155 -0.612907 0 -0.746193 -0.665729 0 -0.610507 -0.792011 0 -0.661312 -0.750111 0 -0.681282 -0.732021 0 -0.936872 -0.349672 0 -0.900432 -0.434996 0 -0.929776 -0.368125 0 -0.856242 -0.516575 0 -0.804681 -0.593708 0 -0.844328 -0.535827 0 -0.995562 -0.0941082 0 -1 -6.18325e-08 0 -0.996898 -0.0787031 0 -0.960294 -0.278991 0 -0.982287 -0.187381 0 -0.965247 -0.261339 0 -0.980136 0.198329 0 -0.982642 0.185511 0 -0.961087 0.276247 0 -0.994298 0.106637 0 -0.999902 0.0140276 0 -0.995651 0.0931605 0 -0.847375 0.530995 0 -0.841414 0.540391 0 -0.887875 0.460084 0 -0.931172 0.364581 0 -0.893157 0.449744 0 -0.926694 0.375816 0 -0.660479 0.750844 0 -0.667714 0.744417 0 -0.59546 0.803385 0 -0.727224 0.6864 0 -0.787709 0.616047 0 -0.734161 0.678975 0 -0.350356 0.936617 0 -0.343093 0.939301 0 -0.42867 0.903461 0 -0.518027 0.855364 0 -0.510557 0.859844 0 -0.588049 0.808825 0 -0.170522 0.985354 0 -0.254563 0.967056 0 -0.261577 0.965183 0 -0.163841 0.986487 0 -0.0779845 0.996955 0 0.0152314 0.999884 0 -0.0717089 0.997426 0 0.290854 0.956767 0 -0.378722 -0.92551 -0 0.200456 0.979703 0 0.205199 0.97872 0 0.113608 0.993526 0 0.463296 0.886204 0 0.468255 0.883593 0 -0.383329 -0.923612 -0 0.54384 0.839189 0 0.548706 0.836015 0 -0.941844 -0.336049 -0 0.969055 0.246845 0 -0.94216 -0.335162 -0 0.619654 0.784875 0 0.623723 0.781645 0 0.906442 0.422331 0 -0.906557 -0.422083 -0 0.863155 0.504939 0 -0.692528 -0.721391 -0 0.690079 0.723734 0 -0.863055 -0.505111 -0 -0.754501 -0.656298 -0 -0.812361 -0.583155 -0 -0.755166 -0.655533 -0 -0.812314 -0.583221 -0 0.969395 0.245508 0 0.988022 0.154314 0 0.987837 0.155494 0 0.108315 0.994117 0 0.0210403 0.999779 0 -0.436088 0.899904 0 -0.794222 0.607628 0 -0.957536 0.288313 0 -0.985313 -0.170756 0 -0.891007 -0.453991 0 -0.587785 -0.809017 0 -0.28159 -0.959535 0 0.177663 -0.984091 0 0.599337 -0.800497 0 0.82708 -0.562083 0 0.992115 -0.125333 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 - - - - - - - - - - - - - - -

0 2 1 3 5 4 2 7 6 8 5 7 2 10 9 5 3 7 2 12 11 2 14 13 2 16 15 14 2 15 2 18 17 16 2 17 2 20 19 18 2 19 2 21 20 22 23 2 2 23 21 24 25 2 2 25 22 2 26 24 9 27 2 2 27 26 10 2 11 0 12 2 28 29 2 1 2 29 30 31 2 2 31 28 32 33 2 2 33 30 6 34 2 2 34 32 35 36 7 6 7 36 7 37 35 38 7 39 38 37 7 40 7 41 40 39 7 42 7 43 42 41 7 7 3 44 44 43 7 3 46 45 44 3 45 3 48 47 46 3 47 49 50 3 48 3 50 51 53 52 54 55 53 53 57 56 56 58 53 53 59 57 53 61 60 58 61 53 53 63 62 60 63 53 53 65 64 62 65 53 53 66 52 64 66 53 67 68 53 53 51 67 69 70 53 69 53 68 71 53 70 53 73 72 71 73 53 53 75 74 72 75 53 53 77 76 74 77 53 53 79 78 76 79 53 80 53 55 78 54 53 81 82 53 81 53 80 83 84 53 83 53 82 85 86 53 85 53 84 87 88 53 87 53 86 89 90 53 89 53 88 91 53 90 53 93 92 91 93 53 53 95 94 92 95 53 53 97 96 94 97 53 53 99 98 96 99 53 53 101 100 98 101 53 53 103 102 100 103 53 53 102 104 105 107 106 108 105 106 109 111 110 106 113 112 106 112 114 112 116 115 117 118 114 114 115 117 119 115 116 120 117 115 121 122 118 115 114 112 117 121 118 123 122 121 114 118 124 114 108 106 125 127 126 128 130 129 131 133 132 134 127 135 136 138 137 139 141 140 142 144 143 145 132 146 133 147 132 148 143 144 149 150 135 148 151 143 127 153 152 154 134 135 155 156 143 155 143 157 156 158 143 159 129 130 160 162 161 163 165 164 143 167 166 142 169 168 156 171 170 151 148 172 173 143 174 175 177 176 178 180 179 181 183 182 184 186 185 143 151 187 188 190 189 132 191 131 147 192 149 145 146 193 169 142 143 137 138 146 137 194 136 140 141 137 195 169 143 196 197 140 195 143 161 198 199 196 196 199 197 200 192 147 163 161 143 201 150 149 149 202 201 152 126 127 187 157 143 130 125 203 204 203 125 205 206 128 207 159 130 143 158 208 206 165 128 165 210 209 211 143 208 209 164 165 212 161 163 213 212 163 161 214 160 215 143 211 162 195 161 216 217 195 143 215 218 176 143 218 195 217 169 176 219 143 168 169 220 142 222 221 142 223 144 221 223 142 224 144 225 219 167 143 226 227 148 224 148 144 172 148 227 228 229 151 166 230 143 231 143 230 151 229 187 232 187 233 233 187 234 187 232 157 235 236 157 143 231 237 238 143 237 157 236 155 239 155 240 240 155 241 155 239 156 170 158 156 143 238 242 243 158 244 242 245 143 158 246 208 243 246 158 245 247 143 208 248 211 208 249 248 250 211 251 247 252 143 211 253 215 250 253 211 252 254 143 215 255 218 215 256 255 254 257 143 218 259 258 218 260 259 143 257 261 258 176 218 261 262 143 176 177 219 263 264 219 265 167 219 265 219 264 167 267 266 268 143 262 269 143 268 166 167 266 270 271 166 272 230 166 272 166 271 230 274 273 275 143 276 275 277 143 231 230 273 278 279 231 269 276 143 237 231 279 238 281 280 282 143 277 282 174 143 242 238 280 283 284 242 173 285 143 245 242 284 252 247 286 247 287 286 288 289 252 143 285 290 252 289 254 143 290 291 143 291 292 261 257 293 293 257 294 295 296 261 143 292 297 261 296 262 143 297 298 298 299 143 269 268 300 300 268 301 302 303 269 182 304 143 269 303 276 299 182 143 305 182 299 277 275 306 306 275 307 308 309 277 183 310 182 277 309 282 311 183 312 310 183 311 173 174 313 313 174 314 315 316 173 305 181 182 173 316 285 290 318 317 319 321 320 321 183 181 317 291 290 291 322 292 291 323 322 319 183 321 292 324 297 292 325 324 326 328 327 321 181 326 298 329 299 298 330 329 326 327 321 299 331 305 299 332 331 181 333 326 326 333 143 181 334 333 181 335 334 143 333 336 333 337 336 333 338 337 143 336 339 184 143 339 339 341 340 339 342 341 340 184 339 340 344 343 340 345 344 343 184 340 346 184 343 346 348 347 346 349 348 347 184 346 347 351 350 347 352 351 350 184 347 353 184 350 353 355 354 353 356 355 354 184 353 354 358 357 354 359 358 357 184 354 178 184 357 360 184 178 178 179 360 361 362 360 363 184 364 364 360 362 360 364 184 365 366 363 367 365 363 366 369 368 184 363 366 370 184 371 371 366 368 366 371 184 372 373 370 374 372 370 373 376 375 184 370 373 377 184 378 378 373 375 373 378 184 379 380 377 381 379 377 380 383 382 184 377 380 384 184 385 385 380 382 380 385 184 386 387 384 388 386 384 387 390 389 184 384 387 391 184 392 392 387 389 387 392 184 393 394 391 395 393 391 394 397 396 184 391 394 398 184 399 399 394 396 394 399 184 400 401 398 402 400 398 401 404 403 184 398 401 405 406 401 405 401 403 184 401 406 407 408 406 409 407 406 408 411 410 184 406 408 412 413 408 412 408 410 184 408 413 414 186 413 415 414 413 186 417 416 184 413 186 418 185 186 418 186 416 185 420 419 184 185 421 185 419 421 422 421 423 423 421 424 184 421 425 421 422 425 426 425 427 184 425 428 425 426 428 429 428 430 430 428 431 184 428 432 428 429 432 433 432 434 184 432 435 432 433 435 436 435 437 437 435 438 439 440 436 435 436 184 436 440 441 184 436 442 436 441 442 443 442 444 444 442 445 446 447 443 442 443 184 443 447 448 184 443 449 443 448 449 450 449 451 451 449 452 453 454 450 449 450 184 450 454 455 184 450 456 450 455 456 457 456 458 458 456 459 460 461 457 456 457 184 457 461 462 184 457 463 457 462 463 464 463 465 465 463 466 467 468 464 463 464 184 464 468 469 184 464 470 464 469 470 471 470 472 472 470 473 474 475 471 470 471 184 471 475 476 184 471 477 471 476 477 478 477 479 479 477 480 481 482 478 477 478 184 478 482 483 184 478 484 478 483 484 485 484 486 184 484 487 484 485 487 488 487 489 489 487 490 184 487 491 487 488 491 492 491 493 184 491 494 491 492 494 495 494 496 496 494 497 184 494 498 494 495 498 499 498 500 184 498 190 498 499 190 189 190 501 501 190 502 503 188 504 184 190 188 503 505 188 506 505 507 505 184 188 505 509 508 506 509 505 510 508 511 508 184 505 510 512 508 513 512 514 512 184 508 512 516 515 513 516 512 517 515 518 515 184 512 517 519 515 520 519 521 519 184 515 519 523 522 520 523 519 524 522 525 522 184 519 524 526 522 527 526 528 526 184 522 526 530 529 527 530 526 531 529 532 529 184 526 531 533 529 534 533 535 533 184 529 533 537 536 534 537 533 538 536 539 536 184 533 538 540 536 541 540 542 540 184 536 540 544 543 541 544 540 545 543 546 543 184 540 545 547 543 548 547 549 547 184 543 547 550 184 548 550 547 550 552 551 550 553 552 551 554 550 555 554 556 554 184 550 554 557 184 555 557 554 557 559 558 557 560 559 558 561 557 562 561 563 561 184 557 561 564 184 562 564 561 564 566 565 564 567 566 565 568 564 569 568 570 568 184 564 568 571 184 569 571 568 571 573 572 571 574 573 572 575 571 576 575 577 575 184 571 575 578 184 576 578 575 578 580 579 578 581 580 579 582 578 583 582 584 582 184 578 582 585 184 583 585 582 585 587 586 585 588 587 586 589 585 590 589 591 589 184 585 589 592 184 590 592 589 592 594 593 592 595 594 593 596 592 597 596 598 596 184 592 597 599 596 163 143 165 599 184 596 600 602 601 143 600 601 602 604 603 604 602 600 604 605 603 606 603 607 605 607 603 608 606 609 606 607 609 608 611 610 610 606 608 612 610 611 610 614 613 614 610 612 613 616 615 614 616 613 617 613 618 615 618 613 617 618 619 620 617 621 617 619 621 622 623 617 617 620 622 624 625 623 624 623 622 626 623 625 623 628 627 628 623 626 627 630 629 628 630 627 627 632 631 629 632 627 627 631 633 634 633 635 633 631 635 636 633 637 633 634 637 638 639 633 633 636 638 143 639 638 639 641 640 641 639 143 642 640 643 641 643 640 644 645 642 642 643 644 646 645 647 644 647 645 143 130 128 165 143 128 127 125 143 143 125 130 135 143 149 135 127 143 149 143 147 132 143 146 132 147 143 143 140 137 146 143 137 648 196 143 143 196 140 601 648 143 649 646 650 646 647 650 649 652 651 651 646 649 651 654 653 654 651 652 653 656 655 654 656 653 655 657 118 653 655 118 657 659 658 659 657 655 659 661 660 658 659 660 662 659 663 659 662 661 663 665 664 662 663 664 666 667 663 663 667 665 663 669 668 668 666 663 670 671 669 669 671 668 672 669 673 672 670 669 674 673 675 669 675 673 676 675 677 676 674 675 678 677 679 675 679 677 680 679 681 680 678 679 682 683 679 681 679 683 684 682 685 684 683 682 686 687 682 685 682 687 688 686 689 688 687 686 690 689 691 686 691 689 691 693 692 692 690 691 694 693 124 693 694 692 694 124 118 695 697 696 698 699 114 700 702 701 703 705 704 706 708 707 709 711 710 712 714 713 715 717 716 718 720 719 721 723 722 724 726 725 727 729 728 730 109 110 111 724 110 168 731 142 732 730 733 731 340 341 247 731 287 432 429 731 731 392 389 496 731 495 467 464 731 731 540 538 517 731 519 571 569 731 731 557 555 589 731 591 582 579 731 599 597 731 593 731 596 598 596 731 598 731 597 595 731 594 593 594 731 590 731 592 731 595 592 589 586 731 731 590 591 731 587 588 586 587 731 731 585 583 588 585 731 731 584 582 583 584 731 580 581 731 731 579 580 578 576 731 578 731 581 577 575 731 577 731 576 572 573 731 572 731 575 574 571 731 574 731 573 568 731 570 569 570 731 566 731 565 731 568 565 564 731 567 731 566 567 563 731 562 731 564 562 558 731 561 731 563 561 560 731 559 731 558 559 555 556 731 731 560 557 731 554 551 556 554 731 731 552 553 551 552 731 731 550 548 553 550 731 731 549 547 548 549 731 731 545 546 547 545 731 731 543 544 546 543 731 731 541 542 544 541 731 539 731 538 542 540 731 536 537 731 536 731 539 534 535 731 534 731 537 533 531 731 533 731 535 532 529 731 532 731 531 530 527 731 530 731 529 528 526 731 528 731 527 524 525 731 524 731 526 522 523 731 522 731 525 520 521 731 520 731 523 731 517 518 519 731 521 516 731 515 731 518 515 514 731 513 731 516 513 510 731 512 731 514 512 508 731 511 731 510 511 506 731 509 731 508 509 505 731 507 731 506 507 504 731 503 731 505 503 189 731 188 731 504 188 502 731 501 731 189 501 499 731 190 731 502 190 498 731 500 731 499 500 496 497 731 731 498 495 731 494 492 497 494 731 731 493 491 492 493 731 731 488 489 491 488 731 731 490 487 489 490 731 731 485 486 487 485 731 731 484 483 486 484 731 731 482 481 483 482 731 731 478 479 481 478 731 731 480 477 479 480 731 731 476 475 477 476 731 731 474 471 475 474 731 731 472 473 471 472 731 731 470 469 473 470 731 731 468 467 469 468 731 465 466 731 731 464 465 463 462 731 463 731 466 461 460 731 461 731 462 457 458 731 457 731 460 459 456 731 459 731 458 455 454 731 455 731 456 453 450 731 453 731 454 451 452 731 451 731 450 449 448 731 449 731 452 447 446 731 447 731 448 443 444 731 443 731 446 445 442 731 445 731 444 441 440 731 441 731 442 439 436 731 439 731 440 437 438 731 437 731 436 435 433 731 435 731 438 434 432 731 434 731 433 431 731 430 429 430 731 426 731 428 731 431 428 425 731 427 731 426 427 423 731 422 731 425 422 421 731 424 731 423 424 420 731 419 731 421 419 418 731 185 731 420 185 417 731 416 731 418 416 414 731 186 731 417 186 413 731 415 731 414 415 410 731 412 731 413 412 408 731 411 731 410 411 409 731 407 731 408 407 405 731 406 731 409 406 404 731 403 731 405 403 400 731 401 731 404 401 398 731 402 731 400 402 396 731 399 731 398 399 394 731 397 731 396 397 395 731 393 731 394 393 392 731 391 731 395 391 731 390 387 390 731 389 731 386 388 387 386 731 731 384 385 388 384 731 731 382 383 385 382 731 731 380 379 383 380 731 731 381 377 379 381 731 731 378 375 377 378 731 731 376 373 375 376 731 731 372 374 373 372 731 731 370 371 374 370 731 731 368 369 371 368 731 731 366 365 369 366 731 731 367 363 365 367 731 731 364 362 363 364 731 731 361 360 362 361 731 731 179 180 360 179 731 731 178 357 180 178 731 731 358 359 357 358 731 731 354 355 359 354 731 731 356 353 355 356 731 731 350 351 353 350 731 731 352 347 351 352 731 731 348 349 347 348 731 731 346 343 349 346 731 731 344 345 343 344 731 342 731 341 345 340 731 339 336 731 339 731 342 337 338 731 337 731 336 333 334 731 333 731 338 335 181 731 335 731 334 305 331 731 305 731 181 332 299 731 332 731 331 329 330 731 329 731 299 298 297 731 298 731 330 324 325 731 324 731 297 292 322 731 292 731 325 323 291 731 323 731 322 317 318 731 317 731 291 290 285 731 290 731 318 316 315 731 316 731 285 173 313 731 173 731 315 314 174 731 314 731 313 282 309 731 282 731 174 308 277 731 308 731 309 306 307 731 306 731 277 275 276 731 275 731 307 303 302 731 303 731 276 269 300 731 269 731 302 301 268 731 301 731 300 262 296 731 262 731 268 295 261 731 295 731 296 293 294 731 293 731 261 257 254 731 257 731 294 289 288 731 289 731 254 252 286 731 252 731 288 731 247 245 287 731 286 283 731 284 731 245 284 280 731 242 731 283 242 238 731 281 731 280 281 279 731 237 731 238 237 231 731 278 731 279 278 274 731 273 731 231 273 272 731 230 731 274 230 270 731 271 731 272 271 266 731 166 731 270 166 167 731 267 731 266 267 264 731 265 731 167 265 219 731 263 731 264 263 175 731 177 731 219 177 258 731 176 731 175 176 260 731 259 731 258 259 255 731 218 731 260 218 215 731 256 731 255 256 250 731 253 731 215 253 211 731 251 731 250 251 249 731 248 731 211 248 246 731 208 731 249 208 244 731 243 731 246 243 170 731 158 731 244 158 156 731 171 731 170 171 240 731 239 731 156 239 155 731 241 731 240 241 235 731 236 731 155 236 232 731 157 731 235 157 234 731 233 731 232 233 229 731 187 731 234 187 151 731 228 731 229 228 227 731 172 731 151 172 148 731 226 731 227 226 225 731 224 731 148 224 223 731 144 731 225 144 222 731 221 731 223 221 168 220 731 731 222 142 731 169 217 220 169 731 731 216 195 217 216 731 731 162 160 195 162 731 731 214 161 160 214 731 731 212 213 161 212 731 731 163 164 213 163 731 731 209 210 164 209 731 731 165 206 210 165 731 731 205 128 206 205 731 731 129 159 128 129 731 731 207 130 159 207 731 731 203 204 130 203 731 731 125 126 204 125 731 731 152 153 126 152 731 731 127 134 153 127 731 731 154 135 134 154 731 731 150 201 135 150 731 731 202 149 201 202 731 731 192 200 149 192 731 731 147 133 200 147 731 731 131 191 133 131 731 731 132 145 191 132 731 731 193 146 145 193 731 731 138 136 146 138 731 731 194 137 136 194 731 731 141 139 137 141 731 731 140 197 139 140 731 731 199 198 197 199 731 731 196 648 198 196 731 734 735 731 731 735 599 734 737 736 736 735 734 738 737 739 737 738 736 739 741 740 738 739 740 741 743 742 743 741 739 744 742 745 743 745 742 746 733 744 744 745 746 746 732 733 727 728 725 109 730 732 725 726 727 724 111 726 729 719 720 728 729 720 712 716 714 723 718 719 721 722 713 718 723 721 713 722 712 714 716 717 747 707 708 717 715 706 708 706 715 709 747 711 747 709 707 701 710 748 748 710 711 702 700 704 701 748 700 695 705 703 705 702 704 749 696 697 697 695 703 698 749 699 749 698 696 699 108 114 750 752 751 753 752 754 752 750 754 755 756 754 753 754 756 757 759 758 757 760 759 761 763 762 761 765 764 765 761 762 762 767 766 763 767 762 768 770 769 768 769 771 772 774 773 775 774 772 773 776 772 777 779 778 780 782 781 779 784 783 784 779 777 785 783 786 784 786 783 787 788 785 785 786 787 788 790 789 790 788 787 791 789 792 790 792 789 793 794 791 791 792 793 794 796 795 796 794 793 797 795 798 796 798 795 799 800 797 797 798 799 800 802 801 802 800 799 803 801 804 802 804 801 805 806 803 803 804 805 806 808 807 808 806 805 809 807 810 808 810 807 811 812 809 809 810 811 812 814 813 814 812 811 814 815 813 778 816 777 817 816 818 778 818 816 819 820 817 817 818 819 820 822 821 822 820 819 823 821 824 822 824 821 825 826 823 823 824 825 826 828 827 828 826 825 829 827 830 828 830 827 831 832 829 829 830 831 832 834 833 834 832 831 835 833 836 834 836 833 837 838 835 835 836 837 838 840 839 840 838 837 841 839 842 840 842 839 843 844 841 841 842 843 844 846 845 846 844 843 847 845 848 846 848 845 849 782 780 847 848 780 850 852 851 781 854 853 855 857 856 858 860 859 861 863 862 864 866 865 867 869 868 870 872 871 873 875 874 876 878 877 879 881 880 882 884 883 885 887 886 888 890 889 891 893 892 894 896 895 897 899 898 899 897 900 901 902 898 897 898 902 901 904 903 903 902 901 905 904 906 904 905 903 907 908 906 905 906 908 907 910 909 909 908 907 911 910 912 910 911 909 813 913 912 911 912 913 815 913 813 892 900 891 892 899 900 895 896 893 895 893 891 894 887 885 894 885 896 886 888 889 887 888 886 881 890 880 889 890 881 882 879 884 879 880 884 873 874 883 874 882 883 877 878 875 877 875 873 876 869 867 876 867 878 868 870 871 869 870 868 863 872 862 871 872 863 864 861 866 861 862 866 855 856 865 856 864 865 859 860 857 859 857 855 858 852 850 858 850 860 851 853 854 852 853 851 781 847 780 854 781 782 914 916 915 917 919 918 917 921 920 922 924 923 925 927 926 923 928 922 929 931 930 930 931 922 924 922 931 932 934 933 935 937 936 938 925 939 940 941 934 939 941 940 926 943 942 944 946 945 942 946 947 935 949 948 950 944 945 951 953 952 954 950 955 918 957 956 921 959 958 960 962 961 963 960 961 964 966 965 967 962 968 969 971 970 972 974 973 975 977 976 978 980 979 981 983 982 984 985 929 929 985 986 987 989 988 990 992 991 993 994 975 965 974 995 973 971 996 963 997 956 967 998 964 951 954 999 958 959 952 928 923 1000 1001 949 1002 1003 928 1000 1004 1001 1002 928 1006 1005 1006 928 1003 1007 1005 1008 1005 1006 1008 1009 1007 1010 1007 1009 1005 1010 1011 1009 1004 1013 1012 972 973 996 1014 1015 1012 1016 1018 1017 1019 1018 1020 1018 1016 1020 915 1019 1021 1014 1023 1022 916 1019 915 1024 1023 1025 1026 1028 1027 1026 1027 1025 1028 1030 1029 916 914 1031 1029 1033 1032 916 1035 1034 1036 1034 1037 1034 1035 1037 1038 1036 1039 1036 1038 1034 1038 1041 1040 1042 1044 1043 1039 1041 1038 1045 1042 1046 1044 1040 1043 1047 1048 1045 1042 1045 1044 929 1050 1049 1048 1051 1045 989 987 979 936 1052 932 1017 1018 1009 1011 1017 1009 1020 1021 1019 1031 1035 916 1050 1033 1051 1049 1051 1048 1047 1045 1046 1040 1044 1038 1049 1050 1051 1050 1032 1033 1029 1030 1033 1028 1026 1030 1027 1024 1025 1024 1022 1023 1022 1015 1014 1012 1013 1014 1004 1002 1013 1001 948 949 948 937 935 937 1052 936 932 933 936 934 941 933 940 938 939 938 927 925 927 943 926 942 947 926 946 944 947 945 955 950 955 999 954 999 953 951 952 959 951 958 920 921 920 919 917 919 957 918 956 997 918 963 961 997 960 968 962 968 998 967 998 966 964 965 995 964 974 972 995 996 971 969 969 970 991 992 977 991 970 990 991 993 975 976 976 977 992 981 994 993 982 983 988 982 994 981 980 978 984 982 988 989 987 978 979 1053 980 929 984 929 980 930 1053 929 1054 1056 1055 1057 1059 1058 1054 1061 1060 1060 1056 1054 1062 1061 1063 1061 1062 1060 1064 1065 1063 1062 1063 1065 1064 1067 1066 1066 1065 1064 1068 1067 1069 1067 1068 1066 1070 1071 1069 1068 1069 1071 1070 1073 1072 1072 1071 1070 1074 1073 1075 1073 1074 1072 1076 1077 1075 1074 1075 1077 1076 1079 1078 1078 1077 1076 1080 1079 1081 1079 1080 1078 1082 1083 1081 1080 1081 1083 1082 1085 1084 1084 1083 1082 1085 1086 1084 1087 1055 1056 1088 1087 1089 1087 1088 1055 1090 1091 1089 1088 1089 1091 1090 1093 1092 1092 1091 1090 1094 1093 1095 1093 1094 1092 1096 1097 1095 1094 1095 1097 1096 1099 1098 1098 1097 1096 1100 1099 1101 1099 1100 1098 1102 1103 1101 1100 1101 1103 1102 1105 1104 1104 1103 1102 1106 1105 1107 1105 1106 1104 1108 1109 1107 1106 1107 1109 1108 1111 1110 1110 1109 1108 1112 1111 1059 1111 1112 1110 1113 1115 1114 1059 1057 1112 1116 1118 1117 1119 1121 1120 1122 1124 1123 1125 1127 1126 1128 1130 1129 1131 1133 1132 1134 1136 1135 1137 1139 1138 1140 1142 1141 1143 1145 1144 1146 1148 1147 1149 1151 1150 1152 1154 1153 1153 1155 1152 1154 1157 1156 1157 1154 1152 1158 1156 1159 1157 1159 1156 1160 1161 1158 1158 1159 1160 1161 1163 1162 1163 1161 1160 1164 1162 1165 1163 1165 1162 1086 1085 1164 1164 1165 1086 1148 1146 1155 1153 1148 1155 1149 1147 1151 1146 1147 1149 1142 1150 1141 1150 1151 1141 1144 1145 1140 1145 1142 1140 1134 1135 1143 1134 1143 1144 1136 1137 1138 1136 1138 1135 1139 1130 1128 1137 1130 1139 1131 1129 1133 1128 1129 1131 1124 1132 1123 1132 1133 1123 1126 1127 1122 1127 1124 1122 1116 1117 1125 1116 1125 1126 1118 1121 1117 1114 1115 1119 1114 1119 1120 1166 1168 1167 1113 1058 1115 1121 1118 1120 1118 1169 1120 1170 1172 1171 1167 1168 1172 1057 1058 1113 1166 1112 1168 1112 1057 1168 1170 1167 1172 1173 1170 1171 1118 1173 1169 1171 1169 1173 1174 1176 1175 1177 1179 1178 1180 1181 1178 1182 1181 1180 1183 1185 1184 1186 1188 1187 1189 1191 1190 1192 1194 1193 1195 1197 1196 1198 1200 1199 1201 1203 1202 1204 1206 1205 1207 1209 1208 1210 1212 1211 1213 1215 1214 1216 1218 1217 1219 1221 1220 1222 1224 1223 1225 1227 1226 1228 1230 1229 1231 1233 1232 1234 1236 1235 1237 1239 1238 1240 1242 1241 1243 1245 1244 1246 1248 1247 1249 1251 1250 1252 1254 1253 1255 1257 1256 1258 1260 1259 1261 1263 1262 1256 1262 1263 1264 1265 1261 1261 1262 1264 1265 1267 1266 1267 1265 1264 1268 1182 1269 1270 1272 1271 1273 1275 1274 1275 1273 1269 1276 1274 1277 1273 1274 1276 1278 1280 1279 1281 1277 1282 1283 1284 1278 1284 1280 1278 1285 1284 1283 1286 1287 1282 1285 1288 1284 1289 1287 1286 1285 1290 1288 1291 1292 1290 1289 1291 1290 1292 1288 1290 1277 1281 1276 1291 1289 1286 1293 1279 1280 1287 1281 1282 1294 1295 1293 1279 1293 1295 1275 1269 1182 1180 1295 1294 1182 1268 1271 1180 1294 1182 1272 1270 1296 1271 1268 1270 1296 1266 1297 1297 1272 1296 1256 1263 1255 1266 1267 1297 1257 1255 1298 1259 1298 1258 1298 1259 1257 1249 1260 1251 1251 1260 1258 1254 1252 1250 1250 1252 1249 1299 1244 1253 1254 1299 1253 1247 1245 1243 1243 1244 1299 1246 1300 1248 1247 1248 1245 1237 1300 1239 1246 1239 1300 1242 1240 1238 1238 1240 1237 1232 1233 1241 1242 1232 1241 1231 1235 1301 1233 1231 1301 1234 1225 1236 1235 1236 1301 1227 1302 1226 1234 1227 1225 1230 1228 1302 1226 1302 1228 1220 1221 1229 1230 1220 1229 1219 1223 1224 1221 1219 1224 1222 1223 1303 1213 1303 1215 1303 1213 1222 1217 1214 1216 1216 1214 1215 1208 1304 1218 1218 1304 1217 1212 1209 1207 1209 1304 1208 1201 1210 1211 1211 1212 1207 1203 1305 1202 1201 1202 1210 1205 1305 1204 1203 1204 1305 1196 1197 1206 1206 1197 1205 1200 1198 1195 1196 1200 1195 1199 1189 1306 1198 1199 1306 1191 1193 1190 1189 1190 1306 1192 1307 1194 1191 1192 1193 1184 1185 1307 1194 1307 1185 1186 1187 1183 1184 1186 1183 1188 1176 1174 1187 1188 1174 1175 1308 1179 1175 1176 1308 1177 1178 1181 1308 1178 1179 1309 1311 1310 1312 1314 1313 1315 1316 1309 1309 1310 1315 1316 1318 1317 1318 1316 1315 1319 1317 1320 1318 1320 1317 1321 1322 1319 1319 1320 1321 1323 1322 1321 1324 1325 1323 1322 1323 1325 1324 1327 1326 1326 1325 1324 1328 1327 1329 1327 1328 1326 1330 1332 1331 1333 1334 1329 1335 1337 1336 1338 1340 1339 1341 1343 1342 1344 1341 1345 1346 1348 1347 1349 1351 1350 1352 1313 1353 1312 1354 1314 1355 1357 1356 1358 1360 1359 1361 1363 1362 1364 1366 1365 1367 1369 1368 1370 1372 1371 1373 1375 1374 1374 1375 1367 1371 1368 1369 1368 1374 1367 1363 1372 1370 1370 1371 1369 1362 1364 1361 1363 1361 1372 1366 1356 1365 1362 1366 1364 1357 1355 1360 1365 1356 1357 1358 1359 1352 1360 1355 1359 1314 1353 1313 1353 1358 1352 1312 1348 1354 1349 1346 1347 1346 1354 1348 1342 1350 1351 1351 1349 1347 1341 1344 1343 1342 1343 1350 1336 1344 1345 1339 1337 1335 1336 1345 1335 1332 1340 1338 1338 1339 1335 1331 1333 1330 1332 1330 1340 1329 1334 1328 1331 1334 1333 1376 1378 1377 1379 1381 1380 1382 1384 1383 1385 1386 1381 1384 1388 1387 1385 1390 1389 1387 1388 1391 1392 1393 1390 1391 1394 1387 1395 1396 1393 1394 1391 1397 1398 1400 1399 1383 1384 1387 1401 1398 1402 1403 1382 1383 1404 1402 1405 1403 1383 1406 1383 1377 1406 1380 1407 1379 1377 1408 1376 1377 1378 1406 1407 1410 1409 1376 1408 1411 1412 1414 1413 1415 1417 1416 1418 1420 1419 1421 1423 1422 1424 1426 1425 1427 1429 1428 1430 1431 1425 1432 1434 1433 1435 1437 1436 1438 1440 1439 1439 1435 1438 1438 1435 1436 1439 1440 1441 1428 1439 1441 1442 1437 1435 1443 1431 1444 1445 1432 1446 1445 1422 1423 1443 1444 1442 1428 1429 1416 1425 1426 1447 1431 1443 1425 1448 1449 1421 1428 1416 1417 1450 1451 1448 1452 1453 1397 1454 1450 1410 1417 1418 1419 1420 1455 1419 1456 1458 1457 1459 1411 1408 1460 1462 1461 1463 1464 1405 1460 1464 1462 1465 1457 1466 1461 1465 1467 1468 1470 1469 1456 1471 1469 1472 1474 1473 1474 1470 1468 1475 1477 1476 1475 1478 1473 1479 1480 1477 1481 1482 1397 1483 1484 1480 1485 1397 1482 1483 1486 1484 1487 1489 1488 1486 1491 1490 1492 1494 1493 1495 1496 1491 1497 1499 1498 1495 1501 1500 1502 1504 1503 1505 1506 1501 1507 1504 1508 1506 1412 1413 1509 1511 1510 1413 1414 1512 1513 1512 1514 1493 1489 1492 1399 1396 1395 1455 1408 1419 1459 1408 1455 1418 1417 1415 1427 1428 1441 1453 1424 1433 1452 1426 1424 1447 1430 1425 1442 1435 1443 1452 1424 1453 1453 1433 1434 1432 1433 1446 1445 1446 1422 1423 1421 1449 1449 1448 1451 1451 1450 1454 1410 1450 1409 1407 1409 1379 1380 1381 1386 1386 1385 1389 1390 1385 1392 1393 1392 1395 1396 1399 1400 1400 1398 1401 1401 1402 1404 1405 1402 1463 1464 1463 1462 1460 1461 1467 1467 1465 1466 1466 1457 1458 1456 1457 1471 1469 1471 1468 1470 1474 1472 1472 1473 1478 1478 1475 1476 1477 1475 1479 1480 1479 1483 1484 1486 1490 1490 1491 1496 1496 1495 1500 1501 1495 1505 1506 1505 1412 1414 1514 1512 1514 1510 1513 1509 1510 1507 1513 1510 1511 1502 1508 1504 1508 1509 1507 1498 1502 1503 1497 1494 1499 1497 1498 1503 1488 1485 1487 1497 1493 1494 1492 1489 1487 1515 1397 1488 1485 1488 1397 1394 1397 1515 1516 1518 1517 1519 1521 1520 1521 1522 1520 1519 1524 1523 1523 1521 1519 1525 1524 1526 1524 1525 1523 1527 1528 1526 1525 1526 1528 1527 1530 1529 1529 1528 1527 1531 1530 1532 1530 1531 1529 1533 1534 1532 1531 1532 1534 1533 1536 1535 1535 1534 1533 1537 1536 1538 1536 1537 1535 1539 1541 1540 1542 1544 1543 1545 1547 1546 1548 1550 1549 1551 1553 1552 1554 1556 1555 1557 1559 1558 1560 1562 1561 1563 1565 1564 1566 1568 1567 1569 1571 1570 1572 1574 1573 1575 1577 1576 1578 1580 1579 1581 1582 1579 1583 1582 1581 1580 1578 1572 1581 1579 1580 1573 1574 1575 1572 1578 1574 1568 1576 1577 1576 1573 1575 1571 1566 1567 1567 1568 1577 1566 1571 1569 1560 1561 1570 1570 1561 1569 1564 1565 1562 1560 1564 1562 1563 1556 1554 1565 1563 1554 1555 1557 1558 1555 1556 1557 1552 1559 1551 1552 1558 1559 1545 1553 1547 1547 1553 1551 1550 1548 1546 1546 1548 1545 1541 1539 1549 1550 1541 1549 1540 1518 1516 1539 1540 1516 1517 1542 1543 1517 1518 1542 1537 1538 1544 1538 1543 1544

-
-
-
- - - - 0.529468 0.214506 -0.172 0.557468 0.214506 -0.172 0.557468 0.214506 0.033 0.529468 0.214506 0.033 0.557468 0.242506 -0.172 0.557468 0.242506 0.033 0.557468 0.214506 0.033 0.557468 0.214506 -0.172 0.557468 0.242506 0.033 0.529468 0.242506 -0.172 0.529468 0.242506 0.033 0.557468 0.242506 -0.172 0.529468 0.242506 -0.172 0.529468 0.214506 0.033 0.529468 0.242506 0.033 0.529468 0.214506 -0.172 0.529468 0.242506 0.033 0.557468 0.214506 0.033 0.557468 0.242506 0.033 0.529468 0.214506 0.033 0.557468 0.214506 -0.172 0.529468 0.242506 -0.172 0.557468 0.242506 -0.172 0.529468 0.214506 -0.172 - - - - - - - - - - 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 - - - - - - - - - - - - - - -

0 1 2 0 2 3 4 5 6 6 7 4 8 9 10 8 11 9 12 13 14 13 12 15 16 17 18 17 16 19 20 21 22 20 23 21

-
-
-
- - - - 0.529468 0.671506 0.2 -0.0245319 0.671506 0.172 0.529468 0.671506 0.172 -0.0245319 0.671506 0.2 -0.0245319 0.671506 0.172 -0.0245319 0.643506 0.172 0.529468 0.643506 0.172 0.529468 0.671506 0.172 0.529468 0.643506 0.2 -0.0245319 0.643506 0.172 -0.0245319 0.643506 0.2 0.529468 0.643506 0.172 0.529468 0.643506 0.2 -0.0245319 0.671506 0.2 0.529468 0.671506 0.2 -0.0245319 0.643506 0.2 -0.0245319 0.671506 0.2 -0.0245319 0.643506 0.2 -0.0245319 0.643506 0.172 -0.0245319 0.671506 0.172 0.529468 0.671506 0.2 0.529468 0.643506 0.172 0.529468 0.643506 0.2 0.529468 0.671506 0.172 - - - - - - - - - - 0 1 0 0 1 0 0 1 0 0 1 0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 - - - - - - - - - - - - - - -

0 2 1 1 3 0 4 6 5 4 7 6 8 10 9 8 9 11 12 14 13 12 13 15 16 18 17 18 16 19 20 22 21 21 23 20

-
-
-
- - - - -0.0525319 0.643506 0.478 -0.0525319 0.214506 0.478 -0.0245319 0.214506 0.478 -0.0245319 0.643506 0.478 -0.0525319 0.643506 0.478 -0.0525319 0.643506 0.45 -0.0525319 0.214506 0.45 -0.0525319 0.214506 0.478 -0.0525319 0.643506 0.45 -0.0245319 0.643506 0.45 -0.0245319 0.214506 0.45 -0.0525319 0.214506 0.45 -0.0245319 0.643506 0.478 -0.0245319 0.214506 0.478 -0.0245319 0.214506 0.45 -0.0245319 0.643506 0.45 -0.0525319 0.214506 0.478 -0.0525319 0.214506 0.45 -0.0245319 0.214506 0.45 -0.0245319 0.214506 0.478 -0.0525319 0.643506 0.478 -0.0245319 0.643506 0.478 -0.0245319 0.643506 0.45 -0.0525319 0.643506 0.45 - - - - - - - - - - 0 0 1 0 0 1 0 0 1 0 0 1 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 - - - - - - - - - - - - - - -

0 1 2 0 2 3 4 5 6 6 7 4 8 9 10 10 11 8 12 13 14 12 14 15 16 17 18 16 18 19 20 21 22 22 23 20

-
-
-
- - - - -0.0245319 -0.0204943 -0.2 -0.0525319 -0.0204943 0.2 -0.0245319 -0.0204943 0.2 -0.0525319 -0.0204943 -0.2 -0.0525319 -0.0204943 0.2 -0.0525319 -0.0484943 -0.2 -0.0525319 -0.0484943 0.2 -0.0525319 -0.0204943 -0.2 -0.0245319 -0.0484943 -0.2 -0.0245319 -0.0484943 0.2 -0.0525319 -0.0484943 0.2 -0.0525319 -0.0484943 -0.2 -0.0245319 -0.0484943 -0.2 -0.0245319 -0.0204943 -0.2 -0.0245319 -0.0204943 0.2 -0.0245319 -0.0484943 0.2 -0.0525319 -0.0204943 0.2 -0.0525319 -0.0484943 0.2 -0.0245319 -0.0484943 0.2 -0.0245319 -0.0204943 0.2 -0.0525319 -0.0204943 -0.2 -0.0245319 -0.0204943 -0.2 -0.0245319 -0.0484943 -0.2 -0.0525319 -0.0484943 -0.2 - - - - - - - - - - 0 1 0 0 1 0 0 1 0 0 1 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 - - - - - - - - - - - - - - -

0 1 2 1 0 3 4 5 6 4 7 5 8 9 10 10 11 8 12 13 14 12 14 15 16 17 18 16 18 19 20 21 22 22 23 20

-
-
-
- - - - 0.214968 0.242506 0.45 -0.0245319 0.242506 0.478 0.214968 0.242506 0.478 -0.0245319 0.242506 0.45 -0.0245319 0.242506 0.478 0.214968 0.214506 0.478 0.214968 0.242506 0.478 -0.0245319 0.214506 0.478 -0.0245319 0.214506 0.478 0.214968 0.214506 0.45 0.214968 0.214506 0.478 -0.0245319 0.214506 0.45 -0.0245319 0.242506 0.45 0.214968 0.242506 0.45 0.214968 0.214506 0.45 -0.0245319 0.214506 0.45 0.214968 0.242506 0.45 0.214968 0.242506 0.478 0.214968 0.214506 0.478 0.214968 0.214506 0.45 -0.0245319 0.214506 0.478 -0.0245319 0.242506 0.45 -0.0245319 0.214506 0.45 -0.0245319 0.242506 0.478 - - - - - - - - - - 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 1 0 0 1 0 0 1 0 0 1 0 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 - - - - - - - - - - - - - - -

0 1 2 1 0 3 4 5 6 5 4 7 8 9 10 8 11 9 12 13 14 14 15 12 16 17 18 16 18 19 20 21 22 20 23 21

-
-
-
- - - - 0.557468 -0.0204943 0.2 0.557468 0.643506 0.2 0.557468 0.643506 0.172 0.557468 -0.0204943 0.172 0.557468 -0.0204943 0.172 0.557468 0.643506 0.172 0.529468 0.643506 0.172 0.529468 -0.0204943 0.172 0.529468 0.643506 0.172 0.529468 0.643506 0.2 0.529468 -0.0204943 0.2 0.529468 -0.0204943 0.172 0.529468 -0.0204943 0.2 0.529468 0.643506 0.2 0.557468 0.643506 0.2 0.557468 -0.0204943 0.2 0.557468 0.643506 0.2 0.529468 0.643506 0.2 0.529468 0.643506 0.172 0.557468 0.643506 0.172 0.557468 -0.0204943 0.2 0.529468 -0.0204943 0.172 0.529468 -0.0204943 0.2 0.557468 -0.0204943 0.172 - - - - - - - - - - 1 0 0 1 0 0 1 0 0 1 0 0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 - - - - - - - - - - - - - - -

0 2 1 0 3 2 4 6 5 4 7 6 8 10 9 10 8 11 12 14 13 12 15 14 16 18 17 18 16 19 20 22 21 21 23 20

-
-
-
- - - - 0.557468 0.671506 0.2 0.529468 0.671506 0.478 0.557468 0.671506 0.478 0.529468 0.671506 0.2 0.529468 0.671506 0.478 0.529468 0.643506 0.2 0.529468 0.643506 0.478 0.529468 0.671506 0.2 0.557468 0.643506 0.2 0.557468 0.643506 0.478 0.529468 0.643506 0.478 0.529468 0.643506 0.2 0.557468 0.643506 0.2 0.557468 0.671506 0.2 0.557468 0.671506 0.478 0.557468 0.643506 0.478 0.529468 0.671506 0.478 0.529468 0.643506 0.478 0.557468 0.643506 0.478 0.557468 0.671506 0.478 0.529468 0.671506 0.2 0.557468 0.671506 0.2 0.557468 0.643506 0.2 0.529468 0.643506 0.2 - - - - - - - - - - 0 1 0 0 1 0 0 1 0 0 1 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 - - - - - - - - - - - - - - -

0 1 2 1 0 3 4 5 6 4 7 5 8 9 10 10 11 8 12 13 14 12 14 15 16 17 18 16 18 19 20 21 22 22 23 20

-
-
-
- - - - -0.013 0.0095 0.005 -0.013 0.0145 0.023666 -0.013 0.0095 0.023666 -0.013 -0.0145 0.023666 -0.013 -0.0145 0 -0.013 -0.0095 0.005 -0.013 0.0145 0 -0.013 -0.0095 0.023666 0.013 -0.0145 0.023666 0.013 -0.0095 0.005 0.013 -0.0145 0 0.013 0.0095 0.005 0.013 0.0095 0.023666 0.013 0.0145 0.023666 0.013 0.0145 0 0.013 -0.0095 0.023666 -0.013 0.0095 0.005 0.013 -0.0095 0.005 -0.013 -0.0095 0.005 0.013 0.0095 0.005 -0.013 0.0145 0 0.013 -0.0145 0 0.013 0.0145 0 -0.013 -0.0145 0 -0.00469846 0.0095 0.0282899 -0.0114185 0.0095 0.0279604 -0.0110512 0.0095 0.028799 -0.00492404 0.0095 0.0291318 -0.0106663 0.0095 0.0296298 -0.0102626 0.0095 0.0304516 -0.00433013 0.0095 0.0275 -0.0121008 0.0095 0.0262611 -0.0117681 0.0095 0.0271142 0.0025 0.0095 0.0256699 0.013 0.0095 0.005 0.0017101 0.0095 0.0253015 0.013 0.0095 0.023666 0.00383022 0.0095 0.0267861 0.0127165 0.0095 0.0245367 -0.00983911 0.0095 0.0312633 -0.00939568 0.0095 0.0320646 -0.005 0.0095 0.03 0.0114183 0.0095 0.0279601 0.011768 0.0095 0.0271139 0.00433013 0.0095 0.0275 -0.00844211 0.0095 0.0336276 -0.0079298 0.0095 0.0343867 -0.00492404 0.0095 0.0308682 -0.00622421 0.0095 0.0365385 -0.00383022 0.0095 0.0332139 -0.00433013 0.0095 0.0325 0.00469846 0.0095 0.0282899 -0.00321394 0.0095 0.0338302 -0.00491981 0.0095 0.0378223 -0.00420849 0.0095 0.0384009 -0.00559123 0.0095 0.037201 0.00844199 0.0095 0.0336274 0.00492404 0.0095 0.0308682 0.00469846 0.0095 0.0317101 0.00892993 0.0095 0.0328525 -0.0017101 0.0095 0.0346985 -0.00264914 0.0095 0.0393555 -0.00179785 0.0095 0.0397035 -0.00345157 0.0095 0.0389194 0.0025 0.0095 0.0343301 0.00345164 0.0095 0.0389117 0.00420731 0.0095 0.0383957 -0.000868241 0.0095 0.034924 -0.000906918 0.0095 0.0399235 -1.90972e-13 0.0095 0.04 0 0.0095 0.035 0.0017101 0.0095 0.0346985 0.00264929 0.0095 0.0393549 0.000915238 0.0095 0.0399174 0.00180163 0.0095 0.0396935 0.000868241 0.0095 0.034924 0.00491971 0.0095 0.0378219 0.00321394 0.0095 0.0338302 0.00682246 0.0095 0.0358444 0.00738982 0.0095 0.0351255 0.00433013 0.0095 0.0325 0.0055898 0.0095 0.0371972 0.00622291 0.0095 0.0365359 0.00383022 0.0095 0.0332139 -0.0025 0.0095 0.0343301 0.00792892 0.0095 0.0343855 0.00983908 0.0095 0.0312633 0.0102622 0.0095 0.0304512 0.00492404 0.0095 0.0291318 0.0110512 0.0095 0.0287989 0.010666 0.0095 0.0296294 -0.00469846 0.0095 0.0317101 -0.00739091 0.0095 0.0351273 -0.00682262 0.0095 0.0358448 0.0121008 0.0095 0.026261 0.0124168 0.0095 0.0254017 -0.00893059 0.0095 0.0328534 0.00321394 0.0095 0.0261698 0.000868241 0.0095 0.025076 -1.71512e-17 0.0095 0.025 -0.013 0.0095 0.023666 -0.0025 0.0095 0.0256699 -0.013 0.0095 0.005 0.00939518 0.0095 0.0320639 0.005 0.0095 0.03 -0.00383022 0.0095 0.0267861 -0.0124169 0.0095 0.0254019 -0.0127165 0.0095 0.0245367 -0.00321394 0.0095 0.0261698 -0.0017101 0.0095 0.0253015 -0.000868241 0.0095 0.025076 -0.00682246 0.0145 0.0358444 -0.00433013 0.0145 0.0325 -0.00622291 0.0145 0.0365359 -0.00844199 0.0145 0.0336274 -0.00492404 0.0145 0.0308682 -0.00792892 0.0145 0.0343855 0.00383022 0.0145 0.0332139 0.00622421 0.0145 0.0365385 0.00559123 0.0145 0.037201 -0.00383022 0.0145 0.0332139 -0.00420731 0.0145 0.0383957 -0.00321394 0.0145 0.0338302 -0.0025 0.0145 0.0343301 -0.00491971 0.0145 0.0378219 0.00739091 0.0145 0.0351273 0.00469846 0.0145 0.0317101 0.0079298 0.0145 0.0343867 0.00492404 0.0145 0.0308682 0.00844211 0.0145 0.0336276 0.00682262 0.0145 0.0358448 0.00433013 0.0145 0.0325 0.00345157 0.0145 0.0389194 0.00264914 0.0145 0.0393555 0.0017101 0.0145 0.0346985 0.00321394 0.0145 0.0338302 0.00420849 0.0145 0.0384009 0.0025 0.0145 0.0343301 0.000906918 0.0145 0.0399235 -1.91355e-13 0.0145 0.04 -1.77636e-18 0.0145 0.035 0.00179785 0.0145 0.0397035 0.000868241 0.0145 0.034924 -0.000915238 0.0145 0.0399174 -0.000868241 0.0145 0.034924 0.00491981 0.0145 0.0378223 -0.00180163 0.0145 0.0396935 -0.0017101 0.0145 0.0346985 -0.00264929 0.0145 0.0393549 -0.00345164 0.0145 0.0389117 0.00893059 0.0145 0.0328534 0.005 0.0145 0.03 0.00983911 0.0145 0.0312633 0.00939568 0.0145 0.0320646 0.0106663 0.0145 0.0296298 0.00492404 0.0145 0.0291318 0.00469846 0.0145 0.0282899 0.0102626 0.0145 0.0304516 0.0117681 0.0145 0.0271142 0.0114185 0.0145 0.0279604 0.0110512 0.0145 0.028799 0.00433013 0.0145 0.0275 -0.00738982 0.0145 0.0351255 -0.00469846 0.0145 0.0317101 0.0124169 0.0145 0.0254019 0.0121008 0.0145 0.0262611 0.0127165 0.0145 0.0245367 0.00383022 0.0145 0.0267861 0.013 0.0145 0.023666 -0.005 0.0145 0.03 0.00321394 0.0145 0.0261698 -0.00892993 0.0145 0.0328525 0.0025 0.0145 0.0256699 0.013 0.0145 0 -0.00492404 0.0145 0.0291318 -0.00939518 0.0145 0.0320639 0.0017101 0.0145 0.0253015 -0.00983908 0.0145 0.0312633 0.000868241 0.0145 0.025076 0 0.0145 0.025 -0.0102622 0.0145 0.0304512 -0.00321394 0.0145 0.0261698 -0.013 0.0145 0.023666 -0.0025 0.0145 0.0256699 -0.010666 0.0145 0.0296294 -0.0124168 0.0145 0.0254017 -0.00433013 0.0145 0.0275 -0.0121008 0.0145 0.026261 -0.00469846 0.0145 0.0282899 -0.0110512 0.0145 0.0287989 -0.0114183 0.0145 0.0279601 -0.0055898 0.0145 0.0371972 -0.011768 0.0145 0.0271139 -0.00383022 0.0145 0.0267861 -0.0127165 0.0145 0.0245367 -0.013 0.0145 0 -0.0017101 0.0145 0.0253015 -0.000868241 0.0145 0.025076 0.00433013 -0.0095 0.0275 0.0114185 -0.0095 0.0279604 0.00469846 -0.0095 0.0282899 -0.00844199 -0.0095 0.0336274 -0.00492404 -0.0095 0.0308682 -0.00792892 -0.0095 0.0343855 0.00433013 -0.0095 0.0325 0.00682262 -0.0095 0.0358448 0.00622421 -0.0095 0.0365385 0.0110512 -0.0095 0.028799 0.0106663 -0.0095 0.0296298 -0.00420731 -0.0095 0.0383957 -0.00321394 -0.0095 0.0338302 -0.0025 -0.0095 0.0343301 -0.00491971 -0.0095 0.0378219 -0.0055898 -0.0095 0.0371972 0.00469846 -0.0095 0.0317101 0.0079298 -0.0095 0.0343867 0.00739091 -0.0095 0.0351273 0.00492404 -0.0095 0.0308682 0.00844211 -0.0095 0.0336276 -0.00180163 -0.0095 0.0396935 -0.0017101 -0.0095 0.0346985 -0.000868241 -0.0095 0.034924 0.00345157 -0.0095 0.0389194 0.00264914 -0.0095 0.0393555 0.0017101 -0.0095 0.0346985 0.00420849 -0.0095 0.0384009 0.0025 -0.0095 0.0343301 0.000868241 -0.0095 0.034924 0.00179785 -0.0095 0.0397035 0.000906918 -0.0095 0.0399235 -1.91342e-13 -0.0095 0.04 0 -0.0095 0.035 -0.000915238 -0.0095 0.0399174 0.00321394 -0.0095 0.0338302 0.00491981 -0.0095 0.0378223 -0.00264929 -0.0095 0.0393549 0.00383022 -0.0095 0.0332139 0.00559123 -0.0095 0.037201 -0.00345164 -0.0095 0.0389117 0.00893059 -0.0095 0.0328534 0.00983911 -0.0095 0.0312633 0.00939568 -0.0095 0.0320646 0.005 -0.0095 0.03 0.00492404 -0.0095 0.0291318 0.0102626 -0.0095 0.0304516 -0.00433013 -0.0095 0.0325 -0.00622291 -0.0095 0.0365359 -0.00682246 -0.0095 0.0358444 -0.00383022 -0.0095 0.0332139 0.0117681 -0.0095 0.0271142 -0.00738982 -0.0095 0.0351255 -0.00469846 -0.0095 0.0317101 0.0121008 -0.0095 0.0262611 0.0124169 -0.0095 0.0254019 0.00383022 -0.0095 0.0267861 0.013 -0.0095 0.023666 0.0127165 -0.0095 0.0245367 -0.00892993 -0.0095 0.0328525 0.00321394 -0.0095 0.0261698 -0.005 -0.0095 0.03 0.0025 -0.0095 0.0256699 0.013 -0.0095 0.005 -0.00939518 -0.0095 0.0320639 -0.00983908 -0.0095 0.0312633 0.0017101 -0.0095 0.0253015 -0.00492404 -0.0095 0.0291318 0.000868241 -0.0095 0.025076 7.27366e-18 -0.0095 0.025 -0.0102622 -0.0095 0.0304512 -0.0025 -0.0095 0.0256699 -0.013 -0.0095 0.023666 -0.013 -0.0095 0.005 -0.010666 -0.0095 0.0296294 -0.011768 -0.0095 0.0271139 -0.0121008 -0.0095 0.026261 -0.00433013 -0.0095 0.0275 -0.00469846 -0.0095 0.0282899 -0.0110512 -0.0095 0.0287989 -0.0114183 -0.0095 0.0279601 -0.00383022 -0.0095 0.0267861 -0.0124168 -0.0095 0.0254017 -0.0127165 -0.0095 0.0245367 -0.00321394 -0.0095 0.0261698 -0.000868241 -0.0095 0.025076 -0.0017101 -0.0095 0.0253015 0.013 -0.0145 0 -0.013 -0.0145 0 -0.013 -0.0145 0.023666 -0.0127165 -0.0145 0.0245367 -0.0124169 -0.0145 0.0254019 0.0127165 -0.0145 0.0245367 0.013 -0.0145 0.023666 0.0121008 -0.0145 0.026261 0.0124168 -0.0145 0.0254017 -0.0121008 -0.0145 0.0262611 0.0110512 -0.0145 0.0287989 0.0114183 -0.0145 0.0279601 -0.0110512 -0.0145 0.028799 0.011768 -0.0145 0.0271139 -0.0117681 -0.0145 0.0271142 -0.0114185 -0.0145 0.0279604 0.0102622 -0.0145 0.0304512 -0.0102626 -0.0145 0.0304516 -0.00983911 -0.0145 0.0312633 -0.0106663 -0.0145 0.0296298 0.010666 -0.0145 0.0296294 -0.00893059 -0.0145 0.0328534 -0.00844211 -0.0145 0.0336276 0.00892993 -0.0145 0.0328525 -0.00939568 -0.0145 0.0320646 0.00939518 -0.0145 0.0320639 0.00983908 -0.0145 0.0312633 -0.0079298 -0.0145 0.0343867 -0.00739091 -0.0145 0.0351273 0.00792892 -0.0145 0.0343855 0.00844199 -0.0145 0.0336274 -0.00622421 -0.0145 0.0365385 0.00622291 -0.0145 0.0365359 0.00682246 -0.0145 0.0358444 0.00738982 -0.0145 0.0351255 -0.00682262 -0.0145 0.0358448 -0.00491981 -0.0145 0.0378223 0.00491971 -0.0145 0.0378219 0.0055898 -0.0145 0.0371972 -0.00559123 -0.0145 0.037201 -0.00345157 -0.0145 0.0389194 0.00264929 -0.0145 0.0393549 0.00345164 -0.0145 0.0389117 0.00420731 -0.0145 0.0383957 -0.00420849 -0.0145 0.0384009 0.00180163 -0.0145 0.0396935 -0.00179785 -0.0145 0.0397035 -0.000906918 -0.0145 0.0399235 -0.00264914 -0.0145 0.0393555 0.000915238 -0.0145 0.0399174 -1.90977e-13 -0.0145 0.04 0.0127165 -0.0145 0.0245367 0.013 -0.0095 0.023666 0.013 -0.0145 0.023666 0.011768 -0.0145 0.0271139 0.0121008 -0.0095 0.0262611 0.0121008 -0.0145 0.026261 0.0124168 -0.0145 0.0254017 0.0124169 -0.0095 0.0254019 0.0127165 -0.0095 0.0245367 0.0110512 -0.0095 0.028799 0.0110512 -0.0145 0.0287989 0.010666 -0.0145 0.0296294 0.0117681 -0.0095 0.0271142 0.0114183 -0.0145 0.0279601 0.0114185 -0.0095 0.0279604 0.00983908 -0.0145 0.0312633 0.00939518 -0.0145 0.0320639 0.00983911 -0.0095 0.0312633 0.0102622 -0.0145 0.0304512 0.0102626 -0.0095 0.0304516 0.0106663 -0.0095 0.0296298 0.00844199 -0.0145 0.0336274 0.00844211 -0.0095 0.0336276 0.00893059 -0.0095 0.0328534 0.00939568 -0.0095 0.0320646 0.00892993 -0.0145 0.0328525 0.00682262 -0.0095 0.0358448 0.00739091 -0.0095 0.0351273 0.00682246 -0.0145 0.0358444 0.0079298 -0.0095 0.0343867 0.00792892 -0.0145 0.0343855 0.00738982 -0.0145 0.0351255 0.00559123 -0.0095 0.037201 0.00622421 -0.0095 0.0365385 0.0055898 -0.0145 0.0371972 0.00622291 -0.0145 0.0365359 0.00420849 -0.0095 0.0384009 0.00420731 -0.0145 0.0383957 0.00345164 -0.0145 0.0389117 0.00491971 -0.0145 0.0378219 0.00491981 -0.0095 0.0378223 0.00264914 -0.0095 0.0393555 0.00180163 -0.0145 0.0396935 0.00179785 -0.0095 0.0397035 0.00264929 -0.0145 0.0393549 0.00345157 -0.0095 0.0389194 -0.000906918 -0.0145 0.0399235 -0.000915238 -0.0095 0.0399174 -1.91342e-13 -0.0095 0.04 -1.90977e-13 -0.0145 0.04 0.000906918 -0.0095 0.0399235 0.000915238 -0.0145 0.0399174 -0.00345164 -0.0095 0.0389117 -0.00345157 -0.0145 0.0389194 -0.00420849 -0.0145 0.0384009 -0.00180163 -0.0095 0.0396935 -0.00179785 -0.0145 0.0397035 -0.00264914 -0.0145 0.0393555 -0.00682262 -0.0145 0.0358448 -0.00622291 -0.0095 0.0365359 -0.00622421 -0.0145 0.0365385 -0.00559123 -0.0145 0.037201 -0.00491971 -0.0095 0.0378219 -0.00491981 -0.0145 0.0378223 -0.00844211 -0.0145 0.0336276 -0.00893059 -0.0145 0.0328534 -0.00844199 -0.0095 0.0336274 -0.0079298 -0.0145 0.0343867 -0.00792892 -0.0095 0.0343855 -0.00738982 -0.0095 0.0351255 -0.00892993 -0.0095 0.0328525 -0.00939568 -0.0145 0.0320646 -0.00983911 -0.0145 0.0312633 -0.00939518 -0.0095 0.0320639 -0.0102626 -0.0145 0.0304516 -0.00983908 -0.0095 0.0312633 -0.0102622 -0.0095 0.0304512 -0.0106663 -0.0145 0.0296298 -0.0110512 -0.0145 0.028799 -0.010666 -0.0095 0.0296294 -0.0114185 -0.0145 0.0279604 -0.0110512 -0.0095 0.0287989 -0.0114183 -0.0095 0.0279601 -0.0117681 -0.0145 0.0271142 -0.0121008 -0.0145 0.0262611 -0.011768 -0.0095 0.0271139 -0.0124169 -0.0145 0.0254019 -0.0121008 -0.0095 0.026261 -0.0124168 -0.0095 0.0254017 -0.0127165 -0.0145 0.0245367 -0.013 -0.0145 0.023666 -0.0127165 -0.0095 0.0245367 -0.013 -0.0095 0.023666 -0.00682246 -0.0095 0.0358444 -0.00739091 -0.0145 0.0351273 -0.0055898 -0.0095 0.0371972 -0.00420731 -0.0095 0.0383957 -0.00264929 -0.0095 0.0393549 -1.91355e-13 0.0145 0.04 -1.90972e-13 0.0095 0.04 -0.000906918 0.0095 0.0399235 -0.00179785 0.0095 0.0397035 -0.000915238 0.0145 0.0399174 -0.00264914 0.0095 0.0393555 -0.00180163 0.0145 0.0396935 -0.00264929 0.0145 0.0393549 -0.00345157 0.0095 0.0389194 -0.00420849 0.0095 0.0384009 -0.00420731 0.0145 0.0383957 -0.00345164 0.0145 0.0389117 -0.00491981 0.0095 0.0378223 -0.00491971 0.0145 0.0378219 -0.00559123 0.0095 0.037201 -0.0055898 0.0145 0.0371972 -0.00622291 0.0145 0.0365359 -0.00622421 0.0095 0.0365385 -0.00682262 0.0095 0.0358448 -0.00682246 0.0145 0.0358444 -0.00893059 0.0095 0.0328534 -0.00939568 0.0095 0.0320646 -0.00892993 0.0145 0.0328525 -0.00738982 0.0145 0.0351255 -0.00739091 0.0095 0.0351273 -0.0079298 0.0095 0.0343867 -0.00844211 0.0095 0.0336276 -0.00792892 0.0145 0.0343855 -0.00844199 0.0145 0.0336274 -0.00939518 0.0145 0.0320639 -0.00983911 0.0095 0.0312633 -0.00983908 0.0145 0.0312633 -0.0102626 0.0095 0.0304516 -0.0102622 0.0145 0.0304512 -0.010666 0.0145 0.0296294 -0.0106663 0.0095 0.0296298 -0.0110512 0.0095 0.028799 -0.0110512 0.0145 0.0287989 -0.0114185 0.0095 0.0279604 -0.0114183 0.0145 0.0279601 -0.011768 0.0145 0.0271139 -0.0117681 0.0095 0.0271142 -0.0121008 0.0095 0.0262611 -0.0121008 0.0145 0.026261 -0.0124169 0.0095 0.0254019 -0.0124168 0.0145 0.0254017 -0.0127165 0.0145 0.0245367 -0.0127165 0.0095 0.0245367 -0.013 0.0095 0.023666 -0.013 0.0145 0.023666 0.000906918 0.0145 0.0399235 0.00179785 0.0145 0.0397035 0.000915238 0.0095 0.0399174 0.00180163 0.0095 0.0396935 0.00264914 0.0145 0.0393555 0.00345157 0.0145 0.0389194 0.00264929 0.0095 0.0393549 0.00420849 0.0145 0.0384009 0.00345164 0.0095 0.0389117 0.00420731 0.0095 0.0383957 0.00491981 0.0145 0.0378223 0.00559123 0.0145 0.037201 0.00491971 0.0095 0.0378219 0.00622421 0.0145 0.0365385 0.0055898 0.0095 0.0371972 0.00622291 0.0095 0.0365359 0.00682262 0.0145 0.0358448 0.00739091 0.0145 0.0351273 0.00682246 0.0095 0.0358444 0.0079298 0.0145 0.0343867 0.00738982 0.0095 0.0351255 0.00792892 0.0095 0.0343855 0.00844211 0.0145 0.0336276 0.00893059 0.0145 0.0328534 0.00844199 0.0095 0.0336274 0.00939568 0.0145 0.0320646 0.00892993 0.0095 0.0328525 0.00939518 0.0095 0.0320639 0.00983911 0.0145 0.0312633 0.0102626 0.0145 0.0304516 0.00983908 0.0095 0.0312633 0.0106663 0.0145 0.0296298 0.0102622 0.0095 0.0304512 0.010666 0.0095 0.0296294 0.0110512 0.0145 0.028799 0.0114185 0.0145 0.0279604 0.0110512 0.0095 0.0287989 0.0117681 0.0145 0.0271142 0.0114183 0.0095 0.0279601 0.011768 0.0095 0.0271139 0.0121008 0.0145 0.0262611 0.0124169 0.0145 0.0254019 0.0121008 0.0095 0.026261 0.0127165 0.0145 0.0245367 0.0124168 0.0095 0.0254017 0.0127165 0.0095 0.0245367 0.013 0.0145 0.023666 0.013 0.0095 0.023666 -1.71512e-17 0.0095 0.025 -0.000868241 -0.0095 0.025076 7.27366e-18 -0.0095 0.025 -0.0017101 -0.0095 0.0253015 -0.000868241 0.0095 0.025076 -0.0017101 0.0095 0.0253015 -0.0025 -0.0095 0.0256699 -0.0025 0.0095 0.0256699 -0.00321394 -0.0095 0.0261698 -0.00383022 -0.0095 0.0267861 -0.00321394 0.0095 0.0261698 -0.00383022 0.0095 0.0267861 -0.00433013 -0.0095 0.0275 -0.00433013 0.0095 0.0275 -0.00469846 -0.0095 0.0282899 -0.00492404 -0.0095 0.0291318 -0.00469846 0.0095 0.0282899 -0.00492404 0.0095 0.0291318 -0.005 -0.0095 0.03 -0.005 0.0095 0.03 -0.00492404 -0.0095 0.0308682 -0.00469846 -0.0095 0.0317101 -0.00492404 0.0095 0.0308682 -0.00469846 0.0095 0.0317101 -0.00433013 -0.0095 0.0325 -0.00433013 0.0095 0.0325 -0.00383022 -0.0095 0.0332139 -0.00321394 -0.0095 0.0338302 -0.00383022 0.0095 0.0332139 -0.00321394 0.0095 0.0338302 -0.0025 -0.0095 0.0343301 -0.0025 0.0095 0.0343301 -0.0017101 -0.0095 0.0346985 -0.000868241 -0.0095 0.034924 -0.0017101 0.0095 0.0346985 -0.000868241 0.0095 0.034924 0 -0.0095 0.035 0 0.0095 0.035 0.000868241 0.0095 0.025076 0.000868241 -0.0095 0.025076 0.0017101 0.0095 0.0253015 0.0017101 -0.0095 0.0253015 0.0025 0.0095 0.0256699 0.00321394 0.0095 0.0261698 0.0025 -0.0095 0.0256699 0.00321394 -0.0095 0.0261698 0.00383022 0.0095 0.0267861 0.00383022 -0.0095 0.0267861 0.00433013 0.0095 0.0275 0.00469846 0.0095 0.0282899 0.00433013 -0.0095 0.0275 0.00469846 -0.0095 0.0282899 0.00492404 0.0095 0.0291318 0.00492404 -0.0095 0.0291318 0.005 0.0095 0.03 0.00492404 0.0095 0.0308682 0.005 -0.0095 0.03 0.00492404 -0.0095 0.0308682 0.00469846 0.0095 0.0317101 0.00469846 -0.0095 0.0317101 0.00433013 0.0095 0.0325 0.00383022 0.0095 0.0332139 0.00433013 -0.0095 0.0325 0.00383022 -0.0095 0.0332139 0.00321394 0.0095 0.0338302 0.00321394 -0.0095 0.0338302 0.0025 0.0095 0.0343301 0.0017101 0.0095 0.0346985 0.0025 -0.0095 0.0343301 0.0017101 -0.0095 0.0346985 0.000868241 0.0095 0.034924 0.000868241 -0.0095 0.034924 -0.005 0.0145 0.03 -0.00492404 0.0395 0.0291318 -0.005 0.0395 0.03 6.12323e-19 0.0395 0.035 0.000868241 0.0145 0.034924 -1.77636e-18 0.0145 0.035 -0.00469846 0.0395 0.0282899 -0.00492404 0.0145 0.0291318 -0.00469846 0.0145 0.0282899 -0.00433013 0.0395 0.0275 -0.00433013 0.0145 0.0275 -0.00383022 0.0395 0.0267861 -0.00321394 0.0395 0.0261698 -0.00383022 0.0145 0.0267861 -0.00321394 0.0145 0.0261698 -0.0025 0.0395 0.0256699 -0.0025 0.0145 0.0256699 -0.0017101 0.0395 0.0253015 -0.000868241 0.0395 0.025076 -0.0017101 0.0145 0.0253015 -0.000868241 0.0145 0.025076 -1.22465e-18 0.0395 0.025 0 0.0145 0.025 -0.00492404 0.0145 0.0308682 -0.00492404 0.0395 0.0308682 -0.00469846 0.0145 0.0317101 -0.00469846 0.0395 0.0317101 -0.00433013 0.0145 0.0325 -0.00383022 0.0145 0.0332139 -0.00433013 0.0395 0.0325 -0.00383022 0.0395 0.0332139 -0.00321394 0.0145 0.0338302 -0.00321394 0.0395 0.0338302 -0.0025 0.0145 0.0343301 -0.0017101 0.0145 0.0346985 -0.0025 0.0395 0.0343301 -0.0017101 0.0395 0.0346985 -0.000868241 0.0145 0.034924 -0.000868241 0.0395 0.034924 0.0017101 0.0395 0.0346985 0.0017101 0.0145 0.0346985 0.000868241 0.0395 0.034924 0.00383022 0.0395 0.0332139 0.00383022 0.0145 0.0332139 0.00321394 0.0395 0.0338302 0.0025 0.0395 0.0343301 0.00321394 0.0145 0.0338302 0.0025 0.0145 0.0343301 0.00469846 0.0395 0.0317101 0.00492404 0.0395 0.0308682 0.00492404 0.0145 0.0308682 0.00433013 0.0145 0.0325 0.00433013 0.0395 0.0325 0.00469846 0.0145 0.0317101 0.00469846 0.0145 0.0282899 0.00492404 0.0395 0.0291318 0.00469846 0.0395 0.0282899 0.00492404 0.0145 0.0291318 0.005 0.0145 0.03 0.005 0.0395 0.03 0.00321394 0.0395 0.0261698 0.00321394 0.0145 0.0261698 0.00383022 0.0395 0.0267861 0.00433013 0.0395 0.0275 0.00383022 0.0145 0.0267861 0.00433013 0.0145 0.0275 0.0025 0.0145 0.0256699 0.0025 0.0395 0.0256699 0.0017101 0.0395 0.0253015 0.0017101 0.0145 0.0253015 0.000868241 0.0395 0.025076 0.000868241 0.0145 0.025076 -0.0025 0.0395 0.0256699 0.00469846 0.0395 0.0317101 0.00433013 0.0395 0.0325 -0.00383022 0.0395 0.0267861 0.00321394 0.0395 0.0338302 -0.00433013 0.0395 0.0275 0.00492404 0.0395 0.0291318 0.005 0.0395 0.03 -1.22465e-18 0.0395 0.025 -0.000868241 0.0395 0.025076 0.00492404 0.0395 0.0308682 -0.0017101 0.0395 0.0253015 0.000868241 0.0395 0.025076 0.0017101 0.0395 0.0253015 0.00469846 0.0395 0.0282899 0.00383022 0.0395 0.0267861 0.0025 0.0395 0.0256699 0.00321394 0.0395 0.0261698 0.00433013 0.0395 0.0275 -0.00321394 0.0395 0.0261698 0.00383022 0.0395 0.0332139 0.0025 0.0395 0.0343301 0.0017101 0.0395 0.0346985 -0.00469846 0.0395 0.0282899 -0.00492404 0.0395 0.0291318 0.000868241 0.0395 0.034924 6.12323e-19 0.0395 0.035 -0.005 0.0395 0.03 -0.00492404 0.0395 0.0308682 -0.00433013 0.0395 0.0325 -0.0025 0.0395 0.0343301 -0.00383022 0.0395 0.0332139 -0.00469846 0.0395 0.0317101 -0.000868241 0.0395 0.034924 -0.0017101 0.0395 0.0346985 -0.00321394 0.0395 0.0338302 - - - - - - - - - - -1 1.82602e-16 0 -1 1.82602e-16 0 -1 1.82602e-16 0 -1 1.82602e-16 0 -1 1.82602e-16 0 -1 1.82602e-16 0 -1 1.82602e-16 0 -1 1.82602e-16 0 1 -1.82602e-16 0 1 -1.82602e-16 0 1 -1.82602e-16 0 1 -1.82602e-16 0 1 -1.82602e-16 0 1 -1.82602e-16 0 1 -1.82602e-16 0 1 -1.82602e-16 0 0 0 1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 0.947948 0 0.318425 0.953688 0 0.300797 0.953688 0 0.300797 0.927989 0 0.372608 0.935158 0 0.354232 0.93515 0 0.354253 0.941783 0 0.336222 0.941787 0 0.336209 0.947947 0 0.318428 0.911783 0 0.410672 0.911776 0 0.410688 0.902508 0 0.430673 0.928003 0 0.372573 0.920229 0 0.39138 0.920243 0 0.391347 0.880956 0 0.473198 0.868261 0 0.496107 0.88096 0 0.47319 0.892294 0 0.451455 0.892305 0 0.451433 0.902519 0 0.43065 0.837646 0 0.546213 0.837663 0 0.546188 0.853975 0 0.520314 0.868283 0 0.49607 0.853945 0 0.520363 0.771266 0 0.636513 0.797066 0 0.603892 0.77124 0 0.636545 0.81891 0 0.573922 0.818863 0 0.573988 0.797005 0 0.603973 0.703042 0 0.711148 0.740462 0 0.672098 0.702929 0 0.71126 0.740371 0 0.672198 0.599055 0 0.800708 0.598927 0 0.800803 0.525656 0 0.850697 0.656795 0 0.754069 0.656824 0 0.754044 0.432188 0 0.901784 0.313777 0 0.949497 0.313362 0 0.949634 0.43217 0 0.901792 0.525699 0 0.850671 -0.167209 0 0.985921 -0.168447 0 0.985711 -9.13249e-08 0 1 -9.13249e-08 0 1 0.167209 0 0.985922 0.168447 0 0.985711 -0.525656 0 0.850697 -0.525699 0 0.850671 -0.599055 0 0.800708 -0.313777 0 0.949497 -0.313362 0 0.949634 -0.432188 0 0.901784 -0.771266 0 0.636513 -0.740372 0 0.672198 -0.740462 0 0.672098 -0.703042 0 0.711148 -0.656795 0 0.754069 -0.656824 0 0.754044 -0.837663 0 0.546188 -0.853975 0 0.520314 -0.837646 0 0.546213 -0.81891 0 0.573922 -0.818863 0 0.573988 -0.797005 0 0.603973 -0.853945 0 0.520363 -0.868283 0 0.49607 -0.88096 0 0.47319 -0.868261 0 0.496107 -0.892305 0 0.451433 -0.880956 0 0.473198 -0.892294 0 0.451455 -0.902519 0 0.43065 -0.911783 0 0.410672 -0.902508 0 0.430673 -0.920243 0 0.391347 -0.911776 0 0.410688 -0.920229 0 0.39138 -0.928003 0 0.372573 -0.935158 0 0.354232 -0.927989 0 0.372608 -0.941787 0 0.336209 -0.93515 0 0.354253 -0.941783 0 0.336222 -0.947947 0 0.318428 -0.953688 0 0.300797 -0.947948 0 0.318425 -0.953688 0 0.300797 -0.77124 0 0.636545 -0.797066 0 0.603892 -0.702929 0 0.71126 -0.598928 0 0.800803 -0.43217 0 0.901792 -9.13249e-08 0 1 -9.13249e-08 0 1 -0.167209 0 0.985921 -0.313362 0 0.949634 -0.168447 0 0.985711 -0.432188 0 0.901784 -0.313777 0 0.949497 -0.43217 0 0.901792 -0.525699 0 0.850671 -0.599055 0 0.800708 -0.598928 0 0.800803 -0.525656 0 0.850697 -0.656824 0 0.754044 -0.656795 0 0.754069 -0.703042 0 0.711148 -0.702929 0 0.71126 -0.740372 0 0.672198 -0.740462 0 0.672098 -0.771266 0 0.636513 -0.77124 0 0.636545 -0.853975 0 0.520314 -0.868283 0 0.49607 -0.853945 0 0.520363 -0.797005 0 0.603973 -0.797066 0 0.603892 -0.81891 0 0.573922 -0.837663 0 0.546188 -0.818863 0 0.573988 -0.837646 0 0.546213 -0.868261 0 0.496107 -0.88096 0 0.47319 -0.880956 0 0.473198 -0.892305 0 0.451433 -0.892294 0 0.451455 -0.902508 0 0.430673 -0.902519 0 0.43065 -0.911783 0 0.410672 -0.911776 0 0.410688 -0.920243 0 0.391347 -0.920229 0 0.39138 -0.927989 0 0.372608 -0.928003 0 0.372573 -0.935158 0 0.354232 -0.93515 0 0.354253 -0.941787 0 0.336209 -0.941783 0 0.336222 -0.947948 0 0.318425 -0.947947 0 0.318428 -0.953688 0 0.300797 -0.953688 0 0.300797 0.167209 0 0.985922 0.313362 0 0.949634 0.168447 0 0.985711 0.313777 0 0.949497 0.432188 0 0.901784 0.525699 0 0.850671 0.43217 0 0.901792 0.599055 0 0.800708 0.525656 0 0.850697 0.598927 0 0.800803 0.656824 0 0.754044 0.703042 0 0.711148 0.656795 0 0.754069 0.740462 0 0.672098 0.702929 0 0.71126 0.740371 0 0.672198 0.771266 0 0.636513 0.797066 0 0.603892 0.77124 0 0.636545 0.81891 0 0.573922 0.797005 0 0.603973 0.818863 0 0.573988 0.837663 0 0.546188 0.853975 0 0.520314 0.837646 0 0.546213 0.868283 0 0.49607 0.853945 0 0.520363 0.868261 0 0.496107 0.88096 0 0.47319 0.892305 0 0.451433 0.880956 0 0.473198 0.902519 0 0.43065 0.892294 0 0.451455 0.902508 0 0.430673 0.911783 0 0.410672 0.920243 0 0.391347 0.911776 0 0.410688 0.928003 0 0.372573 0.920229 0 0.39138 0.927989 0 0.372608 0.935158 0 0.354232 0.941787 0 0.336209 0.93515 0 0.354253 0.947947 0 0.318428 0.941783 0 0.336222 0.947948 0 0.318425 0.953688 0 0.300797 0.953688 0 0.300797 -8.74228e-08 0 -1 -0.173648 0 -0.984808 -8.74228e-08 0 -1 -0.34202 0 -0.939693 -0.173648 0 -0.984808 -0.34202 0 -0.939693 -0.5 0 -0.866025 -0.5 0 -0.866026 -0.642788 0 -0.766044 -0.766045 0 -0.642788 -0.642788 0 -0.766044 -0.766045 0 -0.642788 -0.866025 0 -0.5 -0.866025 0 -0.5 -0.939692 0 -0.342021 -0.984808 0 -0.173648 -0.939693 0 -0.34202 -0.984808 0 -0.173648 -1 0 1.19249e-08 -1 0 1.19249e-08 -0.984808 0 0.173648 -0.939693 0 0.34202 -0.984808 0 0.173648 -0.939693 0 0.34202 -0.866025 0 0.5 -0.866025 0 0.5 -0.766044 0 0.642788 -0.642788 0 0.766044 -0.766044 0 0.642788 -0.642788 0 0.766044 -0.5 0 0.866026 -0.5 0 0.866026 -0.34202 0 0.939693 -0.173648 0 0.984808 -0.34202 0 0.939693 -0.173648 0 0.984808 1.74846e-07 0 1 1.74846e-07 0 1 0.173648 0 -0.984808 0.173648 0 -0.984808 0.34202 0 -0.939693 0.34202 0 -0.939693 0.5 0 -0.866025 0.642788 0 -0.766044 0.5 0 -0.866025 0.642788 0 -0.766044 0.766044 0 -0.642788 0.766044 0 -0.642788 0.866025 0 -0.5 0.939693 0 -0.34202 0.866025 0 -0.5 0.939693 0 -0.34202 0.984808 0 -0.173648 0.984808 0 -0.173648 1 0 7.54979e-08 0.984808 0 0.173648 1 0 -4.37114e-08 0.984808 0 0.173648 0.939693 0 0.34202 0.939693 0 0.34202 0.866025 0 0.5 0.766044 0 0.642788 0.866025 0 0.5 0.766044 0 0.642788 0.642788 0 0.766044 0.642788 0 0.766044 0.5 0 0.866025 0.34202 0 0.939693 0.5 0 0.866025 0.34202 0 0.939693 0.173648 0 0.984808 0.173648 0 0.984808 -1 0 -1.19249e-08 -0.984808 0 -0.173648 -1 0 -1.19249e-08 -8.74228e-08 0 1 0.173648 0 0.984808 -8.74228e-08 0 1 -0.939693 0 -0.34202 -0.984808 0 -0.173648 -0.939693 0 -0.34202 -0.866025 0 -0.5 -0.866025 0 -0.5 -0.766044 0 -0.642788 -0.642788 0 -0.766044 -0.766044 0 -0.642788 -0.642788 0 -0.766044 -0.5 0 -0.866026 -0.5 0 -0.866026 -0.34202 0 -0.939693 -0.173648 0 -0.984808 -0.34202 0 -0.939693 -0.173648 0 -0.984808 1.74846e-07 0 -1 1.74846e-07 0 -1 -0.984808 0 0.173648 -0.984808 0 0.173648 -0.939693 0 0.34202 -0.939692 0 0.342021 -0.866025 0 0.5 -0.766045 0 0.642788 -0.866025 0 0.5 -0.766045 0 0.642788 -0.642788 0 0.766044 -0.642788 0 0.766044 -0.5 0 0.866026 -0.34202 0 0.939693 -0.5 0 0.866025 -0.34202 0 0.939693 -0.173648 0 0.984808 -0.173648 0 0.984808 0.34202 0 0.939693 0.34202 0 0.939693 0.173648 0 0.984808 0.766044 0 0.642788 0.766044 0 0.642788 0.642788 0 0.766044 0.5 0 0.866025 0.642788 0 0.766044 0.5 0 0.866025 0.939693 0 0.34202 0.984808 0 0.173648 0.984808 0 0.173648 0.866025 0 0.5 0.866025 0 0.5 0.939693 0 0.34202 0.939693 0 -0.34202 0.984808 0 -0.173648 0.939693 0 -0.34202 0.984808 0 -0.173648 1 0 -7.54979e-08 1 0 4.37114e-08 0.642788 0 -0.766044 0.642788 0 -0.766044 0.766044 0 -0.642788 0.866025 0 -0.5 0.766044 0 -0.642788 0.866025 0 -0.5 0.5 0 -0.866025 0.5 0 -0.866025 0.34202 0 -0.939693 0.34202 0 -0.939693 0.173648 0 -0.984808 0.173648 0 -0.984808 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 - - - - - - - - - - - - - - -

0 2 1 3 5 4 6 5 0 1 6 0 5 3 7 5 6 4 8 10 9 11 13 12 14 11 9 14 13 11 8 9 15 14 9 10 16 18 17 16 17 19 20 22 21 21 23 20 24 26 25 27 29 28 30 32 31 33 35 34 28 24 27 36 38 37 39 41 40 42 44 43 45 47 46 48 50 49 51 44 42 52 54 53 49 52 55 56 58 57 59 56 57 60 62 61 63 60 61 64 66 65 62 60 67 68 70 69 65 72 71 73 75 74 73 69 70 68 62 67 67 70 68 66 77 76 78 80 79 81 83 82 84 60 63 85 79 58 84 54 52 84 63 54 86 88 87 52 53 55 89 90 51 88 51 90 91 50 92 48 93 50 94 44 95 46 91 92 47 45 96 95 44 37 37 97 36 96 41 47 27 41 39 36 33 34 98 99 34 27 39 29 100 102 101 59 104 103 104 86 103 80 78 82 55 48 49 93 92 50 91 46 47 41 96 40 26 24 28 30 25 32 30 24 25 105 30 106 31 106 30 107 100 105 107 105 106 108 100 101 105 100 108 102 110 109 101 102 109 102 34 99 110 102 99 98 34 35 97 33 36 95 37 38 43 44 94 89 51 42 87 88 90 104 88 86 57 104 59 85 58 56 80 58 79 77 83 81 83 80 82 77 66 64 77 81 76 64 65 71 72 74 71 73 70 75 74 75 71 111 113 112 114 116 115 117 119 118 112 113 120 121 123 122 122 120 124 125 127 126 128 127 129 130 131 118 131 130 126 132 134 133 135 137 136 138 140 139 141 134 142 140 144 143 140 143 139 145 117 135 146 143 144 147 148 146 147 146 144 123 149 147 149 148 147 150 128 129 149 123 121 151 153 152 154 156 155 157 155 152 158 156 159 156 154 160 158 161 156 111 163 162 161 165 164 163 116 162 161 164 166 167 166 168 114 115 169 167 168 170 169 171 114 168 173 172 174 175 169 173 176 172 174 177 175 178 173 179 177 174 180 181 183 182 184 180 174 185 187 186 174 188 184 189 188 190 122 124 121 151 150 153 191 120 113 120 191 124 112 163 111 163 115 116 169 175 171 189 184 188 190 186 192 186 190 188 192 186 187 193 194 185 185 186 193 193 181 182 193 182 194 195 183 196 183 195 182 195 197 179 196 197 195 195 179 173 178 176 173 170 168 172 166 167 161 158 165 161 160 159 156 157 154 155 151 152 155 128 150 151 126 127 128 126 130 125 117 118 131 135 136 145 117 145 119 137 132 136 133 134 141 137 134 132 141 142 138 140 138 142 198 200 199 201 203 202 204 206 205 207 200 208 209 211 210 212 210 213 214 216 215 214 218 217 219 221 220 205 216 204 222 224 223 225 226 222 227 229 228 229 231 230 231 221 232 230 231 232 225 234 233 219 232 221 219 220 235 236 237 206 211 238 220 238 235 220 217 218 239 238 211 209 240 242 241 243 208 200 240 244 243 245 247 246 245 246 248 249 198 199 245 251 250 252 253 198 251 203 250 198 253 254 255 254 256 257 201 202 258 254 255 202 259 257 260 255 261 259 263 262 260 261 264 259 265 263 266 261 267 263 265 268 269 271 270 272 268 265 273 275 274 265 276 272 276 278 277 210 212 209 239 241 242 213 248 246 210 248 213 247 245 250 251 202 203 259 262 257 277 272 276 275 273 278 275 278 276 279 280 275 274 275 280 281 279 270 281 280 279 282 269 270 279 282 270 271 284 283 269 284 271 271 267 261 283 267 271 266 264 261 258 255 260 253 256 254 249 252 198 207 199 200 244 208 243 242 240 243 217 239 242 215 218 214 204 216 214 233 237 236 236 206 204 233 226 225 233 234 237 226 224 222 223 224 228 229 227 231 228 224 227 285 287 286 288 290 289 285 291 287 292 294 293 291 288 287 295 297 296 298 300 299 301 303 302 304 305 302 306 308 307 309 311 310 312 314 313 312 307 315 316 318 317 318 320 319 321 323 322 323 324 317 325 327 326 328 329 322 330 332 331 326 331 333 334 335 332 330 334 332 325 326 333 330 331 326 327 325 328 322 329 321 328 325 329 317 324 316 324 323 321 319 320 313 320 318 316 314 312 315 319 313 314 308 306 310 308 315 307 309 303 311 306 309 310 302 305 301 303 301 311 295 304 297 305 304 295 296 300 298 297 300 296 299 294 292 299 292 298 289 290 293 289 293 294 290 288 291 336 338 337 339 341 340 342 344 343 345 347 346 348 350 349 351 353 352 354 356 355 357 359 358 359 361 360 362 364 363 365 367 366 368 370 369 362 369 371 372 374 373 375 376 373 377 379 378 380 381 377 382 384 383 385 387 386 388 390 389 391 393 392 394 396 395 397 399 398 400 402 401 403 405 404 406 407 401 401 402 406 408 407 409 406 409 407 408 411 410 411 408 409 412 413 410 410 411 412 414 413 415 412 415 413 414 417 416 417 414 415 418 419 416 416 417 418 420 419 421 418 421 419 420 423 422 423 420 421 424 425 422 422 423 424 426 425 427 424 427 425 428 426 427 403 404 400 400 404 402 429 405 430 430 405 403 394 395 429 429 430 394 396 397 431 395 396 431 399 432 398 397 398 431 432 390 388 390 432 399 433 389 393 433 388 389 391 392 383 433 393 391 382 385 384 392 382 383 387 379 386 385 386 384 380 377 378 378 379 387 372 381 374 374 381 380 375 368 376 376 372 373 369 370 371 368 375 370 367 363 364 362 371 364 365 366 358 363 367 365 357 361 359 366 357 358 352 353 360 361 352 360 354 355 351 351 355 353 345 356 347 347 356 354 350 346 349 350 345 346 348 339 340 348 349 339 341 342 343 340 341 343 336 337 344 342 336 344 434 436 435 437 436 438 434 438 436 437 440 439 440 437 438 441 442 439 439 440 441 443 445 444 441 445 442 446 444 447 444 446 443 447 449 448 448 446 447 450 451 449 448 449 451 452 450 453 450 452 451 454 456 455 457 459 458 453 457 458 460 459 461 457 461 459 460 462 454 462 460 461 455 456 463 454 462 456 453 458 452 455 463 464 443 442 445 465 467 466 464 465 466 468 469 467 466 467 469 470 468 471 468 470 469 471 473 472 472 470 471 474 475 473 472 473 475 463 465 464 474 476 475 477 479 478 476 477 478 480 481 479 478 479 481 482 480 483 480 482 481 477 476 474 434 435 484 484 486 485 486 484 435 487 488 485 485 486 487 489 488 490 487 490 488 489 492 491 492 489 490 493 494 491 491 492 493 495 494 496 493 496 494 495 498 497 498 495 496 499 500 497 497 498 499 501 500 502 499 502 500 501 504 503 504 501 502 505 506 503 503 504 505 507 506 508 505 508 506 507 510 509 510 507 508 511 512 509 509 510 511 513 512 514 511 514 512 513 516 515 516 513 514 517 518 515 515 516 517 519 518 520 517 520 518 519 522 521 522 519 520 523 524 521 521 522 523 525 524 526 523 526 524 525 528 527 528 525 526 529 530 527 527 528 529 529 531 530 532 534 533 535 536 533 532 533 536 535 538 537 537 536 535 539 538 540 538 539 537 541 542 540 539 540 542 541 544 543 543 542 541 545 544 546 544 545 543 547 548 546 545 546 548 547 550 549 549 548 547 551 550 552 550 551 549 553 554 552 551 552 554 553 556 555 555 554 553 557 556 558 556 557 555 559 560 558 557 558 560 559 562 561 561 560 559 563 562 564 562 563 561 565 566 564 563 564 566 565 568 567 567 566 565 568 569 567 570 534 532 570 572 571 571 534 570 573 572 574 572 573 571 575 576 574 573 574 576 575 578 577 577 576 575 579 578 580 578 579 577 581 582 580 579 580 582 581 584 583 583 582 581 585 584 586 584 585 583 587 588 586 585 586 588 587 590 589 589 588 587 591 590 592 590 591 589 593 594 592 591 592 594 593 596 595 595 594 593 597 596 598 596 597 595 599 600 598 597 598 600 599 602 601 601 600 599 603 602 569 602 603 601 603 569 568 604 606 605 607 609 608 610 611 605 604 605 611 610 613 612 612 611 610 614 613 615 613 614 612 616 617 615 614 615 617 616 619 618 618 617 616 620 619 621 619 620 618 622 623 621 620 621 623 622 625 624 624 623 622 625 626 624 627 606 604 627 629 628 628 606 627 630 629 631 629 630 628 632 633 631 630 631 633 632 635 634 634 633 632 636 635 637 635 636 634 638 639 637 636 637 639 638 641 640 640 639 638 642 641 609 641 642 640 643 645 644 642 609 607 646 648 647 649 651 650 652 654 653 655 657 656 658 660 659 661 663 662 664 666 665 667 669 668 670 671 664 664 665 670 671 673 672 673 671 670 674 672 675 673 675 672 626 625 674 674 675 626 668 666 667 666 668 665 669 660 658 667 660 669 661 659 663 658 659 661 654 662 653 662 663 653 656 657 652 657 654 652 646 647 655 646 655 656 648 649 650 648 650 647 651 643 644 649 643 651 608 645 607 644 645 608 676 678 677 679 681 680 682 684 683 685 687 686 688 690 689 691 693 692 692 694 691 689 690 694 692 689 694 688 684 682 690 688 682 683 685 686 683 684 685 677 686 687 678 676 695 677 687 676 696 678 695 696 679 680 679 696 695 681 697 680 698 697 699 681 699 697 700 701 698 698 699 700 701 703 702 703 701 700 702 703 704 705 707 706 708 710 709 710 705 706 707 711 706 709 704 708 710 708 705 704 709 702

-
-
-
- - - - 0.557468 -0.0204943 -0.2 0.529468 -0.0204943 0.2 0.557468 -0.0204943 0.2 0.529468 -0.0204943 -0.2 0.529468 -0.0204943 0.2 0.529468 -0.0484943 -0.2 0.529468 -0.0484943 0.2 0.529468 -0.0204943 -0.2 0.557468 -0.0484943 -0.2 0.557468 -0.0484943 0.2 0.529468 -0.0484943 0.2 0.529468 -0.0484943 -0.2 0.557468 -0.0484943 -0.2 0.557468 -0.0204943 -0.2 0.557468 -0.0204943 0.2 0.557468 -0.0484943 0.2 0.529468 -0.0204943 0.2 0.529468 -0.0484943 0.2 0.557468 -0.0484943 0.2 0.557468 -0.0204943 0.2 0.529468 -0.0204943 -0.2 0.557468 -0.0204943 -0.2 0.557468 -0.0484943 -0.2 0.529468 -0.0484943 -0.2 - - - - - - - - - - 0 1 0 0 1 0 0 1 0 0 1 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 - - - - - - - - - - - - - - -

0 1 2 1 0 3 4 5 6 4 7 5 8 9 10 10 11 8 12 13 14 12 14 15 16 17 18 16 18 19 20 21 22 22 23 20

-
-
-
- - - - -0.0245319 -0.0484943 0.2 0.529468 -0.0484943 0.2 0.529468 -0.0484943 0.172 -0.0245319 -0.0484943 0.172 -0.0245319 -0.0204943 0.172 0.529468 -0.0484943 0.172 0.529468 -0.0204943 0.172 -0.0245319 -0.0484943 0.172 0.529468 -0.0204943 0.172 0.529468 -0.0204943 0.2 -0.0245319 -0.0204943 0.2 -0.0245319 -0.0204943 0.172 0.529468 -0.0204943 0.2 0.529468 -0.0484943 0.2 -0.0245319 -0.0484943 0.2 -0.0245319 -0.0204943 0.2 0.529468 -0.0484943 0.2 0.529468 -0.0204943 0.2 0.529468 -0.0204943 0.172 0.529468 -0.0484943 0.172 -0.0245319 -0.0484943 0.2 -0.0245319 -0.0204943 0.172 -0.0245319 -0.0204943 0.2 -0.0245319 -0.0484943 0.172 - - - - - - - - - - -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 1 0 0 1 0 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 - - - - - - - - - - - - - - -

0 2 1 0 3 2 4 6 5 5 7 4 8 10 9 10 8 11 12 14 13 12 15 14 16 18 17 18 16 19 20 22 21 21 23 20

-
-
-
- - - - 0.023758 -0.0204943 -0.136198 0.023758 -0.0064943 -0.136198 0.0245999 -0.0064943 -0.136424 0.0254681 -0.0064943 -0.1365 0.0254681 -0.0204943 -0.1365 0.0245999 -0.0204943 -0.136424 0.0222542 -0.0064943 -0.13533 0.0216379 -0.0204943 -0.134714 0.0216379 -0.0064943 -0.134714 0.0222542 -0.0204943 -0.13533 0.0229681 -0.0064943 -0.13583 0.0229681 -0.0204943 -0.13583 0.0205441 -0.0204943 -0.132368 0.0205441 -0.0064943 -0.132368 0.0207696 -0.0064943 -0.13321 0.0207696 -0.0204943 -0.13321 0.021138 -0.0064943 -0.134 0.021138 -0.0204943 -0.134 0.0207696 -0.0064943 -0.12979 0.0205441 -0.0064943 -0.130632 0.0207696 -0.0204943 -0.12979 0.0204681 -0.0064943 -0.1315 0.0204681 -0.0204943 -0.1315 0.0205441 -0.0204943 -0.130632 0.0216379 -0.0064943 -0.128286 0.0222542 -0.0204943 -0.12767 0.0222542 -0.0064943 -0.12767 0.021138 -0.0204943 -0.129 0.0216379 -0.0204943 -0.128286 0.021138 -0.0064943 -0.129 0.0245999 -0.0204943 -0.126576 0.0245999 -0.0064943 -0.126576 0.023758 -0.0064943 -0.126802 0.023758 -0.0204943 -0.126802 0.0229681 -0.0064943 -0.12717 0.0229681 -0.0204943 -0.12717 0.0271782 -0.0064943 -0.126802 0.0263363 -0.0064943 -0.126576 0.0271782 -0.0204943 -0.126802 0.0254681 -0.0064943 -0.1265 0.0254681 -0.0204943 -0.1265 0.0263363 -0.0204943 -0.126576 0.028682 -0.0064943 -0.12767 0.0292983 -0.0204943 -0.128286 0.0292983 -0.0064943 -0.128286 0.0279681 -0.0204943 -0.12717 0.028682 -0.0204943 -0.12767 0.0279681 -0.0064943 -0.12717 0.0303921 -0.0204943 -0.130632 0.0303921 -0.0064943 -0.130632 0.0301666 -0.0064943 -0.12979 0.0301666 -0.0204943 -0.12979 0.0297982 -0.0064943 -0.129 0.0297982 -0.0204943 -0.129 0.0303921 -0.0204943 -0.132368 0.0303921 -0.0064943 -0.132368 0.0304681 -0.0064943 -0.1315 0.0304681 -0.0204943 -0.1315 0.0301666 -0.0204943 -0.13321 0.0301666 -0.0064943 -0.13321 0.0297982 -0.0064943 -0.134 0.0297982 -0.0204943 -0.134 0.0292983 -0.0204943 -0.134714 0.0292983 -0.0064943 -0.134714 0.028682 -0.0204943 -0.13533 0.028682 -0.0064943 -0.13533 0.0279681 -0.0064943 -0.13583 0.0279681 -0.0204943 -0.13583 0.0271782 -0.0204943 -0.136198 0.0271782 -0.0064943 -0.136198 0.0263363 -0.0204943 -0.136424 0.0263363 -0.0064943 -0.136424 -0.0245319 -0.0064943 -0.107 -0.0245319 -0.0064943 -0.057 -0.0245319 -0.0204943 -0.057 -0.0245319 -0.0204943 -0.107 0.0404681 -0.0064943 -0.172 -0.0245319 -0.0064943 -0.107 -0.0245319 -0.0204943 -0.107 0.0404681 -0.0204943 -0.172 0.0904681 -0.0064943 -0.172 0.0404681 -0.0064943 -0.172 0.0404681 -0.0204943 -0.172 0.0904681 -0.0204943 -0.172 0.0904681 -0.0064943 -0.172 0.0904681 -0.0204943 -0.172 -0.0245319 -0.0204943 -0.057 -0.0245319 -0.0064943 -0.057 0.0207696 -0.0064943 -0.13321 0.0205441 -0.0064943 -0.132368 -0.0245319 -0.0064943 -0.107 0.0216379 -0.0064943 -0.134714 0.0404681 -0.0064943 -0.172 0.0222542 -0.0064943 -0.13533 0.028682 -0.0064943 -0.12767 0.0292983 -0.0064943 -0.128286 0.0904681 -0.0064943 -0.172 0.023758 -0.0064943 -0.136198 0.0245999 -0.0064943 -0.136424 0.0254681 -0.0064943 -0.1365 0.0229681 -0.0064943 -0.13583 0.021138 -0.0064943 -0.134 0.0204681 -0.0064943 -0.1315 0.0205441 -0.0064943 -0.130632 0.0304681 -0.0064943 -0.1315 0.0303921 -0.0064943 -0.132368 0.0207696 -0.0064943 -0.12979 0.021138 -0.0064943 -0.129 0.0216379 -0.0064943 -0.128286 0.0222542 -0.0064943 -0.12767 0.0229681 -0.0064943 -0.12717 0.023758 -0.0064943 -0.126802 -0.0245319 -0.0064943 -0.057 0.0245999 -0.0064943 -0.126576 0.0263363 -0.0064943 -0.126576 0.0254681 -0.0064943 -0.1265 0.0279681 -0.0064943 -0.12717 0.0271782 -0.0064943 -0.126802 0.0301666 -0.0064943 -0.12979 0.0297982 -0.0064943 -0.129 0.0303921 -0.0064943 -0.130632 0.0301666 -0.0064943 -0.13321 0.0292983 -0.0064943 -0.134714 0.0297982 -0.0064943 -0.134 0.0279681 -0.0064943 -0.13583 0.028682 -0.0064943 -0.13533 0.0263363 -0.0064943 -0.136424 0.0271782 -0.0064943 -0.136198 0.0216379 -0.0204943 -0.134714 0.0222542 -0.0204943 -0.13533 0.0404681 -0.0204943 -0.172 0.0207696 -0.0204943 -0.13321 -0.0245319 -0.0204943 -0.107 0.0205441 -0.0204943 -0.132368 0.028682 -0.0204943 -0.12767 0.0904681 -0.0204943 -0.172 0.0292983 -0.0204943 -0.128286 0.023758 -0.0204943 -0.136198 0.0245999 -0.0204943 -0.136424 0.0254681 -0.0204943 -0.1365 0.0229681 -0.0204943 -0.13583 0.021138 -0.0204943 -0.134 0.0205441 -0.0204943 -0.130632 0.0204681 -0.0204943 -0.1315 0.0304681 -0.0204943 -0.1315 0.0303921 -0.0204943 -0.132368 0.021138 -0.0204943 -0.129 0.0207696 -0.0204943 -0.12979 0.0222542 -0.0204943 -0.12767 0.0216379 -0.0204943 -0.128286 0.023758 -0.0204943 -0.126802 0.0229681 -0.0204943 -0.12717 -0.0245319 -0.0204943 -0.057 0.0245999 -0.0204943 -0.126576 0.0263363 -0.0204943 -0.126576 0.0254681 -0.0204943 -0.1265 0.0279681 -0.0204943 -0.12717 0.0271782 -0.0204943 -0.126802 0.0301666 -0.0204943 -0.12979 0.0297982 -0.0204943 -0.129 0.0303921 -0.0204943 -0.130632 0.0301666 -0.0204943 -0.13321 0.0292983 -0.0204943 -0.134714 0.0297982 -0.0204943 -0.134 0.0279681 -0.0204943 -0.13583 0.028682 -0.0204943 -0.13533 0.0263363 -0.0204943 -0.136424 0.0271782 -0.0204943 -0.136198 - - - - - - - - - - 0.34202 0 0.939693 0.34202 0 0.939693 0.173648 0 0.984808 -1.74846e-07 0 1 -1.74846e-07 0 1 0.173648 0 0.984808 0.642788 0 0.766044 0.766044 0 0.642788 0.766044 0 0.642788 0.642788 0 0.766044 0.5 0 0.866026 0.5 0 0.866026 0.984808 0 0.173648 0.984808 0 0.173648 0.939693 0 0.34202 0.939693 0 0.34202 0.866025 0 0.5 0.866025 0 0.5 0.939692 0 -0.342021 0.984808 0 -0.173648 0.939693 0 -0.34202 1 0 1.19249e-08 1 0 1.19249e-08 0.984808 0 -0.173648 0.766045 0 -0.642788 0.642788 0 -0.766044 0.642788 0 -0.766044 0.866025 0 -0.5 0.766045 0 -0.642788 0.866025 0 -0.5 0.173648 0 -0.984808 0.173648 0 -0.984808 0.34202 0 -0.939693 0.34202 0 -0.939693 0.5 0 -0.866025 0.5 0 -0.866026 -0.34202 -0 -0.939693 -0.173648 -0 -0.984808 -0.34202 -0 -0.939693 8.74228e-08 0 -1 8.74228e-08 0 -1 -0.173648 -0 -0.984808 -0.642788 -0 -0.766044 -0.766044 -0 -0.642788 -0.766044 -0 -0.642788 -0.5 -0 -0.866025 -0.642788 -0 -0.766044 -0.5 -0 -0.866025 -0.984808 -0 -0.173648 -0.984808 -0 -0.173648 -0.939693 -0 -0.34202 -0.939693 -0 -0.34202 -0.866025 -0 -0.5 -0.866025 -0 -0.5 -0.984808 0 0.173648 -0.984808 0 0.173648 -1 -0 -4.37114e-08 -1 0 7.54979e-08 -0.939693 0 0.34202 -0.939693 0 0.34202 -0.866025 0 0.5 -0.866025 0 0.5 -0.766044 0 0.642788 -0.766044 0 0.642788 -0.642788 0 0.766044 -0.642788 0 0.766044 -0.5 0 0.866025 -0.5 0 0.866025 -0.34202 0 0.939693 -0.34202 0 0.939693 -0.173648 0 0.984808 -0.173648 0 0.984808 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 - - - - - - - - - - - - - - -

0 2 1 3 5 4 6 8 7 9 11 10 12 14 13 15 17 16 18 20 19 21 23 22 24 26 25 27 29 28 30 32 31 33 35 34 36 38 37 39 41 40 42 44 43 45 47 46 48 50 49 51 53 52 54 56 55 56 54 57 55 59 58 58 54 55 60 61 59 58 59 61 62 60 63 60 62 61 63 65 64 64 62 63 66 67 65 64 65 67 68 66 69 66 68 67 69 71 70 70 68 69 3 4 71 70 71 4 57 48 49 57 49 56 52 50 51 51 50 48 44 53 43 44 52 53 42 46 47 42 43 46 45 38 36 47 45 36 41 39 37 38 41 37 30 31 40 40 31 39 34 32 33 33 32 30 26 35 25 26 34 35 24 28 29 24 25 28 27 20 18 29 27 18 23 21 19 20 23 19 12 13 22 22 13 21 16 14 15 15 14 12 8 17 7 8 16 17 6 9 10 6 7 9 11 0 1 10 11 1 5 3 2 0 5 2 72 74 73 74 72 75 76 78 77 78 76 79 80 82 81 82 80 83 84 86 85 84 87 86 88 90 89 91 93 92 94 96 95 97 98 92 92 98 99 92 93 100 92 100 97 101 91 90 92 90 91 90 88 101 90 103 102 89 90 102 104 96 105 90 107 106 103 90 106 90 109 108 107 90 108 90 111 110 109 90 110 112 113 90 111 90 113 114 115 112 112 115 113 116 117 112 112 117 114 96 94 112 112 94 116 118 119 96 96 119 95 96 104 120 96 120 118 92 121 96 105 96 121 122 123 92 92 123 121 124 125 92 92 125 122 126 127 92 92 127 124 99 126 92 128 130 129 131 133 132 134 136 135 137 130 138 130 139 138 130 140 129 130 137 140 141 132 128 130 128 132 132 141 131 132 143 142 133 143 132 144 145 135 132 147 146 142 147 132 132 149 148 146 149 132 132 151 150 148 151 132 152 132 153 150 153 132 154 152 155 152 153 155 156 152 157 152 154 157 135 152 134 152 156 134 158 135 159 135 136 159 135 160 144 135 158 160 130 135 161 145 161 135 162 130 163 130 161 163 164 130 165 130 162 165 166 130 167 130 164 167 139 130 166

-
-
-
- - - - -0.0200729 -0.433 -0.0947737 -0.0340729 -0.542 0.0142263 -0.0200729 -0.542 0.0142263 -0.0340729 -0.433 -0.0947737 -0.0200729 -0.542 0.0142263 -0.0340729 -0.542 -0.0357737 -0.0200729 -0.542 -0.0357737 -0.0340729 -0.542 0.0142263 -0.0200729 -0.542 -0.0357737 -0.0340729 -0.483 -0.0947737 -0.0200729 -0.483 -0.0947737 -0.0340729 -0.542 -0.0357737 -0.0340729 -0.483 -0.0947737 -0.0340729 -0.433 -0.0947737 -0.0200729 -0.433 -0.0947737 -0.0200729 -0.483 -0.0947737 -0.0200729 -0.509319 -0.042524 -0.0200729 -0.542 0.0142263 -0.0200729 -0.50975 -0.0420926 -0.0200729 -0.542 -0.0357737 -0.0200729 -0.515447 -0.0453815 -0.0200729 -0.5155 -0.0447737 -0.0200729 -0.515031 -0.0430237 -0.0200729 -0.514681 -0.042524 -0.0200729 -0.51375 -0.0478048 -0.0200729 -0.483 -0.0947737 -0.0200729 -0.513197 -0.0480626 -0.0200729 -0.512608 -0.0482205 -0.0200729 -0.512 -0.0482737 -0.0200729 -0.514681 -0.0470235 -0.0200729 -0.51425 -0.0474549 -0.0200729 -0.515289 -0.0459708 -0.0200729 -0.515031 -0.0465237 -0.0200729 -0.515447 -0.044166 -0.0200729 -0.515289 -0.0435767 -0.0200729 -0.433 -0.0947737 -0.0200729 -0.508711 -0.0435767 -0.0200729 -0.508553 -0.044166 -0.0200729 -0.51425 -0.0420926 -0.0200729 -0.51375 -0.0417426 -0.0200729 -0.513197 -0.0414848 -0.0200729 -0.512608 -0.0413269 -0.0200729 -0.511392 -0.0413269 -0.0200729 -0.512 -0.0412737 -0.0200729 -0.51025 -0.0417426 -0.0200729 -0.510803 -0.0414848 -0.0200729 -0.508969 -0.0430237 -0.0200729 -0.5085 -0.0447737 -0.0200729 -0.508553 -0.0453815 -0.0200729 -0.508711 -0.0459708 -0.0200729 -0.509319 -0.0470235 -0.0200729 -0.508969 -0.0465237 -0.0200729 -0.51025 -0.0478048 -0.0200729 -0.50975 -0.0474549 -0.0200729 -0.511392 -0.0482205 -0.0200729 -0.510803 -0.0480626 -0.0340729 -0.508553 -0.044166 -0.0340729 -0.508711 -0.0435767 -0.0340729 -0.433 -0.0947737 -0.0340729 -0.542 0.0142263 -0.0340729 -0.509319 -0.042524 -0.0340729 -0.50975 -0.0420926 -0.0340729 -0.511392 -0.0413269 -0.0340729 -0.512 -0.0412737 -0.0340729 -0.51375 -0.0417426 -0.0340729 -0.542 -0.0357737 -0.0340729 -0.513197 -0.0414848 -0.0340729 -0.51375 -0.0478048 -0.0340729 -0.483 -0.0947737 -0.0340729 -0.51025 -0.0417426 -0.0340729 -0.510803 -0.0414848 -0.0340729 -0.508969 -0.0430237 -0.0340729 -0.508553 -0.0453815 -0.0340729 -0.5085 -0.0447737 -0.0340729 -0.508711 -0.0459708 -0.0340729 -0.509319 -0.0470235 -0.0340729 -0.508969 -0.0465237 -0.0340729 -0.51025 -0.0478048 -0.0340729 -0.50975 -0.0474549 -0.0340729 -0.511392 -0.0482205 -0.0340729 -0.510803 -0.0480626 -0.0340729 -0.512608 -0.0482205 -0.0340729 -0.512 -0.0482737 -0.0340729 -0.513197 -0.0480626 -0.0340729 -0.514681 -0.0470235 -0.0340729 -0.51425 -0.0474549 -0.0340729 -0.515289 -0.0459708 -0.0340729 -0.515031 -0.0465237 -0.0340729 -0.5155 -0.0447737 -0.0340729 -0.515447 -0.0453815 -0.0340729 -0.515289 -0.0435767 -0.0340729 -0.515447 -0.044166 -0.0340729 -0.514681 -0.042524 -0.0340729 -0.515031 -0.0430237 -0.0340729 -0.51425 -0.0420926 -0.0340729 -0.512608 -0.0413269 -0.0340729 -0.5155 -0.0447737 -0.0340729 -0.515447 -0.044166 -0.0200729 -0.515447 -0.044166 -0.0200729 -0.512 -0.0482737 -0.0340729 -0.511392 -0.0482205 -0.0340729 -0.512 -0.0482737 -0.0340729 -0.515289 -0.0435767 -0.0200729 -0.515289 -0.0435767 -0.0200729 -0.515031 -0.0430237 -0.0340729 -0.515031 -0.0430237 -0.0340729 -0.514681 -0.042524 -0.0200729 -0.514681 -0.042524 -0.0340729 -0.51425 -0.0420926 -0.0200729 -0.51425 -0.0420926 -0.0200729 -0.51375 -0.0417426 -0.0340729 -0.51375 -0.0417426 -0.0340729 -0.513197 -0.0414848 -0.0200729 -0.513197 -0.0414848 -0.0340729 -0.512608 -0.0413269 -0.0200729 -0.512608 -0.0413269 -0.0340729 -0.512 -0.0412737 -0.0200729 -0.512 -0.0412737 -0.0200729 -0.5155 -0.0447737 -0.0340729 -0.515447 -0.0453815 -0.0200729 -0.515447 -0.0453815 -0.0340729 -0.515289 -0.0459708 -0.0200729 -0.515289 -0.0459708 -0.0340729 -0.515031 -0.0465237 -0.0340729 -0.514681 -0.0470235 -0.0200729 -0.515031 -0.0465237 -0.0200729 -0.514681 -0.0470235 -0.0340729 -0.51425 -0.0474549 -0.0200729 -0.51425 -0.0474549 -0.0340729 -0.51375 -0.0478048 -0.0340729 -0.513197 -0.0480626 -0.0200729 -0.51375 -0.0478048 -0.0200729 -0.513197 -0.0480626 -0.0340729 -0.512608 -0.0482205 -0.0200729 -0.512608 -0.0482205 -0.0200729 -0.510803 -0.0480626 -0.0340729 -0.510803 -0.0480626 -0.0200729 -0.511392 -0.0482205 -0.0200729 -0.509319 -0.0470235 -0.0340729 -0.509319 -0.0470235 -0.0200729 -0.50975 -0.0474549 -0.0200729 -0.51025 -0.0478048 -0.0340729 -0.50975 -0.0474549 -0.0340729 -0.51025 -0.0478048 -0.0200729 -0.508711 -0.0459708 -0.0200729 -0.508553 -0.0453815 -0.0340729 -0.508553 -0.0453815 -0.0340729 -0.508969 -0.0465237 -0.0200729 -0.508969 -0.0465237 -0.0340729 -0.508711 -0.0459708 -0.0340729 -0.508711 -0.0435767 -0.0200729 -0.508553 -0.044166 -0.0200729 -0.508711 -0.0435767 -0.0340729 -0.508553 -0.044166 -0.0340729 -0.5085 -0.0447737 -0.0200729 -0.5085 -0.0447737 -0.0200729 -0.50975 -0.0420926 -0.0340729 -0.50975 -0.0420926 -0.0200729 -0.509319 -0.042524 -0.0200729 -0.508969 -0.0430237 -0.0340729 -0.509319 -0.042524 -0.0340729 -0.508969 -0.0430237 -0.0340729 -0.51025 -0.0417426 -0.0200729 -0.51025 -0.0417426 -0.0200729 -0.510803 -0.0414848 -0.0340729 -0.510803 -0.0414848 -0.0200729 -0.511392 -0.0413269 -0.0340729 -0.511392 -0.0413269 - - - - - - - - - - 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 0 1 -1.19249e-08 0 0.984808 -0.173648 0 0.984808 -0.173648 0 8.74228e-08 1 0 -0.173648 0.984808 0 8.74228e-08 1 0 0.939693 -0.34202 0 0.939693 -0.34202 0 0.866025 -0.5 0 0.866025 -0.5 0 0.766044 -0.642788 0 0.766044 -0.642788 0 0.642788 -0.766044 0 0.642788 -0.766044 0 0.5 -0.866026 0 0.5 -0.866026 0 0.34202 -0.939693 0 0.34202 -0.939693 0 0.173648 -0.984808 0 0.173648 -0.984808 -0 -1.74846e-07 -1 -0 -1.74846e-07 -1 0 1 -1.19249e-08 0 0.984808 0.173648 0 0.984808 0.173648 0 0.939693 0.34202 0 0.939692 0.342021 0 0.866025 0.5 0 0.766045 0.642788 0 0.866025 0.5 0 0.766045 0.642788 0 0.642788 0.766044 0 0.642788 0.766044 0 0.5 0.866026 0 0.34202 0.939693 0 0.5 0.866025 0 0.34202 0.939693 0 0.173648 0.984808 0 0.173648 0.984808 0 -0.34202 0.939693 0 -0.34202 0.939693 0 -0.173648 0.984808 0 -0.766044 0.642788 0 -0.766044 0.642788 0 -0.642788 0.766044 0 -0.5 0.866025 0 -0.642788 0.766044 0 -0.5 0.866025 0 -0.939693 0.34202 0 -0.984808 0.173648 0 -0.984808 0.173648 0 -0.866025 0.5 0 -0.866025 0.5 0 -0.939693 0.34202 -0 -0.939693 -0.34202 -0 -0.984808 -0.173648 -0 -0.939693 -0.34202 -0 -0.984808 -0.173648 -0 -1 -7.54979e-08 0 -1 4.37114e-08 -0 -0.642788 -0.766044 -0 -0.642788 -0.766044 -0 -0.766044 -0.642788 -0 -0.866025 -0.5 -0 -0.766044 -0.642788 -0 -0.866025 -0.5 -0 -0.5 -0.866025 -0 -0.5 -0.866025 -0 -0.34202 -0.939693 -0 -0.34202 -0.939693 -0 -0.173648 -0.984808 -0 -0.173648 -0.984808 - - - - - - - - - - - - - - -

0 1 2 1 0 3 4 5 6 5 4 7 8 9 10 9 8 11 12 13 14 12 14 15 16 17 18 19 20 21 22 23 19 24 19 25 26 25 27 25 28 27 25 26 24 29 19 30 19 24 30 31 19 32 19 29 32 19 31 20 19 33 34 21 33 19 35 36 37 34 22 19 19 38 39 23 38 19 17 19 40 39 40 19 17 40 41 42 17 43 17 41 43 44 17 45 17 42 45 17 44 18 46 35 16 17 16 35 35 46 36 35 47 48 37 47 35 49 25 48 35 48 25 50 25 51 25 49 51 52 25 53 25 50 53 54 25 55 25 52 55 28 25 54 56 57 58 59 60 61 62 63 59 64 65 66 65 67 68 69 70 59 59 70 62 59 61 69 71 60 58 59 58 60 58 57 71 58 72 73 56 58 73 74 72 68 58 68 72 75 76 68 68 76 74 77 78 68 68 78 75 79 80 68 68 80 77 81 82 68 68 82 79 68 67 83 68 83 81 84 85 65 65 85 67 86 87 65 65 87 84 88 89 65 65 89 86 90 91 65 65 91 88 92 93 65 65 93 90 64 94 65 65 94 92 65 59 66 63 95 59 59 95 66 96 97 98 99 100 101 102 103 97 98 97 103 104 102 105 102 104 103 105 106 107 107 104 105 108 109 106 107 106 109 110 108 111 108 110 109 111 112 113 113 110 111 114 115 112 113 112 115 114 116 117 114 117 115 118 96 98 118 119 96 119 120 121 120 119 118 122 123 121 121 120 122 124 123 125 122 125 123 124 126 127 126 124 125 128 129 127 127 126 128 130 129 131 128 131 129 130 132 133 132 130 131 134 101 133 133 132 134 135 136 137 134 99 101 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 156 163 156 162 157 163 164 165 165 162 163 166 167 164 165 164 167 116 166 117 166 116 167 160 159 158 158 157 160 161 150 152 159 161 152 153 155 151 150 153 151 146 145 154 154 145 155 148 144 149 149 144 146 138 147 139 138 148 147 140 142 141 140 139 142 143 136 135 141 143 135 100 99 137 136 100 137

-
-
-
- - - - -0.0525319 0.643506 -0.172 -0.0525319 -0.0204943 -0.172 -0.0245319 -0.0204943 -0.172 -0.0245319 0.643506 -0.172 -0.0525319 0.643506 -0.172 -0.0525319 0.643506 -0.2 -0.0525319 -0.0204943 -0.2 -0.0525319 -0.0204943 -0.172 -0.0525319 0.643506 -0.2 -0.0245319 0.643506 -0.2 -0.0245319 -0.0204943 -0.2 -0.0525319 -0.0204943 -0.2 -0.0245319 0.643506 -0.172 -0.0245319 -0.0204943 -0.172 -0.0245319 -0.0204943 -0.2 -0.0245319 0.643506 -0.2 -0.0525319 -0.0204943 -0.172 -0.0525319 -0.0204943 -0.2 -0.0245319 -0.0204943 -0.2 -0.0245319 -0.0204943 -0.172 -0.0525319 0.643506 -0.172 -0.0245319 0.643506 -0.172 -0.0245319 0.643506 -0.2 -0.0525319 0.643506 -0.2 - - - - - - - - - - 0 0 1 0 0 1 0 0 1 0 0 1 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 - - - - - - - - - - - - - - -

0 1 2 0 2 3 4 5 6 6 7 4 8 9 10 10 11 8 12 13 14 12 14 15 16 17 18 16 18 19 20 21 22 22 23 20

-
-
-
- - - - -0.0245319 -0.0204943 -0.172 0.529468 -0.0484943 -0.172 0.529468 -0.0204943 -0.172 -0.0245319 -0.0484943 -0.172 -0.0245319 -0.0484943 -0.172 0.529468 -0.0484943 -0.2 0.529468 -0.0484943 -0.172 -0.0245319 -0.0484943 -0.2 -0.0245319 -0.0484943 -0.2 -0.0245319 -0.0204943 -0.2 0.529468 -0.0204943 -0.2 0.529468 -0.0484943 -0.2 0.529468 -0.0204943 -0.2 -0.0245319 -0.0204943 -0.172 0.529468 -0.0204943 -0.172 -0.0245319 -0.0204943 -0.2 0.529468 -0.0484943 -0.172 0.529468 -0.0484943 -0.2 0.529468 -0.0204943 -0.2 0.529468 -0.0204943 -0.172 -0.0245319 -0.0484943 -0.172 -0.0245319 -0.0204943 -0.172 -0.0245319 -0.0204943 -0.2 -0.0245319 -0.0484943 -0.2 - - - - - - - - - - 0 0 1 0 0 1 0 0 1 0 0 1 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 - - - - - - - - - - - - - - -

0 1 2 1 0 3 4 5 6 4 7 5 8 9 10 8 10 11 12 13 14 13 12 15 16 17 18 16 18 19 20 21 22 22 23 20

-
-
-
- - - - 0.261968 0.214506 0.033 0.261968 0.242506 0.033 0.242968 0.242506 0.033 0.242968 0.214506 0.033 -0.0245319 0.242506 0.033 0.214968 0.214506 0.033 0.214968 0.242506 0.033 -0.0245319 0.214506 0.033 0.289968 0.242506 0.033 0.529468 0.214506 0.033 0.529468 0.242506 0.033 0.289968 0.214506 0.033 0.242968 0.214506 0.033 -0.0245319 0.214506 0.005 0.529468 0.214506 0.005 0.261968 0.214506 0.033 0.242968 0.214506 0.768 0.214968 0.214506 0.768 0.261968 0.214506 0.768 0.289968 0.214506 0.033 0.289968 0.214506 0.768 0.214968 0.214506 0.033 0.529468 0.214506 0.033 -0.0245319 0.214506 0.033 -0.0245319 0.242506 0.005 0.529468 0.242506 0.005 0.529468 0.214506 0.005 -0.0245319 0.214506 0.005 0.214968 0.242506 0.033 -0.0245319 0.242506 0.005 -0.0245319 0.242506 0.033 0.242968 0.242506 0.033 0.214968 0.242506 0.768 0.242968 0.242506 0.768 0.261968 0.242506 0.033 0.529468 0.242506 0.005 0.261968 0.242506 0.768 0.289968 0.242506 0.768 0.289968 0.242506 0.033 0.529468 0.242506 0.033 0.529468 0.214506 0.033 0.529468 0.242506 0.005 0.529468 0.242506 0.033 0.529468 0.214506 0.005 -0.0245319 0.214506 0.033 -0.0245319 0.242506 0.033 -0.0245319 0.242506 0.005 -0.0245319 0.214506 0.005 0.214968 0.214506 0.033 0.214968 0.242506 0.768 0.214968 0.242506 0.033 0.214968 0.214506 0.768 0.242968 0.242506 0.033 0.242968 0.242506 0.768 0.242968 0.214506 0.768 0.242968 0.214506 0.033 0.261968 0.242506 0.033 0.261968 0.214506 0.768 0.261968 0.242506 0.768 0.261968 0.214506 0.033 0.289968 0.242506 0.768 0.289968 0.214506 0.768 0.289968 0.214506 0.033 0.289968 0.242506 0.033 0.214968 0.242506 0.768 0.242968 0.214506 0.768 0.242968 0.242506 0.768 0.214968 0.214506 0.768 0.261968 0.242506 0.768 0.289968 0.214506 0.768 0.289968 0.242506 0.768 0.261968 0.214506 0.768 - - - - - - - - - - 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 - - - - - - - - - - - - - - -

0 1 2 0 2 3 4 5 6 5 4 7 8 9 10 9 8 11 12 13 14 12 14 15 12 16 17 18 19 20 21 13 12 14 19 15 17 21 12 22 19 14 18 15 19 21 23 13 24 25 26 26 27 24 28 29 30 29 28 31 31 32 33 31 34 35 36 37 38 38 39 35 35 34 38 32 31 28 35 29 31 36 38 34 40 41 42 41 40 43 44 45 46 46 47 44 48 49 50 48 51 49 52 53 54 54 55 52 56 57 58 57 56 59 60 61 62 60 62 63 64 65 66 65 64 67 68 69 70 69 68 71

-
-
-
- - - - -0.0245319 0.671506 0.2 -0.0525319 0.671506 0.478 -0.0245319 0.671506 0.478 -0.0525319 0.671506 0.2 -0.0525319 0.671506 0.478 -0.0525319 0.643506 0.2 -0.0525319 0.643506 0.478 -0.0525319 0.671506 0.2 -0.0245319 0.643506 0.2 -0.0245319 0.643506 0.478 -0.0525319 0.643506 0.478 -0.0525319 0.643506 0.2 -0.0245319 0.643506 0.478 -0.0245319 0.671506 0.2 -0.0245319 0.671506 0.478 -0.0245319 0.643506 0.2 -0.0525319 0.671506 0.478 -0.0525319 0.643506 0.478 -0.0245319 0.643506 0.478 -0.0245319 0.671506 0.478 -0.0525319 0.671506 0.2 -0.0245319 0.671506 0.2 -0.0245319 0.643506 0.2 -0.0525319 0.643506 0.2 - - - - - - - - - - 0 1 0 0 1 0 0 1 0 0 1 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 1 1.23909e-16 0 1 1.23909e-16 0 1 1.23909e-16 0 1 1.23909e-16 0 0 0 1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 - - - - - - - - - - - - - - -

0 1 2 1 0 3 4 5 6 4 7 5 8 9 10 10 11 8 12 13 14 13 12 15 16 17 18 16 18 19 20 21 22 22 23 20

-
-
-
- - - - -0.000626526 0.00998029 0 -0.000622683 0.00998057 0.00901385 0.000617957 0.00998075 0.00901365 0.00992113 -0.00125348 0 0.01 2.83277e-18 0.01 0.00991813 -0.001277 0.01 -0.00184828 0.00982771 0.00912254 -0.0018725 0.00982307 0 -0.00308896 0.00951091 0 -0.00303313 0.00952889 0.00933252 -0.00425672 0.00904873 0 -0.00415287 0.00909673 0.00963012 -0.00519615 0.008544 0.01 -0.00535734 0.00844383 0 -0.00637348 0.00770573 0 -0.00624468 0.00781051 0.01 -0.00728909 0.00684607 0 -0.00719095 0.00694911 0.01 -0.00801948 0.00597394 0.01 -0.00808974 0.00587842 0 -0.00876278 0.00481804 0 -0.0087167 0.00490094 0.01 -0.0092976 0.00368165 0 -0.00927118 0.0037477 0.01 -0.00967386 0.00253309 0.01 -0.00968576 0.00248719 0 -0.00992113 0.00125348 0 -0.00991813 0.001277 0.01 -0.01 6.12323e-19 0 -0.01 6.12323e-19 0.01 0.000629313 0.00998011 0 0.00184372 0.00982838 0.00912193 0.00187521 0.00982253 0 0.00302838 0.00953031 0.00933146 0.00309151 0.00951004 0 0.00425903 0.00904759 0 0.00415069 0.00909786 0.00962944 0.00519615 0.008544 0.01 0.00535937 0.00844247 0 0.00624468 0.00781051 0.01 0.00637518 0.00770424 0 0.00729044 0.00684454 0 0.00719095 0.00694911 0.01 0.00801948 0.00597394 0.01 0.00809073 0.00587694 0 0.0087167 0.00490094 0.01 0.00876344 0.00481669 0 0.00927118 0.0037477 0.01 0.00967386 0.00253309 0.01 0.00929798 0.00368054 0 0.00991813 0.001277 0.01 0.00968592 0.00248638 0 0.00992113 0.00125348 0 0.01 1.83697e-18 0 0.0087167 -0.00490094 0.01 0.00876278 -0.00481804 0 0.00927118 -0.0037477 0.01 0.00967386 -0.00253309 0.01 0.0092976 -0.00368165 0 0.00968576 -0.00248719 0 0.00637348 -0.00770573 0 0.00719095 -0.00694911 0.01 0.00624468 -0.00781051 0.01 0.00808974 -0.00587842 0 0.00801948 -0.00597394 0.01 0.00728909 -0.00684607 0 0.00415287 -0.00909673 0.00963012 0.00303313 -0.00952889 0.00933252 0.00308896 -0.00951091 0 0.00519615 -0.008544 0.01 0.00425672 -0.00904873 0 0.00535734 -0.00844383 0 0.00184828 -0.00982771 0.00912254 0.000626526 -0.00998029 0 0.0018725 -0.00982307 0 -0.000617957 -0.00998075 0.00901365 -0.000629313 -0.00998011 0 0.000622683 -0.00998057 0.00901385 -0.00425903 -0.00904759 0 -0.00415069 -0.00909786 0.00962944 -0.00519615 -0.008544 0.01 -0.00187521 -0.00982253 0 -0.00184372 -0.00982838 0.00912193 -0.00302838 -0.00953031 0.00933146 -0.00719095 -0.00694911 0.01 -0.00801948 -0.00597394 0.01 -0.00729044 -0.00684454 0 -0.00637518 -0.00770424 0 -0.00624468 -0.00781051 0.01 -0.00927118 -0.0037477 0.01 -0.00929798 -0.00368054 0 -0.00876344 -0.00481669 0 -0.00809073 -0.00587694 0 -0.0087167 -0.00490094 0.01 -0.00967386 -0.00253309 0.01 -0.00968592 -0.00248638 0 -0.00992113 -0.00125348 0 -0.00991813 -0.001277 0.01 -0.00535937 -0.00844247 0 -0.00309151 -0.00951004 0 0.00991813 0.001277 0.01 0.00991813 -0.001277 0.01 0.01 2.83277e-18 0.01 0.00719095 -0.00694911 0.01 0.00801948 -0.00597394 0.01 0.00719095 0.00694911 0.01 0.00967386 0.00253309 0.01 0.00967386 -0.00253309 0.01 0.00927118 -0.0037477 0.01 0.00927118 0.0037477 0.01 0.0087167 0.00490094 0.01 0.0087167 -0.00490094 0.01 0.00801948 0.00597394 0.01 0.00624468 0.00781051 0.01 0.00519615 0.008544 0.01 0.00624468 -0.00781051 0.01 0.00519615 -0.008544 0.01 -0.00991813 0.001277 0.01 -0.01 6.12323e-19 0.01 -0.00991813 -0.001277 0.01 -0.00967386 -0.00253309 0.01 -0.00967386 0.00253309 0.01 -0.00927118 -0.0037477 0.01 -0.00927118 0.0037477 0.01 -0.0087167 -0.00490094 0.01 -0.0087167 0.00490094 0.01 -0.00801948 -0.00597394 0.01 -0.00801948 0.00597394 0.01 -0.00719095 -0.00694911 0.01 -0.00624468 -0.00781051 0.01 -0.00719095 0.00694911 0.01 -0.00624468 0.00781051 0.01 -0.00519615 -0.008544 0.01 -0.00519615 0.008544 0.01 -0.00535734 0.00844383 0 -0.00425672 0.00904873 0 0.00876278 -0.00481804 0 0.00535937 0.00844247 0 0.00637518 0.00770424 0 0.00809073 0.00587694 0 0.00729044 0.00684454 0 0.00876344 0.00481669 0 0.00425903 0.00904759 0 0.00929798 0.00368054 0 0.00309151 0.00951004 0 0.00187521 0.00982253 0 0.00968592 0.00248638 0 0.00992113 0.00125348 0 0.000629313 0.00998011 0 0.01 1.83697e-18 0 -0.000626526 0.00998029 0 -0.00308896 0.00951091 0 0.00968576 -0.00248719 0 0.0092976 -0.00368165 0 -0.0018725 0.00982307 0 0.00992113 -0.00125348 0 -0.00728909 0.00684607 0 0.00637348 -0.00770573 0 -0.00808974 0.00587842 0 0.00728909 -0.00684607 0 -0.00637348 0.00770573 0 0.00808974 -0.00587842 0 0.00425672 -0.00904873 0 -0.00876278 0.00481804 0 0.00535734 -0.00844383 0 -0.00992113 0.00125348 0 0.0018725 -0.00982307 0 0.000626526 -0.00998029 0 -0.00968576 0.00248719 0 -0.0092976 0.00368165 0 0.00308896 -0.00951091 0 -0.00309151 -0.00951004 0 -0.00968592 -0.00248638 0 -0.00187521 -0.00982253 0 -0.000629313 -0.00998011 0 -0.00992113 -0.00125348 0 -0.01 6.12323e-19 0 -0.00535937 -0.00844247 0 -0.00637518 -0.00770424 0 -0.00809073 -0.00587694 0 -0.00929798 -0.00368054 0 -0.00425903 -0.00904759 0 -0.00876344 -0.00481669 0 -0.00729044 -0.00684454 0 -0.0139795 0.0125 0.0237579 -0.0139795 0.0125 0.0222421 -0.0139795 -0.0125 0.0237579 0.00151367 0.0125 0.00908207 0.00184372 0.00982838 0.00912193 0.000617957 0.00998075 0.00901365 -0.0138156 -0.0125 0.0252649 -0.0138156 0.0125 0.0252649 -0.0134897 -0.0125 0.0267454 -0.0134897 0.0125 0.0267454 -0.0130057 0.0125 0.0281819 -0.0130057 -0.0125 0.0281819 -0.0123692 -0.0125 0.0295577 -0.0123692 0.0125 0.0295577 -0.0115876 -0.0125 0.0308566 -0.0115876 0.0125 0.0308566 -0.0106703 0.0125 0.0320634 -0.0106703 -0.0125 0.0320634 -0.00962779 -0.0125 0.0331639 -0.00962779 0.0125 0.0331639 -0.00847244 -0.0125 0.0341453 -0.00847244 0.0125 0.0341453 -0.00721775 0.0125 0.034996 -0.00721775 -0.0125 0.034996 -0.00587845 -0.0125 0.0357061 -0.00587845 0.0125 0.0357061 -0.00447022 -0.0125 0.0362671 -0.00447022 0.0125 0.0362671 -0.00300959 0.0125 0.0366727 -0.00300959 -0.0125 0.0366727 -0.00151367 -0.0125 0.0369179 -0.00151367 0.0125 0.0369179 -3.42901e-18 -0.0125 0.037 -3.42901e-18 0.0125 0.037 -0.0139795 -0.0125 0.0222421 -0.0138156 0.0125 0.0207351 -0.0138156 -0.0125 0.0207351 -0.0134897 -0.0125 0.0192546 -0.0134897 0.0125 0.0192546 -0.0130057 0.0125 0.0178181 -0.0130057 -0.0125 0.0178181 -0.0123692 0.0125 0.0164423 -0.0123692 -0.0125 0.0164423 -0.0115876 -0.0125 0.0151434 -0.0115876 0.0125 0.0151434 -0.0106703 0.0125 0.0139366 -0.0106703 -0.0125 0.0139366 -0.00962779 0.0125 0.0128361 -0.00962779 -0.0125 0.0128361 -0.00847244 -0.0125 0.0118547 -0.00847244 0.0125 0.0118547 -0.00721775 0.0125 0.011004 -0.00721775 -0.0125 0.011004 -0.00587845 0.0125 0.0102939 -0.00587845 -0.0125 0.0102939 -0.00447022 0.0125 0.00973286 -0.00519615 0.008544 0.01 -0.00184828 0.00982771 0.00912254 -0.00303313 0.00952889 0.00933252 -0.00300959 0.0125 0.00932731 -0.00415287 0.00909673 0.00963012 -0.00184372 -0.00982838 0.00912193 -0.00300959 -0.0125 0.00932731 -0.00302838 -0.00953031 0.00933146 -0.00151367 0.0125 0.00908207 -0.000622683 0.00998057 0.00901385 1.71451e-18 0.0125 0.009 0.000622683 -0.00998057 0.00901385 0.00184828 -0.00982771 0.00912254 0.00151367 -0.0125 0.00908207 -0.000617957 -0.00998075 0.00901365 -0.00151367 -0.0125 0.00908207 0.00721775 -0.0125 0.011004 0.00587845 -0.0125 0.0102939 0.00721775 0.0125 0.011004 0.00447022 0.0125 0.00973286 0.00587845 0.0125 0.0102939 0.00519615 0.008544 0.01 0.00962779 -0.0125 0.0128361 0.0106703 0.0125 0.0139366 0.0106703 -0.0125 0.0139366 0.00847244 0.0125 0.0118547 0.00962779 0.0125 0.0128361 0.00847244 -0.0125 0.0118547 0.0130057 0.0125 0.0178181 0.0130057 -0.0125 0.0178181 0.0123692 -0.0125 0.0164423 0.0123692 0.0125 0.0164423 0.0115876 -0.0125 0.0151434 0.0115876 0.0125 0.0151434 0.0139795 -0.0125 0.0222421 0.0138156 -0.0125 0.0207351 0.0139795 0.0125 0.0222421 0.0134897 -0.0125 0.0192546 0.0134897 0.0125 0.0192546 0.0138156 0.0125 0.0207351 0.0138156 -0.0125 0.0252649 0.0134897 0.0125 0.0267454 0.0134897 -0.0125 0.0267454 0.0139795 0.0125 0.0237579 0.0138156 0.0125 0.0252649 0.0139795 -0.0125 0.0237579 0.0115876 0.0125 0.0308566 0.0115876 -0.0125 0.0308566 0.0123692 -0.0125 0.0295577 0.0123692 0.0125 0.0295577 0.0130057 -0.0125 0.0281819 0.0130057 0.0125 0.0281819 0.00847244 0.0125 0.0341453 0.00962779 -0.0125 0.0331639 0.00962779 0.0125 0.0331639 0.0106703 -0.0125 0.0320634 0.0106703 0.0125 0.0320634 0.00721775 0.0125 0.034996 0.00847244 -0.0125 0.0341453 0.00721775 -0.0125 0.034996 0.00587845 0.0125 0.0357061 0.00447022 0.0125 0.0362671 0.00587845 -0.0125 0.0357061 0.00300959 0.0125 0.0366727 0.00447022 -0.0125 0.0362671 0.00300959 -0.0125 0.0366727 0.00151367 0.0125 0.0369179 0.00151367 -0.0125 0.0369179 0.00303313 -0.00952889 0.00933252 0.00415287 -0.00909673 0.00963012 0.00300959 -0.0125 0.00932731 0.00300959 0.0125 0.00932731 0.00302838 0.00953031 0.00933146 0.00415069 0.00909786 0.00962944 1.71451e-18 -0.0125 0.009 0.00519615 -0.008544 0.01 0.00447022 -0.0125 0.00973286 -0.00519615 -0.008544 0.01 -0.00415069 -0.00909786 0.00962944 -0.00447022 -0.0125 0.00973286 -0.00447022 -0.0125 0.0362671 -0.00587845 -0.0125 0.0357061 0.0123692 -0.0125 0.0164423 0.00587845 -0.0125 0.0357061 0.00447022 -0.0125 0.0362671 0.0134897 -0.0125 0.0267454 0.0138156 -0.0125 0.0207351 -3.42901e-18 -0.0125 0.037 -0.00151367 -0.0125 0.0369179 0.0134897 -0.0125 0.0192546 -0.00300959 -0.0125 0.0366727 0.0130057 -0.0125 0.0178181 0.00300959 -0.0125 0.0366727 0.0138156 -0.0125 0.0252649 0.00151367 -0.0125 0.0369179 0.0139795 -0.0125 0.0222421 0.0139795 -0.0125 0.0237579 0.00721775 -0.0125 0.034996 0.0123692 -0.0125 0.0295577 0.00847244 -0.0125 0.0341453 0.0130057 -0.0125 0.0281819 0.00962779 -0.0125 0.0331639 0.0115876 -0.0125 0.0308566 0.0106703 -0.0125 0.0320634 0.0115876 -0.0125 0.0151434 0.0106703 -0.0125 0.0139366 -0.00721775 -0.0125 0.034996 -0.00847244 -0.0125 0.0341453 0.00962779 -0.0125 0.0128361 -0.00962779 -0.0125 0.0331639 0.00847244 -0.0125 0.0118547 0.00721775 -0.0125 0.011004 -0.0106703 -0.0125 0.0320634 -0.0115876 -0.0125 0.0308566 0.00587845 -0.0125 0.0102939 -0.0123692 -0.0125 0.0295577 -0.0130057 -0.0125 0.0281819 0.00447022 -0.0125 0.00973286 -0.0134897 -0.0125 0.0267454 0.00300959 -0.0125 0.00932731 0.00151367 -0.0125 0.00908207 -0.0138156 -0.0125 0.0252649 -0.0139795 -0.0125 0.0237579 1.71451e-18 -0.0125 0.009 -0.0138156 -0.0125 0.0207351 -0.0134897 -0.0125 0.0192546 -0.00447022 -0.0125 0.00973286 -0.0139795 -0.0125 0.0222421 -0.00300959 -0.0125 0.00932731 -0.00151367 -0.0125 0.00908207 -0.0115876 -0.0125 0.0151434 -0.00847244 -0.0125 0.0118547 -0.0123692 -0.0125 0.0164423 -0.00721775 -0.0125 0.011004 -0.00587845 -0.0125 0.0102939 -0.0130057 -0.0125 0.0178181 -0.00962779 -0.0125 0.0128361 -0.0106703 -0.0125 0.0139366 -0.0115876 0.0125 0.0308566 -0.0106703 0.0125 0.0320634 -0.00268116 0.0125 0.0252498 -0.00300959 0.0125 0.0366727 -0.00151367 0.0125 0.0369179 -0.000607769 0.0125 0.0264468 -0.00721775 0.0125 0.034996 -0.00175 0.0125 0.0260311 -0.00847244 0.0125 0.0341453 0.00344683 0.0125 0.0236078 0.00328892 0.0125 0.0241971 0.0134897 0.0125 0.0267454 -0.00447022 0.0125 0.0362671 0.00303109 0.0125 0.02475 0.00268116 0.0125 0.0252498 0.0115876 0.0125 0.0308566 -1.20059e-17 0.0125 0.0265 0.00151367 0.0125 0.0369179 0.000607769 0.0125 0.0264468 0.00224976 0.0125 0.0256812 0.00175 0.0125 0.0260311 0.00847244 0.0125 0.0341453 0.00300959 0.0125 0.0366727 0.00447022 0.0125 0.0362671 0.00119707 0.0125 0.0262889 0.00587845 0.0125 0.0357061 0.00721775 0.0125 0.034996 0.00962779 0.0125 0.0331639 -3.42901e-18 0.0125 0.037 0.0106703 0.0125 0.0320634 -0.00587845 0.0125 0.0357061 -0.00119707 0.0125 0.0262889 0.0130057 0.0125 0.0281819 0.0123692 0.0125 0.0295577 -0.00962779 0.0125 0.0331639 -0.00224976 0.0125 0.0256812 0.0139795 0.0125 0.0222421 0.0035 0.0125 0.023 0.0139795 0.0125 0.0237579 0.0138156 0.0125 0.0252649 0.0134897 0.0125 0.0192546 0.00344683 0.0125 0.0223922 0.0138156 0.0125 0.0207351 -0.00303109 0.0125 0.02475 -0.0123692 0.0125 0.0295577 0.00328892 0.0125 0.0218029 0.0130057 0.0125 0.0178181 -0.00328892 0.0125 0.0241971 -0.0130057 0.0125 0.0281819 -0.0134897 0.0125 0.0267454 0.0123692 0.0125 0.0164423 0.00303109 0.0125 0.02125 0.00268116 0.0125 0.0207502 0.0115876 0.0125 0.0151434 -0.0138156 0.0125 0.0252649 -0.00344683 0.0125 0.0236078 0.00175 0.0125 0.0199689 0.00224976 0.0125 0.0203188 0.00847244 0.0125 0.0118547 -0.0035 0.0125 0.023 -0.0139795 0.0125 0.0222421 -0.0139795 0.0125 0.0237579 -0.00344683 0.0125 0.0223922 -0.0134897 0.0125 0.0192546 -0.0138156 0.0125 0.0207351 0.00721775 0.0125 0.011004 0.00587845 0.0125 0.0102939 -0.00328892 0.0125 0.0218029 -0.0130057 0.0125 0.0178181 0.000607769 0.0125 0.0195532 0.00119707 0.0125 0.0197111 0.00447022 0.0125 0.00973286 -0.00303109 0.0125 0.02125 0.00300959 0.0125 0.00932731 0.00151367 0.0125 0.00908207 -0.0115876 0.0125 0.0151434 -0.0123692 0.0125 0.0164423 0 0.0125 0.0195 1.71451e-18 0.0125 0.009 -0.00962779 0.0125 0.0128361 -0.00268116 0.0125 0.0207502 -0.00224976 0.0125 0.0203188 -0.00151367 0.0125 0.00908207 -0.000607769 0.0125 0.0195532 -0.00847244 0.0125 0.0118547 -0.00175 0.0125 0.0199689 -0.00721775 0.0125 0.011004 -0.00447022 0.0125 0.00973286 -0.00119707 0.0125 0.0197111 -0.00300959 0.0125 0.00932731 -0.00587845 0.0125 0.0102939 0.00962779 0.0125 0.0128361 -0.0106703 0.0125 0.0139366 0.0106703 0.0125 0.0139366 -1.20059e-17 0.0125 0.0265 5.09156e-18 0.0375 0.0265 -0.000607769 0.0375 0.0264468 -0.00119707 0.0375 0.0262889 -0.000607769 0.0125 0.0264468 -0.00175 0.0375 0.0260311 -0.00119707 0.0125 0.0262889 -0.00175 0.0125 0.0260311 -0.00224976 0.0375 0.0256812 -0.00268116 0.0375 0.0252498 -0.00224976 0.0125 0.0256812 -0.00303109 0.0375 0.02475 -0.00268116 0.0125 0.0252498 -0.00303109 0.0125 0.02475 -0.00328892 0.0375 0.0241971 -0.00344683 0.0375 0.0236078 -0.00328892 0.0125 0.0241971 -0.0035 0.0375 0.023 -0.00344683 0.0125 0.0236078 -0.0035 0.0125 0.023 -0.00344683 0.0375 0.0223922 -0.00328892 0.0375 0.0218029 -0.00344683 0.0125 0.0223922 -0.00303109 0.0375 0.02125 -0.00328892 0.0125 0.0218029 -0.00303109 0.0125 0.02125 -0.00268116 0.0375 0.0207502 -0.00224976 0.0375 0.0203188 -0.00268116 0.0125 0.0207502 -0.00175 0.0375 0.0199689 -0.00224976 0.0125 0.0203188 -0.00175 0.0125 0.0199689 -0.00119707 0.0375 0.0197111 -0.000607769 0.0375 0.0195532 -0.00119707 0.0125 0.0197111 0 0.0375 0.0195 -0.000607769 0.0125 0.0195532 0 0.0125 0.0195 0.000607769 0.0125 0.0264468 0.00119707 0.0125 0.0262889 0.000607769 0.0375 0.0264468 0.00119707 0.0375 0.0262889 0.00175 0.0125 0.0260311 0.00224976 0.0125 0.0256812 0.00175 0.0375 0.0260311 0.00268116 0.0125 0.0252498 0.00224976 0.0375 0.0256812 0.00268116 0.0375 0.0252498 0.00303109 0.0125 0.02475 0.00328892 0.0125 0.0241971 0.00303109 0.0375 0.02475 0.00344683 0.0125 0.0236078 0.00328892 0.0375 0.0241971 0.00344683 0.0375 0.0236078 0.0035 0.0125 0.023 0.00344683 0.0125 0.0223922 0.0035 0.0375 0.023 0.00328892 0.0125 0.0218029 0.00344683 0.0375 0.0223922 0.00328892 0.0375 0.0218029 0.00303109 0.0125 0.02125 0.00268116 0.0125 0.0207502 0.00303109 0.0375 0.02125 0.00224976 0.0125 0.0203188 0.00268116 0.0375 0.0207502 0.00224976 0.0375 0.0203188 0.00175 0.0125 0.0199689 0.00119707 0.0125 0.0197111 0.00175 0.0375 0.0199689 0.000607769 0.0125 0.0195532 0.00119707 0.0375 0.0197111 0.000607769 0.0375 0.0195532 0.00328892 0.0375 0.0218029 0.00303109 0.0375 0.02125 -0.00175 0.0375 0.0260311 0.00119707 0.0375 0.0262889 0.00303109 0.0375 0.02475 0.00328892 0.0375 0.0241971 0.0035 0.0375 0.023 5.09156e-18 0.0375 0.0265 0.00344683 0.0375 0.0236078 0.00344683 0.0375 0.0223922 -0.00119707 0.0375 0.0262889 -0.000607769 0.0375 0.0264468 0.00268116 0.0375 0.0252498 0.00175 0.0375 0.0260311 0.000607769 0.0375 0.0264468 0.00224976 0.0375 0.0256812 -0.00224976 0.0375 0.0256812 -0.00268116 0.0375 0.0252498 0.00268116 0.0375 0.0207502 0.00224976 0.0375 0.0203188 -0.00303109 0.0375 0.02475 0.00175 0.0375 0.0199689 -0.00328892 0.0375 0.0241971 0.00119707 0.0375 0.0197111 0.000607769 0.0375 0.0195532 -0.00344683 0.0375 0.0236078 0 0.0375 0.0195 -0.0035 0.0375 0.023 -0.000607769 0.0375 0.0195532 -0.00119707 0.0375 0.0197111 -0.00328892 0.0375 0.0218029 -0.00344683 0.0375 0.0223922 -0.00175 0.0375 0.0199689 -0.00224976 0.0375 0.0203188 -0.00268116 0.0375 0.0207502 -0.00303109 0.0375 0.02125 - - - - - - - - - - -0.0627906 0.998027 0 -0.0622684 0.998059 0 0.0617961 0.998089 0 0.992115 -0.125333 0 1 -8.74228e-08 0 0.991813 -0.1277 0 -0.184828 0.982771 0 -0.187381 0.982287 0 -0.309017 0.951057 0 -0.303314 0.952891 0 -0.425779 0.904827 0 -0.415289 0.90969 0 -0.519615 0.8544 0 -0.535827 0.844328 0 -0.637424 0.770513 0 -0.624468 0.781051 0 -0.728969 0.684547 0 -0.719095 0.694912 0 -0.801948 0.597394 0 -0.809017 0.587785 0 -0.876307 0.481754 0 -0.871669 0.490094 0 -0.929776 0.368125 0 -0.927118 0.37477 0 -0.967386 0.253309 0 -0.968583 0.24869 0 -0.992115 0.125333 0 -0.991813 0.1277 0 -1 1.82865e-12 0 -1 -3.80664e-29 0 0.0627906 0.998027 0 0.184373 0.982856 0 0.187381 0.982287 0 0.302839 0.953042 0 0.309017 0.951057 0 0.425779 0.904827 0 0.415069 0.90979 0 0.519615 0.8544 0 0.535827 0.844328 0 0.624468 0.781051 0 0.637424 0.770513 0 0.728969 0.684547 0 0.719095 0.694912 0 0.801948 0.597394 0 0.809017 0.587785 0 0.871669 0.490094 0 0.876307 0.481754 0 0.927118 0.37477 0 0.967386 0.253309 0 0.929777 0.368124 0 0.991813 0.1277 0 0.968583 0.24869 0 0.992115 0.125333 0 1 -8.74228e-08 0 0.871669 -0.490094 0 0.876307 -0.481754 0 0.927118 -0.37477 0 0.967386 -0.253309 0 0.929776 -0.368125 0 0.968583 -0.24869 0 0.637424 -0.770513 0 0.719095 -0.694911 0 0.624468 -0.781051 0 0.809017 -0.587785 0 0.801948 -0.597394 0 0.728969 -0.684547 0 0.415289 -0.90969 0 0.303314 -0.952891 0 0.309017 -0.951056 0 0.519615 -0.8544 0 0.425779 -0.904827 0 0.535827 -0.844328 0 0.184828 -0.982771 0 0.0627905 -0.998027 0 0.187381 -0.982287 0 -0.0617959 -0.998089 0 -0.0627906 -0.998027 0 0.0622685 -0.998059 0 -0.425779 -0.904827 0 -0.415069 -0.90979 0 -0.519615 -0.8544 0 -0.187381 -0.982287 0 -0.184373 -0.982856 0 -0.302839 -0.953042 0 -0.719095 -0.694911 0 -0.801948 -0.597394 0 -0.728969 -0.684547 0 -0.637424 -0.770513 0 -0.624468 -0.781051 0 -0.927118 -0.37477 0 -0.929776 -0.368125 0 -0.876307 -0.481754 0 -0.809017 -0.587785 0 -0.871669 -0.490094 0 -0.967386 -0.253308 0 -0.968583 -0.24869 0 -0.992115 -0.125334 0 -0.991813 -0.1277 0 -0.535827 -0.844328 0 -0.309017 -0.951056 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0.998533 0 0.0541389 -0.998533 0 -0.0541389 -0.998533 0 0.0541389 0.108119 0 -0.994138 0.131694 0 -0.99129 0.0441397 0 -0.999025 -0.986826 0 0.161782 -0.986827 0 0.161782 -0.96355 0 0.267528 -0.96355 0 0.267528 -0.928977 0 0.370138 -0.928977 0 0.370138 -0.883512 0 0.468409 -0.883512 0 0.468408 -0.827689 0 0.561187 -0.827689 0 0.561187 -0.762162 0 0.647386 -0.762162 0 0.647386 -0.687699 0 0.725996 -0.687699 0 0.725996 -0.605174 0 0.796093 -0.605174 0 0.796093 -0.515554 0 0.856857 -0.515554 0 0.856857 -0.419889 0 0.907575 -0.419889 0 0.907575 -0.319302 0 0.947653 -0.319302 0 0.947653 -0.21497 0 0.976621 -0.214971 0 0.97662 -0.108119 0 0.994138 -0.108119 0 0.994138 1.74846e-07 0 1 -3.01992e-07 0 1 -0.998533 0 -0.0541389 -0.986827 0 -0.161782 -0.986826 0 -0.161782 -0.96355 0 -0.267528 -0.96355 0 -0.267528 -0.928977 0 -0.370138 -0.928977 0 -0.370138 -0.883512 0 -0.468409 -0.883512 0 -0.468409 -0.827689 0 -0.561187 -0.827689 0 -0.561187 -0.762162 0 -0.647386 -0.762162 0 -0.647386 -0.687699 0 -0.725996 -0.687699 0 -0.725996 -0.605174 0 -0.796093 -0.605174 0 -0.796093 -0.515554 0 -0.856857 -0.515554 0 -0.856857 -0.419889 0 -0.907575 -0.419889 0 -0.907575 -0.319302 0 -0.947653 -0.371154 0 -0.928571 -0.13202 0 -0.991247 -0.216652 0 -0.976249 -0.21497 0 -0.976621 -0.296634 0 -0.954991 -0.131694 0 -0.99129 -0.214971 0 -0.97662 -0.216313 0 -0.976324 -0.108119 0 -0.994138 -0.0444774 0 -0.99901 -8.74228e-08 0 -1 0.0444772 0 -0.99901 0.13202 0 -0.991247 0.108119 0 -0.994138 -0.0441399 0 -0.999025 -0.108119 0 -0.994138 0.515554 0 -0.856857 0.419889 0 -0.907575 0.515554 0 -0.856857 0.319302 0 -0.947653 0.419889 0 -0.907575 0.371154 0 -0.928571 0.687699 0 -0.725995 0.762162 0 -0.647386 0.762162 0 -0.647386 0.605174 0 -0.796093 0.687699 0 -0.725995 0.605174 0 -0.796093 0.928977 0 -0.370138 0.928977 0 -0.370138 0.883512 0 -0.468408 0.883512 0 -0.468408 0.827689 0 -0.561187 0.827689 0 -0.561187 0.998533 0 -0.0541388 0.986827 0 -0.161782 0.998533 0 -0.0541388 0.96355 0 -0.267528 0.96355 0 -0.267528 0.986827 0 -0.161782 0.986827 0 0.161782 0.96355 0 0.267528 0.96355 0 0.267528 0.998533 0 0.054139 0.986827 0 0.161782 0.998533 0 0.054139 0.827689 0 0.561187 0.827689 0 0.561187 0.883512 0 0.468408 0.883512 0 0.468408 0.928977 0 0.370138 0.928977 0 0.370138 0.605174 0 0.796093 0.687699 0 0.725995 0.687699 0 0.725995 0.762162 0 0.647386 0.762162 0 0.647386 0.515554 0 0.856857 0.605174 0 0.796093 0.515554 0 0.856857 0.419889 0 0.907575 0.319302 0 0.947653 0.419889 0 0.907575 0.21497 0 0.976621 0.319302 0 0.947653 0.21497 0 0.976621 0.108119 0 0.994138 0.108119 0 0.994138 0.216652 0 -0.976249 0.296634 0 -0.954991 0.21497 0 -0.976621 0.21497 0 -0.976621 0.216313 0 -0.976324 0.296477 0 -0.95504 -8.74228e-08 0 -1 0.371154 0 -0.928571 0.319302 0 -0.947653 -0.371154 0 -0.928571 -0.296478 0 -0.95504 -0.319301 0 -0.947653 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -8.74228e-08 0 1 -8.74228e-08 0 1 -0.173648 0 0.984808 -0.34202 0 0.939693 -0.173648 0 0.984808 -0.5 0 0.866025 -0.34202 0 0.939693 -0.5 0 0.866026 -0.642788 0 0.766044 -0.766045 0 0.642788 -0.642788 0 0.766044 -0.866025 0 0.5 -0.766045 0 0.642788 -0.866025 0 0.5 -0.939692 0 0.342021 -0.984808 0 0.173648 -0.939693 0 0.34202 -1 0 -1.19249e-08 -0.984808 0 0.173648 -1 0 -1.19249e-08 -0.984808 0 -0.173648 -0.939693 0 -0.34202 -0.984808 0 -0.173648 -0.866025 0 -0.5 -0.939693 0 -0.34202 -0.866025 0 -0.5 -0.766044 0 -0.642788 -0.642788 0 -0.766044 -0.766044 0 -0.642788 -0.5 0 -0.866026 -0.642788 0 -0.766044 -0.5 0 -0.866026 -0.34202 0 -0.939693 -0.173648 0 -0.984808 -0.34202 0 -0.939693 1.74846e-07 0 -1 -0.173648 0 -0.984808 1.74846e-07 0 -1 0.173648 0 0.984808 0.34202 0 0.939693 0.173648 0 0.984808 0.34202 0 0.939693 0.5 0 0.866025 0.642788 0 0.766044 0.5 0 0.866025 0.766044 0 0.642788 0.642788 0 0.766044 0.766044 0 0.642788 0.866025 0 0.5 0.939693 0 0.34202 0.866025 0 0.5 0.984808 0 0.173648 0.939693 0 0.34202 0.984808 0 0.173648 1 0 -7.54979e-08 0.984808 0 -0.173648 1 0 4.37114e-08 0.939693 0 -0.34202 0.984808 0 -0.173648 0.939693 0 -0.34202 0.866025 0 -0.5 0.766044 0 -0.642788 0.866025 0 -0.5 0.642788 0 -0.766044 0.766044 0 -0.642788 0.642788 0 -0.766044 0.5 0 -0.866025 0.34202 0 -0.939693 0.5 0 -0.866025 0.173648 0 -0.984808 0.34202 0 -0.939693 0.173648 0 -0.984808 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 - - - - - - - - - - - - - - -

0 1 2 3 4 5 6 0 7 0 6 1 8 9 7 6 7 9 8 10 11 11 9 8 12 10 13 10 12 11 14 15 13 12 13 15 14 16 17 17 15 14 18 16 19 16 18 17 20 21 19 18 19 21 20 22 23 23 21 20 24 22 25 22 24 23 26 27 25 24 25 27 26 28 29 29 27 26 0 2 30 31 32 30 30 2 31 32 33 34 33 32 31 35 34 36 33 36 34 37 38 35 35 36 37 38 39 40 39 38 37 41 40 42 39 42 40 43 44 41 41 42 43 45 44 43 46 45 47 45 46 44 48 49 47 46 47 49 48 50 51 51 49 48 52 50 4 50 52 51 52 4 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 73 73 72 77 78 79 80 81 82 83 84 85 86 84 87 88 89 90 91 85 92 86 91 92 93 94 90 89 93 89 91 90 94 95 93 92 85 96 95 97 94 97 95 29 28 96 96 97 29 88 87 98 84 86 87 98 78 80 80 88 98 99 83 79 99 79 78 81 76 82 99 81 83 75 73 77 82 76 75 67 74 68 74 67 72 69 66 70 66 68 70 60 62 71 62 69 71 65 64 61 65 61 60 63 55 54 63 54 64 56 58 57 55 58 56 5 59 3 57 59 5 4 3 53 100 101 102 103 104 105 101 106 107 106 101 100 108 107 109 106 109 107 110 111 108 108 109 110 110 112 111 105 104 112 111 112 104 103 105 113 113 114 115 115 103 113 114 116 115 117 118 119 120 121 117 117 119 120 121 122 123 122 121 120 123 122 124 125 123 124 125 126 127 126 125 124 126 128 127 128 129 130 130 127 128 131 129 132 129 131 130 131 132 133 134 135 136 137 138 139 139 138 140 137 141 142 141 137 139 143 144 142 142 141 143 145 144 146 143 146 144 145 147 148 147 145 146 149 150 148 148 147 149 151 152 153 154 150 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 177 179 182 183 179 178 181 180 171 177 182 181 172 175 173 180 172 171 175 174 173 176 165 167 176 167 174 168 170 166 168 166 165 163 162 169 162 170 169 157 164 158 164 163 158 159 156 160 157 156 159 161 134 136 160 134 161 135 151 153 135 153 136 154 155 152 154 152 151 155 150 149 184 185 186 187 188 189 190 191 184 184 186 190 191 192 193 192 191 190 194 193 195 192 195 193 196 197 194 194 195 196 197 198 199 198 197 196 200 199 201 198 201 199 202 203 200 200 201 202 203 204 205 204 203 202 206 205 207 204 207 205 208 209 206 206 207 208 209 210 211 210 209 208 212 211 213 210 213 211 214 215 212 212 213 214 216 215 214 216 217 215 186 185 218 218 219 220 219 218 185 221 220 222 219 222 220 223 224 221 221 222 223 224 225 226 225 224 223 227 226 228 225 228 226 229 230 227 227 228 229 230 231 232 231 230 229 233 232 234 231 234 232 235 236 233 233 234 235 236 237 238 237 236 235 237 239 240 241 242 243 243 242 244 245 246 247 241 248 249 189 249 250 251 252 253 254 255 245 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 294 292 297 298 298 293 292 299 297 300 297 299 298 301 302 300 299 300 302 301 303 304 304 302 301 305 303 306 303 305 304 217 307 306 305 306 307 216 307 217 296 295 287 293 295 294 286 288 289 296 287 286 291 290 282 289 288 290 284 281 280 281 291 282 274 283 285 285 284 280 275 279 276 274 276 283 277 269 278 275 277 279 268 270 271 278 269 268 273 272 264 271 270 272 266 263 262 263 273 264 256 265 267 267 266 262 257 260 258 256 258 265 308 309 310 188 311 312 313 259 261 251 314 254 260 257 315 257 316 315 260 315 261 315 316 309 312 311 313 311 259 313 310 252 308 187 311 188 250 187 189 248 250 249 243 248 241 317 318 319 243 244 239 318 247 246 240 239 244 238 237 240 319 238 317 238 240 317 246 319 318 255 246 245 314 255 254 253 314 251 310 253 252 316 310 309 320 321 322 323 324 325 326 327 328 329 330 331 324 332 333 334 335 336 337 338 339 325 340 323 341 339 342 343 341 342 337 340 338 339 338 342 324 333 325 337 323 340 336 333 332 335 334 327 336 332 334 329 326 328 326 335 327 320 331 330 330 329 328 321 344 322 320 322 331 345 344 346 321 346 344 347 348 345 345 346 347 349 348 347 349 350 348 351 350 352 349 352 350 353 354 351 351 352 353 355 354 353 356 357 355 354 355 357 356 358 359 359 357 356 360 358 361 358 360 359 362 363 361 360 361 363 364 365 366 367 368 369 370 371 372 373 374 375 371 370 376 370 377 376 373 375 372 371 373 372 374 366 365 375 374 365 364 368 367 364 366 368 363 362 369 362 367 369 378 379 380 381 382 383 384 385 386 387 388 389 381 383 390 391 392 393 394 395 396 397 398 399 396 395 400 401 402 400 403 404 398 401 403 402 397 399 405 382 406 394 407 392 405 384 408 385 408 390 409 391 410 388 391 393 411 412 413 380 386 413 412 414 415 416 416 387 417 418 419 420 378 421 422 423 418 424 421 425 422 426 425 427 423 428 429 430 429 431 432 427 433 434 435 436 437 438 439 437 440 438 441 442 440 443 444 434 445 446 441 447 448 449 450 446 445 451 452 447 450 453 454 455 452 456 457 458 459 460 461 455 462 463 464 465 466 467 466 468 463 464 463 468 463 462 459 468 466 465 466 461 467 462 457 459 388 410 389 460 467 461 455 456 460 458 453 450 469 435 430 439 432 433 470 453 458 458 457 470 454 446 450 445 441 440 442 438 440 437 439 433 433 427 425 426 422 425 421 378 380 379 412 380 413 386 385 385 408 409 409 390 383 383 382 394 406 395 394 396 400 402 402 403 398 404 399 398 397 405 392 407 393 392 411 410 391 387 389 417 387 416 415 415 414 419 418 423 419 414 420 419 428 423 424 431 429 428 471 430 431 435 469 436 430 471 469 434 436 443 434 444 448 449 451 447 444 449 448 452 455 447 472 473 474 475 476 474 472 474 476 475 477 478 478 476 475 479 477 480 477 479 478 481 482 480 479 480 482 481 483 484 484 482 481 485 483 486 483 485 484 487 488 486 485 486 488 487 489 490 490 488 487 491 489 492 489 491 490 493 494 492 491 492 494 493 495 496 496 494 493 497 495 498 495 497 496 499 500 498 497 498 500 499 501 502 502 500 499 503 501 504 501 503 502 505 506 504 503 504 506 505 507 508 508 506 505 507 509 508 510 473 472 510 511 512 512 473 510 513 511 514 511 513 512 515 516 514 513 514 516 515 517 518 518 516 515 519 517 520 517 519 518 521 522 520 519 520 522 521 523 524 524 522 521 525 523 526 523 525 524 527 528 526 525 526 528 527 529 530 530 528 527 531 529 532 529 531 530 533 534 532 531 532 534 533 535 536 536 534 533 537 535 538 535 537 536 539 540 538 537 538 540 539 541 542 542 540 539 543 541 509 541 543 542 543 509 507 544 545 546 547 548 549 550 551 552 553 554 555 556 548 557 547 549 558 548 547 557 559 556 557 552 558 549 555 551 550 551 558 552 554 553 544 555 550 553 546 545 560 554 544 546 561 560 562 545 562 560 561 563 564 563 561 562 565 566 564 564 563 565 567 566 565 567 568 569 569 566 567 570 571 568 569 568 571 572 573 574 570 575 571 576 577 578 578 579 576 579 574 573 579 573 576 570 572 575 575 572 574

-
-
-
- - - - -0.0200729 -0.028 -0.0357737 -0.0340729 -0.028 0.0142263 -0.0200729 -0.028 0.0142263 -0.0340729 -0.028 -0.0357737 -0.0340729 -0.028 0.0142263 -0.0200729 -0.137 -0.0947737 -0.0200729 -0.028 0.0142263 -0.0340729 -0.137 -0.0947737 -0.0340729 -0.087 -0.0947737 -0.0200729 -0.087 -0.0947737 -0.0200729 -0.137 -0.0947737 -0.0340729 -0.137 -0.0947737 -0.0200729 -0.087 -0.0947737 -0.0340729 -0.028 -0.0357737 -0.0200729 -0.028 -0.0357737 -0.0340729 -0.087 -0.0947737 -0.0200729 -0.0586078 -0.0482205 -0.0200729 -0.087 -0.0947737 -0.0200729 -0.058 -0.0482737 -0.0200729 -0.028 -0.0357737 -0.0200729 -0.0549689 -0.0465237 -0.0200729 -0.0553188 -0.0470235 -0.0200729 -0.028 0.0142263 -0.0200729 -0.137 -0.0947737 -0.0200729 -0.0606812 -0.042524 -0.0200729 -0.0591971 -0.0480626 -0.0200729 -0.05975 -0.0478048 -0.0200729 -0.0602498 -0.0474549 -0.0200729 -0.0606812 -0.0470235 -0.0200729 -0.0610311 -0.0465237 -0.0200729 -0.0612889 -0.0459708 -0.0200729 -0.0614468 -0.0453815 -0.0200729 -0.0614468 -0.044166 -0.0200729 -0.0615 -0.0447737 -0.0200729 -0.0610311 -0.0430237 -0.0200729 -0.0612889 -0.0435767 -0.0200729 -0.05975 -0.0417426 -0.0200729 -0.0602498 -0.0420926 -0.0200729 -0.0586078 -0.0413269 -0.0200729 -0.0591971 -0.0414848 -0.0200729 -0.058 -0.0412737 -0.0200729 -0.0573922 -0.0413269 -0.0200729 -0.0568029 -0.0414848 -0.0200729 -0.0557502 -0.0420926 -0.0200729 -0.05625 -0.0417426 -0.0200729 -0.0549689 -0.0430237 -0.0200729 -0.0553188 -0.042524 -0.0200729 -0.0545532 -0.044166 -0.0200729 -0.0547111 -0.0435767 -0.0200729 -0.0545532 -0.0453815 -0.0200729 -0.0545 -0.0447737 -0.0200729 -0.0547111 -0.0459708 -0.0200729 -0.0557502 -0.0474549 -0.0200729 -0.05625 -0.0478048 -0.0200729 -0.0573922 -0.0482205 -0.0200729 -0.0568029 -0.0480626 -0.0340729 -0.0557502 -0.0474549 -0.0340729 -0.0553188 -0.0470235 -0.0340729 -0.028 -0.0357737 -0.0340729 -0.0586078 -0.0482205 -0.0340729 -0.058 -0.0482737 -0.0340729 -0.087 -0.0947737 -0.0340729 -0.028 0.0142263 -0.0340729 -0.0573922 -0.0413269 -0.0340729 -0.058 -0.0412737 -0.0340729 -0.0568029 -0.0414848 -0.0340729 -0.0557502 -0.0420926 -0.0340729 -0.05625 -0.0417426 -0.0340729 -0.0549689 -0.0430237 -0.0340729 -0.0553188 -0.042524 -0.0340729 -0.0545532 -0.044166 -0.0340729 -0.0547111 -0.0435767 -0.0340729 -0.0545532 -0.0453815 -0.0340729 -0.0545 -0.0447737 -0.0340729 -0.0549689 -0.0465237 -0.0340729 -0.0547111 -0.0459708 -0.0340729 -0.05625 -0.0478048 -0.0340729 -0.0573922 -0.0482205 -0.0340729 -0.0568029 -0.0480626 -0.0340729 -0.0591971 -0.0480626 -0.0340729 -0.0602498 -0.0474549 -0.0340729 -0.05975 -0.0478048 -0.0340729 -0.0610311 -0.0465237 -0.0340729 -0.0606812 -0.0470235 -0.0340729 -0.0614468 -0.0453815 -0.0340729 -0.0612889 -0.0459708 -0.0340729 -0.0615 -0.0447737 -0.0340729 -0.137 -0.0947737 -0.0340729 -0.0606812 -0.042524 -0.0340729 -0.0612889 -0.0435767 -0.0340729 -0.0614468 -0.044166 -0.0340729 -0.0610311 -0.0430237 -0.0340729 -0.05975 -0.0417426 -0.0340729 -0.0602498 -0.0420926 -0.0340729 -0.0586078 -0.0413269 -0.0340729 -0.0591971 -0.0414848 -0.0340729 -0.0615 -0.0447737 -0.0340729 -0.0614468 -0.044166 -0.0200729 -0.0614468 -0.044166 -0.0200729 -0.058 -0.0482737 -0.0340729 -0.0573922 -0.0482205 -0.0340729 -0.058 -0.0482737 -0.0340729 -0.0612889 -0.0435767 -0.0200729 -0.0612889 -0.0435767 -0.0200729 -0.0610311 -0.0430237 -0.0340729 -0.0610311 -0.0430237 -0.0340729 -0.0606812 -0.042524 -0.0200729 -0.0606812 -0.042524 -0.0340729 -0.0602498 -0.0420926 -0.0200729 -0.0602498 -0.0420926 -0.0200729 -0.05975 -0.0417426 -0.0340729 -0.05975 -0.0417426 -0.0340729 -0.0591971 -0.0414848 -0.0200729 -0.0591971 -0.0414848 -0.0340729 -0.0586078 -0.0413269 -0.0200729 -0.0586078 -0.0413269 -0.0340729 -0.058 -0.0412737 -0.0200729 -0.058 -0.0412737 -0.0200729 -0.0615 -0.0447737 -0.0340729 -0.0614468 -0.0453815 -0.0200729 -0.0614468 -0.0453815 -0.0340729 -0.0612889 -0.0459708 -0.0200729 -0.0612889 -0.0459708 -0.0340729 -0.0610311 -0.0465237 -0.0340729 -0.0606812 -0.0470235 -0.0200729 -0.0610311 -0.0465237 -0.0200729 -0.0606812 -0.0470235 -0.0340729 -0.0602498 -0.0474549 -0.0200729 -0.0602498 -0.0474549 -0.0340729 -0.05975 -0.0478048 -0.0340729 -0.0591971 -0.0480626 -0.0200729 -0.05975 -0.0478048 -0.0200729 -0.0591971 -0.0480626 -0.0340729 -0.0586078 -0.0482205 -0.0200729 -0.0586078 -0.0482205 -0.0200729 -0.0568029 -0.0480626 -0.0340729 -0.0568029 -0.0480626 -0.0200729 -0.0573922 -0.0482205 -0.0200729 -0.0553188 -0.0470235 -0.0340729 -0.0553188 -0.0470235 -0.0200729 -0.0557502 -0.0474549 -0.0200729 -0.05625 -0.0478048 -0.0340729 -0.0557502 -0.0474549 -0.0340729 -0.05625 -0.0478048 -0.0200729 -0.0547111 -0.0459708 -0.0200729 -0.0545532 -0.0453815 -0.0340729 -0.0545532 -0.0453815 -0.0340729 -0.0549689 -0.0465237 -0.0200729 -0.0549689 -0.0465237 -0.0340729 -0.0547111 -0.0459708 -0.0340729 -0.0547111 -0.0435767 -0.0200729 -0.0545532 -0.044166 -0.0200729 -0.0547111 -0.0435767 -0.0340729 -0.0545532 -0.044166 -0.0340729 -0.0545 -0.0447737 -0.0200729 -0.0545 -0.0447737 -0.0200729 -0.0557502 -0.0420926 -0.0340729 -0.0557502 -0.0420926 -0.0200729 -0.0553188 -0.042524 -0.0200729 -0.0549689 -0.0430237 -0.0340729 -0.0553188 -0.042524 -0.0340729 -0.0549689 -0.0430237 -0.0340729 -0.05625 -0.0417426 -0.0200729 -0.05625 -0.0417426 -0.0200729 -0.0568029 -0.0414848 -0.0340729 -0.0568029 -0.0414848 -0.0200729 -0.0573922 -0.0413269 -0.0340729 -0.0573922 -0.0413269 - - - - - - - - - - 0 1 0 0 1 0 0 1 0 0 1 0 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 0 1 -1.19249e-08 0 0.984808 -0.173648 0 0.984808 -0.173648 0 8.74228e-08 1 0 -0.173648 0.984808 0 8.74228e-08 1 0 0.939693 -0.34202 0 0.939693 -0.34202 0 0.866025 -0.5 0 0.866025 -0.5 0 0.766044 -0.642788 0 0.766044 -0.642788 0 0.642788 -0.766044 0 0.642788 -0.766044 0 0.5 -0.866026 0 0.5 -0.866026 0 0.34202 -0.939693 0 0.34202 -0.939693 0 0.173648 -0.984808 0 0.173648 -0.984808 -0 -1.74846e-07 -1 -0 -1.74846e-07 -1 0 1 -1.19249e-08 0 0.984808 0.173648 0 0.984808 0.173648 0 0.939693 0.34202 0 0.939692 0.342021 0 0.866025 0.5 0 0.766045 0.642788 0 0.866025 0.5 0 0.766045 0.642788 0 0.642788 0.766044 0 0.642788 0.766044 0 0.5 0.866026 0 0.34202 0.939693 0 0.5 0.866025 0 0.34202 0.939693 0 0.173648 0.984808 0 0.173648 0.984808 0 -0.34202 0.939693 0 -0.34202 0.939693 0 -0.173648 0.984808 0 -0.766044 0.642788 0 -0.766044 0.642788 0 -0.642788 0.766044 0 -0.5 0.866025 0 -0.642788 0.766044 0 -0.5 0.866025 0 -0.939693 0.34202 0 -0.984808 0.173648 0 -0.984808 0.173648 0 -0.866025 0.5 0 -0.866025 0.5 0 -0.939693 0.34202 -0 -0.939693 -0.34202 -0 -0.984808 -0.173648 -0 -0.939693 -0.34202 -0 -0.984808 -0.173648 -0 -1 -7.54979e-08 0 -1 4.37114e-08 -0 -0.642788 -0.766044 -0 -0.642788 -0.766044 -0 -0.766044 -0.642788 -0 -0.866025 -0.5 -0 -0.766044 -0.642788 -0 -0.866025 -0.5 -0 -0.5 -0.866025 -0 -0.5 -0.866025 -0 -0.34202 -0.939693 -0 -0.34202 -0.939693 -0 -0.173648 -0.984808 -0 -0.173648 -0.984808 - - - - - - - - - - - - - - -

0 1 2 1 0 3 4 5 6 4 7 5 8 9 10 10 11 8 12 13 14 13 12 15 16 17 18 19 20 21 22 23 24 17 25 26 16 25 17 17 27 28 26 27 17 17 29 30 28 29 17 23 17 31 30 31 17 32 23 33 23 31 33 34 23 35 23 32 35 23 34 24 36 22 37 22 24 37 38 22 39 22 36 39 22 38 40 40 41 22 19 22 42 41 42 22 43 19 44 19 42 44 45 19 46 19 43 46 47 19 48 19 45 48 49 19 50 19 47 50 20 19 51 19 49 51 21 52 19 17 19 53 52 53 19 54 17 55 17 53 55 18 17 54 56 57 58 59 60 61 62 63 64 58 65 62 63 62 65 66 67 58 58 67 65 68 69 58 58 69 66 70 71 58 58 71 68 72 73 58 58 73 70 74 75 58 58 75 72 58 57 74 61 76 58 56 58 76 77 78 61 61 78 76 59 61 79 61 60 77 61 80 81 79 61 81 61 82 83 80 61 83 61 84 85 82 61 85 86 84 87 61 87 84 87 62 88 89 90 87 87 90 86 87 88 91 87 91 89 92 93 62 62 93 88 94 95 62 62 95 92 64 94 62 96 97 98 99 100 101 102 103 97 98 97 103 104 102 105 102 104 103 105 106 107 107 104 105 108 109 106 107 106 109 110 108 111 108 110 109 111 112 113 113 110 111 114 115 112 113 112 115 114 116 117 114 117 115 118 96 98 118 119 96 119 120 121 120 119 118 122 123 121 121 120 122 124 123 125 122 125 123 124 126 127 126 124 125 128 129 127 127 126 128 130 129 131 128 131 129 130 132 133 132 130 131 134 101 133 133 132 134 135 136 137 134 99 101 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 156 163 156 162 157 163 164 165 165 162 163 166 167 164 165 164 167 116 166 117 166 116 167 160 159 158 158 157 160 161 150 152 159 161 152 153 155 151 150 153 151 146 145 154 154 145 155 148 144 149 149 144 146 138 147 139 138 148 147 140 142 141 140 139 142 143 136 135 141 143 135 100 99 137 136 100 137

-
-
-
- - - - 0.477758 -0.0204943 -0.136198 0.477758 -0.0064943 -0.136198 0.4786 -0.0064943 -0.136424 0.479468 -0.0064943 -0.1365 0.479468 -0.0204943 -0.1365 0.4786 -0.0204943 -0.136424 0.476254 -0.0064943 -0.13533 0.475638 -0.0204943 -0.134714 0.475638 -0.0064943 -0.134714 0.476254 -0.0204943 -0.13533 0.476968 -0.0064943 -0.13583 0.476968 -0.0204943 -0.13583 0.474544 -0.0204943 -0.132368 0.474544 -0.0064943 -0.132368 0.47477 -0.0064943 -0.13321 0.47477 -0.0204943 -0.13321 0.475138 -0.0064943 -0.134 0.475138 -0.0204943 -0.134 0.47477 -0.0064943 -0.12979 0.474544 -0.0064943 -0.130632 0.47477 -0.0204943 -0.12979 0.474468 -0.0064943 -0.1315 0.474468 -0.0204943 -0.1315 0.474544 -0.0204943 -0.130632 0.475638 -0.0064943 -0.128286 0.476254 -0.0204943 -0.12767 0.476254 -0.0064943 -0.12767 0.475138 -0.0204943 -0.129 0.475638 -0.0204943 -0.128286 0.475138 -0.0064943 -0.129 0.4786 -0.0204943 -0.126576 0.4786 -0.0064943 -0.126576 0.477758 -0.0064943 -0.126802 0.477758 -0.0204943 -0.126802 0.476968 -0.0064943 -0.12717 0.476968 -0.0204943 -0.12717 0.481178 -0.0064943 -0.126802 0.480336 -0.0064943 -0.126576 0.481178 -0.0204943 -0.126802 0.479468 -0.0064943 -0.1265 0.479468 -0.0204943 -0.1265 0.480336 -0.0204943 -0.126576 0.482682 -0.0064943 -0.12767 0.483298 -0.0204943 -0.128286 0.483298 -0.0064943 -0.128286 0.481968 -0.0204943 -0.12717 0.482682 -0.0204943 -0.12767 0.481968 -0.0064943 -0.12717 0.484392 -0.0204943 -0.130632 0.484392 -0.0064943 -0.130632 0.484167 -0.0064943 -0.12979 0.484167 -0.0204943 -0.12979 0.483798 -0.0064943 -0.129 0.483798 -0.0204943 -0.129 0.484392 -0.0204943 -0.132368 0.484392 -0.0064943 -0.132368 0.484468 -0.0064943 -0.1315 0.484468 -0.0204943 -0.1315 0.484167 -0.0204943 -0.13321 0.484167 -0.0064943 -0.13321 0.483798 -0.0064943 -0.134 0.483798 -0.0204943 -0.134 0.483298 -0.0204943 -0.134714 0.483298 -0.0064943 -0.134714 0.482682 -0.0204943 -0.13533 0.482682 -0.0064943 -0.13533 0.481968 -0.0064943 -0.13583 0.481968 -0.0204943 -0.13583 0.481178 -0.0204943 -0.136198 0.481178 -0.0064943 -0.136198 0.480336 -0.0204943 -0.136424 0.480336 -0.0064943 -0.136424 0.464468 -0.0064943 -0.172 0.414468 -0.0064943 -0.172 0.414468 -0.0204943 -0.172 0.464468 -0.0204943 -0.172 0.529468 -0.0064943 -0.107 0.464468 -0.0064943 -0.172 0.464468 -0.0204943 -0.172 0.529468 -0.0204943 -0.107 0.529468 -0.0064943 -0.107 0.529468 -0.0204943 -0.107 0.529468 -0.0204943 -0.057 0.529468 -0.0064943 -0.057 0.414468 -0.0064943 -0.172 0.529468 -0.0064943 -0.057 0.529468 -0.0204943 -0.057 0.414468 -0.0204943 -0.172 0.464468 -0.0064943 -0.172 0.4786 -0.0064943 -0.136424 0.477758 -0.0064943 -0.136198 0.476254 -0.0064943 -0.12767 0.529468 -0.0064943 -0.057 0.414468 -0.0064943 -0.172 0.479468 -0.0064943 -0.1365 0.4786 -0.0064943 -0.126576 0.479468 -0.0064943 -0.1265 0.476968 -0.0064943 -0.13583 0.476254 -0.0064943 -0.13533 0.475638 -0.0064943 -0.134714 0.475138 -0.0064943 -0.134 0.47477 -0.0064943 -0.13321 0.474468 -0.0064943 -0.1315 0.474544 -0.0064943 -0.132368 0.47477 -0.0064943 -0.12979 0.474544 -0.0064943 -0.130632 0.475638 -0.0064943 -0.128286 0.475138 -0.0064943 -0.129 0.477758 -0.0064943 -0.126802 0.476968 -0.0064943 -0.12717 0.529468 -0.0064943 -0.107 0.480336 -0.0064943 -0.126576 0.481968 -0.0064943 -0.12717 0.481178 -0.0064943 -0.126802 0.483298 -0.0064943 -0.128286 0.482682 -0.0064943 -0.12767 0.484167 -0.0064943 -0.12979 0.483798 -0.0064943 -0.129 0.484468 -0.0064943 -0.1315 0.484392 -0.0064943 -0.130632 0.483298 -0.0064943 -0.134714 0.484167 -0.0064943 -0.13321 0.484392 -0.0064943 -0.132368 0.483798 -0.0064943 -0.134 0.481968 -0.0064943 -0.13583 0.482682 -0.0064943 -0.13533 0.480336 -0.0064943 -0.136424 0.481178 -0.0064943 -0.136198 0.476254 -0.0204943 -0.12767 0.414468 -0.0204943 -0.172 0.529468 -0.0204943 -0.057 0.464468 -0.0204943 -0.172 0.477758 -0.0204943 -0.136198 0.4786 -0.0204943 -0.136424 0.479468 -0.0204943 -0.1365 0.4786 -0.0204943 -0.126576 0.479468 -0.0204943 -0.1265 0.476254 -0.0204943 -0.13533 0.476968 -0.0204943 -0.13583 0.475138 -0.0204943 -0.134 0.475638 -0.0204943 -0.134714 0.47477 -0.0204943 -0.13321 0.474468 -0.0204943 -0.1315 0.474544 -0.0204943 -0.132368 0.47477 -0.0204943 -0.12979 0.474544 -0.0204943 -0.130632 0.475638 -0.0204943 -0.128286 0.475138 -0.0204943 -0.129 0.477758 -0.0204943 -0.126802 0.476968 -0.0204943 -0.12717 0.529468 -0.0204943 -0.107 0.480336 -0.0204943 -0.126576 0.481968 -0.0204943 -0.12717 0.481178 -0.0204943 -0.126802 0.483298 -0.0204943 -0.128286 0.482682 -0.0204943 -0.12767 0.484167 -0.0204943 -0.12979 0.483798 -0.0204943 -0.129 0.484468 -0.0204943 -0.1315 0.484392 -0.0204943 -0.130632 0.483298 -0.0204943 -0.134714 0.484167 -0.0204943 -0.13321 0.484392 -0.0204943 -0.132368 0.483798 -0.0204943 -0.134 0.481968 -0.0204943 -0.13583 0.482682 -0.0204943 -0.13533 0.480336 -0.0204943 -0.136424 0.481178 -0.0204943 -0.136198 - - - - - - - - - - 0.34202 0 0.939693 0.34202 0 0.939693 0.173648 0 0.984808 -1.74846e-07 0 1 -1.74846e-07 0 1 0.173648 0 0.984808 0.642788 0 0.766044 0.766044 0 0.642788 0.766044 0 0.642788 0.642788 0 0.766044 0.5 0 0.866026 0.5 0 0.866026 0.984808 0 0.173648 0.984808 0 0.173648 0.939693 0 0.34202 0.939693 0 0.34202 0.866025 0 0.5 0.866025 0 0.5 0.939692 0 -0.342021 0.984808 0 -0.173648 0.939693 0 -0.34202 1 0 1.19249e-08 1 0 1.19249e-08 0.984808 0 -0.173648 0.766045 0 -0.642788 0.642788 0 -0.766044 0.642788 0 -0.766044 0.866025 0 -0.5 0.766045 0 -0.642788 0.866025 0 -0.5 0.173648 0 -0.984808 0.173648 0 -0.984808 0.34202 0 -0.939693 0.34202 0 -0.939693 0.5 0 -0.866025 0.5 0 -0.866026 -0.34202 -0 -0.939693 -0.173648 -0 -0.984808 -0.34202 -0 -0.939693 8.74228e-08 0 -1 8.74228e-08 0 -1 -0.173648 -0 -0.984808 -0.642788 -0 -0.766044 -0.766044 -0 -0.642788 -0.766044 -0 -0.642788 -0.5 -0 -0.866025 -0.642788 -0 -0.766044 -0.5 -0 -0.866025 -0.984808 -0 -0.173648 -0.984808 -0 -0.173648 -0.939693 -0 -0.34202 -0.939693 -0 -0.34202 -0.866025 -0 -0.5 -0.866025 -0 -0.5 -0.984808 0 0.173648 -0.984808 0 0.173648 -1 -0 -4.37114e-08 -1 0 7.54979e-08 -0.939693 0 0.34202 -0.939693 0 0.34202 -0.866025 0 0.5 -0.866025 0 0.5 -0.766044 0 0.642788 -0.766044 0 0.642788 -0.642788 0 0.766044 -0.642788 0 0.766044 -0.5 0 0.866025 -0.5 0 0.866025 -0.34202 0 0.939693 -0.34202 0 0.939693 -0.173648 0 0.984808 -0.173648 0 0.984808 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 1 0 0 1 0 0 1 0 0 1 0 0 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 - - - - - - - - - - - - - - -

0 2 1 3 5 4 6 8 7 9 11 10 12 14 13 15 17 16 18 20 19 21 23 22 24 26 25 27 29 28 30 32 31 33 35 34 36 38 37 39 41 40 42 44 43 45 47 46 48 50 49 51 53 52 54 56 55 56 54 57 55 59 58 58 54 55 60 61 59 58 59 61 62 60 63 60 62 61 63 65 64 64 62 63 66 67 65 64 65 67 68 66 69 66 68 67 69 71 70 70 68 69 3 4 71 70 71 4 57 48 49 57 49 56 52 50 51 51 50 48 44 53 43 44 52 53 42 46 47 42 43 46 45 38 36 47 45 36 41 39 37 38 41 37 30 31 40 40 31 39 34 32 33 33 32 30 26 35 25 26 34 35 24 28 29 24 25 28 27 20 18 29 27 18 23 21 19 20 23 19 12 13 22 22 13 21 16 14 15 15 14 12 8 17 7 8 16 17 6 9 10 6 7 9 11 0 1 10 11 1 5 3 2 0 5 2 72 74 73 74 72 75 76 78 77 78 76 79 80 82 81 80 83 82 84 86 85 86 84 87 88 90 89 91 93 92 88 89 94 95 92 96 88 98 97 90 88 97 88 100 99 98 88 99 93 101 88 100 88 101 102 103 93 93 103 101 104 105 93 93 105 102 106 107 93 93 107 104 93 91 106 108 109 92 92 109 91 92 95 108 110 111 92 96 92 111 112 113 110 110 113 111 114 115 110 110 115 112 116 117 110 110 117 114 118 119 110 110 119 116 110 88 120 121 122 110 110 122 118 110 120 123 110 123 121 124 125 88 88 125 120 126 127 88 88 127 124 94 126 88 128 130 129 131 133 132 131 134 133 135 136 130 131 138 137 132 138 131 131 140 139 137 140 131 129 131 141 139 141 131 142 129 143 129 141 143 144 129 145 129 142 145 146 129 147 129 144 147 129 146 128 148 130 149 130 128 149 130 148 135 150 130 151 136 151 130 152 150 153 150 151 153 154 150 155 150 152 155 156 150 157 150 154 157 158 150 159 150 156 159 150 160 131 161 150 162 150 158 162 150 163 160 150 161 163 164 131 165 131 160 165 166 131 167 131 164 167 134 131 166

-
-
-
- - - - 0.0599681 0.862506 -0.363 0.0599681 0.834506 -0.391 0.0599681 0.862506 -0.391 0.0599681 0.834506 -0.363 0.444968 0.834506 -0.391 0.444968 0.862506 -0.363 0.444968 0.862506 -0.391 0.444968 0.834506 -0.363 -0.0245319 0.671506 -0.172 0.529468 0.671506 -0.172 0.0599681 0.671506 -0.2 0.472968 0.671506 -0.2 0.529468 0.671506 -0.2 0.444968 0.671506 -0.2 0.472968 0.671506 -0.363 0.444968 0.671506 -0.363 0.0319681 0.671506 -0.363 0.0319681 0.671506 -0.2 -0.0245319 0.671506 -0.2 0.0599681 0.671506 -0.363 0.0599681 0.671506 -0.2 0.444968 0.643506 -0.2 0.0599681 0.643506 -0.2 0.444968 0.671506 -0.2 -0.0245319 0.671506 -0.2 0.0319681 0.643506 -0.2 -0.0245319 0.643506 -0.2 0.0319681 0.671506 -0.2 0.529468 0.643506 -0.172 0.529468 0.671506 -0.172 -0.0245319 0.671506 -0.172 -0.0245319 0.643506 -0.172 0.529468 0.643506 -0.2 0.472968 0.671506 -0.2 0.529468 0.671506 -0.2 0.472968 0.643506 -0.2 -0.0245319 0.643506 -0.172 -0.0245319 0.643506 -0.2 0.0319681 0.643506 -0.2 0.0599681 0.643506 -0.2 0.529468 0.643506 -0.172 0.0599681 0.643506 -0.391 0.0319681 0.643506 -0.391 0.472968 0.643506 -0.2 0.444968 0.643506 -0.391 0.472968 0.643506 -0.391 0.444968 0.643506 -0.2 0.529468 0.643506 -0.2 -0.0245319 0.671506 -0.172 -0.0245319 0.671506 -0.2 -0.0245319 0.643506 -0.2 -0.0245319 0.643506 -0.172 0.529468 0.671506 -0.172 0.529468 0.643506 -0.172 0.529468 0.643506 -0.2 0.529468 0.671506 -0.2 0.0319681 0.671506 -0.363 0.0319681 0.890506 -0.363 0.0319681 0.890506 -0.391 0.0319681 0.643506 -0.2 0.0319681 0.643506 -0.391 0.0319681 0.671506 -0.2 0.0599681 0.806506 -0.391 0.0599681 0.806506 -0.363 0.0599681 0.671506 -0.363 0.0599681 0.671506 -0.2 0.0599681 0.643506 -0.2 0.0599681 0.643506 -0.391 0.0319681 0.643506 -0.391 0.0319681 0.890506 -0.391 0.0599681 0.806506 -0.391 0.444968 0.806506 -0.391 0.472968 0.643506 -0.391 0.444968 0.643506 -0.391 0.0599681 0.834506 -0.391 0.444968 0.834506 -0.391 0.472968 0.890506 -0.391 0.0599681 0.643506 -0.391 0.0599681 0.862506 -0.391 0.444968 0.862506 -0.391 0.472968 0.671506 -0.363 0.472968 0.890506 -0.391 0.472968 0.890506 -0.363 0.472968 0.643506 -0.391 0.472968 0.643506 -0.2 0.472968 0.671506 -0.2 0.444968 0.671506 -0.363 0.444968 0.643506 -0.2 0.444968 0.671506 -0.2 0.444968 0.806506 -0.391 0.444968 0.643506 -0.391 0.444968 0.806506 -0.363 0.0599681 0.806506 -0.363 0.0319681 0.890506 -0.363 0.0319681 0.671506 -0.363 0.472968 0.890506 -0.363 0.444968 0.834506 -0.363 0.444968 0.806506 -0.363 0.472968 0.671506 -0.363 0.444968 0.671506 -0.363 0.444968 0.862506 -0.363 0.0599681 0.671506 -0.363 0.0599681 0.862506 -0.363 0.0599681 0.834506 -0.363 0.472968 0.890506 -0.363 0.0319681 0.890506 -0.391 0.0319681 0.890506 -0.363 0.472968 0.890506 -0.391 0.444968 0.862506 -0.363 0.0599681 0.862506 -0.363 0.0599681 0.862506 -0.391 0.444968 0.862506 -0.391 0.444968 0.834506 -0.363 0.444968 0.834506 -0.391 0.0599681 0.834506 -0.391 0.0599681 0.834506 -0.363 0.444968 0.806506 -0.363 0.0599681 0.806506 -0.363 0.0599681 0.806506 -0.391 0.444968 0.806506 -0.391 - - - - - - - - - - 1 0 0 1 0 0 1 0 0 1 0 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 0 0 1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 - - - - - - - - - - - - - - -

0 1 2 1 0 3 4 5 6 4 7 5 8 9 10 11 9 12 10 9 13 11 14 15 13 9 11 15 13 11 16 17 10 10 17 8 8 17 18 19 16 10 20 21 22 20 23 21 24 25 26 24 27 25 28 29 30 28 30 31 32 33 34 32 35 33 36 37 38 36 39 40 38 39 36 41 39 42 43 44 45 42 39 38 40 46 43 40 39 46 40 43 47 44 43 46 48 49 50 48 50 51 52 53 54 54 55 52 56 57 58 59 56 60 58 60 56 56 59 61 62 63 64 65 66 64 64 67 62 64 66 67 68 69 70 71 72 73 70 74 75 76 72 71 68 70 77 71 75 76 69 78 74 69 76 78 69 74 70 75 71 70 79 76 75 78 76 79 80 81 82 83 80 84 81 80 83 84 80 85 86 87 88 86 89 90 91 89 86 86 90 87 92 93 94 95 96 97 95 97 98 98 97 99 96 95 100 94 101 92 97 96 92 102 95 93 96 103 92 95 102 100 92 103 93 93 103 102 104 105 106 105 104 107 108 109 110 108 110 111 112 113 114 114 115 112 116 117 118 116 118 119

-
-
-
- - - - -0.131073 -0.008 -0.0197737 -0.131073 -0.028 -0.0947737 -0.131073 -0.008 -0.0947737 -0.131073 0 0.0142263 -0.131073 -0.028 0.0142263 -0.131073 0 -0.0197737 -0.131073 -0.028 0.0422263 -0.131073 -0.542 0.0422263 -0.131073 -0.542 0.0142263 -0.131073 -0.028 0.0142263 -0.159073 -0.028 0.0142263 -0.131073 -0.542 0.0142263 -0.159073 -0.542 0.0142263 -0.131073 -0.028 0.0142263 -0.131073 -0.542 0.0422263 -0.0340729 -0.57 0.0422263 -0.0620729 -0.542 0.0422263 -0.159073 -0.57 0.0422263 -0.159073 0 0.0422263 -0.131073 -0.028 0.0422263 -0.0620729 -0.028 0.0422263 -0.0340729 0 0.0422263 -0.159073 -0.028 0.0142263 -0.159073 0 0.0422263 -0.159073 -0.028 -0.0947737 -0.159073 -0.542 -0.0947737 -0.159073 -0.57 -0.122774 -0.159073 -0.542 0.0142263 -0.159073 -0.57 0.0422263 -0.159073 0 -0.122774 -0.131073 -0.57 0.0142263 -0.131073 -0.562 -0.0197737 -0.131073 -0.542 0.0142263 -0.131073 -0.57 -0.0197737 -0.131073 -0.562 -0.0947737 -0.131073 -0.542 -0.0947737 -0.0965729 -0.57 -0.0477737 -0.159073 -0.57 -0.122774 -0.0340729 -0.57 -0.122774 -0.103554 -0.57 -0.0430138 -0.103885 -0.57 -0.0419426 -0.131073 -0.57 -0.0197737 -0.0933188 -0.57 -0.0335165 -0.0620729 -0.57 -0.0197737 -0.0943622 -0.57 -0.0331069 -0.099827 -0.57 -0.0335165 -0.100798 -0.57 -0.0340769 -0.0987836 -0.57 -0.0474405 -0.0976907 -0.57 -0.04769 -0.100798 -0.57 -0.0464705 -0.099827 -0.57 -0.047031 -0.102437 -0.57 -0.0449499 -0.101674 -0.57 -0.0457716 -0.103068 -0.57 -0.0440237 -0.104052 -0.57 -0.0408342 -0.103885 -0.57 -0.0386048 -0.103554 -0.57 -0.0375337 -0.104052 -0.57 -0.0397132 -0.103068 -0.57 -0.0365237 -0.102437 -0.57 -0.0355975 -0.101674 -0.57 -0.0347758 -0.0976907 -0.57 -0.0328575 -0.0965729 -0.57 -0.0327737 -0.0987836 -0.57 -0.0331069 -0.0954551 -0.57 -0.0328575 -0.0892609 -0.57 -0.0386048 -0.0890939 -0.57 -0.0397132 -0.131073 -0.57 0.0142263 -0.159073 -0.57 0.0422263 -0.092348 -0.57 -0.0340769 -0.0914716 -0.57 -0.0347758 -0.0907092 -0.57 -0.0355975 -0.0900777 -0.57 -0.0365237 -0.0895913 -0.57 -0.0375337 -0.0620729 -0.57 0.0142263 -0.0340729 -0.57 0.0422263 -0.0890939 -0.57 -0.0408342 -0.0892609 -0.57 -0.0419426 -0.0895913 -0.57 -0.0430138 -0.0900777 -0.57 -0.0440237 -0.0914716 -0.57 -0.0457716 -0.0907092 -0.57 -0.0449499 -0.0933188 -0.57 -0.047031 -0.092348 -0.57 -0.0464705 -0.0954551 -0.57 -0.04769 -0.0943622 -0.57 -0.0474405 -0.0340729 0 -0.122774 -0.092348 0 -0.0464705 -0.0914716 0 -0.0457716 -0.0890939 0 -0.0397132 -0.0892609 0 -0.0386048 -0.0620729 0 -0.0197737 -0.0965729 0 -0.0327737 -0.0954551 0 -0.0328575 -0.0965729 0 -0.0477737 -0.159073 0 -0.122774 -0.0976907 0 -0.04769 -0.0943622 0 -0.0331069 -0.0933188 0 -0.0335165 -0.092348 0 -0.0340769 -0.0914716 0 -0.0347758 -0.0907092 0 -0.0355975 -0.0900777 0 -0.0365237 -0.0895913 0 -0.0375337 -0.0620729 0 0.0142263 -0.0340729 0 0.0422263 -0.0890939 0 -0.0408342 -0.0895913 0 -0.0430138 -0.0892609 0 -0.0419426 -0.0900777 0 -0.0440237 -0.0907092 0 -0.0449499 -0.0943622 0 -0.0474405 -0.0933188 0 -0.047031 -0.0954551 0 -0.04769 -0.131073 0 -0.0197737 -0.103885 0 -0.0419426 -0.103554 0 -0.0430138 -0.099827 0 -0.047031 -0.0987836 0 -0.0474405 -0.101674 0 -0.0457716 -0.100798 0 -0.0464705 -0.103068 0 -0.0440237 -0.102437 0 -0.0449499 -0.104052 0 -0.0397132 -0.104052 0 -0.0408342 -0.103554 0 -0.0375337 -0.103885 0 -0.0386048 -0.102437 0 -0.0355975 -0.103068 0 -0.0365237 -0.100798 0 -0.0340769 -0.101674 0 -0.0347758 -0.0987836 0 -0.0331069 -0.099827 0 -0.0335165 -0.0976907 0 -0.0328575 -0.159073 0 0.0422263 -0.131073 0 0.0142263 -0.0620729 -0.028 0.0422263 -0.0620729 -0.028 0.0142263 -0.0620729 -0.542 0.0142263 -0.0620729 -0.542 0.0422263 -0.0620729 -0.008 -0.0197737 -0.0620729 0 0.0142263 -0.0620729 0 -0.0197737 -0.0620729 -0.028 -0.0947737 -0.0620729 -0.008 -0.0947737 -0.0620729 -0.028 0.0142263 -0.0620729 -0.028 0.0142263 -0.0340729 -0.542 0.0142263 -0.0620729 -0.542 0.0142263 -0.0340729 -0.028 0.0142263 -0.0620729 -0.562 -0.0197737 -0.0620729 -0.542 0.0142263 -0.0620729 -0.542 -0.0947737 -0.0620729 -0.57 0.0142263 -0.0620729 -0.562 -0.0947737 -0.0620729 -0.57 -0.0197737 -0.0340729 -0.542 0.0142263 -0.0340729 -0.57 -0.122774 -0.0340729 -0.542 -0.0947737 -0.0340729 -0.028 0.0142263 -0.0340729 0 0.0422263 -0.0340729 -0.028 -0.0947737 -0.0340729 0 -0.122774 -0.0340729 -0.57 0.0422263 -0.0340729 -0.542 -0.0947737 -0.0340729 -0.028 -0.0947737 -0.0620729 -0.028 -0.0947737 -0.0620729 -0.542 -0.0947737 -0.131073 -0.008 -0.0947737 -0.0620729 -0.028 -0.0947737 -0.0620729 -0.008 -0.0947737 -0.131073 -0.028 -0.0947737 -0.131073 -0.542 -0.0947737 -0.0620729 -0.562 -0.0947737 -0.0620729 -0.542 -0.0947737 -0.131073 -0.562 -0.0947737 -0.0620729 -0.542 -0.122774 -0.0620729 -0.028 -0.0947737 -0.0620729 -0.028 -0.122774 -0.0620729 -0.542 -0.0947737 -0.0620729 -0.028 -0.122774 -0.131073 -0.028 -0.122774 -0.159073 0 -0.122774 -0.0340729 0 -0.122774 -0.131073 -0.542 -0.122774 -0.159073 -0.57 -0.122774 -0.0340729 -0.57 -0.122774 -0.0620729 -0.542 -0.122774 -0.131073 -0.028 -0.0947737 -0.131073 -0.542 -0.0947737 -0.131073 -0.542 -0.122774 -0.131073 -0.028 -0.122774 -0.131073 -0.542 -0.0947737 -0.131073 -0.028 -0.0947737 -0.159073 -0.028 -0.0947737 -0.159073 -0.542 -0.0947737 -0.159073 -0.542 0.0142263 -0.131073 -0.542 0.0142263 -0.131073 -0.542 -0.0947737 -0.159073 -0.542 -0.0947737 -0.131073 -0.028 -0.0947737 -0.159073 -0.028 0.0142263 -0.159073 -0.028 -0.0947737 -0.131073 -0.028 0.0142263 -0.0620729 -0.542 -0.122774 -0.131073 -0.542 -0.0947737 -0.0620729 -0.542 -0.0947737 -0.131073 -0.542 -0.122774 -0.131073 -0.562 -0.0197737 -0.0620729 -0.57 -0.0197737 -0.0620729 -0.562 -0.0197737 -0.131073 -0.57 -0.0197737 -0.0620729 -0.562 -0.0197737 -0.0900777 -0.562 -0.0365237 -0.0907092 -0.562 -0.0355975 -0.131073 -0.562 -0.0197737 -0.0965729 -0.562 -0.0327737 -0.0976907 -0.562 -0.0328575 -0.0620729 -0.562 -0.0947737 -0.131073 -0.562 -0.0947737 -0.0965729 -0.562 -0.0477737 -0.103068 -0.562 -0.0440237 -0.102437 -0.562 -0.0449499 -0.0987836 -0.562 -0.0474405 -0.0976907 -0.562 -0.04769 -0.100798 -0.562 -0.0464705 -0.099827 -0.562 -0.047031 -0.101674 -0.562 -0.0457716 -0.103554 -0.562 -0.0430138 -0.104052 -0.562 -0.0408342 -0.103885 -0.562 -0.0419426 -0.103885 -0.562 -0.0386048 -0.104052 -0.562 -0.0397132 -0.103068 -0.562 -0.0365237 -0.103554 -0.562 -0.0375337 -0.101674 -0.562 -0.0347758 -0.102437 -0.562 -0.0355975 -0.099827 -0.562 -0.0335165 -0.100798 -0.562 -0.0340769 -0.0987836 -0.562 -0.0331069 -0.0954551 -0.562 -0.0328575 -0.0933188 -0.562 -0.0335165 -0.0943622 -0.562 -0.0331069 -0.0914716 -0.562 -0.0347758 -0.092348 -0.562 -0.0340769 -0.0890939 -0.562 -0.0397132 -0.0892609 -0.562 -0.0386048 -0.0895913 -0.562 -0.0375337 -0.0892609 -0.562 -0.0419426 -0.0890939 -0.562 -0.0408342 -0.0895913 -0.562 -0.0430138 -0.0907092 -0.562 -0.0449499 -0.0900777 -0.562 -0.0440237 -0.092348 -0.562 -0.0464705 -0.0914716 -0.562 -0.0457716 -0.0943622 -0.562 -0.0474405 -0.0933188 -0.562 -0.047031 -0.0954551 -0.562 -0.04769 -0.0954551 -0.562 -0.04769 -0.0965729 -0.562 -0.0477737 -0.0965729 -0.57 -0.0477737 -0.092348 -0.562 -0.0464705 -0.0933188 -0.562 -0.047031 -0.0933188 -0.57 -0.047031 -0.0943622 -0.562 -0.0474405 -0.0954551 -0.57 -0.04769 -0.0943622 -0.57 -0.0474405 -0.0907092 -0.57 -0.0449499 -0.0900777 -0.562 -0.0440237 -0.0907092 -0.562 -0.0449499 -0.092348 -0.57 -0.0464705 -0.0914716 -0.57 -0.0457716 -0.0914716 -0.562 -0.0457716 -0.0892609 -0.562 -0.0419426 -0.0892609 -0.57 -0.0419426 -0.0890939 -0.562 -0.0408342 -0.0895913 -0.562 -0.0430138 -0.0900777 -0.57 -0.0440237 -0.0895913 -0.57 -0.0430138 -0.0895913 -0.562 -0.0375337 -0.0892609 -0.562 -0.0386048 -0.0892609 -0.57 -0.0386048 -0.0890939 -0.57 -0.0397132 -0.0890939 -0.562 -0.0397132 -0.0890939 -0.57 -0.0408342 -0.0907092 -0.57 -0.0355975 -0.0914716 -0.562 -0.0347758 -0.0907092 -0.562 -0.0355975 -0.0895913 -0.57 -0.0375337 -0.0900777 -0.57 -0.0365237 -0.0900777 -0.562 -0.0365237 -0.0933188 -0.562 -0.0335165 -0.0933188 -0.57 -0.0335165 -0.0943622 -0.562 -0.0331069 -0.092348 -0.562 -0.0340769 -0.0914716 -0.57 -0.0347758 -0.092348 -0.57 -0.0340769 -0.0976907 -0.562 -0.0328575 -0.0965729 -0.562 -0.0327737 -0.0965729 -0.57 -0.0327737 -0.0954551 -0.57 -0.0328575 -0.0954551 -0.562 -0.0328575 -0.0943622 -0.57 -0.0331069 -0.099827 -0.57 -0.0335165 -0.100798 -0.562 -0.0340769 -0.099827 -0.562 -0.0335165 -0.0976907 -0.57 -0.0328575 -0.0987836 -0.57 -0.0331069 -0.0987836 -0.562 -0.0331069 -0.102437 -0.562 -0.0355975 -0.102437 -0.57 -0.0355975 -0.103068 -0.562 -0.0365237 -0.101674 -0.562 -0.0347758 -0.100798 -0.57 -0.0340769 -0.101674 -0.57 -0.0347758 -0.104052 -0.562 -0.0397132 -0.103885 -0.562 -0.0386048 -0.103885 -0.57 -0.0386048 -0.103554 -0.57 -0.0375337 -0.103554 -0.562 -0.0375337 -0.103068 -0.57 -0.0365237 -0.103885 -0.562 -0.0419426 -0.104052 -0.562 -0.0408342 -0.104052 -0.57 -0.0408342 -0.104052 -0.57 -0.0397132 -0.103885 -0.57 -0.0419426 -0.103554 -0.562 -0.0430138 -0.103554 -0.57 -0.0430138 -0.103068 -0.562 -0.0440237 -0.102437 -0.562 -0.0449499 -0.103068 -0.57 -0.0440237 -0.102437 -0.57 -0.0449499 -0.101674 -0.562 -0.0457716 -0.101674 -0.57 -0.0457716 -0.100798 -0.562 -0.0464705 -0.099827 -0.562 -0.047031 -0.100798 -0.57 -0.0464705 -0.099827 -0.57 -0.047031 -0.0987836 -0.562 -0.0474405 -0.0987836 -0.57 -0.0474405 -0.0976907 -0.562 -0.04769 -0.0976907 -0.57 -0.04769 -0.131073 -0.028 -0.0947737 -0.0620729 -0.028 -0.122774 -0.0620729 -0.028 -0.0947737 -0.131073 -0.028 -0.122774 -0.0620729 0 -0.0197737 -0.131073 -0.008 -0.0197737 -0.0620729 -0.008 -0.0197737 -0.131073 0 -0.0197737 -0.102437 -0.008 -0.0449499 -0.103068 -0.008 -0.0440237 -0.131073 -0.008 -0.0947737 -0.0976907 -0.008 -0.04769 -0.0965729 -0.008 -0.0477737 -0.0620729 -0.008 -0.0947737 -0.0976907 -0.008 -0.0328575 -0.0965729 -0.008 -0.0327737 -0.131073 -0.008 -0.0197737 -0.099827 -0.008 -0.047031 -0.0987836 -0.008 -0.0474405 -0.101674 -0.008 -0.0457716 -0.100798 -0.008 -0.0464705 -0.103554 -0.008 -0.0430138 -0.104052 -0.008 -0.0408342 -0.103885 -0.008 -0.0419426 -0.103885 -0.008 -0.0386048 -0.104052 -0.008 -0.0397132 -0.103068 -0.008 -0.0365237 -0.103554 -0.008 -0.0375337 -0.101674 -0.008 -0.0347758 -0.102437 -0.008 -0.0355975 -0.099827 -0.008 -0.0335165 -0.100798 -0.008 -0.0340769 -0.0987836 -0.008 -0.0331069 -0.0620729 -0.008 -0.0197737 -0.0943622 -0.008 -0.0331069 -0.0954551 -0.008 -0.0328575 -0.092348 -0.008 -0.0340769 -0.0933188 -0.008 -0.0335165 -0.0907092 -0.008 -0.0355975 -0.0914716 -0.008 -0.0347758 -0.0892609 -0.008 -0.0386048 -0.0890939 -0.008 -0.0397132 -0.0895913 -0.008 -0.0375337 -0.0900777 -0.008 -0.0365237 -0.0890939 -0.008 -0.0408342 -0.0892609 -0.008 -0.0419426 -0.0895913 -0.008 -0.0430138 -0.0907092 -0.008 -0.0449499 -0.0900777 -0.008 -0.0440237 -0.092348 -0.008 -0.0464705 -0.0914716 -0.008 -0.0457716 -0.0943622 -0.008 -0.0474405 -0.0933188 -0.008 -0.047031 -0.0954551 -0.008 -0.04769 -0.104052 -0.008 -0.0397132 -0.104052 0 -0.0408342 -0.104052 0 -0.0397132 -0.0965729 -0.008 -0.0477737 -0.0954551 0 -0.04769 -0.0965729 0 -0.0477737 -0.103885 0 -0.0386048 -0.103885 -0.008 -0.0386048 -0.103554 0 -0.0375337 -0.103554 -0.008 -0.0375337 -0.103068 -0.008 -0.0365237 -0.103068 0 -0.0365237 -0.102437 0 -0.0355975 -0.102437 -0.008 -0.0355975 -0.101674 0 -0.0347758 -0.101674 -0.008 -0.0347758 -0.100798 -0.008 -0.0340769 -0.100798 0 -0.0340769 -0.099827 0 -0.0335165 -0.099827 -0.008 -0.0335165 -0.0987836 0 -0.0331069 -0.0987836 -0.008 -0.0331069 -0.0976907 -0.008 -0.0328575 -0.0976907 0 -0.0328575 -0.0965729 -0.008 -0.0327737 -0.0965729 0 -0.0327737 -0.104052 -0.008 -0.0408342 -0.103885 -0.008 -0.0419426 -0.103885 0 -0.0419426 -0.103554 0 -0.0430138 -0.103554 -0.008 -0.0430138 -0.103068 -0.008 -0.0440237 -0.103068 0 -0.0440237 -0.102437 -0.008 -0.0449499 -0.102437 0 -0.0449499 -0.101674 0 -0.0457716 -0.101674 -0.008 -0.0457716 -0.100798 -0.008 -0.0464705 -0.100798 0 -0.0464705 -0.099827 -0.008 -0.047031 -0.099827 0 -0.047031 -0.0987836 0 -0.0474405 -0.0987836 -0.008 -0.0474405 -0.0976907 -0.008 -0.04769 -0.0976907 0 -0.04769 -0.0943622 -0.008 -0.0474405 -0.0943622 0 -0.0474405 -0.0954551 -0.008 -0.04769 -0.0914716 -0.008 -0.0457716 -0.0914716 0 -0.0457716 -0.092348 -0.008 -0.0464705 -0.0933188 -0.008 -0.047031 -0.092348 0 -0.0464705 -0.0933188 0 -0.047031 -0.0900777 -0.008 -0.0440237 -0.0895913 -0.008 -0.0430138 -0.0895913 0 -0.0430138 -0.0907092 0 -0.0449499 -0.0907092 -0.008 -0.0449499 -0.0900777 0 -0.0440237 -0.0890939 0 -0.0397132 -0.0890939 -0.008 -0.0408342 -0.0890939 -0.008 -0.0397132 -0.0890939 0 -0.0408342 -0.0892609 0 -0.0419426 -0.0892609 -0.008 -0.0419426 -0.0900777 -0.008 -0.0365237 -0.0900777 0 -0.0365237 -0.0895913 -0.008 -0.0375337 -0.0892609 -0.008 -0.0386048 -0.0895913 0 -0.0375337 -0.0892609 0 -0.0386048 -0.0914716 -0.008 -0.0347758 -0.092348 0 -0.0340769 -0.0914716 0 -0.0347758 -0.0907092 0 -0.0355975 -0.0907092 -0.008 -0.0355975 -0.0933188 0 -0.0335165 -0.092348 -0.008 -0.0340769 -0.0933188 -0.008 -0.0335165 -0.0943622 0 -0.0331069 -0.0943622 -0.008 -0.0331069 -0.0954551 0 -0.0328575 -0.0954551 -0.008 -0.0328575 -0.0620729 -0.542 0.0142263 -0.0340729 -0.542 0.0142263 -0.0340729 -0.542 -0.0947737 -0.0620729 -0.542 -0.0947737 -0.0340729 -0.028 -0.0947737 -0.0620729 -0.028 0.0142263 -0.0620729 -0.028 -0.0947737 -0.0340729 -0.028 0.0142263 -0.0620729 -0.542 0.0142263 -0.131073 -0.542 0.0422263 -0.0620729 -0.542 0.0422263 -0.131073 -0.542 0.0142263 -0.131073 -0.542 0.0142263 -0.0620729 -0.542 0.0142263 -0.0620729 -0.57 0.0142263 -0.131073 -0.57 0.0142263 -0.131073 -0.028 0.0422263 -0.0620729 -0.028 0.0142263 -0.0620729 -0.028 0.0422263 -0.131073 -0.028 0.0142263 -0.131073 0 0.0142263 -0.0620729 0 0.0142263 -0.0620729 -0.028 0.0142263 -0.131073 -0.028 0.0142263 - - - - - - - - - - 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.149042 0 0.988831 0 0 1 1.46292e-11 0 1 -0.56332 0 0.826239 -0.433884 0 0.900969 -0.433884 0 0.900969 -0.294755 0 0.955573 -0.149042 0 0.988831 -0.294755 0 0.955573 -0.781832 0 0.62349 -0.866025 0 0.5 -0.781832 0 0.62349 -0.56332 0 0.826239 -0.680173 0 0.733052 -0.680173 0 0.733052 -0.974928 0 0.222521 -0.974928 0 0.222521 -0.997204 0 0.0747301 -0.930874 0 0.365341 -0.866025 0 0.5 -0.930874 0 0.365341 -0.930874 -0 -0.365341 -0.974928 -0 -0.222521 -0.974928 -0 -0.222521 -0.997204 -0 -0.07473 -0.997204 -0 -0.0747302 -0.997204 0 0.07473 -0.781831 -0 -0.62349 -0.680173 -0 -0.733052 -0.781832 -0 -0.62349 -0.930874 -0 -0.365341 -0.866026 -0 -0.5 -0.866025 -0 -0.5 -0.433884 -0 -0.900969 -0.433884 -0 -0.900969 -0.294755 -0 -0.955573 -0.56332 -0 -0.826239 -0.680173 -0 -0.733052 -0.56332 -0 -0.826239 0.149042 0 -0.988831 8.74228e-08 0 -1 8.74228e-08 0 -1 -0.149042 -0 -0.988831 -0.149042 -0 -0.988831 -0.294755 -0 -0.955573 0.433884 0 -0.900969 0.56332 0 -0.826239 0.433884 0 -0.900969 0.149042 0 -0.988831 0.294755 0 -0.955573 0.294755 0 -0.955573 0.781831 0 -0.62349 0.781832 0 -0.62349 0.866025 0 -0.5 0.680173 0 -0.733052 0.56332 0 -0.826239 0.680173 0 -0.733052 0.997204 0 -0.0747303 0.974928 0 -0.222521 0.974928 0 -0.222521 0.930874 0 -0.365341 0.930874 0 -0.365341 0.866025 0 -0.5 0.974928 0 0.222521 0.997204 0 0.0747303 0.997204 0 0.0747303 0.997204 0 -0.0747303 0.974928 0 0.222521 0.930874 0 0.365341 0.930874 0 0.365341 0.866025 0 0.5 0.781831 0 0.62349 0.866025 0 0.5 0.781831 0 0.62349 0.680173 0 0.733052 0.680173 0 0.733052 0.56332 0 0.826239 0.433884 0 0.900969 0.56332 0 0.826239 0.433884 0 0.900969 0.294755 0 0.955573 0.294755 0 0.955573 0.149042 0 0.988831 0.149042 0 0.988831 -0 -1 -2.47818e-16 -0 -1 -2.47818e-16 -0 -1 -2.47818e-16 -0 -1 -2.47818e-16 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0 -1 -1.85037e-16 0.997204 0 -0.0747303 0.997204 0 0.0747303 0.997204 0 -0.0747303 8.74228e-08 0 1 -0.149042 0 0.988831 8.74228e-08 0 1 0.974928 0 -0.222521 0.974928 0 -0.222521 0.930874 0 -0.365341 0.930874 0 -0.365341 0.866025 0 -0.5 0.866025 0 -0.5 0.781831 0 -0.62349 0.781831 0 -0.62349 0.680173 0 -0.733052 0.680173 0 -0.733052 0.56332 0 -0.826239 0.56332 0 -0.826239 0.433884 0 -0.900969 0.433884 0 -0.900969 0.294755 0 -0.955573 0.294755 0 -0.955573 0.149042 0 -0.988831 0.149042 0 -0.988831 -1.74846e-07 -0 -1 3.01992e-07 0 -1 0.997204 0 0.0747303 0.974928 0 0.222521 0.974928 0 0.222521 0.930874 0 0.365341 0.930874 0 0.365341 0.866025 0 0.5 0.866025 0 0.5 0.781831 0 0.62349 0.781832 0 0.62349 0.680173 0 0.733052 0.680173 0 0.733052 0.56332 0 0.826239 0.56332 0 0.826239 0.433884 0 0.900969 0.433884 0 0.900969 0.294755 0 0.955573 0.294755 0 0.955573 0.149042 0 0.988831 0.149042 0 0.988831 -0.294755 0 0.955573 -0.294755 0 0.955573 -0.149042 0 0.988831 -0.680173 0 0.733052 -0.680173 0 0.733052 -0.56332 0 0.826239 -0.433884 0 0.900969 -0.56332 0 0.826239 -0.433884 0 0.900969 -0.866025 0 0.5 -0.930874 0 0.365341 -0.930874 0 0.365341 -0.781831 0 0.62349 -0.781832 0 0.62349 -0.866026 0 0.5 -0.997204 -0 -0.07473 -0.997204 0 0.0747302 -0.997204 -0 -0.0747301 -0.997204 0 0.07473 -0.974928 0 0.222521 -0.974928 0 0.222521 -0.866025 -0 -0.5 -0.866025 -0 -0.5 -0.930874 -0 -0.365341 -0.974928 -0 -0.222521 -0.930874 -0 -0.365341 -0.974928 -0 -0.222521 -0.680173 -0 -0.733052 -0.56332 -0 -0.826239 -0.680173 -0 -0.733052 -0.781832 -0 -0.62349 -0.781832 -0 -0.62349 -0.433884 -0 -0.900969 -0.56332 -0 -0.826239 -0.433884 -0 -0.900969 -0.294755 -0 -0.955573 -0.294755 -0 -0.955573 -0.149042 -0 -0.988831 -0.149042 -0 -0.988831 0 1 0 0 1 0 0 1 0 0 1 0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 0 1 0 0 1 0 0 1 0 0 1 0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -1 -2.47818e-16 -0 -1 -2.47818e-16 -0 -1 -2.47818e-16 -0 -1 -2.47818e-16 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 - - - - - - - - - - - - - - -

0 1 2 3 4 0 1 0 4 0 5 3 6 7 8 6 8 9 10 11 12 10 13 11 14 15 16 15 14 17 18 17 14 18 19 20 18 14 19 15 21 20 18 20 21 15 20 16 22 23 24 25 24 26 27 28 23 29 24 23 26 24 29 26 27 25 23 22 27 26 28 27 30 31 32 31 30 33 34 35 31 35 32 31 36 37 38 39 40 41 42 43 44 45 41 46 47 37 48 37 36 48 49 37 50 37 47 50 51 37 52 37 49 52 53 39 41 37 51 53 41 37 53 54 41 40 41 55 56 57 55 41 41 58 59 56 58 41 60 46 41 59 60 41 41 61 62 63 61 41 63 41 45 43 62 64 65 66 43 41 67 68 42 69 43 43 41 62 70 71 43 70 43 69 72 73 43 72 43 71 65 43 73 74 43 75 66 76 43 43 77 78 76 77 43 38 43 79 78 79 43 80 38 81 38 79 81 82 38 83 38 80 83 84 38 85 38 82 85 36 38 84 57 41 54 68 37 41 44 43 64 68 67 74 68 74 75 75 43 38 86 87 88 89 90 91 92 91 93 94 95 96 97 91 98 97 93 91 99 91 100 99 98 91 101 91 102 101 100 91 90 103 91 103 102 91 104 105 91 89 91 106 91 107 108 91 105 86 86 109 91 107 91 109 86 88 110 86 110 109 86 111 112 87 86 112 86 94 113 111 86 113 114 115 116 86 95 94 117 118 95 95 118 96 119 120 95 95 120 117 121 122 95 95 122 119 121 114 116 114 123 124 124 115 114 114 125 126 123 114 126 114 127 128 125 114 128 114 129 130 127 114 130 114 131 132 129 114 132 92 133 114 133 131 114 92 114 91 105 104 134 134 104 135 108 106 91 134 114 95 95 114 121 134 135 114 136 137 138 138 139 136 140 141 142 143 140 144 141 140 145 140 143 145 146 147 148 146 149 147 150 151 152 150 153 151 152 154 150 150 155 153 156 157 158 159 160 156 161 157 162 163 157 156 160 163 156 157 161 158 160 159 161 160 161 162 164 165 166 164 166 167 168 169 170 169 168 171 172 173 174 173 172 175 176 177 178 176 179 177 180 181 182 180 182 183 182 184 185 185 184 186 182 181 184 180 186 187 186 180 183 184 187 186 188 189 190 188 190 191 192 193 194 192 194 195 196 197 198 196 198 199 200 201 202 200 203 201 204 205 206 205 204 207 208 209 210 209 208 211 212 213 214 215 216 217 218 219 220 221 222 219 223 224 219 219 224 220 225 226 219 219 226 223 219 222 227 219 227 225 215 228 219 221 219 228 229 230 215 215 230 228 231 232 215 215 232 229 233 234 215 215 234 231 235 236 215 215 236 233 237 238 215 215 238 235 215 217 239 215 239 237 240 216 212 215 212 216 241 242 212 212 242 240 243 244 212 212 244 241 212 245 246 212 214 243 212 246 247 212 247 213 212 248 249 245 212 249 218 250 212 248 212 250 251 252 218 218 252 250 253 254 218 218 254 251 255 256 218 218 256 253 220 257 218 218 257 255 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 323 322 321 325 326 325 321 323 327 328 326 326 325 327 329 328 330 327 330 328 329 331 332 331 329 330 333 334 332 332 331 333 335 334 336 333 336 334 335 337 338 337 335 336 339 340 338 338 337 339 259 340 341 339 341 340 260 259 341 324 315 317 324 322 315 316 319 318 317 316 318 311 310 320 319 311 320 312 314 309 309 314 310 303 313 304 304 313 312 307 305 308 307 303 305 306 297 299 306 308 297 298 301 300 299 298 300 293 292 302 301 293 302 294 296 291 291 296 292 285 295 286 286 295 294 289 287 290 289 285 287 288 279 281 288 290 279 280 283 282 281 280 282 275 274 284 283 275 284 276 278 273 273 278 274 267 277 268 268 277 276 271 269 272 271 267 269 270 261 263 270 272 261 262 264 266 263 262 266 258 260 265 264 258 265 342 343 344 342 345 343 346 347 348 346 349 347 350 351 352 353 352 354 355 354 352 356 357 358 359 352 360 352 353 360 361 352 362 352 359 362 352 361 350 358 352 363 351 363 352 364 358 365 358 363 365 366 358 367 358 364 367 368 358 369 358 366 369 370 358 371 358 368 371 372 358 373 358 370 373 358 374 356 358 372 374 375 358 357 376 375 377 375 357 377 378 375 379 375 376 379 380 375 381 375 378 381 375 382 383 384 375 385 375 380 385 375 384 382 375 386 387 383 386 375 355 375 388 387 388 375 389 355 390 355 388 390 391 355 392 355 389 392 393 355 394 355 391 394 354 355 395 355 393 395 396 397 398 399 400 401 398 402 403 403 396 398 404 405 402 403 402 405 406 404 407 404 406 405 407 408 409 409 406 407 410 411 408 409 408 411 412 410 413 410 412 411 413 414 415 415 412 413 416 417 414 415 414 417 418 416 419 416 418 417 420 418 419 420 419 421 396 422 397 423 424 422 397 422 424 425 423 426 423 425 424 426 427 428 428 425 426 429 430 427 428 427 430 431 429 432 429 431 430 432 433 434 434 431 432 435 436 433 434 433 436 437 435 438 435 437 436 438 439 440 440 437 438 399 401 439 440 439 401 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 470 473 469 474 468 474 469 473 475 476 475 473 474 477 478 476 476 475 477 421 478 479 477 479 478 420 421 479 471 462 472 472 468 470 464 463 466 462 471 463 465 467 458 464 466 465 456 459 457 467 456 458 460 451 461 459 461 457 455 450 452 452 451 460 444 454 453 454 450 455 446 445 448 444 453 445 447 449 441 446 448 447 442 400 443 449 442 441 399 443 400 480 481 482 480 482 483 484 485 486 484 487 485 488 489 490 489 488 491 492 493 494 494 495 492 496 497 498 496 499 497 500 501 502 502 503 500

-
-
-
- - - - -0.0245319 0.671506 -0.2 -0.0525319 0.671506 0.2 -0.0245319 0.671506 0.2 -0.0525319 0.671506 -0.2 -0.0525319 0.671506 0.2 -0.0525319 0.643506 -0.2 -0.0525319 0.643506 0.2 -0.0525319 0.671506 -0.2 -0.0245319 0.643506 -0.2 -0.0245319 0.643506 0.2 -0.0525319 0.643506 0.2 -0.0525319 0.643506 -0.2 -0.0245319 0.643506 0.2 -0.0245319 0.671506 -0.2 -0.0245319 0.671506 0.2 -0.0245319 0.643506 -0.2 -0.0525319 0.671506 0.2 -0.0525319 0.643506 0.2 -0.0245319 0.643506 0.2 -0.0245319 0.671506 0.2 -0.0525319 0.671506 -0.2 -0.0245319 0.671506 -0.2 -0.0245319 0.643506 -0.2 -0.0525319 0.643506 -0.2 - - - - - - - - - - 0 1 0 0 1 0 0 1 0 0 1 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 1 1.23909e-16 0 1 1.23909e-16 0 1 1.23909e-16 0 1 1.23909e-16 0 0 0 1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 - - - - - - - - - - - - - - -

0 1 2 1 0 3 4 5 6 4 7 5 8 9 10 10 11 8 12 13 14 13 12 15 16 17 18 16 18 19 20 21 22 22 23 20

-
-
-
- - - - -0.0525319 0.242506 -0.172 -0.0525319 0.214506 0.033 -0.0525319 0.242506 0.033 -0.0525319 0.214506 -0.172 -0.0245319 0.214506 -0.172 -0.0245319 0.214506 0.033 -0.0525319 0.214506 0.033 -0.0525319 0.214506 -0.172 -0.0245319 0.242506 -0.172 -0.0245319 0.242506 0.033 -0.0245319 0.214506 0.033 -0.0245319 0.214506 -0.172 -0.0245319 0.242506 -0.172 -0.0525319 0.242506 0.033 -0.0245319 0.242506 0.033 -0.0525319 0.242506 -0.172 -0.0525319 0.242506 0.033 -0.0245319 0.214506 0.033 -0.0245319 0.242506 0.033 -0.0525319 0.214506 0.033 -0.0525319 0.242506 -0.172 -0.0245319 0.242506 -0.172 -0.0245319 0.214506 -0.172 -0.0525319 0.214506 -0.172 - - - - - - - - - - -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 - - - - - - - - - - - - - - -

0 1 2 1 0 3 4 5 6 6 7 4 8 9 10 10 11 8 12 13 14 13 12 15 16 17 18 17 16 19 20 21 22 22 23 20

-
-
-
- - - - 0.529468 0.643506 -0.172 0.557468 -0.0204943 -0.172 0.557468 0.643506 -0.172 0.529468 -0.0204943 -0.172 0.557468 -0.0204943 -0.172 0.557468 0.643506 -0.2 0.557468 0.643506 -0.172 0.557468 -0.0204943 -0.2 0.557468 0.643506 -0.2 0.529468 -0.0204943 -0.2 0.529468 0.643506 -0.2 0.557468 -0.0204943 -0.2 0.529468 0.643506 -0.2 0.529468 -0.0204943 -0.172 0.529468 0.643506 -0.172 0.529468 -0.0204943 -0.2 0.557468 0.643506 -0.172 0.557468 0.643506 -0.2 0.529468 0.643506 -0.2 0.529468 0.643506 -0.172 0.557468 -0.0204943 -0.172 0.529468 -0.0204943 -0.172 0.529468 -0.0204943 -0.2 0.557468 -0.0204943 -0.2 - - - - - - - - - - 0 0 1 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 1 0 0 1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 - - - - - - - - - - - - - - -

0 1 2 1 0 3 4 5 6 4 7 5 8 9 10 9 8 11 12 13 14 13 12 15 16 17 18 16 18 19 20 21 22 22 23 20

-
-
-
- - - - -0.0525319 0.643506 0.2 -0.0525319 -0.0204943 0.172 -0.0525319 0.643506 0.172 -0.0525319 -0.0204943 0.2 -0.0525319 0.643506 0.172 -0.0245319 -0.0204943 0.172 -0.0245319 0.643506 0.172 -0.0525319 -0.0204943 0.172 -0.0245319 0.643506 0.2 -0.0245319 -0.0204943 0.172 -0.0245319 -0.0204943 0.2 -0.0245319 0.643506 0.172 -0.0525319 0.643506 0.2 -0.0245319 -0.0204943 0.2 -0.0525319 -0.0204943 0.2 -0.0245319 0.643506 0.2 -0.0525319 -0.0204943 0.2 -0.0245319 -0.0204943 0.2 -0.0245319 -0.0204943 0.172 -0.0525319 -0.0204943 0.172 -0.0525319 0.643506 0.2 -0.0245319 0.643506 0.172 -0.0245319 0.643506 0.2 -0.0525319 0.643506 0.172 - - - - - - - - - - -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 - - - - - - - - - - - - - - -

0 2 1 1 3 0 4 6 5 5 7 4 8 10 9 8 9 11 12 14 13 12 13 15 16 18 17 18 16 19 20 22 21 21 23 20

-
-
-
- - - - 0.529468 0.643506 0.478 0.529468 0.214506 0.45 0.529468 0.643506 0.45 0.529468 0.214506 0.478 0.529468 0.643506 0.45 0.557468 0.214506 0.45 0.557468 0.643506 0.45 0.529468 0.214506 0.45 0.557468 0.643506 0.478 0.557468 0.214506 0.45 0.557468 0.214506 0.478 0.557468 0.643506 0.45 0.529468 0.643506 0.478 0.557468 0.214506 0.478 0.529468 0.214506 0.478 0.557468 0.643506 0.478 0.529468 0.214506 0.478 0.557468 0.214506 0.478 0.557468 0.214506 0.45 0.529468 0.214506 0.45 0.529468 0.643506 0.478 0.557468 0.643506 0.45 0.557468 0.643506 0.478 0.529468 0.643506 0.45 - - - - - - - - - - -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 - - - - - - - - - - - - - - -

0 2 1 1 3 0 4 6 5 5 7 4 8 10 9 8 9 11 12 14 13 12 13 15 16 18 17 18 16 19 20 22 21 21 23 20

-
-
-
- - - - 0.529468 0.242506 0.478 0.289968 0.214506 0.478 0.289968 0.242506 0.478 0.529468 0.214506 0.478 0.529468 0.242506 0.478 0.289968 0.242506 0.45 0.529468 0.242506 0.45 0.289968 0.242506 0.478 0.529468 0.242506 0.45 0.289968 0.242506 0.45 0.289968 0.214506 0.45 0.529468 0.214506 0.45 0.529468 0.214506 0.478 0.289968 0.214506 0.45 0.289968 0.214506 0.478 0.529468 0.214506 0.45 0.289968 0.242506 0.478 0.289968 0.214506 0.45 0.289968 0.242506 0.45 0.289968 0.214506 0.478 0.529468 0.242506 0.478 0.529468 0.214506 0.45 0.529468 0.214506 0.478 0.529468 0.242506 0.45 - - - - - - - - - - 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 - - - - - - - - - - - - - - -

0 2 1 1 3 0 4 6 5 5 7 4 8 10 9 10 8 11 12 14 13 12 13 15 16 18 17 16 17 19 20 22 21 21 23 20

+

0 1 2 3 4 5 6 7 8 9 10 11 0 2 12 5 13 9 2 14 3 2 3 12 15 6 8 16 17 15 11 6 15 16 15 8 10 6 11 3 5 12 5 4 13 18 19 10 5 9 11 18 10 9 10 19 4 13 4 19 20 21 22 20 22 23 24 25 26 25 24 27 28 29 30 28 30 31 32 33 34 35 36 37 38 35 37 32 34 35 34 39 36 34 36 35 40 41 42 43 40 44 45 41 43 40 43 41 42 41 46 45 43 47 48 49 50 48 51 49 52 53 54 52 54 55 56 57 58 56 59 57 60 61 62 61 60 63 64 65 66 64 67 65 68 69 70 70 71 68 72 73 74 73 72 75 76 77 78 79 80 81 82 77 83 84 85 86 80 86 81 81 86 85 77 81 85 87 76 78 85 78 77 83 77 76 88 89 90 88 91 89 92 93 94 94 95 92 96 97 98 96 98 99 100 101 102 100 102 103 104 105 106 106 107 104 108 109 110 108 110 111 112 113 114 114 115 112 116 117 118 116 118 119 120 121 122 122 123 120 124 125 126 124 127 125 128 129 130 129 128 131 132 133 134 132 135 133 136 137 138 137 136 139 140 141 142 141 140 143 144 145 146 144 147 148 144 149 145 150 151 152 149 151 145 144 148 149 145 151 153 153 151 154 151 150 154 154 155 153 156 157 158 157 156 159 160 161 162 163 164 165 166 167 165 162 167 160 165 164 166 165 167 162 168 169 170 171 172 169 168 173 174 169 175 170 174 169 168 176 177 173 169 174 171 178 172 171 176 178 177 178 171 177 179 180 181 179 182 180 183 184 185 184 181 185 183 186 187 187 186 182 184 183 187 180 188 181 179 181 184 181 188 189 190 191 192 190 192 193 194 195 196 196 197 194 198 199 200 200 201 198 202 203 204 202 204 205 206 207 208 206 209 207 210 211 212 212 213 210 214 215 216 214 217 215 218 219 220 219 218 221 222 223 224 223 222 225 226 227 228 227 226 229 230 231 232 232 233 230 234 235 236 237 238 239 240 241 242 243 244 245 236 235 246 245 234 236 237 246 235 247 248 243 239 246 237 247 237 248 246 249 250 251 247 250 246 239 249 247 238 237 250 249 251 247 251 238 248 240 252 253 244 243 254 248 252 245 255 234 248 234 240 242 252 240 240 234 255 245 244 255 254 253 243 248 254 243 256 257 258 258 259 256 256 260 261 260 262 261 256 261 257 262 259 258 261 262 263 262 258 263 264 265 266 267 268 269 270 265 264 268 270 269 271 272 273 267 274 264 264 266 267 268 265 270 272 271 275 276 275 277 276 272 275 273 264 274 277 278 276 279 270 276 272 264 273 278 271 273 273 279 278 267 269 274 276 278 279 270 279 269 280 281 282 283 284 285 281 283 286 287 280 282 283 281 280 288 280 287 289 281 286 290 284 291 290 285 284 290 291 292 293 283 285 281 289 294 285 295 294 281 294 295 285 294 293 283 293 286 282 292 296 297 288 298 282 296 287 288 299 280 300 296 292 288 297 299 280 299 291 292 291 301 299 301 291 292 301 300 302 303 304 304 305 302 306 307 308 306 308 309 310 311 312 312 313 310 314 315 316 314 316 317 318 319 320 318 320 321 322 323 324 323 322 325 326 324 323 327 328 329 323 330 326 329 322 324 328 331 329 329 332 327 331 328 333 322 329 331 334 335 336 334 337 335 338 339 340 338 341 339 342 343 344 343 342 345 346 347 348 347 346 349 350 351 352 352 353 350 354 355 356 355 354 357 358 359 360 360 361 358 362 363 364 362 364 365 366 367 368 366 368 369 370 371 372 370 372 373 374 375 376 374 377 375 378 379 380 381 382 383 378 384 379 381 385 386 380 387 388 381 386 382 381 383 379 382 389 383 378 380 388 383 380 379 390 391 392 393 394 395 393 396 397 398 390 392 393 397 394 393 391 396 397 396 399 400 390 398 396 391 390 401 392 391 402 403 404 404 405 402 406 407 408 406 408 409 410 411 412 411 410 413 414 415 416 416 417 414 418 419 420 420 421 418 422 423 424 422 424 425 426 427 428 429 430 428 431 428 427 432 433 434 430 426 428 435 431 432 431 436 437 434 435 432 438 436 431 431 435 428 432 431 437 439 427 440 440 427 426 439 441 427 442 443 444 445 446 444 443 447 448 449 444 443 450 451 452 447 443 442 449 443 453 449 454 455 451 450 453 456 449 455 450 449 453 450 454 449 445 444 457 446 442 444 458 459 460 459 458 461 462 463 464 462 465 463 466 467 468 466 469 467 470 471 472 470 472 473 474 475 476 474 476 477 478 479 480 480 481 478 482 483 484 483 482 485 486 487 488 487 486 489 490 491 492 492 493 490 494 495 496 494 496 497 498 499 500 498 500 501 502 503 504 504 505 502 506 507 508 506 508 509 510 511 512 510 512 513

@@ -999,133 +78,9 @@ - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 + -2.08167e-16 -1 0 -0.543 1 -2.08167e-16 0 -0.028 0 0 1 -0.028 0 0 0 1 - - 2.91434e-16 1 0 0.287 -1 2.91434e-16 0 -0.227 0 0 1 -0.2615 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - - - 2.35922e-16 1 0 0.287 -1 2.35922e-16 0 0.227 0 0 1 -0.1615 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - - - 1 0 0 0.283573 0 1 0 0.285 0 0 1 -0.339726 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - - - -5.27356e-16 -1 0 0.287 -1 5.27356e-16 0 0.227 0 0 -1 -0.3615 0 0 0 1 - - - - 1 0 0 0.283573 0 1 0 0.285 0 0 1 -0.339726 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - - - 1 0 0 0.283573 0 1 0 0.285 0 0 1 -0.339726 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - - - 2.91434e-16 1 0 0.287 -1 2.91434e-16 0 -0.227 0 0 1 -0.1615 0 0 0 1 - - - - 2.35922e-16 1 0 0.287 -1 2.35922e-16 0 0.227 0 0 1 -0.2615 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - - - -4.23273e-16 -1 0 0.287 -1 4.23273e-16 0 -0.227 0 0 -1 -0.3615 0 0 0 1 - - - - -1.59595e-16 -1 0 0.311506 1 -1.59595e-16 0 -0.252468 0 0 1 -5.55112e-17 0 0 0 1 - - @@ -1135,7 +90,7 @@ - + @@ -1144,258 +99,6 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
diff --git a/src/tsukuba2022/meshes/front_wheel.dae b/src/tsukuba2022/meshes/front_wheel.dae new file mode 100644 index 0000000..75b9a25 --- /dev/null +++ b/src/tsukuba2022/meshes/front_wheel.dae @@ -0,0 +1,174 @@ + + + + + 2022-09-07T14:55:35 + 2022-09-07T14:55:35 + + Z_UP + + + + + + + + + + + + + + + + + + 0.258824 0.278431 0.301961 1 + + + 1 1 1 1 + + + 1 + + + + + + 1 + + + + + + + + + + 0.0862745 0.321569 0.576471 1 + + + 1 1 1 1 + + + 1 + + + + + + 1 + + + + + + + + + + + -0.0433497 -0.0191026 0.080792 -0.0417029 -0.0211691 0.0777227 -0.0279678 -0.0211691 0.0836525 -0.0954726 -0.0098263 -0.0274738 -0.0967503 -0.0133457 -0.0107229 -0.0987424 -0.0098263 -0.0109437 0.00143348 -0.0226067 0.0844055 0.00149777 -0.0211691 0.0881913 -0.0134282 -0.0211691 0.0871758 -0.0290723 -0.0191026 0.086956 0.0149389 -0.0233729 0.0790413 0.0156774 -0.0226067 0.0829491 0.028082 -0.0233729 0.0753797 0.0294704 -0.0226067 0.0791065 0.0489928 -0.0234449 0.0586116 0.0515899 -0.0233729 0.0617186 0.0404173 -0.0233729 0.0695495 0.0424156 -0.0226067 0.0729881 0.0541405 -0.0226067 0.0647699 0.0612783 -0.0233729 0.0521121 0.0643079 -0.0226067 0.0546885 0.0383827 -0.0234449 0.0660483 0.0593713 -0.0195768 0.0264543 0.0640358 -0.0215182 0.0244771 0.0589781 -0.0215182 0.0349472 0.0581935 -0.0234449 0.0494887 0.061813 -0.0195768 0.0201012 0.0672514 -0.0215182 0.0133029 0.0646403 -0.0195768 0.00681493 0.0685322 -0.0215182 0.00174606 0.0688465 -0.0228204 -0.0223696 0.0716367 -0.0228204 -0.0104127 0.0651992 -0.0215182 -0.0211845 0.0749391 -0.0234449 0.0148237 0.0763664 -0.0234449 0.00194565 0.0789116 -0.0233729 0.0156094 0.0678415 -0.0215182 -0.00986106 0.0635825 -0.0195768 -0.0134965 0.072366 -0.0228204 0.00184373 -0.058272 -0.0164687 0.07473 -0.0563801 -0.0191026 0.0723038 0.0618187 -0.0195768 -0.0200861 -0.0700633 -0.0164687 0.0638071 -0.0677885 -0.0191026 0.0617354 -0.0542382 -0.0211691 0.0695569 -0.0820116 -0.0133457 0.0524377 -0.0798389 -0.0164687 0.0510485 -0.0772468 -0.0191026 0.0493911 -0.0873178 -0.0164687 0.0368214 -0.0896939 -0.0133457 0.0378234 -0.0922846 -0.0164687 0.021535 -0.0947959 -0.0133457 0.022121 -0.0971709 -0.0133457 0.00578221 -0.0991716 -0.0098263 0.00590127 -0.0945966 -0.0164687 0.00562903 -0.101234 0.00202505 0.00602396 -0.0987593 0.00202505 0.0230459 -0.100539 0.00601501 0.00598266 -0.09069 -0.00601501 -0.0438096 -0.0967893 -0.00601501 -0.0278527 -0.0139585 0.0191026 0.0906185 0.00160916 0.0164687 0.0947503 0.00155692 0.0191026 0.091674 -0.0700633 0.0164687 0.0638071 -0.0719699 0.0133457 0.0655434 -0.0598578 0.0133457 0.0767636 0.0424156 0.0226067 0.0729881 0.0294704 0.0226067 0.0791065 0.044318 0.0211691 0.0762618 0.028082 0.0233729 0.0753797 0.0404173 0.0233729 0.0695495 0.0581935 0.0234449 0.0494887 0.0657201 0.0234449 0.0389421 0.0551451 0.0228204 0.0468963 0.0758827 0.0211691 0.0449639 0.0726253 0.0226067 0.0430337 0.0643079 0.0226067 0.0546885 0.0804146 0.0233729 0.00204879 0.0763664 0.0234449 0.00194565 0.0749391 0.0234449 0.0148237 0.0622774 0.0228204 0.0369021 0.071356 0.0234449 0.0272752 0.0678415 0.0215182 -0.00986106 0.0646424 0.0195768 -0.00680575 0.0685322 0.0215182 0.00174606 0.0649985 0.0195768 -1.37752e-05 0.0618187 0.0195768 -0.0200861 0.0635825 0.0195768 -0.0134965 0.0651992 0.0215182 -0.0211845 0.0672514 0.0215182 0.0133029 0.0646448 0.0195768 0.00677496 0.0541405 0.0226067 0.0647699 0.0515899 0.0233729 0.0617186 0.0692039 0.0233729 0.0410064 0.0612783 0.0233729 0.0521121 0.0163806 0.0211691 0.0866696 0.00149777 0.0211691 0.0881913 0.0170275 0.0191026 0.0900923 0.0156774 0.0226067 0.0829491 0.0307922 0.0211691 0.0826546 0.00168699 0.0098263 0.0993327 -0.0148195 0.0133457 0.0962081 -0.0151246 0.0098263 0.098189 -0.0134282 0.0211691 0.0871758 -0.058272 0.0164687 0.07473 -0.0460237 0.0133457 0.0857755 -0.0300478 0.0164687 0.089874 -0.0433497 0.0191026 0.080792 -0.0448044 0.0164687 0.0835031 -0.0734517 0.0098263 0.066893 -0.0820116 0.0133457 0.0524377 -0.0837002 0.0098263 0.0535174 -0.0563801 0.0191026 0.0723038 -0.0896939 0.0133457 0.0378234 -0.0915407 0.0098263 0.0386022 -0.0798389 0.0164687 0.0510485 -0.0967477 -0.0098263 0.0225765 -0.0594734 0.0233729 0.0541628 -0.0519099 0.0226067 0.066571 -0.0494644 0.0233729 0.0634348 -0.0777844 0.0226067 0.0328012 -0.0743121 0.0211691 0.0475147 -0.0711221 0.0226067 0.045475 -0.100795 0.00202505 -0.0111712 -0.0974576 0.00202505 -0.0280451 -0.100795 -0.00202505 -0.0111712 -0.0913161 0.00202505 -0.0441121 -0.0974576 -0.00202505 -0.0280451 -0.0880482 0.0211691 0.00523936 -0.0892884 0.0191026 0.0208358 -0.0858963 0.0211691 0.0200442 -0.0808663 -0.0098263 -0.0577102 -0.0819816 -0.00601501 -0.0585061 -0.0709148 -0.00601501 -0.0715195 -0.0913161 -0.00202505 -0.0441121 -0.0825477 -0.00202505 -0.0589101 -0.043038 -0.00601501 -0.0910587 -0.0570215 -0.0098263 -0.0813534 -0.0578079 -0.00601501 -0.0824754 -0.0699501 -0.0098263 -0.0705465 -0.0102443 -0.00601501 -0.100195 -0.0266622 -0.0098263 -0.0957024 -0.0270299 -0.00601501 -0.0970223 -0.0685389 -0.0133457 -0.0691233 -0.0792349 -0.0133457 -0.0565459 -0.0424525 -0.0098263 -0.0898199 -0.041596 -0.0133457 -0.0880078 -0.0272166 -0.00202505 -0.0976922 -0.010315 -0.00202505 -0.100887 -0.0101049 -0.0098263 -0.0988318 -0.0261243 -0.0133457 -0.0937717 0.0238836 -0.00202505 -0.0985601 0.00683609 -0.00601501 -0.100485 0.00688329 -0.00202505 -0.101179 0.00674309 -0.0098263 -0.0991179 0.0233971 -0.0098263 -0.0965526 0.00660705 -0.0133457 -0.0971183 0.0553536 -0.00202505 -0.0849735 0.0399211 -0.00601501 -0.0924676 0.0401968 -0.00202505 -0.093106 0.08915 -0.00601501 -0.0468638 0.07886 -0.0098263 -0.0604228 0.0799477 -0.00601501 -0.0612562 0.0684453 -0.00601501 -0.0738863 0.0689179 -0.00202505 -0.0743964 0.0804997 -0.00202505 -0.0616791 0.0861631 -0.0133457 -0.0452937 0.0944846 -0.0098263 -0.0306999 0.0925784 -0.0133457 -0.0300806 0.0531321 -0.0133457 -0.0815634 0.0542261 -0.0098263 -0.0832427 0.0675142 -0.0098263 -0.0728811 0.0573685 -0.0226067 -0.0619289 0.0670094 -0.0226067 -0.0513428 0.0546658 -0.0233729 -0.0590114 0.0727799 -0.0191026 -0.0557642 0.0623088 -0.0191026 -0.0672619 0.0752221 -0.0164687 -0.0576354 0.0897656 -0.00202505 -0.0471874 0.0964491 -0.00202505 -0.0313382 0.0838805 -0.0164687 -0.0440938 0.0573685 0.0226067 -0.0619289 0.048144 0.0211691 -0.073906 0.0460773 0.0226067 -0.0707334 0.0964491 0.00202505 -0.0313382 0.08915 0.00601501 -0.0468638 0.0879372 0.0098263 -0.0462263 0.0944846 0.0098263 -0.0306999 0.0957877 0.00601501 -0.0311233 0.0700149 0.0211691 -0.0536457 0.078074 0.0211691 -0.0410414 0.0727799 0.0191026 -0.0557642 0.0925784 0.0133457 -0.0300806 0.0861631 0.0133457 -0.0452937 0.0901259 0.0164687 -0.0292837 0.0838805 0.0164687 -0.0440938 0.0871998 0.0191026 -0.0283329 0.083887 0.0211691 -0.0272565 0.0811572 0.0191026 -0.0426622 0.0747225 0.0226067 -0.0392796 0.0712022 0.0233729 -0.0374292 0.0765036 0.0233729 -0.0248575 0.0802859 0.0226067 -0.0260865 0.0676178 0.0234449 -0.0355449 0.0726523 0.0234449 -0.0236062 0.0544174 0.0215182 -0.0416948 0.0606812 0.0215182 -0.0318985 0.0574616 0.0228204 -0.0440273 0.0606381 0.0234449 -0.0464611 0.0638525 0.0233729 -0.048924 0.0688465 0.0228204 -0.0223696 0.0593728 0.0195768 -0.0264531 0.0640757 0.0228204 -0.0336829 0.07886 0.0098263 -0.0604228 0.0799477 0.00601501 -0.0612562 0.0879372 -0.0098263 -0.0462263 0.0772691 -0.0133457 -0.0592038 0.0897656 0.00202505 -0.0471874 0.0957877 -0.00601501 -0.0311233 0.0901259 -0.0164687 -0.0292837 0.0363419 0.0191026 -0.0841773 0.0349613 0.0211691 -0.0809793 0.0599416 -0.0211691 -0.0647066 0.0700149 -0.0211691 -0.0536457 0.0871998 -0.0191026 -0.0283329 0.0811572 -0.0191026 -0.0426622 0.0802859 -0.0226067 -0.0260865 0.0747225 -0.0226067 -0.0392796 0.083887 -0.0211691 -0.0272565 0.078074 -0.0211691 -0.0410414 0.0712022 -0.0233729 -0.0374292 0.0726523 -0.0234449 -0.0236062 0.0676178 -0.0234449 -0.0355449 0.0765036 -0.0233729 -0.0248575 0.0606381 -0.0234449 -0.0464611 0.0638525 -0.0233729 -0.048924 0.0325131 -0.0195768 -0.0562833 0.0264419 -0.0195768 -0.0593781 0.0271728 -0.0215182 -0.0629393 0.0640757 -0.0228204 -0.0336829 0.052592 -0.0195768 -0.0381957 0.0544174 -0.0215182 -0.0416948 0.0562972 -0.0195768 -0.0324896 0.0606812 -0.0215182 -0.0318985 0.0593728 -0.0195768 -0.0264531 0.039378 -0.0098263 -0.0912096 0.054974 -0.00601501 -0.0843908 0.0382198 -0.0195768 -0.052574 0.0374188 -0.0215182 -0.0574417 0.0465882 -0.0215182 -0.0502917 0.0385836 -0.0133457 -0.0893695 0.0229251 -0.0133457 -0.0946047 0.0553536 0.00202505 -0.0849735 0.0401968 0.00202505 -0.093106 -0.0376909 0.0211691 -0.0797455 -0.0236717 0.0211691 -0.0849682 -0.0391794 0.0191026 -0.0828947 0.0237198 -0.00601501 -0.0978842 -0.0621043 0.0211691 -0.0626339 -0.0594383 0.0226067 -0.0599452 -0.0484526 0.0226067 -0.069128 -0.0433351 -0.00202505 -0.0916874 -0.0746314 0.0191026 -0.0532607 -0.0717961 0.0211691 -0.0512372 -0.0894562 -0.0098263 -0.0432136 -0.0876515 -0.0133457 -0.0423418 -0.058207 -0.00202505 -0.0830449 -0.0714044 -0.00202505 -0.0720133 -0.0991716 0.0098263 0.00590127 -0.0987424 0.0098263 -0.0109437 -0.0935465 -0.0133457 -0.0269196 -0.100104 -0.00601501 -0.0110946 0.0483164 -0.0195768 -0.0434784 0.0434971 -0.0195768 -0.0483011 0.0574616 -0.0228204 -0.0440273 0.0201048 -0.0195768 -0.0618111 0.0161452 -0.0215182 -0.0666262 0.0416962 -0.0234449 -0.0640081 0.0439065 -0.0233729 -0.0674011 0.0643997 -0.0164687 -0.069519 0.0500452 -0.0191026 -0.0768246 0.0661522 -0.0133457 -0.0714108 0.0517246 -0.0164687 -0.0794026 0.0804997 0.00202505 -0.0616791 0.0772691 0.0133457 -0.0592038 0.0752221 0.0164687 -0.0576354 0.0684453 0.00601501 -0.0738863 0.0675142 0.0098263 -0.0728811 0.0599416 0.0211691 -0.0647066 0.0670094 0.0226067 -0.0513428 0.0546658 0.0233729 -0.0590114 0.0519139 0.0234449 -0.0560407 0.0562819 0.0195768 -0.0325136 0.00680864 -0.0195768 -0.0646409 0.0135236 -0.0195768 -0.0635774 0.0491944 -0.0228204 -0.0531051 0.0519139 -0.0234449 -0.0560407 0.0318841 -0.0233729 -0.0738519 0.0302791 -0.0234449 -0.0701341 0.0334605 -0.0226067 -0.0775031 0.0460773 -0.0226067 -0.0707334 0.048144 -0.0211691 -0.073906 0.0689179 0.00202505 -0.0743964 0.0661522 0.0133457 -0.0714108 0.0643997 0.0164687 -0.069519 0.054974 0.00601501 -0.0843908 0.0542261 0.0098263 -0.0832427 0.0623088 0.0191026 -0.0672619 0.0491944 0.0228204 -0.0531051 0.039512 0.0228204 -0.0606551 0.0465882 0.0215182 -0.0502917 0.0482901 0.0195768 -0.0435074 0.0525817 0.0195768 -0.0382119 0.039512 -0.0228204 -0.0606551 0.00465307 -0.0215182 -0.0683964 0.0198811 -0.0226067 -0.0820431 0.0189445 -0.0233729 -0.078178 0.0207728 -0.0211691 -0.085723 0.0363419 -0.0191026 -0.0841773 0.0349613 -0.0211691 -0.0809793 0.0375614 -0.0164687 -0.087002 0.0215932 -0.0191026 -0.0891083 0.0223178 -0.0164687 -0.0920985 0.039378 0.0098263 -0.0912096 0.0531321 0.0133457 -0.0815634 0.0517246 0.0164687 -0.0794026 0.0399211 0.00601501 -0.0924676 0.0500452 0.0191026 -0.0768246 0.0416962 0.0234449 -0.0640081 0.0302791 0.0234449 -0.0701341 0.0439065 0.0233729 -0.0674011 0.0318841 0.0233729 -0.0738519 0.0374188 0.0215182 -0.0574417 0.0381946 0.0195768 -0.0525938 0.0434865 0.0195768 -0.0483094 -0.013495 -0.0195768 -0.063582 -0.0069729 -0.0215182 -0.0681989 -0.00679187 -0.0195768 -0.0646442 0.0286929 -0.0228204 -0.0664602 -0.0183983 -0.0215182 -0.0660395 0.00545984 -0.0233729 -0.0802552 0.00518498 -0.0234449 -0.076215 -0.0270299 0.00601501 -0.0970223 -0.0266622 0.0098263 -0.0957024 -0.0101049 0.0098263 -0.0988318 0.00572977 0.0226067 -0.084223 0.0198811 0.0226067 -0.0820431 0.00598677 0.0211691 -0.0880006 0.0385836 0.0133457 -0.0893695 0.0375614 0.0164687 -0.087002 0.0237198 0.00601501 -0.0978842 0.0233971 0.0098263 -0.0965526 0.0207728 0.0211691 -0.085723 0.0334605 0.0226067 -0.0775031 0.0189445 0.0233729 -0.078178 0.0179908 0.0234449 -0.0742425 0.0271728 0.0215182 -0.0629393 0.0286929 0.0228204 -0.0664602 0.0324824 0.0195768 -0.0562999 -0.0200729 -0.0195768 -0.0618224 -0.0264297 -0.0195768 -0.059383 -0.0292944 -0.0215182 -0.0619803 0.0170484 -0.0228204 -0.0703533 0.0179908 -0.0234449 -0.0742425 -0.00818188 -0.0233729 -0.0800235 -0.0205015 -0.0234449 -0.0735888 -0.0215882 -0.0233729 -0.0774897 -0.00858639 -0.0226067 -0.0839798 0.00572977 -0.0226067 -0.084223 -0.00897152 -0.0211691 -0.0877465 0.00622319 -0.0191026 -0.0914758 0.00598677 -0.0211691 -0.0880006 0.00643202 -0.0164687 -0.0945454 0.0238836 0.00202505 -0.0985601 0.0229251 0.0133457 -0.0946047 0.0223178 0.0164687 -0.0920985 0.00683609 0.00601501 -0.100485 0.00674309 0.0098263 -0.0991179 0.0215932 0.0191026 -0.0891083 0.0134997 0.0195768 -0.0635812 0.0161452 0.0215182 -0.0666262 0.00678477 0.0195768 -0.0646447 0.0170484 0.0228204 -0.0703533 0.0200684 0.0195768 -0.0618234 0.0264356 0.0195768 -0.0593815 1.82918e-05 -0.0195768 -0.064999 0.00491337 -0.0228204 -0.0722226 -0.0236717 -0.0211691 -0.0849682 -0.00932581 -0.0191026 -0.0912117 -0.00963875 -0.0164687 -0.0942725 -0.0246065 -0.0191026 -0.0883237 -0.00990105 -0.0133457 -0.0968379 -0.0254322 -0.0164687 -0.0912875 0.00688329 0.00202505 -0.101179 0.00660705 0.0133457 -0.0971183 0.00643202 0.0164687 -0.0945454 -0.0102443 0.00601501 -0.100195 0.00622319 0.0191026 -0.0914758 -0.00777 0.0234449 -0.075995 0.00491337 0.0228204 -0.0722226 0.00518498 0.0234449 -0.076215 0.00545984 0.0233729 -0.0802552 -0.00897152 0.0211691 -0.0877465 -0.00818188 0.0233729 -0.0800235 0.00465307 0.0215182 -0.0683964 -0.0393477 -0.0215182 -0.056138 -0.0382 -0.0195768 -0.0525903 -0.04348 -0.0195768 -0.0483144 -0.00736298 -0.0228204 -0.0720141 -0.00777 -0.0234449 -0.075995 -0.0343735 -0.0233729 -0.0727266 -0.0326431 -0.0234449 -0.0690655 -0.0360729 -0.0226067 -0.0763222 -0.0226555 -0.0226067 -0.0813207 -0.010315 0.00202505 -0.100887 -0.00990105 0.0133457 -0.0968379 -0.00963875 0.0164687 -0.0942725 -0.0226555 0.0226067 -0.0813207 -0.0215882 0.0233729 -0.0774897 -0.00932581 0.0191026 -0.0912117 -0.00858639 0.0226067 -0.0839798 -0.0205015 0.0234449 -0.0735888 -0.00736298 0.0228204 -0.0720141 -0.0069729 0.0215182 -0.0681989 -2.00963e-05 0.0195768 -0.0649985 -0.0482924 -0.0195768 -0.0435056 -0.0525861 -0.0195768 -0.038206 -0.0558019 -0.0215182 -0.0398229 -0.0194275 -0.0228204 -0.0697339 -0.0482691 -0.0215182 -0.0486807 -0.0484526 -0.0226067 -0.069128 -0.0461699 -0.0233729 -0.0658714 -0.0506258 -0.0211691 -0.0722286 -0.0391794 -0.0191026 -0.0828947 -0.0376909 -0.0211691 -0.0797455 -0.0404941 -0.0164687 -0.0856764 -0.0526251 -0.0191026 -0.075081 -0.0272166 0.00202505 -0.0976922 -0.0261243 0.0133457 -0.0937717 -0.0254322 0.0164687 -0.0912875 -0.043038 0.00601501 -0.0910587 -0.0424525 0.0098263 -0.0898199 -0.0246065 0.0191026 -0.0883237 -0.0183983 0.0215182 -0.0660395 -0.0309331 0.0228204 -0.0654475 -0.0292944 0.0215182 -0.0619803 -0.0343735 0.0233729 -0.0727266 -0.0326431 0.0234449 -0.0690655 -0.0135293 0.0195768 -0.0635757 -0.00679887 0.0195768 -0.0646429 -0.0194275 0.0228204 -0.0697339 -0.0324821 -0.0195768 -0.0563004 -0.0309331 -0.0228204 -0.0654475 -0.0617293 -0.0215182 -0.0298196 -0.0562803 -0.0195768 -0.0325165 -0.0566381 -0.0233729 -0.0571211 -0.0537869 -0.0234449 -0.0542456 -0.054391 -0.0164687 -0.0776004 -0.0645568 -0.0191026 -0.0651073 -0.0558711 -0.0133457 -0.0797122 -0.0667232 -0.0164687 -0.0672921 -0.0433351 0.00202505 -0.0916874 -0.041596 0.0133457 -0.0880078 -0.0404941 0.0164687 -0.0856764 -0.0578079 0.00601501 -0.0824754 -0.0570215 0.0098263 -0.0813534 -0.0506258 0.0211691 -0.0722286 -0.0360729 0.0226067 -0.0763222 -0.0461699 0.0233729 -0.0658714 -0.0438457 0.0234449 -0.0625553 -0.0201029 0.0195768 -0.0618115 -0.0618138 -0.0195768 -0.020097 -0.0593753 -0.0195768 -0.0264485 -0.0415489 -0.0228204 -0.0592784 -0.0438457 -0.0234449 -0.0625553 -0.065477 -0.0233729 -0.0467276 -0.0621808 -0.0234449 -0.0443753 -0.0687141 -0.0226067 -0.0490378 -0.0594383 -0.0226067 -0.0599452 -0.0621043 -0.0211691 -0.0626339 -0.058207 0.00202505 -0.0830449 -0.0558711 0.0133457 -0.0797122 -0.054391 0.0164687 -0.0776004 -0.0709148 0.00601501 -0.0715195 -0.0699501 0.0098263 -0.0705465 -0.0526251 0.0191026 -0.075081 -0.0415489 0.0228204 -0.0592784 -0.0509693 0.0228204 -0.051404 -0.0393477 0.0215182 -0.056138 -0.0325161 0.0195768 -0.056281 -0.0264424 0.0195768 -0.0593784 -0.0509693 -0.0228204 -0.051404 -0.0658809 -0.0215182 -0.0189583 -0.0760132 -0.0226067 -0.0367197 -0.0724321 -0.0233729 -0.0349898 -0.0794226 -0.0211691 -0.0383666 -0.0746314 -0.0191026 -0.0532607 -0.0717961 -0.0211691 -0.0512372 -0.0771358 -0.0164687 -0.0550479 -0.082559 -0.0191026 -0.0398818 -0.0853294 -0.0164687 -0.0412201 -0.0714044 0.00202505 -0.0720133 -0.0808663 0.0098263 -0.0577102 -0.0685389 0.0133457 -0.0691233 -0.0667232 0.0164687 -0.0672921 -0.0819816 0.00601501 -0.0585061 -0.0645568 0.0191026 -0.0651073 -0.0621808 0.0234449 -0.0443753 -0.0537869 0.0234449 -0.0542456 -0.0566381 0.0233729 -0.0571211 -0.065477 0.0233729 -0.0467276 -0.0482691 0.0215182 -0.0486807 -0.043502 0.0195768 -0.0482963 -0.0382149 0.0195768 -0.0525781 -0.0681373 -0.0215182 -0.00755171 -0.0646433 -0.0195768 -0.00679926 -0.0649983 -0.0195768 -1.82405e-05 -0.0589235 -0.0228204 -0.0420507 -0.0684334 -0.0215182 0.00407217 -0.0773036 -0.0233729 -0.0222454 -0.073412 -0.0234449 -0.0211255 -0.0825477 0.00202505 -0.0589101 -0.0811254 0.0226067 -0.0233452 -0.0760132 0.0226067 -0.0367197 -0.0847641 0.0211691 -0.0243923 -0.0792349 0.0133457 -0.0565459 -0.0771358 0.0164687 -0.0550479 -0.09069 0.00601501 -0.0438096 -0.0894562 0.0098263 -0.0432136 -0.0794226 0.0211691 -0.0383666 -0.0687141 0.0226067 -0.0490378 -0.0724321 0.0233729 -0.0349898 -0.0687858 0.0234449 -0.0332284 -0.0558019 0.0215182 -0.0398229 -0.0589235 0.0228204 -0.0420507 -0.0483166 0.0195768 -0.0434776 -0.0646449 -0.0195768 0.00677887 -0.06358 -0.0195768 0.0135096 -0.0667609 -0.0215182 0.0155789 -0.0651826 -0.0228204 -0.0314877 -0.0687858 -0.0234449 -0.0332284 -0.0799511 -0.0233729 -0.00886104 -0.0762563 -0.0234449 0.00453768 -0.0802986 -0.0233729 0.00477822 -0.0839039 -0.0226067 -0.00929913 -0.0811254 -0.0226067 -0.0233452 -0.0876672 -0.0211691 -0.00971622 -0.0881116 -0.0191026 -0.0253556 -0.0847641 -0.0211691 -0.0243923 -0.0910683 -0.0164687 -0.0262064 -0.0876515 0.0133457 -0.0423418 -0.0853294 0.0164687 -0.0412201 -0.0967893 0.00601501 -0.0278527 -0.0954726 0.0098263 -0.0274738 -0.082559 0.0191026 -0.0398818 -0.0617293 0.0215182 -0.0298196 -0.0658809 0.0215182 -0.0189583 -0.0593858 0.0195768 -0.026422 -0.0651826 0.0228204 -0.0314877 -0.0562995 0.0195768 -0.0324848 -0.0525861 0.0195768 -0.038206 -0.0635745 -0.0195768 -0.0135328 -0.0695664 -0.0228204 -0.0200189 -0.0911293 -0.0191026 -0.0100999 -0.0880482 -0.0211691 0.00523936 -0.0941873 -0.0164687 -0.0104388 -0.0915253 -0.0191026 0.00544627 -0.0935465 0.0133457 -0.0269196 -0.0910683 0.0164687 -0.0262064 -0.100104 0.00601501 -0.0110946 -0.0881116 0.0191026 -0.0253556 -0.0759263 0.0234449 -0.00841497 -0.0695664 0.0228204 -0.0200189 -0.073412 0.0234449 -0.0211255 -0.0773036 0.0233729 -0.0222454 -0.0876672 0.0211691 -0.00971622 -0.0799511 0.0233729 -0.00886104 -0.0631677 -0.0215182 0.0266375 -0.0593842 -0.0195768 0.026429 -0.0562976 -0.0195768 0.0324867 -0.071949 -0.0228204 -0.00797416 -0.0759263 -0.0234449 -0.00841497 -0.0783361 -0.0233729 0.01828 -0.0743925 -0.0234449 0.0173598 -0.082209 -0.0226067 0.0191838 -0.0842686 -0.0226067 0.00501445 -0.0980821 0.00601501 0.0228878 -0.0967503 0.0133457 -0.0107229 -0.0941873 0.0164687 -0.0104388 -0.0842686 0.0226067 0.00501445 -0.0802986 0.0233729 0.00477822 -0.0911293 0.0191026 -0.0100999 -0.0839039 0.0226067 -0.00929913 -0.0762563 0.0234449 0.00453768 -0.071949 0.0228204 -0.00797416 -0.0681373 0.0215182 -0.00755171 -0.0635824 0.0195768 -0.0134946 -0.0618208 0.0195768 -0.0200791 -0.0525961 -0.0195768 0.0381907 -0.0483061 -0.0195768 0.0434916 -0.0506854 -0.0215182 0.0461595 -0.0722617 -0.0228204 0.00429998 -0.0577574 -0.0215182 0.0369297 -0.0777844 -0.0226067 0.0328012 -0.0741199 -0.0233729 0.0312559 -0.0812733 -0.0211691 0.0342725 -0.0892884 -0.0191026 0.0208358 -0.0858963 -0.0211691 0.0200442 -0.0844828 -0.0191026 0.0356259 -0.100539 -0.00601501 0.00598266 -0.101234 -0.00202505 0.00602396 -0.0971709 0.0133457 0.00578221 -0.0945966 0.0164687 0.00562903 -0.0967477 0.0098263 0.0225765 -0.0915253 0.0191026 0.00544627 -0.0741199 0.0233729 0.0312559 -0.0703887 0.0234449 0.0296825 -0.0743925 0.0234449 0.0173598 -0.0783361 0.0233729 0.01828 -0.0649995 0.0195768 1.37309e-05 -0.0684334 0.0215182 0.00407217 -0.0646438 0.0195768 -0.00678576 -0.0722617 0.0228204 0.00429998 -0.0618235 -0.0195768 0.0200665 -0.0704956 -0.0228204 0.0164504 -0.0421554 -0.0215182 0.0540615 -0.0435068 -0.0195768 0.0482903 -0.0677715 -0.0233729 0.0433327 -0.0643598 -0.0234449 0.0411513 -0.0980821 -0.00601501 0.0228878 -0.0987593 -0.00202505 0.0230459 -0.0928032 0.00601501 0.0391346 -0.0947959 0.0133457 0.022121 -0.0922846 0.0164687 0.021535 -0.0812733 0.0211691 0.0342725 -0.082209 0.0226067 0.0191838 -0.0667609 0.0215182 0.0155789 -0.0704956 0.0228204 0.0164504 -0.0646403 0.0195768 0.00681339 -0.0325069 -0.0195768 0.0562865 -0.0382169 -0.0195768 0.0525776 -0.0667014 -0.0228204 0.0281276 -0.0703887 -0.0234449 0.0296825 -0.0594734 -0.0233729 0.0541628 -0.0564795 -0.0234449 0.0514362 -0.0624138 -0.0226067 0.0568406 -0.0711221 -0.0226067 0.045475 -0.0743121 -0.0211691 0.0475147 -0.0652132 -0.0211691 0.0593901 -0.0915407 -0.0098263 0.0386022 -0.0928032 -0.00601501 0.0391346 -0.093444 -0.00202505 0.0394048 -0.093444 0.00202505 0.0394048 -0.0873178 0.0164687 0.0368214 -0.0848545 0.00601501 0.0542555 -0.0844828 0.0191026 0.0356259 -0.0667014 0.0228204 0.0281276 -0.0609884 0.0228204 0.0389956 -0.0631677 0.0215182 0.0266375 -0.0618121 0.0195768 0.0201032 -0.0635791 0.0195768 0.0135167 -0.0609884 -0.0228204 0.0389956 -0.0324126 -0.0215182 0.0604081 -0.0837002 -0.0098263 0.0535174 -0.0848545 -0.00601501 0.0542555 -0.0854404 -0.00202505 0.0546301 -0.0854404 0.00202505 0.0546301 -0.0744648 0.00601501 0.0678155 -0.0772468 0.0191026 0.0493911 -0.0564795 0.0234449 0.0514362 -0.0643598 0.0234449 0.0411513 -0.0677715 0.0233729 0.0433327 -0.0652132 0.0211691 0.0593901 -0.0577574 0.0215182 0.0369297 -0.0562866 0.0195768 0.0325082 -0.0593732 0.0195768 0.0264505 -0.0217373 -0.0215182 0.065017 -0.020093 -0.0195768 0.0618163 -0.0135302 -0.0195768 0.0635746 -0.0535208 -0.0228204 0.0487418 -0.0104367 -0.0215182 0.0677554 -0.0380324 -0.0233729 0.0708819 -0.0494644 -0.0233729 0.0634348 -0.0361178 -0.0234449 0.0673136 -0.0519099 -0.0226067 0.066571 -0.0598578 -0.0133457 0.0767636 -0.0448044 -0.0164687 0.0835031 -0.0719699 -0.0133457 0.0655434 -0.0734517 -0.0098263 0.066893 -0.0744648 -0.00601501 0.0678155 -0.0749789 -0.00202505 0.0682838 -0.0749789 0.00202505 0.0682838 -0.0677885 0.0191026 0.0617354 -0.0619328 0.00601501 0.0794247 -0.0610902 0.0098263 0.0783442 -0.0624138 0.0226067 0.0568406 -0.0542382 0.0211691 0.0695569 -0.0469743 0.0234449 0.0602414 -0.0506854 0.0215182 0.0461595 -0.0535208 0.0228204 0.0487418 -0.0525731 0.0195768 0.0382214 -0.0068112 -0.0195768 0.0646413 -1.77636e-17 -0.0195768 0.065 0.00116411 -0.0215182 0.0685446 -0.0445136 -0.0228204 0.0570857 -0.0469743 -0.0234449 0.0602414 -0.0255062 -0.0233729 0.0762898 -0.0116298 -0.0234449 0.0755007 -0.0122463 -0.0233729 0.079503 -0.0267672 -0.0226067 0.0800615 -0.0399127 -0.0226067 0.0743863 -0.0610902 -0.0098263 0.0783442 -0.0619328 -0.00601501 0.0794247 -0.0623604 -0.00202505 0.0799731 -0.0623604 0.00202505 0.0799731 -0.0417029 0.0211691 0.0777227 -0.0399127 0.0226067 0.0743863 -0.0476191 0.00601501 0.0887489 -0.0469713 0.0098263 0.0875416 -0.0421554 0.0215182 0.0540615 -0.0324126 0.0215182 0.0604081 -0.0381903 0.0195768 0.0525955 -0.0380324 0.0233729 0.0708819 -0.0361178 0.0234449 0.0673136 -0.0434815 0.0195768 0.0483143 -0.0483009 0.0195768 0.0434965 -0.0445136 0.0228204 0.0570857 -0.0264555 -0.0195768 0.0593712 -0.0342258 -0.0228204 0.0637874 0.00136594 -0.0233729 0.0804291 -0.0128517 -0.0226067 0.0834336 -0.0460237 -0.0133457 0.0857755 -0.0469713 -0.0098263 0.0875416 -0.0476191 -0.00601501 0.0887489 -0.0479479 -0.00202505 0.0893617 -0.0479479 0.00202505 0.0893617 -0.031501 0.0098263 0.0942205 -0.0153332 0.00601501 0.0995432 -0.0319355 0.00601501 0.09552 -0.0242222 0.0234449 0.0724493 -0.0342258 0.0228204 0.0637874 -0.0279678 0.0211691 0.0836525 -0.0255062 0.0233729 0.0762898 0.0127315 -0.0215182 0.0673619 0.0135029 -0.0195768 0.0635817 0.0200725 -0.0195768 0.0618215 -0.0229533 -0.0228204 0.0686541 -0.0242222 -0.0234449 0.0724493 0.00129718 -0.0234449 0.0763802 -0.0300478 -0.0164687 0.089874 -0.0308655 -0.0133457 0.0923197 -0.031501 -0.0098263 0.0942205 -0.0319355 -0.00601501 0.09552 -0.032156 -0.00202505 0.0961795 -0.032156 0.00202505 0.0961795 -0.0308655 0.0133457 0.0923197 -0.0128517 0.0226067 0.0834336 -0.0122463 0.0233729 0.079503 -0.0290723 0.0191026 0.086956 -0.0267672 0.0226067 0.0800615 -0.0116298 0.0234449 0.0755007 -0.0229533 0.0228204 0.0686541 -0.0217373 0.0215182 0.065017 -0.0264198 0.0195768 0.0593872 -0.0324957 0.0195768 0.0562941 0.0264197 -0.0195768 0.0593873 0.0324974 -0.0195768 0.0562931 0.0344451 -0.0215182 0.0592727 -0.0110206 -0.0228204 0.0715457 0.0239325 -0.0215182 0.0642413 -0.0139585 -0.0191026 0.0906185 -0.0144269 -0.0164687 0.0936593 -0.0148195 -0.0133457 0.0962081 -0.0151246 -0.0098263 0.098189 -0.0153332 -0.00601501 0.0995432 -0.015439 -0.00202505 0.10023 -0.015439 0.00202505 0.10023 -0.0144269 0.0164687 0.0936593 0.0149389 0.0233729 0.0790413 0.0141868 0.0234449 0.0750623 0.00129718 0.0234449 0.0763802 0.00136594 0.0233729 0.0804291 -0.0135027 0.0195768 0.0635817 -0.0104367 0.0215182 0.0677554 -0.0200745 0.0195768 0.0618211 -0.0110206 0.0228204 0.0715457 0.0068121 -0.0195768 0.0646411 0.00122923 -0.0228204 0.0723791 0.0439668 -0.0215182 0.0525988 0.0381888 -0.0195768 0.0525965 0.0266684 -0.0234449 0.071585 0.00155692 -0.0191026 0.091674 0.00160916 -0.0164687 0.0947503 0.00165295 -0.0133457 0.0973287 0.00168699 -0.0098263 0.0993327 0.00171025 -0.00601501 0.100703 0.00172206 -0.00202505 0.101398 0.00172206 0.00202505 0.101398 0.00171025 0.00601501 0.100703 0.00165295 0.0133457 0.0973287 0.0252714 0.0228204 0.0678351 0.0266684 0.0234449 0.071585 0.0383827 0.0234449 0.0660483 0.00143348 0.0226067 0.0844055 0.00116411 0.0215182 0.0685446 0.00122923 0.0228204 0.0723791 -0.0068112 0.0195768 0.0646413 0.0522236 -0.0215182 0.0444118 0.0434828 -0.0195768 0.0483134 0.0482968 -0.0195768 0.0435002 0.0134437 -0.0228204 0.0711302 0.0141868 -0.0234449 0.0750623 0.0163806 -0.0211691 0.0866696 0.0170275 -0.0191026 0.0900923 0.0175989 -0.0164687 0.0931154 0.0180778 -0.0133457 0.0956494 0.01845 -0.0098263 0.0976188 0.0187045 -0.00601501 0.0989651 0.0188336 -0.00202505 0.0996484 0.0188336 0.00202505 0.0996484 0.0187045 0.00601501 0.0989651 0.01845 0.0098263 0.0976188 0.0180778 0.0133457 0.0956494 0.0175989 0.0164687 0.0931154 0.0134437 0.0228204 0.0711302 0.0127315 0.0215182 0.0673619 0.0068121 0.0195768 0.0646411 -1.91847e-16 0.0195768 0.065 0.0252714 -0.0228204 0.0678351 0.0307922 -0.0211691 0.0826546 0.0320083 -0.0191026 0.0859187 0.0330823 -0.0164687 0.0888018 0.0339826 -0.0133457 0.0912184 0.0346823 -0.0098263 0.0930965 0.0351606 -0.00601501 0.0943805 0.0354034 -0.00202505 0.0950322 0.0354034 0.00202505 0.0950322 0.0351606 0.00601501 0.0943805 0.0346823 0.0098263 0.0930965 0.0339826 0.0133457 0.0912184 0.0330823 0.0164687 0.0888018 0.0320083 0.0191026 0.0859187 0.0239325 0.0215182 0.0642413 0.0200944 0.0195768 0.0618158 0.0135302 0.0195768 0.0635745 0.0562886 -0.0195768 0.0325051 0.036372 -0.0228204 0.0625885 0.0657201 -0.0234449 0.0389421 0.044318 -0.0211691 0.0762618 0.0460682 -0.0191026 0.0792734 0.0476141 -0.0164687 0.0819336 0.0489098 -0.0133457 0.0841632 0.0499168 -0.0098263 0.0858961 0.0506052 -0.00601501 0.0870807 0.0509547 -0.00202505 0.087682 0.0509547 0.00202505 0.087682 0.0506052 0.00601501 0.0870807 0.0499168 0.0098263 0.0858961 0.0489098 0.0133457 0.0841632 0.0476141 0.0164687 0.0819336 0.0460682 0.0191026 0.0792734 0.0565688 0.0211691 0.067675 0.0671923 0.0211691 0.0571414 0.0489928 0.0234449 0.0586116 0.0344451 0.0215182 0.0592727 0.036372 0.0228204 0.0625885 0.0264563 0.0195768 0.0593706 0.0635778 -0.0195768 0.0135195 0.0464264 -0.0228204 0.0555413 0.0565688 -0.0211691 0.067675 0.0588028 -0.0191026 0.0703476 0.060776 -0.0164687 0.0727082 0.0624299 -0.0133457 0.0746868 0.0637153 -0.0098263 0.0762246 0.0645941 -0.00601501 0.0772758 0.0650401 -0.00202505 0.0778094 0.0650401 0.00202505 0.0778094 0.0645941 0.00601501 0.0772758 0.0637153 0.0098263 0.0762246 0.0624299 0.0133457 0.0746868 0.060776 0.0164687 0.0727082 0.0588028 0.0191026 0.0703476 0.0439668 0.0215182 0.0525988 0.0522236 0.0215182 0.0444118 0.0435062 0.0195768 0.0482906 0.0382187 0.0195768 0.0525761 0.0325044 0.0195768 0.0562883 0.0464264 0.0228204 0.0555413 0.0525731 -0.0195768 0.0382217 0.0551451 -0.0228204 0.0468963 0.0671923 -0.0211691 0.0571414 0.0698458 -0.0191026 0.059398 0.0721896 -0.0164687 0.0613912 0.074154 -0.0133457 0.0630618 0.0756808 -0.0098263 0.0643602 0.0767246 -0.00601501 0.0652478 0.0772544 -0.00202505 0.0656984 0.0772544 0.00202505 0.0656984 0.0767246 0.00601501 0.0652478 0.0756808 0.0098263 0.0643602 0.074154 0.0133457 0.0630618 0.0721896 0.0164687 0.0613912 0.0698458 0.0191026 0.059398 0.0751385 0.0233729 0.028721 0.064644 -0.0195768 -0.00677763 0.0649998 -0.0195768 8.81775e-06 0.0622774 -0.0228204 0.0369021 0.0692039 -0.0233729 0.0410064 0.0726253 -0.0226067 0.0430337 0.0758827 -0.0211691 0.0449639 0.0788794 -0.0191026 0.0467396 0.0815263 -0.0164687 0.048308 0.0837449 -0.0133457 0.0496226 0.0854692 -0.0098263 0.0506443 0.0866479 -0.00601501 0.0513428 0.0872462 -0.00202505 0.0516973 0.0872462 0.00202505 0.0516973 0.0866479 0.00601501 0.0513428 0.0854692 0.0098263 0.0506443 0.0837449 0.0133457 0.0496226 0.0815263 0.0164687 0.048308 0.0788794 0.0191026 0.0467396 0.0710135 0.0228204 0.0140471 0.0640358 0.0215182 0.0244771 0.0589781 0.0215182 0.0349472 0.052597 0.0195768 0.0381888 0.0483083 0.0195768 0.043489 0.071356 -0.0234449 0.0272752 0.0676181 -0.0228204 0.0258464 0.0751385 -0.0233729 0.028721 0.0788534 -0.0226067 0.030141 0.0823902 -0.0211691 0.0314929 0.0856438 -0.0191026 0.0327366 0.0885177 -0.0164687 0.0338351 0.0909266 -0.0133457 0.0347559 0.0927987 -0.0098263 0.0354715 0.0940786 -0.00601501 0.0359607 0.0947281 -0.00202505 0.036209 0.0947281 0.00202505 0.036209 0.0940786 0.00601501 0.0359607 0.0927987 0.0098263 0.0354715 0.0909266 0.0133457 0.0347559 0.0885177 0.0164687 0.0338351 0.0856438 0.0191026 0.0327366 0.0823902 0.0211691 0.0314929 0.0788534 0.0226067 0.030141 0.0789116 0.0233729 0.0156094 0.0593857 0.0195768 0.0264249 0.0562957 0.0195768 0.0324907 0.0676181 0.0228204 0.0258464 0.0710135 -0.0228204 0.0140471 0.082813 -0.0226067 0.0163812 0.0865274 -0.0211691 0.0171159 0.0899444 -0.0191026 0.0177918 0.0929627 -0.0164687 0.0183889 0.0954924 -0.0133457 0.0188893 0.0974586 -0.0098263 0.0192782 0.0988027 -0.00601501 0.0195441 0.0994849 -0.00202505 0.019679 0.0994849 0.00202505 0.019679 0.0988027 0.00601501 0.0195441 0.0974586 0.0098263 0.0192782 0.0954924 0.0133457 0.0188893 0.0929627 0.0164687 0.0183889 0.0899444 0.0191026 0.0177918 0.0865274 0.0211691 0.0171159 0.082813 0.0226067 0.0163812 0.0618232 0.0195768 0.0200665 0.0804146 -0.0233729 0.00204879 0.0843902 -0.0226067 0.00215008 0.0881754 -0.0211691 0.00224652 0.0916575 -0.0191026 0.00233524 0.0947332 -0.0164687 0.0024136 0.0973112 -0.0133457 0.00247928 0.0993148 -0.0098263 0.00253033 0.100684 -0.00601501 0.00256523 0.10138 -0.00202505 0.00258294 0.10138 0.00202505 0.00258294 0.100684 0.00601501 0.00256523 0.0993148 0.0098263 0.00253033 0.0973112 0.0133457 0.00247928 0.0947332 0.0164687 0.0024136 0.0916575 0.0191026 0.00233524 0.0881754 0.0211691 0.00224652 0.0843902 0.0226067 0.00215008 0.0716367 0.0228204 -0.0104127 0.072366 0.0228204 0.00184373 0.0635802 0.0195768 0.0135113 0.0755968 -0.0234449 -0.0109883 0.0796041 -0.0233729 -0.0115708 0.0835397 -0.0226067 -0.0121429 0.0872867 -0.0211691 -0.0126875 0.0907338 -0.0191026 -0.0131885 0.0937785 -0.0164687 -0.0136311 0.0963304 -0.0133457 -0.014002 0.0983138 -0.0098263 -0.0142903 0.0996698 -0.00601501 -0.0144874 0.100358 -0.00202505 -0.0145875 0.100358 0.00202505 -0.0145875 0.0996698 0.00601501 -0.0144874 0.0983138 0.0098263 -0.0142903 0.0963304 0.0133457 -0.014002 0.0937785 0.0164687 -0.0136311 0.0907338 0.0191026 -0.0131885 0.0872867 0.0211691 -0.0126875 0.0835397 0.0226067 -0.0121429 0.0796041 0.0233729 -0.0115708 0.0755968 0.0234449 -0.0109883 0.0068121 -0.0195768 0.0646411 -1.77636e-17 -0.0195768 0.065 -1.91847e-16 0.0195768 0.065 0.0264197 -0.0195768 0.0593873 0.0200725 -0.0195768 0.0618215 0.0200944 0.0195768 0.0618158 0.0135029 -0.0195768 0.0635817 0.0068121 0.0195768 0.0646411 0.0135302 0.0195768 0.0635745 0.0382187 0.0195768 0.0525761 0.0434828 -0.0195768 0.0483134 0.0381888 -0.0195768 0.0525965 0.0264563 0.0195768 0.0593706 0.0325044 0.0195768 0.0562883 0.0324974 -0.0195768 0.0562931 0.0525731 -0.0195768 0.0382217 0.052597 0.0195768 0.0381888 0.0562886 -0.0195768 0.0325051 0.0482968 -0.0195768 0.0435002 0.0435062 0.0195768 0.0482906 0.0483083 0.0195768 0.043489 0.0635778 -0.0195768 0.0135195 0.061813 -0.0195768 0.0201012 0.0618232 0.0195768 0.0200665 0.0593857 0.0195768 0.0264249 0.0593713 -0.0195768 0.0264543 0.0562957 0.0195768 0.0324907 0.0649985 0.0195768 -1.37752e-05 0.064644 -0.0195768 -0.00677763 0.0649998 -0.0195768 8.81775e-06 0.0635802 0.0195768 0.0135113 0.0646448 0.0195768 0.00677496 0.0646403 -0.0195768 0.00681493 0.0618187 -0.0195768 -0.0200861 0.0618187 0.0195768 -0.0200861 0.0593728 -0.0195768 -0.0264531 0.0635825 -0.0195768 -0.0134965 0.0646424 0.0195768 -0.00680575 0.0635825 0.0195768 -0.0134965 0.0483164 -0.0195768 -0.0434784 0.052592 -0.0195768 -0.0381957 0.0525817 0.0195768 -0.0382119 0.0562819 0.0195768 -0.0325136 0.0562972 -0.0195768 -0.0324896 0.0593728 0.0195768 -0.0264531 0.0381946 0.0195768 -0.0525938 0.0325131 -0.0195768 -0.0562833 0.0382198 -0.0195768 -0.052574 0.0482901 0.0195768 -0.0435074 0.0434865 0.0195768 -0.0483094 0.0434971 -0.0195768 -0.0483011 0.0264419 -0.0195768 -0.0593781 0.0324824 0.0195768 -0.0562999 0.0264356 0.0195768 -0.0593815 0.00680864 -0.0195768 -0.0646409 0.0134997 0.0195768 -0.0635812 0.00678477 0.0195768 -0.0646447 0.0135236 -0.0195768 -0.0635774 0.0201048 -0.0195768 -0.0618111 0.0200684 0.0195768 -0.0618234 -0.0135293 0.0195768 -0.0635757 -0.013495 -0.0195768 -0.063582 -0.00679887 0.0195768 -0.0646429 -2.00963e-05 0.0195768 -0.0649985 -0.00679187 -0.0195768 -0.0646442 1.82918e-05 -0.0195768 -0.064999 -0.0264424 0.0195768 -0.0593784 -0.0325161 0.0195768 -0.056281 -0.0324821 -0.0195768 -0.0563004 -0.0200729 -0.0195768 -0.0618224 -0.0201029 0.0195768 -0.0618115 -0.0264297 -0.0195768 -0.059383 -0.0482924 -0.0195768 -0.0435056 -0.043502 0.0195768 -0.0482963 -0.0483166 0.0195768 -0.0434776 -0.04348 -0.0195768 -0.0483144 -0.0382 -0.0195768 -0.0525903 -0.0382149 0.0195768 -0.0525781 -0.0593858 0.0195768 -0.026422 -0.0593753 -0.0195768 -0.0264485 -0.0562995 0.0195768 -0.0324848 -0.0525861 0.0195768 -0.038206 -0.0562803 -0.0195768 -0.0325165 -0.0525861 -0.0195768 -0.038206 -0.0635824 0.0195768 -0.0134946 -0.0646438 0.0195768 -0.00678576 -0.0646433 -0.0195768 -0.00679926 -0.0618138 -0.0195768 -0.020097 -0.0618208 0.0195768 -0.0200791 -0.0635745 -0.0195768 -0.0135328 -0.0649995 0.0195768 1.37309e-05 -0.0646403 0.0195768 0.00681339 -0.0646449 -0.0195768 0.00677887 -0.0649983 -0.0195768 -1.82405e-05 -0.0635791 0.0195768 0.0135167 -0.06358 -0.0195768 0.0135096 -0.0618235 -0.0195768 0.0200665 -0.0618121 0.0195768 0.0201032 -0.0593732 0.0195768 0.0264505 -0.0593842 -0.0195768 0.026429 -0.0562866 0.0195768 0.0325082 -0.0562976 -0.0195768 0.0324867 -0.0525961 -0.0195768 0.0381907 -0.0525731 0.0195768 0.0382214 -0.0483009 0.0195768 0.0434965 -0.0483061 -0.0195768 0.0434916 -0.0434815 0.0195768 0.0483143 -0.0435068 -0.0195768 0.0482903 -0.0382169 -0.0195768 0.0525776 -0.0381903 0.0195768 0.0525955 -0.0324957 0.0195768 0.0562941 -0.0325069 -0.0195768 0.0562865 -0.0264198 0.0195768 0.0593872 -0.0264555 -0.0195768 0.0593712 -0.020093 -0.0195768 0.0618163 -0.0200745 0.0195768 0.0618211 -0.0135027 0.0195768 0.0635817 -0.0135302 -0.0195768 0.0635746 -0.0068112 0.0195768 0.0646413 -0.0068112 -0.0195768 0.0646413 + + + + + + + + + + -0.275376 -0.812877 0.513225 -0.205296 -0.900811 0.382614 -0.13768 -0.900811 0.411806 -0.872957 -0.41814 -0.251208 -0.818086 -0.567903 -0.0906692 -0.902854 -0.41814 -0.100064 0.00463726 -0.961988 0.273051 0.00737321 -0.900811 0.434149 -0.0661043 -0.900811 0.42915 -0.184679 -0.812877 0.552382 0.0192877 -0.994592 0.102051 0.0507165 -0.961988 0.26834 0.0362571 -0.994592 0.0973236 0.0953367 -0.961988 0.255909 -0.0439063 -0.997654 -0.0525265 0.0666083 -0.994592 0.0796856 0.0521833 -0.994592 0.0897963 0.137214 -0.961988 0.236116 0.175144 -0.961988 0.20953 0.0791172 -0.994592 0.0672825 0.208036 -0.961988 0.176917 -0.0343977 -0.997654 -0.0591911 -0.505366 -0.833054 -0.225003 -0.375444 -0.915667 -0.14351 -0.345791 -0.915667 -0.204896 -0.0521518 -0.997654 -0.0443507 -0.526116 -0.833054 -0.170946 -0.394297 -0.915667 -0.0779956 -0.550161 -0.833054 -0.0578242 -0.401807 -0.915667 -0.0102371 -0.22706 -0.971082 0.0737762 -0.236262 -0.971082 0.0343417 -0.382265 -0.915667 0.124206 -0.0671588 -0.997654 -0.0132846 -0.0684379 -0.997654 -0.00174364 0.101884 -0.994592 0.0201535 -0.397758 -0.915667 0.0578158 -0.541103 -0.833054 0.115015 -0.238667 -0.971082 -0.00608068 -0.438658 -0.700798 0.562549 -0.35815 -0.812877 0.459304 -0.526116 -0.833054 0.170946 -0.527419 -0.700798 0.480324 -0.430621 -0.812877 0.39217 -0.267005 -0.900811 0.342416 -0.69346 -0.567903 0.443394 -0.601008 -0.700798 0.384281 -0.490704 -0.812877 0.313753 -0.657307 -0.700798 0.277183 -0.75842 -0.567903 0.319821 -0.694696 -0.700798 0.16211 -0.80156 -0.567903 0.187047 -0.821642 -0.567903 0.0488923 -0.906778 -0.41814 0.0539584 -0.7121 -0.700798 0.042374 -0.994521 0.0861727 0.0591796 -0.970214 0.0861727 0.226403 -0.964981 0.255958 0.0574218 -0.870446 -0.255958 -0.420486 -0.928988 -0.255958 -0.267332 -0.0886699 0.812877 0.575647 0.0121133 0.700798 0.713257 0.00989015 0.812877 0.582352 -0.527419 0.700798 0.480324 -0.608552 0.567903 0.554212 -0.506136 0.567903 0.649086 0.137214 0.961988 0.236116 0.0953365 0.961988 0.255909 0.218169 0.900811 0.375423 0.036257 0.994592 0.0973235 0.0521832 0.994592 0.0897961 -0.0521515 0.997654 -0.0443505 -0.0588966 0.997654 -0.0348989 -0.181871 0.971082 -0.154666 0.373557 0.900811 0.221349 0.234942 0.961988 0.139214 0.208036 0.961988 0.176917 0.103824 0.994592 0.00264524 -0.0684376 0.997654 -0.00174366 -0.0671585 0.997654 -0.0132846 -0.205394 0.971082 -0.121705 -0.0639474 0.997654 -0.0244433 -0.397757 0.915667 0.0578157 -0.550161 0.833054 0.0578242 -0.401807 0.915667 -0.0102371 -0.553192 0.833054 2.59414e-08 -0.526117 0.833054 0.170946 -0.541103 0.833054 0.115015 -0.382265 0.915667 0.124205 -0.394297 0.915667 -0.0779956 -0.550161 0.833054 -0.0578242 0.175144 0.961988 0.20953 0.0666082 0.994592 0.0796855 0.0893498 0.994592 0.0529438 0.0791171 0.994592 0.0672824 0.0806389 0.900811 0.426659 0.00737321 0.900811 0.43415 0.108166 0.812877 0.572304 0.0507165 0.961988 0.26834 0.151584 0.900811 0.406893 0.0154249 0.41814 0.908251 -0.125308 0.567903 0.813501 -0.138292 0.41814 0.897794 -0.0661043 0.900811 0.429151 -0.438658 0.700798 0.562549 -0.38916 0.567903 0.725287 -0.226193 0.700798 0.676549 -0.275376 0.812877 0.513225 -0.337277 0.700798 0.628591 -0.671608 0.41814 0.611638 -0.693461 0.567903 0.443394 -0.765315 0.41814 0.489338 -0.35815 0.812877 0.459304 -0.75842 0.567903 0.319821 -0.837005 0.41814 0.35296 -0.601008 0.700798 0.384281 -0.884616 -0.41814 0.206429 -0.0767868 0.994592 0.0699302 -0.167928 0.961988 0.215357 -0.063864 0.994592 0.0819013 -0.251632 0.961988 0.106112 -0.365825 0.900811 0.233906 -0.23008 0.961988 0.147111 -0.990217 0.0861727 -0.109746 -0.957426 0.0861727 -0.275516 -0.990217 -0.0861726 -0.109746 -0.897093 0.0861727 -0.433358 -0.957426 -0.0861726 -0.275516 -0.433445 0.900811 0.0257924 -0.567198 0.812877 0.132358 -0.422852 0.900811 0.0986741 -0.739404 -0.41814 -0.527675 -0.786863 -0.255958 -0.561544 -0.680643 -0.255958 -0.686447 -0.897093 -0.0861726 -0.433358 -0.810951 -0.0861726 -0.578734 -0.41308 -0.255958 -0.873985 -0.521378 -0.41814 -0.743857 -0.554843 -0.255958 -0.791603 -0.639591 -0.41814 -0.645045 -0.098325 -0.255958 -0.961674 -0.243787 -0.41814 -0.875058 -0.259434 -0.255958 -0.931225 -0.57954 -0.567903 -0.584482 -0.669982 -0.567903 -0.478132 -0.388166 -0.41814 -0.821271 -0.351721 -0.567903 -0.744163 -0.267376 -0.0861726 -0.959731 -0.101335 -0.0861726 -0.991113 -0.0923945 -0.41814 -0.903671 -0.220898 -0.567903 -0.7929 0.234633 -0.0861726 -0.968257 0.065613 -0.255958 -0.964459 0.0676216 -0.0861726 -0.993983 0.0616557 -0.41814 -0.906288 0.213932 -0.41814 -0.882832 0.0558669 -0.567903 -0.821197 0.543795 -0.0861726 -0.834782 0.383165 -0.255958 -0.887508 0.394894 -0.0861726 -0.914676 0.855666 -0.255958 -0.449801 0.721059 -0.41814 -0.552478 0.767341 -0.255958 -0.58794 0.656942 -0.255958 -0.709164 0.677052 -0.0861726 -0.730873 0.790831 -0.0861726 -0.605938 0.728565 -0.567903 -0.382987 0.863923 -0.41814 -0.280706 0.78281 -0.567903 -0.25435 0.449266 -0.567903 -0.689671 0.495818 -0.41814 -0.761133 0.617318 -0.41814 -0.666391 0.185587 -0.961988 -0.20034 0.216775 -0.961988 -0.166094 0.0705797 -0.994592 -0.0761903 0.462328 -0.812877 -0.354238 0.395812 -0.812877 -0.427276 0.566254 -0.700798 -0.433866 0.88186 -0.0861726 -0.463571 0.947519 -0.0861726 -0.307868 0.631432 -0.700798 -0.331927 0.185587 0.961988 -0.20034 0.237004 0.900811 -0.363826 0.14906 0.961988 -0.228822 0.947519 0.0861727 -0.307868 0.855666 0.255958 -0.449801 0.804057 0.41814 -0.422672 0.863923 0.41814 -0.280706 0.919375 0.255958 -0.298723 0.344671 0.900811 -0.264088 0.384344 0.900811 -0.202039 0.462328 0.812877 -0.354238 0.78281 0.567903 -0.25435 0.728565 0.567903 -0.382987 0.678446 0.700798 -0.22044 0.631432 0.700798 -0.331927 0.55393 0.812877 -0.179983 0.41296 0.900811 -0.134179 0.515545 0.812877 -0.271008 0.241727 0.961988 -0.127069 0.09193 0.994592 -0.0483252 0.0987746 0.994592 -0.0320938 0.259724 0.961988 -0.0843896 -0.0605973 0.997654 0.0318544 -0.0651091 0.997654 0.0211552 -0.319051 0.915667 0.244458 -0.355776 0.915667 0.187022 -0.189511 0.971082 0.145204 -0.0543423 0.997654 0.0416372 0.0824406 0.994592 -0.0631663 -0.227059 0.971082 0.0737761 -0.505366 0.833054 0.225003 -0.211325 0.971082 0.111088 0.721059 0.41814 -0.552478 0.767341 0.255958 -0.58794 0.804057 -0.41814 -0.422672 0.65336 -0.567903 -0.500606 0.88186 0.0861727 -0.463571 0.919375 -0.255958 -0.298723 0.678446 -0.700798 -0.22044 0.230859 0.812877 -0.53473 0.172108 0.900811 -0.398646 0.295082 -0.900811 -0.318538 0.34467 -0.900811 -0.264088 0.55393 -0.812877 -0.179983 0.515545 -0.812877 -0.271008 0.259725 -0.961988 -0.0843896 0.241727 -0.961988 -0.127069 0.41296 -0.900811 -0.134179 0.384344 -0.900811 -0.202039 0.0919301 -0.994592 -0.0483252 -0.0651095 -0.997654 0.0211553 -0.0605977 -0.997654 0.0318546 0.0987747 -0.994592 -0.0320939 -0.0543426 -0.997654 0.0416375 0.0824407 -0.994592 -0.0631664 -0.276596 -0.833054 0.479078 -0.225003 -0.833054 0.505366 -0.159315 -0.915667 0.369015 -0.211325 -0.971082 0.111088 -0.447541 -0.833054 0.325158 -0.319052 -0.915667 0.244458 -0.479078 -0.833054 0.276596 -0.355776 -0.915667 0.187022 -0.505366 -0.833054 0.225003 0.360054 -0.41814 -0.833978 0.527643 -0.255958 -0.809987 -0.325158 -0.833054 0.447541 -0.219388 -0.915667 0.336783 -0.273149 -0.915667 0.294862 0.326249 -0.567903 -0.755677 0.193846 -0.567903 -0.799943 0.543795 0.0861727 -0.834782 0.394894 0.0861727 -0.914676 -0.185545 0.900811 -0.392572 -0.116532 0.900811 -0.418283 -0.248884 0.812877 -0.526582 0.227664 -0.255958 -0.939497 -0.305728 0.900811 -0.308335 -0.192283 0.961988 -0.193922 -0.156744 0.961988 -0.223629 -0.425726 -0.0861726 -0.90074 -0.47409 0.812877 -0.338334 -0.353439 0.900811 -0.252232 -0.817946 -0.41814 -0.395125 -0.741149 -0.567903 -0.358027 -0.571828 -0.0861726 -0.815835 -0.701479 -0.0861726 -0.707461 -0.906778 0.41814 0.0539584 -0.902854 0.41814 -0.100064 -0.790996 -0.567903 -0.227622 -0.960805 -0.255958 -0.106487 -0.411101 -0.833054 0.370157 -0.370157 -0.833054 0.411101 -0.189512 -0.971082 0.145205 -0.170946 -0.833054 0.526116 -0.0946599 -0.915667 0.390632 -0.0373673 -0.997654 0.0573627 0.0566883 -0.994592 -0.0870224 0.484785 -0.700798 -0.523322 0.317908 -0.812877 -0.488023 0.559359 -0.567903 -0.603824 0.38937 -0.700798 -0.597724 0.790831 0.0861727 -0.605938 0.65336 0.567903 -0.500607 0.566254 0.700798 -0.433865 0.656942 0.255958 -0.709164 0.617318 0.41814 -0.666391 0.295082 0.900811 -0.318539 0.216775 0.961988 -0.166094 0.0705796 0.994592 -0.0761902 -0.0465239 0.997654 0.0502222 -0.479078 0.833054 0.276596 -0.0578242 -0.833054 0.550161 -0.115015 -0.833054 0.541103 -0.162246 -0.971082 0.175144 -0.0465241 -0.997654 0.0502225 0.041166 -0.994592 -0.0953511 -0.0271354 -0.997654 0.0628527 0.108245 -0.961988 -0.250722 0.14906 -0.961988 -0.228822 0.237004 -0.900811 -0.363826 0.677052 0.0861727 -0.730873 0.559359 0.567903 -0.603824 0.484785 0.700798 -0.523322 0.527643 0.255958 -0.809987 0.495818 0.41814 -0.761133 0.395812 0.812877 -0.427276 -0.162246 0.971082 0.175143 -0.130313 0.971082 0.200044 -0.273148 0.915667 0.294862 -0.411102 0.833054 0.370157 -0.447541 0.833054 0.325158 -0.130313 -0.971082 0.200044 -0.0272811 -0.915667 0.401011 0.0643153 -0.961988 -0.265409 0.0244595 -0.994592 -0.100937 0.102261 -0.900811 -0.421998 0.230859 -0.812877 -0.53473 0.172108 -0.900811 -0.398646 0.282753 -0.700798 -0.65493 0.137169 -0.812877 -0.566053 0.168003 -0.700798 -0.693295 0.360054 0.41814 -0.833978 0.449266 0.567903 -0.689671 0.38937 0.700798 -0.597724 0.383165 0.255958 -0.887508 0.317908 0.812877 -0.488023 -0.0373671 0.997654 0.0573624 -0.0271353 0.997654 0.0628524 0.0566882 0.994592 -0.0870223 0.041166 0.994592 -0.0953509 -0.219387 0.915667 0.336783 -0.325158 0.833054 0.447541 -0.370157 0.833054 0.411102 0.115015 -0.833054 0.541103 0.0408824 -0.915667 0.399853 0.0578243 -0.833054 0.550161 -0.0946309 -0.971082 0.21919 0.10787 -0.915667 0.387192 0.00704927 -0.994592 -0.103618 -0.00464667 -0.997654 0.0683023 -0.259434 0.255958 -0.931225 -0.243787 0.41814 -0.875058 -0.0923945 0.41814 -0.903671 0.0185358 0.961988 -0.272461 0.0643152 0.961988 -0.265409 0.0294718 0.900811 -0.433211 0.326249 0.567903 -0.755677 0.282753 0.700798 -0.65493 0.227664 0.255958 -0.939497 0.213932 0.41814 -0.882832 0.102261 0.900811 -0.421999 0.108244 0.961988 -0.250722 0.0244594 0.994592 -0.100936 -0.0161229 0.997654 0.0665342 -0.159315 0.915667 0.369015 -0.0946307 0.971082 0.219189 -0.276596 0.833054 0.479078 0.170946 -0.833054 0.526116 0.225003 -0.833054 0.505366 0.171754 -0.915667 0.363393 -0.0562265 -0.971082 0.232029 -0.016123 -0.997654 0.0665345 -0.0105637 -0.994592 -0.103319 0.018373 -0.997654 0.0659487 -0.0278728 -0.994592 -0.100048 -0.027777 -0.961988 -0.271674 0.0185358 -0.961988 -0.272461 -0.0441651 -0.900811 -0.43196 0.0395324 -0.812877 -0.581093 0.0294717 -0.900811 -0.43321 0.0484187 -0.700798 -0.711715 0.234633 0.0861727 -0.968257 0.193846 0.567903 -0.799944 0.168003 0.700798 -0.693295 0.0656131 0.255958 -0.964459 0.0616557 0.41814 -0.906288 0.137169 0.812877 -0.566053 -0.115015 0.833054 0.541103 -0.0946598 0.915667 0.390632 -0.0578243 0.833054 0.550161 -0.0562264 0.971082 0.232029 -0.170946 0.833054 0.526117 -0.225003 0.833054 0.505366 1.93446e-08 -0.833054 0.553192 -0.0162046 -0.971082 0.238194 -0.116531 -0.900811 -0.418283 -0.0592415 -0.812877 -0.579415 -0.0725582 -0.700798 -0.70966 -0.156311 -0.812877 -0.561069 -0.0837196 -0.567903 -0.818826 -0.191448 -0.700798 -0.68719 0.0676217 0.0861727 -0.993983 0.0558668 0.567903 -0.821197 0.0484186 0.700798 -0.711715 -0.098325 0.255958 -0.961674 0.0395323 0.812877 -0.581093 0.00696327 0.997654 0.0681047 -0.0162045 0.971082 0.238194 -0.00464664 0.997654 0.0683019 0.00704926 0.994592 -0.103618 -0.0441652 0.900811 -0.43196 -0.0105637 0.994592 -0.103319 -0.0272811 0.915667 0.40101 0.230697 -0.915667 0.329139 0.325158 -0.833054 0.447541 0.370157 -0.833054 0.411101 0.0242835 -0.971082 0.237507 0.00696331 -0.997654 0.0681051 -0.0443801 -0.994592 -0.0938982 0.0292541 -0.997654 0.061895 -0.116696 -0.961988 -0.246902 -0.0732906 -0.961988 -0.263072 -0.101335 0.0861727 -0.991113 -0.0837198 0.567903 -0.818827 -0.0725582 0.700798 -0.70966 -0.0732905 0.961988 -0.263072 -0.0278728 0.994592 -0.100048 -0.0592415 0.812877 -0.579415 -0.0277769 0.961988 -0.271674 0.0183729 0.997654 0.0659483 0.0242835 0.971082 0.237506 0.0408824 0.915667 0.399853 -4.6601e-08 0.833054 0.553192 0.411101 -0.833054 0.370157 0.447541 -0.833054 0.325158 0.327168 -0.915667 0.233483 0.064073 -0.971082 0.229986 0.283004 -0.915667 0.285417 -0.156744 -0.961988 -0.223629 -0.0596106 -0.994592 -0.0850473 -0.249221 -0.900811 -0.355568 -0.248884 -0.812877 -0.526582 -0.185545 -0.900811 -0.392572 -0.30483 -0.700798 -0.644951 -0.334297 -0.812877 -0.476946 -0.267376 0.0861727 -0.959731 -0.220898 0.567903 -0.7929 -0.191448 0.700798 -0.68719 -0.413081 0.255958 -0.873985 -0.388166 0.41814 -0.821271 -0.156311 0.812877 -0.561069 0.10787 0.915667 0.387192 0.102019 0.971082 0.215849 0.171754 0.915667 0.363392 -0.04438 0.994592 -0.0938981 0.0292539 0.997654 0.0618947 0.115015 0.833054 0.541103 0.0578242 0.833054 0.550161 0.0640729 0.971082 0.229986 0.276596 -0.833054 0.479078 0.102019 -0.971082 0.21585 0.361921 -0.915667 0.174833 0.479078 -0.833054 0.276596 -0.0731262 -0.994592 -0.0737497 0.0482027 -0.997654 0.0486137 -0.409442 -0.700798 -0.584157 -0.410092 -0.812877 -0.413589 -0.472426 -0.567903 -0.674017 -0.502276 -0.700798 -0.506559 -0.425726 0.0861727 -0.90074 -0.351721 0.567903 -0.744163 -0.30483 0.700798 -0.644951 -0.554843 0.255958 -0.791603 -0.521378 0.41814 -0.743858 -0.249222 0.900811 -0.355568 -0.116696 0.961988 -0.246902 -0.0596105 0.994592 -0.0850472 0.0392934 0.997654 0.0560604 0.170946 0.833054 0.526117 0.526116 -0.833054 0.170946 0.505366 -0.833054 0.225003 0.137031 -0.971082 0.195504 0.0392936 -0.997654 0.0560607 -0.0845381 -0.994592 -0.0603305 0.0557251 -0.997654 0.0397682 -0.22229 -0.961988 -0.158637 -0.192283 -0.961988 -0.193922 -0.305728 -0.900811 -0.308335 -0.571828 0.0861727 -0.815835 -0.472426 0.567903 -0.674018 -0.409442 0.700798 -0.584157 -0.680643 0.255958 -0.686447 -0.639591 0.41814 -0.645044 -0.334297 0.812877 -0.476946 0.13703 0.971082 0.195503 0.1681 0.971082 0.169533 0.230697 0.915667 0.329139 0.276596 0.833054 0.479078 0.225003 0.833054 0.505366 0.1681 -0.971082 0.169533 0.386262 -0.915667 0.111153 -0.245902 -0.961988 -0.118788 -0.093518 -0.994592 -0.0451757 -0.390982 -0.900811 -0.188872 -0.47409 -0.812877 -0.338334 -0.353439 -0.900811 -0.252231 -0.58066 -0.700798 -0.414387 -0.52445 -0.812877 -0.253346 -0.642339 -0.700798 -0.310295 -0.701479 0.0861727 -0.707461 -0.739404 0.41814 -0.527675 -0.57954 0.567903 -0.584482 -0.502276 0.700798 -0.506559 -0.786863 0.255958 -0.561544 -0.410092 0.812877 -0.413589 0.0557248 0.997654 0.039768 0.0482024 0.997654 0.0486135 -0.0731261 0.994592 -0.0737497 -0.084538 0.994592 -0.0603305 0.283003 0.915667 0.285417 0.370157 0.833054 0.411102 0.325158 0.833054 0.447541 0.399491 -0.915667 0.0442759 0.550161 -0.833054 0.0578242 0.553192 -0.833054 2.24202e-08 0.194333 -0.971082 0.138686 0.401228 -0.915667 -0.0238753 -0.0998076 -0.994592 -0.0287213 0.0657903 -0.997654 0.0189323 -0.810951 0.0861727 -0.578734 -0.26244 0.961988 -0.0755215 -0.245902 0.961988 -0.118788 -0.417278 0.900811 -0.120079 -0.669982 0.567903 -0.478132 -0.58066 0.700798 -0.414387 -0.870446 0.255958 -0.420486 -0.817946 0.41814 -0.395125 -0.390983 0.900811 -0.188872 -0.22229 0.961988 -0.158637 -0.0935179 0.994592 -0.0451757 0.0616441 0.997654 0.0297784 0.327168 0.915667 0.233483 0.194333 0.971082 0.138685 0.411102 0.833054 0.370157 0.550161 -0.833054 -0.0578243 0.541103 -0.833054 -0.115015 0.391421 -0.915667 -0.0913397 0.214976 -0.971082 0.103848 0.0616444 -0.997654 0.0297785 -0.103226 -0.994592 -0.0114406 0.0683393 -0.997654 -0.00406657 -0.103675 -0.994592 0.00616922 -0.271429 -0.961988 -0.0300826 -0.26244 -0.961988 -0.0755216 -0.431569 -0.900811 -0.0478311 -0.559722 -0.812877 -0.161069 -0.417278 -0.900811 -0.120079 -0.68554 -0.700798 -0.197275 -0.74115 0.567903 -0.358027 -0.642339 0.700798 -0.310295 -0.928988 0.255958 -0.267332 -0.872957 0.41814 -0.251208 -0.52445 0.812877 -0.253346 0.361921 0.915667 0.174833 0.386262 0.915667 0.111153 0.505366 0.833054 0.225003 0.214975 0.971082 0.103848 0.479078 0.833054 0.276596 0.447541 0.833054 0.325158 0.541103 -0.833054 0.115015 0.229434 -0.971082 0.0660235 -0.578892 -0.812877 -0.0641591 -0.433445 -0.900811 0.0257924 -0.709019 -0.700798 -0.0785812 -0.581408 -0.812877 0.034597 -0.790996 0.567903 -0.227622 -0.68554 0.700798 -0.197275 -0.960805 0.255958 -0.106487 -0.559722 0.812877 -0.161069 0.0680432 0.997654 0.00754127 0.229434 0.971082 0.0660234 0.0657899 0.997654 0.0189322 -0.0998075 0.994592 -0.0287212 -0.43157 0.900811 -0.0478313 -0.103226 0.994592 -0.0114406 0.370355 -0.915667 -0.156176 0.505366 -0.833054 -0.225003 0.479078 -0.833054 -0.276596 0.237292 -0.971082 0.0262992 0.0680435 -0.997654 0.00754131 -0.101141 -0.994592 0.0236016 0.066669 -0.997654 -0.0155575 -0.265946 -0.961988 0.0620594 -0.272608 -0.961988 0.0162217 -0.941396 0.255958 0.219678 -0.818086 0.567903 -0.0906691 -0.709019 0.700798 -0.078581 -0.272608 0.961988 0.0162217 -0.103674 0.994592 0.00616921 -0.578891 0.812877 -0.0641591 -0.271429 0.961988 -0.0300827 0.0683389 0.997654 -0.00406655 0.237291 0.971082 0.0262992 0.399491 0.915667 0.0442759 0.541103 0.833054 0.115015 0.526117 0.833054 0.170946 0.447541 -0.833054 -0.325158 0.411102 -0.833054 -0.370157 0.297171 -0.915667 -0.270635 0.238323 -0.971082 -0.0141816 0.338634 -0.915667 -0.21652 -0.251632 -0.961988 0.106112 -0.0956972 -0.994592 0.0403549 -0.400093 -0.900811 0.168717 -0.567198 -0.812877 0.132358 -0.422851 -0.900811 0.098674 -0.536671 -0.812877 0.226311 -0.964981 -0.255958 0.0574218 -0.994521 -0.0861726 0.0591796 -0.821642 0.567903 0.0488923 -0.7121 0.700798 0.042374 -0.884616 0.41814 0.206429 -0.581408 0.812877 0.034597 -0.095697 0.994592 0.0403549 0.0630805 0.997654 -0.0266007 0.0666687 0.997654 -0.0155574 -0.101141 0.994592 0.0236015 0.553192 0.833054 2.24202e-08 0.401227 0.915667 -0.0238753 0.550161 0.833054 0.0578242 0.238323 0.971082 -0.0141816 0.526116 -0.833054 -0.170946 0.232498 -0.971082 -0.0542544 0.247158 -0.915667 -0.316964 0.370157 -0.833054 -0.411101 -0.0875006 -0.994592 0.0559474 0.0576779 -0.997654 -0.0368789 -0.941396 -0.255958 0.219678 -0.970214 -0.0861726 0.226403 -0.890729 0.255958 0.375615 -0.801561 0.567903 0.187047 -0.694696 0.700798 0.16211 -0.400093 0.900811 0.168717 -0.265946 0.961988 0.0620594 0.391421 0.915667 -0.0913396 0.232498 0.971082 -0.0542543 0.550161 0.833054 -0.0578242 0.276596 -0.833054 -0.479078 0.325158 -0.833054 -0.447541 0.219985 -0.971082 -0.0927664 0.0630808 -0.997654 -0.0266008 -0.0767868 -0.994592 0.0699303 0.0506157 -0.997654 -0.046096 -0.201908 -0.961988 0.183879 -0.23008 -0.961988 0.147112 -0.365825 -0.900811 0.233906 -0.321032 -0.900811 0.292366 -0.837005 -0.41814 0.35296 -0.890729 -0.255958 0.375615 -0.917996 -0.0861726 0.387114 -0.917996 0.0861727 0.387114 -0.657307 0.700798 0.277182 -0.814438 0.255958 0.520746 -0.53667 0.812877 0.226311 0.219985 0.971082 -0.0927663 0.201143 0.971082 -0.12861 0.370354 0.915667 -0.156176 0.526117 0.833054 -0.170946 0.541103 0.833054 -0.115015 0.201143 -0.971082 -0.12861 0.190036 -0.915667 -0.354175 -0.765315 -0.41814 0.489338 -0.814438 -0.255958 0.520747 -0.839369 -0.0861726 0.536687 -0.839369 0.0861727 0.536687 -0.714716 0.255958 0.650896 -0.490704 0.812877 0.313753 0.0506154 0.997654 -0.0460958 0.0576776 0.997654 -0.0368787 -0.0875005 0.994592 0.0559473 -0.321033 0.900811 0.292367 0.338633 0.915667 -0.21652 0.479078 0.833054 -0.276596 0.505366 0.833054 -0.225003 0.127447 -0.915667 -0.381197 0.170946 -0.833054 -0.526116 0.115015 -0.833054 -0.541103 0.176515 -0.971082 -0.160753 0.0611909 -0.915667 -0.397252 -0.0491041 -0.994592 0.0915164 -0.0638641 -0.994592 0.0819014 0.032368 -0.997654 -0.060325 -0.167928 -0.961988 0.215357 -0.506136 -0.567903 0.649086 -0.337277 -0.700798 0.628591 -0.608552 -0.567903 0.554212 -0.671608 -0.41814 0.611638 -0.714716 -0.255958 0.650896 -0.736595 -0.0861726 0.670822 -0.736595 0.0861727 0.670822 -0.430621 0.812877 0.39217 -0.594434 0.255958 0.762322 -0.55858 0.41814 0.716342 -0.201908 0.961988 0.183879 -0.267005 0.900811 0.342416 0.0420971 0.997654 -0.0539868 0.29717 0.915667 -0.270635 0.176515 0.971082 -0.160753 0.447541 0.833054 -0.325158 0.0578243 -0.833054 -0.550161 6.4185e-08 -0.833054 -0.553192 -0.00682517 -0.915667 -0.40188 0.146808 -0.971082 -0.188272 0.0420974 -0.997654 -0.0539871 -0.0329314 -0.994592 0.0984987 0.0104224 -0.997654 -0.0676621 -0.0158113 -0.994592 0.102647 -0.0865918 -0.961988 0.258999 -0.129117 -0.961988 0.240639 -0.558581 -0.41814 0.716342 -0.594434 -0.255958 0.762322 -0.612631 -0.0861726 0.785658 -0.61263 0.0861727 0.785658 -0.205296 0.900811 0.382615 -0.129117 0.961988 0.240639 -0.45705 0.255958 0.851816 -0.429483 0.41814 0.800439 0.247158 0.915667 -0.316964 0.190036 0.915667 -0.354175 0.325158 0.833054 -0.447542 -0.049104 0.994592 0.0915163 0.0323678 0.997654 -0.0603247 0.370158 0.833054 -0.411101 0.411102 0.833054 -0.370157 0.146808 0.971082 -0.188272 0.225003 -0.833054 -0.505366 0.112879 -0.971082 -0.210375 0.00176358 -0.994592 0.103843 -0.0415752 -0.961988 0.269907 -0.38916 -0.567903 0.725287 -0.429483 -0.41814 0.800439 -0.45705 -0.255958 0.851816 -0.471041 -0.0861726 0.877892 -0.471041 0.0861727 0.877892 -0.288031 0.41814 0.861508 -0.147169 0.255958 0.95542 -0.306518 0.255958 0.916805 0.0217073 0.997654 -0.0649272 0.112878 0.971082 -0.210374 -0.13768 0.900811 0.411806 -0.0329313 0.994592 0.0984986 -0.074645 -0.915667 -0.394945 -0.115015 -0.833054 -0.541103 -0.170946 -0.833054 -0.526116 0.0757014 -0.971082 -0.226425 0.0217074 -0.997654 -0.0649275 -0.0011625 -0.997654 -0.0684503 -0.226193 -0.700798 0.67655 -0.260988 -0.567903 0.780622 -0.288031 -0.41814 0.861508 -0.306518 -0.255958 0.916805 -0.315902 -0.0861726 0.944871 -0.315902 0.0861727 0.944871 -0.260988 0.567903 0.780622 -0.0415752 0.961988 0.269907 -0.0158113 0.994592 0.102647 -0.184679 0.812877 0.552381 -0.0865918 0.961988 0.258999 0.0104223 0.997654 -0.0676618 0.0757013 0.971082 -0.226425 0.127447 0.915667 -0.381197 0.225003 0.833054 -0.505366 0.276596 0.833054 -0.479078 -0.225003 -0.833054 -0.505366 -0.276596 -0.833054 -0.479078 -0.201953 -0.915667 -0.347518 0.0363464 -0.971082 -0.235962 -0.140317 -0.915667 -0.376649 -0.0886699 -0.812877 0.575647 -0.108602 -0.700798 0.705045 -0.125308 -0.567903 0.813501 -0.138292 -0.41814 0.897794 -0.147169 -0.255958 0.95542 -0.151674 -0.0861726 0.984667 -0.151674 0.0861727 0.984667 -0.108602 0.700798 0.705045 0.0192877 0.994592 0.102051 -0.0127139 0.997654 -0.0672689 -0.00116249 0.997654 -0.0684499 0.00176357 0.994592 0.103843 0.115015 0.833054 -0.541103 0.0611908 0.915667 -0.397252 0.170946 0.833054 -0.526117 0.0363464 0.971082 -0.235961 -0.0578241 -0.833054 -0.550161 -0.00405405 -0.971082 -0.23871 -0.257779 -0.915667 -0.308389 -0.325158 -0.833054 -0.447541 -0.0238996 -0.997654 -0.0641529 0.00989015 -0.812877 0.582352 0.0121133 -0.700798 0.713257 0.0139767 -0.567903 0.822977 0.0154249 -0.41814 0.908251 0.0164155 -0.255958 0.966549 0.016918 -0.0861726 0.996137 0.0169175 0.0861727 0.996137 0.016415 0.255958 0.966549 0.0139767 0.567903 0.822977 -0.0833463 0.971082 -0.223724 -0.0238995 0.997654 -0.0641526 -0.0343976 0.997654 -0.0591908 0.00463726 0.961988 0.273051 -0.00682516 0.915667 -0.401879 -0.00405404 0.971082 -0.23871 0.0578243 0.833054 -0.550161 -0.306189 -0.915667 -0.260388 -0.370157 -0.833054 -0.411101 -0.411101 -0.833054 -0.370157 -0.0443379 -0.971082 -0.234592 -0.0127139 -0.997654 -0.0672692 0.0806388 -0.900811 0.426658 0.108166 -0.812877 0.572304 0.13248 -0.700798 0.70095 0.15286 -0.567903 0.808777 0.168698 -0.41814 0.89258 0.179527 -0.255958 0.949871 0.185022 -0.0861726 0.978949 0.185022 0.0861727 0.978949 0.179527 0.255958 0.949871 0.168698 0.41814 0.89258 0.15286 0.567903 0.808777 0.13248 0.700798 0.70095 -0.044338 0.971082 -0.234591 -0.0746448 0.915667 -0.394945 -0.0578244 0.833054 -0.550161 6.4185e-08 0.833054 -0.553192 -0.0833465 -0.971082 -0.223724 0.151584 -0.900811 0.406893 0.20333 -0.812877 0.545792 0.249036 -0.700798 0.668479 0.287344 -0.567903 0.77131 0.317118 -0.41814 0.851231 0.337473 -0.255958 0.905868 0.347804 -0.0861726 0.933599 0.347804 0.0861727 0.933599 0.337473 0.255958 0.905868 0.317118 0.41814 0.851231 0.287345 0.567903 0.77131 0.249036 0.700798 0.668479 0.20333 0.812877 0.545792 -0.140317 0.915667 -0.376649 -0.170946 0.833054 -0.526117 -0.115015 0.833054 -0.541103 -0.479078 -0.833054 -0.276596 -0.119957 -0.971082 -0.20642 -0.0588969 -0.997654 -0.0348991 0.218169 -0.900811 0.375422 0.292644 -0.812877 0.503578 0.358427 -0.700798 0.616776 0.413563 -0.567903 0.711654 0.456416 -0.41814 0.785394 0.485711 -0.255958 0.835805 0.50058 -0.0861726 0.861391 0.50058 0.0861727 0.861391 0.485711 0.255958 0.835805 0.456416 0.41814 0.785394 0.413564 0.567903 0.711654 0.358427 0.700798 0.616776 0.292644 0.812877 0.503578 0.278478 0.900811 0.333152 0.330775 0.900811 0.281297 -0.0439061 0.997654 -0.0525262 -0.201953 0.915667 -0.347518 -0.119957 0.971082 -0.20642 -0.225003 0.833054 -0.505366 -0.541103 -0.833054 -0.115015 -0.153117 -0.971082 -0.183178 0.278478 -0.900811 0.333152 0.37354 -0.812877 0.446878 0.457507 -0.700798 0.54733 0.527885 -0.567903 0.631525 0.582583 -0.41814 0.696962 0.619977 -0.255958 0.741697 0.638956 -0.0861726 0.764402 0.638956 0.0861727 0.764402 0.619977 0.255958 0.741697 0.582583 0.41814 0.696962 0.527885 0.567903 0.631525 0.457507 0.700798 0.54733 0.37354 0.812877 0.446877 -0.257779 0.915667 -0.308389 -0.306189 0.915667 -0.260388 -0.370158 0.833054 -0.411102 -0.325158 0.833054 -0.447541 -0.276596 0.833054 -0.479078 -0.153117 0.971082 -0.183178 -0.447541 -0.833054 -0.325158 -0.181872 -0.971082 -0.154667 0.330775 -0.900811 0.281297 0.44369 -0.812877 0.377321 0.543425 -0.700798 0.462138 0.62702 -0.567903 0.533228 0.69199 -0.41814 0.58848 0.736406 -0.255958 0.626252 0.758949 -0.0861726 0.645423 0.758949 0.0861727 0.645423 0.736406 0.255958 0.626252 0.69199 0.41814 0.58848 0.62702 0.567903 0.533228 0.543425 0.700798 0.462138 0.44369 0.812877 0.377321 0.0970122 0.994592 0.0370821 -0.550161 -0.833054 0.0578242 -0.553192 -0.833054 2.59414e-08 -0.205394 -0.971082 -0.121705 0.08935 -0.994592 0.0529438 0.234942 -0.961988 0.139214 0.373557 -0.900811 0.221349 0.501075 -0.812877 0.29691 0.61371 -0.700798 0.363651 0.708117 -0.567903 0.419591 0.78149 -0.41814 0.463068 0.831651 -0.255958 0.49279 0.857109 -0.0861726 0.507876 0.857109 0.0861727 0.507876 0.831651 0.255958 0.492791 0.78149 0.41814 0.463068 0.708117 0.567903 0.419591 0.61371 0.700798 0.363651 0.501075 0.812877 0.29691 -0.234206 0.971082 -0.0463282 -0.375444 0.915667 -0.14351 -0.34579 0.915667 -0.204896 -0.447542 0.833054 -0.325158 -0.411101 0.833054 -0.370158 -0.0639477 -0.997654 -0.0244435 -0.223008 -0.971082 -0.085243 0.0970123 -0.994592 0.0370821 0.25509 -0.961988 0.0975061 0.405591 -0.900811 0.155034 0.544046 -0.812877 0.207957 0.66634 -0.700798 0.254703 0.768842 -0.567903 0.293883 0.848508 -0.41814 0.324335 0.90297 -0.255958 0.345153 0.930612 -0.0861726 0.355718 0.930612 0.0861727 0.355718 0.90297 0.255958 0.345152 0.848508 0.41814 0.324334 0.768843 0.567903 0.293883 0.66634 0.700798 0.254702 0.544046 0.812877 0.207957 0.405592 0.900811 0.155034 0.25509 0.961988 0.097506 0.101884 0.994592 0.0201535 -0.505366 0.833054 -0.225003 -0.479078 0.833054 -0.276596 -0.223008 0.971082 -0.0852429 -0.234207 -0.971082 -0.0463282 0.2679 -0.961988 0.052993 0.425958 -0.900811 0.0842585 0.571365 -0.812877 0.113021 0.6998 -0.700798 0.138427 0.80745 -0.567903 0.159721 0.891116 -0.41814 0.176271 0.948313 -0.255958 0.187585 0.977343 -0.0861726 0.193327 0.977343 0.0861727 0.193327 0.948313 0.255958 0.187585 0.891116 0.41814 0.176271 0.80745 0.567903 0.159721 0.6998 0.700798 0.138427 0.571365 0.812877 0.113021 0.425959 0.900811 0.0842585 0.2679 0.961988 0.052993 -0.526117 0.833054 -0.170945 0.103824 -0.994592 0.00264519 0.273002 -0.961988 0.00695544 0.434071 -0.900811 0.0110591 0.582247 -0.812877 0.0148343 0.713129 -0.700798 0.0181688 0.822828 -0.567903 0.0209637 0.908088 -0.41814 0.0231359 0.966374 -0.255958 0.0246214 0.995957 -0.0861726 0.0253751 0.995957 0.0861727 0.0253751 0.966374 0.255958 0.0246214 0.908088 0.41814 0.0231364 0.822828 0.567903 0.0209641 0.713129 0.700798 0.0181692 0.582247 0.812877 0.0148346 0.434071 0.900811 0.0110593 0.273002 0.961988 0.00695557 -0.236262 0.971082 0.0343416 -0.238667 0.971082 -0.00608067 -0.541103 0.833054 -0.115015 -0.0677482 -0.997654 0.00984749 0.102778 -0.994592 -0.0149392 0.270251 -0.961988 -0.0392821 0.429696 -0.900811 -0.0624582 0.576379 -0.812877 -0.0837792 0.705941 -0.700798 -0.102612 0.814535 -0.567903 -0.118396 0.898936 -0.41814 -0.130664 0.956635 -0.255958 -0.139051 0.985919 -0.0861726 -0.143308 0.985919 0.0861727 -0.143308 0.956635 0.255958 -0.139051 0.898936 0.41814 -0.130664 0.814536 0.567903 -0.118396 0.705941 0.700798 -0.102612 0.576379 0.812877 -0.0837792 0.429697 0.900811 -0.0624582 0.27025 0.961988 -0.0392821 0.102778 0.994592 -0.0149392 -0.0677478 0.997654 0.00984744 -0.104528 -0 -0.994522 -1.62417e-27 -0 -1 1.37149e-11 0 -1 -0.406737 -0 -0.913545 -0.309017 -0 -0.951057 -0.309017 -0 -0.951057 -0.207912 -0 -0.978148 -0.104528 -0 -0.994522 -0.207912 -0 -0.978148 -0.587785 -0 -0.809017 -0.669131 -0 -0.743145 -0.587785 -0 -0.809017 -0.406737 -0 -0.913545 -0.5 -0 -0.866025 -0.5 -0 -0.866025 -0.809017 -0 -0.587785 -0.809017 -0 -0.587785 -0.866025 -0 -0.5 -0.743145 -0 -0.669131 -0.669131 -0 -0.743145 -0.743145 -0 -0.669131 -0.978148 -0 -0.207912 -0.951057 -0 -0.309017 -0.951056 -0 -0.309017 -0.913545 -0 -0.406737 -0.913545 -0 -0.406737 -0.866025 -0 -0.5 -1 0 4.37114e-08 -0.994522 0 0.104529 -1 0 4.37114e-08 -0.978148 -0 -0.207912 -0.994522 -0 -0.104529 -0.994522 -0 -0.104528 -0.951056 0 0.309017 -0.951057 0 0.309017 -0.913545 0 0.406737 -0.978148 0 0.207912 -0.994522 0 0.104528 -0.978148 0 0.207912 -0.743145 0 0.669131 -0.809017 0 0.587785 -0.809017 0 0.587785 -0.866026 0 0.5 -0.866025 0 0.5 -0.913545 0 0.406737 -0.587785 0 0.809017 -0.5 0 0.866025 -0.587785 0 0.809017 -0.743145 0 0.669131 -0.669131 0 0.743145 -0.669131 0 0.743145 -0.406737 0 0.913545 -0.5 0 0.866025 -0.406737 0 0.913545 -0.104528 0 0.994522 -0.207912 0 0.978148 -0.104528 0 0.994522 -0.207912 0 0.978148 -0.309017 0 0.951056 -0.309017 0 0.951056 0.207912 0 0.978148 0.207912 0 0.978148 0.104528 0 0.994522 8.74228e-08 0 1 0.104528 0 0.994522 8.74228e-08 0 1 0.406737 0 0.913545 0.5 0 0.866025 0.5 0 0.866025 0.309017 0 0.951057 0.309017 0 0.951056 0.406737 0 0.913545 0.743145 0 0.669131 0.669131 0 0.743145 0.743145 0 0.669131 0.669131 0 0.743145 0.587785 0 0.809017 0.587785 0 0.809017 0.913545 0 0.406737 0.913545 0 0.406737 0.866025 0 0.5 0.809017 0 0.587785 0.866025 0 0.5 0.809017 0 0.587785 0.978148 0 0.207912 0.994522 0 0.104528 0.994522 0 0.104528 0.951056 0 0.309017 0.951056 0 0.309017 0.978148 0 0.207912 1 0 -1.19249e-08 0.994522 0 -0.104528 0.994522 0 -0.104528 1 0 -1.19249e-08 0.978148 0 -0.207911 0.978148 0 -0.207912 0.951056 0 -0.309017 0.951056 0 -0.309017 0.913545 0 -0.406737 0.913545 0 -0.406737 0.866025 0 -0.5 0.866025 0 -0.5 0.809017 0 -0.587785 0.809017 0 -0.587785 0.743145 0 -0.669131 0.743145 0 -0.669131 0.669131 0 -0.743145 0.669131 0 -0.743145 0.587785 0 -0.809017 0.587785 0 -0.809017 0.5 0 -0.866026 0.5 0 -0.866026 0.406736 0 -0.913546 0.406736 0 -0.913546 0.309017 0 -0.951057 0.309017 0 -0.951057 0.207912 0 -0.978148 0.207912 0 -0.978148 0.104528 0 -0.994522 0.104528 0 -0.994522 + + + + + + + + + + + + + + +

0 1 2 3 4 5 6 7 8 9 2 8 10 11 6 12 13 11 14 15 16 17 13 16 18 19 20 21 16 12 22 23 24 25 19 15 26 27 23 28 29 27 30 31 32 33 34 35 36 37 32 38 36 31 39 40 0 37 41 32 40 42 43 40 44 1 45 46 42 43 46 47 48 46 49 50 48 51 5 52 53 54 50 52 55 56 57 58 3 59 60 61 62 63 64 65 66 67 68 69 66 70 71 72 73 74 75 76 77 78 79 80 72 81 82 83 84 84 83 85 86 87 88 82 87 83 89 84 90 70 91 92 93 71 94 95 96 97 98 99 67 100 101 102 62 96 103 104 65 105 106 107 108 109 110 111 112 104 108 111 113 114 110 64 115 53 51 116 117 118 119 120 121 122 123 124 125 126 127 124 128 129 130 131 132 133 134 135 58 136 137 138 133 138 139 140 141 142 139 143 144 145 141 146 147 148 142 141 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 160 178 179 177 166 180 181 182 183 184 179 178 185 186 187 187 188 185 189 190 191 192 193 194 194 195 196 195 194 193 197 198 190 198 197 196 199 200 201 199 202 190 190 189 199 202 199 201 200 203 204 205 206 207 208 203 209 203 210 204 211 88 206 210 212 88 86 88 211 213 186 214 190 202 197 192 187 186 192 186 193 215 166 216 185 188 217 179 218 160 217 184 178 168 219 180 220 221 182 222 175 223 219 224 225 226 227 228 229 224 228 230 227 226 227 229 228 231 232 233 230 234 235 236 237 238 239 232 231 240 241 242 30 243 239 243 244 242 243 32 244 245 158 246 30 32 243 32 41 244 231 30 239 247 248 249 230 233 232 226 233 230 235 173 227 225 224 229 166 168 180 225 180 219 161 215 216 166 215 167 215 160 218 215 218 167 169 250 170 165 178 162 163 162 171 245 251 155 252 159 253 246 157 164 163 170 246 254 255 256 159 257 151 258 259 260 158 155 257 140 148 153 154 152 257 137 143 139 152 149 140 136 261 147 258 262 263 264 131 265 136 142 145 266 133 267 266 261 138 268 269 57 3 264 270 5 4 52 132 135 267 271 59 5 264 58 132 272 241 240 247 249 273 241 243 242 249 241 272 241 274 239 275 276 238 234 232 274 277 278 174 232 234 230 223 225 229 230 235 227 180 225 175 173 229 227 279 176 280 223 229 173 281 279 282 223 175 225 283 217 165 177 180 175 281 161 216 216 166 177 185 214 186 186 213 193 217 188 184 160 215 161 284 195 193 162 178 160 195 285 198 165 217 178 213 286 287 283 214 185 288 182 181 199 189 289 195 198 196 193 213 284 209 200 289 285 195 284 189 288 289 191 190 198 203 208 212 208 290 291 201 200 204 199 289 200 292 206 205 88 212 206 210 203 212 212 207 206 211 206 292 243 241 239 273 249 272 293 276 294 239 274 232 295 274 249 235 296 174 296 234 295 297 278 298 235 234 296 299 300 297 235 174 173 176 222 301 172 223 173 216 177 279 223 172 222 161 281 171 222 176 175 302 283 164 176 279 177 281 169 171 281 216 279 214 286 213 287 284 213 283 185 217 162 161 171 284 303 285 163 165 162 285 304 191 164 283 165 305 306 287 302 286 214 288 189 307 289 288 181 285 191 198 303 284 287 290 209 181 285 303 304 291 207 208 307 189 191 308 205 207 308 309 310 200 209 203 289 181 209 311 205 310 312 292 205 212 208 207 291 308 207 311 312 205 241 249 274 236 248 247 238 248 236 274 295 234 248 313 295 293 314 276 277 296 313 278 300 172 296 277 174 315 299 316 174 278 172 317 318 319 300 222 172 320 318 321 301 222 300 322 250 320 176 301 280 252 302 157 282 279 280 323 324 306 169 281 282 286 305 287 306 303 287 302 214 283 171 170 163 303 324 304 164 163 246 304 325 307 157 302 164 306 326 323 286 252 305 182 288 327 309 328 329 304 307 191 303 306 324 290 183 330 325 304 324 182 221 183 327 288 307 291 328 308 328 331 329 209 290 208 181 183 290 310 309 332 328 291 330 310 333 334 311 310 334 205 308 310 248 295 249 275 238 237 335 336 337 295 313 296 338 313 238 339 336 335 298 277 338 340 316 341 277 298 278 319 280 301 297 300 278 282 280 318 299 301 300 169 282 320 319 301 299 170 250 245 319 318 280 342 343 344 318 320 282 251 245 250 250 169 320 305 326 306 345 346 347 252 286 302 246 170 245 348 325 324 158 157 246 325 349 327 159 252 157 323 350 351 253 326 305 352 347 346 183 221 353 325 327 307 324 323 348 331 330 353 349 325 348 353 221 352 220 182 327 354 355 329 356 332 357 290 330 291 183 353 330 358 332 356 332 333 310 308 328 309 309 357 332 358 333 332 248 238 313 294 276 275 359 360 361 313 338 277 362 338 276 363 316 297 363 298 362 364 365 366 298 363 297 367 368 364 297 316 299 369 370 371 299 315 319 322 321 370 317 319 315 251 322 372 318 317 321 373 253 151 321 322 320 251 156 155 251 250 322 326 350 323 351 348 323 253 305 252 245 155 158 348 374 349 257 159 158 349 375 220 151 253 159 351 376 377 373 350 326 352 221 378 346 353 352 349 220 327 374 348 351 354 331 346 349 374 375 355 357 329 378 221 220 379 380 381 357 382 356 330 331 328 353 346 331 383 356 380 384 358 356 309 329 357 357 355 382 383 384 356 276 338 238 385 314 293 336 314 385 338 362 298 314 386 362 361 339 359 363 386 341 340 368 315 363 341 316 371 321 317 316 340 315 387 388 369 368 317 315 389 388 390 371 317 368 391 389 392 371 370 321 393 373 153 372 322 370 391 154 156 156 251 372 350 376 351 377 374 351 373 326 253 155 154 257 394 375 374 152 151 257 375 395 378 153 373 151 377 396 344 350 393 376 347 352 397 398 399 400 375 378 220 374 377 394 401 354 345 395 375 394 347 402 345 397 352 378 355 400 382 400 403 398 331 354 329 354 346 345 380 399 404 355 401 400 399 380 382 383 380 379 356 382 380 276 314 362 337 336 385 405 406 407 362 386 363 408 386 336 340 409 364 409 341 408 410 366 411 340 341 409 412 413 410 364 368 340 372 370 388 367 371 368 156 372 389 371 367 369 154 391 149 388 370 369 414 393 148 388 389 372 391 150 149 156 389 391 376 396 377 344 394 377 393 350 373 152 154 149 394 415 395 140 153 152 395 416 397 148 393 153 403 417 418 414 396 376 402 347 419 345 402 420 395 397 378 415 394 344 403 401 420 416 395 415 420 402 255 419 347 397 418 421 398 422 423 404 354 401 355 345 420 401 424 404 423 404 381 380 382 400 399 399 422 404 424 381 404 314 336 386 359 339 335 425 426 427 386 408 341 339 428 408 407 429 405 365 409 428 366 413 367 409 365 364 430 412 431 364 366 367 432 433 434 413 369 367 435 433 436 387 369 413 150 392 435 388 387 390 437 414 147 392 389 390 150 146 141 150 391 392 396 342 344 343 415 344 414 376 393 149 141 140 415 438 416 148 140 142 416 439 419 147 414 148 343 440 441 396 437 342 255 402 442 417 420 255 416 419 397 415 343 438 254 417 255 439 416 438 443 444 445 442 402 419 398 421 422 446 447 421 401 403 400 420 417 403 448 423 443 448 449 423 399 398 422 422 450 423 424 423 449 339 408 336 451 361 360 405 361 451 408 428 409 361 452 428 453 427 454 411 365 452 455 431 456 365 411 366 434 390 387 410 413 366 392 390 433 412 387 413 457 436 458 434 387 412 459 457 460 434 433 390 461 437 261 435 392 433 459 145 146 146 150 435 342 440 343 343 441 438 437 396 414 142 141 145 462 439 438 136 147 142 439 463 442 261 437 147 441 464 465 461 440 342 466 258 260 417 254 467 439 442 419 438 441 462 446 418 467 463 439 462 467 254 466 442 256 255 421 447 450 447 468 469 403 418 398 417 467 418 470 443 445 423 450 443 422 421 450 450 444 443 448 443 470 339 361 428 406 405 451 471 453 472 428 452 365 473 452 405 474 431 410 474 411 473 475 455 476 411 474 410 477 478 475 410 431 412 436 432 479 430 434 412 146 435 457 434 430 432 145 459 137 432 436 433 480 461 266 436 457 435 459 143 137 459 146 457 440 464 441 465 462 441 461 342 437 145 137 136 462 481 463 138 261 136 463 482 256 266 461 261 483 484 465 480 464 440 466 254 485 260 467 466 463 256 442 481 462 465 468 446 260 463 481 482 469 444 447 485 254 256 486 445 444 486 487 488 418 446 421 467 260 446 489 445 488 490 470 445 450 447 444 469 486 444 489 490 445 361 405 452 425 429 407 427 429 425 452 473 411 429 491 473 471 492 453 474 491 456 455 478 430 474 456 431 493 477 494 431 455 430 495 496 497 478 432 430 498 496 499 479 432 478 144 498 500 436 479 458 501 480 267 460 457 458 502 503 484 143 459 460 464 483 465 484 481 465 480 440 461 137 139 138 481 503 482 133 266 138 482 504 485 267 480 266 484 505 502 464 501 483 258 466 506 507 487 508 482 485 256 481 484 503 509 468 259 504 482 503 258 263 259 506 466 485 469 508 486 508 510 507 446 468 447 468 260 259 488 487 511 508 469 509 488 512 513 489 488 513 445 486 488 429 473 405 454 427 426 514 515 516 473 491 474 517 491 427 518 514 516 476 456 517 519 494 520 456 476 455 497 458 479 475 478 455 460 458 496 477 479 478 143 460 498 497 479 477 139 144 131 496 458 497 521 501 135 496 498 460 265 131 144 143 498 144 483 505 484 522 523 524 501 464 480 133 139 131 525 504 503 132 267 133 504 526 506 267 135 501 502 527 528 521 505 483 529 524 523 259 263 530 504 506 485 503 502 525 510 509 530 526 504 525 530 263 529 262 258 506 531 532 507 533 511 534 468 509 469 259 530 509 535 511 533 511 512 488 486 508 487 487 534 511 535 512 511 429 427 491 472 453 454 536 537 538 491 517 456 539 517 453 540 494 475 540 476 539 541 542 543 476 540 475 544 545 541 475 494 477 546 547 548 477 493 497 499 547 500 495 497 493 265 500 549 495 499 496 126 521 134 498 499 500 270 264 265 500 265 144 505 527 502 528 525 502 521 483 501 132 131 264 525 550 526 58 135 132 526 551 262 134 521 135 528 552 553 505 126 527 529 263 554 523 530 529 526 262 506 550 525 528 531 510 523 526 550 551 532 534 507 554 263 262 555 556 557 534 558 533 509 510 508 530 523 510 559 533 555 560 535 533 487 507 534 534 532 558 559 560 533 453 517 427 561 492 471 514 492 561 517 539 476 492 562 539 538 518 536 540 562 520 519 545 493 540 520 494 548 499 495 494 519 493 563 546 564 545 495 493 565 563 566 548 495 545 4 565 54 499 548 547 59 127 134 549 500 547 3 270 4 265 549 270 527 552 528 528 553 550 126 505 521 58 264 3 567 551 550 134 58 59 551 568 554 127 126 134 553 569 269 527 124 552 524 529 570 571 572 573 551 554 262 550 553 567 574 531 522 568 551 567 524 575 522 570 529 554 532 573 558 573 576 571 510 531 507 531 523 522 555 572 556 532 574 573 572 555 558 559 555 557 533 558 555 453 492 539 515 514 561 577 578 579 539 562 540 580 562 514 519 581 541 581 520 580 582 543 583 519 520 581 584 585 582 541 545 519 549 547 563 544 548 545 270 549 565 548 544 546 51 53 52 547 546 563 271 125 127 565 549 563 586 268 57 270 565 4 552 569 553 269 567 553 124 527 126 59 3 5 567 587 568 127 59 271 568 588 570 125 124 127 576 589 590 123 569 552 575 524 591 522 575 592 568 570 554 587 567 269 576 574 592 588 568 587 592 575 128 591 524 570 590 593 571 594 595 556 531 574 532 522 592 574 596 556 595 597 557 556 558 573 572 572 594 556 596 597 556 492 514 562 536 518 516 598 599 600 562 580 520 518 601 580 579 602 577 542 581 601 543 585 544 581 542 541 603 584 604 541 543 544 605 606 607 585 546 544 50 606 608 546 585 564 53 609 271 563 564 566 609 610 125 565 566 54 610 55 123 54 52 4 569 57 269 268 587 269 123 552 124 5 53 271 587 611 588 125 271 609 588 612 591 123 125 610 268 586 613 569 55 57 128 575 614 589 592 128 588 591 570 587 268 611 615 616 617 612 588 611 128 130 589 614 575 591 571 593 594 618 617 593 574 576 573 592 589 576 619 595 620 619 621 595 572 571 594 594 622 595 596 595 621 518 580 514 623 538 537 577 538 623 580 601 581 538 624 601 625 600 626 583 542 624 627 604 628 542 583 543 607 566 564 582 585 543 54 566 606 584 564 585 48 608 47 564 584 607 609 53 116 566 607 606 610 609 629 50 54 606 55 610 630 50 51 52 631 613 586 268 613 611 55 569 123 116 629 609 632 612 611 629 630 610 612 633 614 630 56 55 613 631 114 56 586 57 634 121 120 589 130 635 612 614 591 611 613 632 618 590 635 633 612 632 635 130 634 614 129 128 593 617 622 636 620 637 576 590 571 589 635 590 638 620 636 595 622 620 594 593 622 622 637 620 619 620 638 518 538 601 578 577 623 639 625 640 601 624 542 641 624 577 642 604 582 642 583 641 643 627 644 583 642 582 645 646 643 582 604 584 647 648 47 603 607 584 51 49 116 607 603 605 116 649 629 606 605 608 629 650 630 48 50 608 630 651 56 48 49 51 56 652 586 649 116 49 114 632 613 629 649 650 632 113 633 630 650 651 633 653 129 651 652 56 654 111 114 652 631 586 634 130 655 120 635 634 633 129 614 113 632 114 615 618 120 633 113 653 616 637 617 655 130 129 656 636 637 656 657 658 590 618 593 635 120 618 659 636 658 660 638 636 622 617 637 616 656 637 659 660 636 538 577 624 598 602 579 600 602 598 624 641 583 602 661 641 639 662 625 642 661 628 627 646 603 642 628 604 647 608 605 604 627 603 44 43 648 605 603 646 49 45 649 647 605 646 649 663 650 47 608 647 650 664 651 47 46 48 651 665 652 46 45 49 652 666 631 45 663 649 114 631 654 663 664 650 113 110 653 664 665 651 653 115 655 665 666 652 667 109 111 666 654 631 121 634 668 669 657 670 653 655 129 113 111 110 671 615 122 115 653 110 121 672 122 668 634 655 616 670 656 670 117 669 618 615 617 615 120 122 658 657 673 670 616 671 658 674 675 659 658 675 636 656 658 602 641 577 626 600 599 676 677 678 641 661 642 679 661 600 680 676 678 644 628 679 681 682 683 627 628 644 645 682 684 643 646 627 685 39 686 645 647 646 45 687 663 648 647 645 663 688 664 43 47 648 664 689 665 43 42 46 665 690 666 42 687 45 666 691 654 687 688 663 654 667 111 688 689 664 104 692 63 690 665 689 115 63 668 666 690 691 693 694 109 691 667 654 672 121 692 122 672 695 115 668 655 110 109 64 117 671 695 63 115 64 695 672 696 692 121 668 119 697 669 698 673 699 615 671 616 122 695 671 700 673 698 673 674 658 656 670 657 657 699 673 700 674 673 602 600 661 640 625 626 701 702 703 661 679 628 704 679 625 705 682 643 705 644 704 706 707 708 644 705 643 709 710 706 645 643 682 42 39 687 684 648 645 687 685 688 44 648 684 688 711 689 44 40 43 689 712 690 40 39 42 690 713 691 39 685 687 691 714 667 685 711 688 667 693 109 711 712 689 694 64 109 713 690 712 715 716 118 691 713 714 694 717 718 714 693 667 696 672 112 118 695 696 63 692 668 64 694 65 715 118 696 63 65 104 697 699 669 112 672 692 719 720 721 722 723 697 671 117 670 695 118 117 724 698 719 725 700 698 657 669 699 698 699 726 724 725 698 625 679 600 727 662 639 676 662 727 679 704 644 662 728 704 703 680 701 705 728 683 681 710 684 705 683 682 729 6 730 681 684 682 731 711 685 44 684 710 732 712 711 1 44 710 733 713 712 1 0 40 734 714 713 0 686 39 735 693 714 686 731 685 717 694 693 731 732 711 718 65 694 732 733 712 99 98 95 733 734 713 736 737 102 735 714 734 718 738 736 717 693 735 715 696 107 739 740 723 104 112 692 718 105 65 722 119 716 108 104 105 715 741 716 107 696 112 697 723 726 723 742 739 117 119 669 119 118 716 719 740 720 698 726 719 699 697 726 726 740 719 724 719 721 625 662 704 677 676 727 743 744 745 704 728 705 746 728 676 681 747 706 747 683 746 729 708 748 683 747 681 686 0 9 706 710 681 731 686 749 710 709 1 732 731 750 1 709 2 733 732 751 0 2 9 734 733 752 686 9 749 735 734 753 731 749 750 717 735 754 732 750 751 718 717 738 733 751 752 105 718 736 734 752 753 108 105 755 754 735 753 742 756 757 717 754 738 741 715 758 716 741 759 108 107 112 105 736 755 742 722 759 106 108 755 759 741 103 758 715 107 757 760 739 761 762 720 119 722 697 716 759 722 763 720 762 764 721 720 726 723 740 740 761 720 763 764 720 662 676 728 701 680 678 765 766 767 728 746 683 680 768 746 745 769 743 707 747 768 708 730 709 747 707 706 749 9 770 708 709 706 750 749 771 730 2 709 751 750 772 2 730 8 752 751 773 9 8 770 753 752 774 749 770 771 754 753 775 750 771 772 738 754 776 751 772 773 736 738 737 752 773 774 755 736 102 753 774 775 106 755 101 754 775 776 758 106 777 737 738 776 103 741 60 756 759 103 106 758 107 755 102 101 778 779 780 106 101 777 103 96 756 60 741 758 739 760 761 781 780 760 722 742 723 759 756 742 782 762 783 782 784 762 740 739 761 761 785 762 763 762 784 680 746 676 786 703 702 743 703 786 746 768 747 703 787 768 788 767 789 748 707 787 790 12 10 707 748 708 7 791 770 708 729 730 791 792 771 8 730 6 792 793 772 770 8 7 793 794 773 771 770 791 794 795 774 772 771 792 795 796 775 773 772 793 796 797 776 774 773 794 797 798 737 775 774 795 798 100 102 776 775 796 100 799 101 737 776 797 799 61 777 102 737 798 800 801 802 756 96 803 777 60 758 777 101 799 781 757 803 60 777 61 803 96 95 60 62 103 760 780 785 804 783 805 742 757 739 756 803 757 806 783 804 762 785 783 761 760 785 785 805 783 782 783 806 680 703 768 744 743 786 807 808 809 768 787 707 810 787 743 811 10 729 748 810 811 812 7 11 748 811 729 813 791 812 729 10 6 814 792 813 7 6 11 815 793 814 791 7 812 816 794 815 792 791 813 817 795 816 793 792 814 818 796 817 794 793 815 819 797 818 795 794 816 820 798 819 796 795 817 821 100 820 797 796 818 822 799 821 798 797 819 823 61 822 100 798 820 97 62 823 100 821 799 98 803 95 799 822 61 778 781 98 62 61 823 779 805 780 96 62 97 824 804 805 824 800 825 757 781 760 803 98 781 826 804 825 827 806 804 785 780 805 779 824 805 826 827 804 703 743 787 765 769 745 767 769 765 787 810 748 769 828 810 807 788 808 828 790 811 829 812 13 811 790 10 830 813 829 11 10 12 831 814 830 812 11 13 832 815 831 813 812 829 833 816 832 814 813 830 834 817 833 815 814 831 835 818 834 816 815 832 836 819 835 817 816 833 837 820 836 818 817 834 838 821 837 819 818 835 839 822 838 820 819 836 840 823 839 821 820 837 841 97 840 822 821 838 95 841 99 839 823 822 69 778 67 840 97 823 68 67 99 95 97 841 779 801 824 801 70 802 781 778 780 778 98 67 825 800 842 801 779 69 825 843 844 826 825 844 804 824 825 769 810 743 789 767 766 24 845 22 810 828 811 846 828 767 19 25 847 790 846 21 848 829 17 790 21 12 849 830 848 13 12 16 850 831 849 829 13 17 851 832 850 830 829 848 852 833 851 831 830 849 853 834 852 832 831 850 854 835 853 833 832 851 855 836 854 834 833 852 856 837 855 835 834 853 857 838 856 836 835 854 858 839 857 837 836 855 859 840 858 838 837 856 860 841 859 839 838 857 68 99 860 840 839 858 91 861 862 840 859 841 68 861 66 860 99 841 92 863 802 864 842 865 778 69 779 67 66 69 866 842 864 842 843 825 824 801 800 800 865 842 866 843 842 769 767 828 808 788 789 26 867 27 828 846 790 846 788 868 18 17 15 21 868 14 869 848 18 16 21 14 870 849 869 17 16 15 871 850 870 848 17 18 872 851 871 849 848 869 873 852 872 850 849 870 874 853 873 851 850 871 875 854 874 852 851 872 876 855 875 853 852 873 877 856 876 854 853 874 878 857 877 855 854 875 879 858 878 856 855 876 880 859 879 857 856 877 881 860 880 858 857 878 861 68 881 859 858 879 66 861 91 859 880 860 863 865 802 881 68 860 882 883 884 94 71 863 69 70 801 66 91 70 885 864 882 886 866 864 800 802 865 864 865 887 885 886 864 788 846 767 888 807 809 24 807 888 846 868 21 889 868 807 869 20 890 14 889 25 870 890 891 15 14 25 871 891 892 18 15 19 872 892 893 869 18 20 873 893 894 870 869 890 874 894 895 871 870 891 875 895 896 872 871 892 876 896 897 873 872 893 877 897 898 874 873 894 878 898 899 875 874 895 879 899 900 876 875 896 880 900 901 877 876 897 881 901 902 878 877 898 861 902 862 879 878 899 91 862 76 880 879 900 92 76 94 881 880 901 903 81 72 881 902 861 863 71 887 71 93 72 70 92 802 91 76 92 882 73 883 864 887 882 865 863 887 887 73 882 885 882 884 788 807 868 845 24 888 904 29 905 868 889 14 906 889 24 20 19 907 906 847 25 890 20 908 847 907 19 891 890 909 907 908 20 892 891 910 908 909 890 893 892 911 909 910 891 894 893 912 910 911 892 895 894 913 911 912 893 896 895 914 912 913 894 897 896 915 913 914 895 898 897 916 914 915 896 899 898 917 915 916 897 900 899 918 916 917 898 901 900 919 917 918 899 902 901 920 918 919 900 862 902 921 919 920 901 76 862 74 920 921 902 94 76 75 921 74 862 922 89 923 80 924 883 92 94 863 75 93 94 925 883 924 926 884 883 887 71 73 73 80 883 925 926 883 807 24 889 26 23 22 847 927 907 889 906 25 23 928 906 907 929 908 928 927 847 908 930 909 927 929 907 909 931 910 929 930 908 910 932 911 930 931 909 911 933 912 931 932 910 912 934 913 932 933 911 913 935 914 933 934 912 914 936 915 934 935 913 915 937 916 935 936 914 916 938 917 936 937 915 917 939 918 937 938 916 918 940 919 938 939 917 919 941 920 939 940 918 920 942 921 940 941 919 921 943 74 941 942 920 74 944 75 942 943 921 75 945 93 943 944 74 93 903 72 945 75 944 79 81 946 93 945 903 947 924 923 947 948 924 73 72 80 80 949 924 925 924 948 23 906 24 28 27 867 927 33 929 906 928 847 27 950 928 929 35 930 950 33 927 930 951 931 33 35 929 931 952 932 35 951 930 932 953 933 951 952 931 933 954 934 952 953 932 934 955 935 953 954 933 935 956 936 954 955 934 936 957 937 955 956 935 937 958 938 956 957 936 938 959 939 957 958 937 939 960 940 958 959 938 940 961 941 959 960 939 941 962 942 960 961 940 942 963 943 961 962 941 943 964 944 962 963 942 944 965 945 963 964 943 945 966 903 964 965 944 903 946 81 965 966 945 79 949 81 903 966 946 967 923 89 924 949 923 80 81 949 949 922 923 947 923 967 23 27 928 905 29 28 968 951 35 928 950 927 29 38 950 969 952 951 38 34 33 970 953 952 34 968 35 971 954 953 968 969 951 972 955 954 969 970 952 973 956 955 970 971 953 974 957 956 971 972 954 975 958 957 972 973 955 976 959 958 973 974 956 977 960 959 974 975 957 978 961 960 975 976 958 979 962 961 976 977 959 980 963 962 977 978 960 981 964 963 978 979 961 982 965 964 979 980 962 983 966 965 980 981 963 984 946 966 981 982 964 77 79 946 982 983 965 78 922 79 983 984 966 82 84 985 984 77 946 89 922 986 987 967 89 949 79 922 922 78 986 90 987 89 29 950 27 36 904 37 31 988 34 950 38 33 31 34 38 988 989 968 988 968 34 989 990 969 989 969 968 990 991 970 990 970 969 991 992 971 991 971 970 992 993 972 992 972 971 993 994 973 993 973 972 994 995 974 994 974 973 995 996 975 995 975 974 996 997 976 996 976 975 997 998 977 997 977 976 998 999 978 998 978 977 999 1000 979 999 979 978 1000 1001 980 1000 980 979 1001 1002 981 1001 981 980 1002 1003 982 1002 982 981 1003 1004 983 1003 983 982 1004 1005 984 1004 984 983 1005 1006 77 1005 77 984 1006 1007 78 1006 78 77 1007 985 986 78 1007 986 985 84 986 90 84 85 89 986 84 29 904 36 38 29 36 988 30 231 32 31 36 989 231 233 30 988 31 990 233 226 231 989 988 991 226 228 233 990 989 992 228 224 226 991 990 993 224 219 228 992 991 994 219 168 224 993 992 995 168 167 219 994 993 996 167 218 168 995 994 997 218 179 167 996 995 998 179 184 218 997 996 999 184 188 179 998 997 1000 188 187 184 999 998 1001 187 192 188 1000 999 1002 192 194 187 1001 1000 1003 194 196 192 1002 1001 1004 196 197 194 1003 1002 1005 197 202 196 1004 1003 1006 202 201 197 1005 1004 1007 201 204 202 1006 1005 985 204 210 201 1007 1006 82 210 88 204 985 1007 87 82 88 210 82 985 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1100 1101 1098 1102 1103 1099 1100 1099 1103 1104 1102 1105 1102 1104 1103 1105 1106 1107 1107 1104 1105 1108 1109 1106 1107 1106 1109 1110 1108 1111 1108 1110 1109 1111 1112 1113 1113 1110 1111 1114 1115 1112 1113 1112 1115 1116 1114 1117 1114 1116 1115 1117 1118 1119 1119 1116 1117 1120 1121 1118 1119 1118 1121 1122 1120 1123 1120 1122 1121 1123 1124 1125 1125 1122 1123 1126 1127 1124 1125 1124 1127 1009 1126 1010 1126 1009 1127 1094 1093 1101 1101 1093 1098 1096 1092 1097 1097 1092 1094 1086 1095 1087 1086 1096 1095 1088 1090 1089 1088 1087 1090 1091 1080 1082 1089 1091 1082 1083 1085 1081 1080 1083 1081 1076 1075 1084 1084 1075 1085 1078 1074 1079 1079 1074 1076 1068 1077 1069 1068 1078 1077 1070 1072 1071 1070 1069 1072 1073 1062 1064 1071 1073 1064 1065 1067 1063 1062 1065 1063 1059 1061 1066 1066 1061 1067 1053 1060 1054 1054 1060 1059 1057 1055 1058 1057 1053 1055 1056 1047 1049 1056 1058 1047 1048 1051 1050 1049 1048 1050 1043 1042 1052 1051 1043 1052 1044 1046 1041 1041 1046 1042 1035 1045 1036 1036 1045 1044 1039 1037 1040 1039 1035 1037 1038 1029 1031 1038 1040 1029 1030 1033 1032 1031 1030 1032 1025 1024 1034 1033 1025 1034 1026 1028 1023 1023 1028 1024 1017 1027 1018 1018 1027 1026 1021 1019 1022 1021 1017 1019 1020 1011 1013 1020 1022 1011 1012 1014 1016 1013 1012 1016 1008 1010 1015 1014 1008 1015

+
+
+
+ + + + -0.064778 0.0195768 -0.00536766 -0.064778 -0.0195768 0.00536766 -0.064778 0.0195768 0.00536766 7.9602e-18 -0.0195768 -0.065 7.9602e-18 0.0195768 -0.065 0.0106986 0.0195768 -0.0641135 -0.063011 0.0195768 0.0159566 -0.063011 -0.0195768 0.0159566 -0.0595253 -0.0195768 0.0261102 -0.0595253 0.0195768 0.0261102 -0.0544158 -0.0195768 0.0355516 -0.0544158 0.0195768 0.0355516 -0.0478221 0.0195768 0.0440233 -0.0478221 -0.0195768 0.0440233 -0.0399238 -0.0195768 0.0512941 -0.0399238 0.0195768 0.0512941 -0.0309366 -0.0195768 0.0571658 -0.0309366 0.0195768 0.0571658 -0.0211055 0.0195768 0.0614781 -0.0211055 -0.0195768 0.0614781 -0.0106986 -0.0195768 0.0641135 -0.0106986 0.0195768 0.0641135 -1.59204e-17 -0.0195768 0.065 -1.59204e-17 0.0195768 0.065 -0.064778 -0.0195768 -0.00536766 -0.063011 0.0195768 -0.0159566 -0.063011 -0.0195768 -0.0159566 -0.0595253 0.0195768 -0.0261102 -0.0595253 -0.0195768 -0.0261102 -0.0544158 -0.0195768 -0.0355516 -0.0544158 0.0195768 -0.0355516 -0.0478221 0.0195768 -0.0440233 -0.0478221 -0.0195768 -0.0440233 -0.0399238 0.0195768 -0.0512941 -0.0399238 -0.0195768 -0.0512941 -0.0309366 -0.0195768 -0.0571658 -0.0309366 0.0195768 -0.0571658 -0.0211055 0.0195768 -0.0614781 -0.0211055 -0.0195768 -0.0614781 -0.0106986 0.0195768 -0.0641135 -0.0106986 -0.0195768 -0.0641135 0.0211055 -0.0195768 -0.0614781 0.0106986 -0.0195768 -0.0641135 0.0211055 0.0195768 -0.0614781 0.0478221 -0.0195768 -0.0440233 0.0399238 -0.0195768 -0.0512941 0.0478221 0.0195768 -0.0440233 0.0309366 -0.0195768 -0.0571658 0.0309366 0.0195768 -0.0571658 0.0399238 0.0195768 -0.0512941 0.0595253 -0.0195768 -0.0261102 0.063011 0.0195768 -0.0159566 0.063011 -0.0195768 -0.0159566 0.0544158 0.0195768 -0.0355516 0.0595253 0.0195768 -0.0261102 0.0544158 -0.0195768 -0.0355516 0.063011 0.0195768 0.0159566 0.063011 -0.0195768 0.0159566 0.064778 -0.0195768 0.00536766 0.064778 0.0195768 0.00536766 0.064778 -0.0195768 -0.00536766 0.064778 0.0195768 -0.00536766 0.0478221 -0.0195768 0.0440233 0.0544158 -0.0195768 0.0355516 0.0478221 0.0195768 0.0440233 0.0595253 -0.0195768 0.0261102 0.0595253 0.0195768 0.0261102 0.0544158 0.0195768 0.0355516 0.0309366 0.0195768 0.0571658 0.0399238 -0.0195768 0.0512941 0.0399238 0.0195768 0.0512941 0.0211055 0.0195768 0.0614781 0.0309366 -0.0195768 0.0571658 0.0211055 -0.0195768 0.0614781 0.0106986 0.0195768 0.0641135 0.0106986 -0.0195768 0.0641135 -1.59204e-17 -0.0195768 0.065 0.0595253 -0.0195768 -0.0261102 0.063011 -0.0195768 -0.0159566 0.0211055 -0.0195768 0.0614781 0.064778 -0.0195768 -0.00536766 0.064778 -0.0195768 0.00536766 0.063011 -0.0195768 0.0159566 0.0309366 -0.0195768 0.0571658 0.0106986 -0.0195768 0.0641135 0.0595253 -0.0195768 0.0261102 0.0544158 -0.0195768 0.0355516 0.0478221 -0.0195768 0.0440233 0.0399238 -0.0195768 0.0512941 -0.0106986 -0.0195768 0.0641135 0.0544158 -0.0195768 -0.0355516 0.0478221 -0.0195768 -0.0440233 -0.0211055 -0.0195768 0.0614781 -0.0309366 -0.0195768 0.0571658 0.0399238 -0.0195768 -0.0512941 -0.0399238 -0.0195768 0.0512941 0.0309366 -0.0195768 -0.0571658 0.0211055 -0.0195768 -0.0614781 -0.0478221 -0.0195768 0.0440233 -0.0544158 -0.0195768 0.0355516 0.0106986 -0.0195768 -0.0641135 -0.0595253 -0.0195768 0.0261102 -0.063011 -0.0195768 0.0159566 7.9602e-18 -0.0195768 -0.065 -0.0211055 -0.0195768 -0.0614781 -0.064778 -0.0195768 -0.00536766 -0.0309366 -0.0195768 -0.0571658 -0.064778 -0.0195768 0.00536766 -0.0106986 -0.0195768 -0.0641135 -0.0478221 -0.0195768 -0.0440233 -0.0595253 -0.0195768 -0.0261102 -0.0544158 -0.0195768 -0.0355516 -0.0399238 -0.0195768 -0.0512941 -0.063011 -0.0195768 -0.0159566 -1.59204e-17 0.0195768 0.065 0.063011 0.0195768 -0.0159566 0.0595253 0.0195768 -0.0261102 0.0211055 0.0195768 0.0614781 0.064778 0.0195768 0.00536766 0.064778 0.0195768 -0.00536766 0.063011 0.0195768 0.0159566 0.0309366 0.0195768 0.0571658 0.0106986 0.0195768 0.0641135 0.0595253 0.0195768 0.0261102 0.0478221 0.0195768 0.0440233 0.0544158 0.0195768 0.0355516 0.0399238 0.0195768 0.0512941 0.0544158 0.0195768 -0.0355516 -0.0106986 0.0195768 0.0641135 0.0478221 0.0195768 -0.0440233 -0.0211055 0.0195768 0.0614781 -0.0309366 0.0195768 0.0571658 0.0399238 0.0195768 -0.0512941 -0.0399238 0.0195768 0.0512941 0.0309366 0.0195768 -0.0571658 0.0211055 0.0195768 -0.0614781 -0.0478221 0.0195768 0.0440233 -0.0544158 0.0195768 0.0355516 0.0106986 0.0195768 -0.0641135 -0.0595253 0.0195768 0.0261102 -0.063011 0.0195768 0.0159566 7.9602e-18 0.0195768 -0.065 -0.0211055 0.0195768 -0.0614781 -0.0309366 0.0195768 -0.0571658 -0.064778 0.0195768 -0.00536766 -0.0106986 0.0195768 -0.0641135 -0.064778 0.0195768 0.00536766 -0.0478221 0.0195768 -0.0440233 -0.0544158 0.0195768 -0.0355516 -0.0595253 0.0195768 -0.0261102 -0.063011 0.0195768 -0.0159566 -0.0399238 0.0195768 -0.0512941 + + + + + + + + + + -0.996584 0 -0.0825794 -0.996584 0 0.0825794 -0.996584 0 0.0825794 -8.74228e-08 0 -1 -8.74228e-08 0 -1 0.164595 0 -0.986361 -0.9694 0 0.245485 -0.9694 0 0.245486 -0.915773 0 0.401695 -0.915773 0 0.401695 -0.837166 0 0.546948 -0.837166 0 0.546948 -0.735724 0 0.677282 -0.735724 0 0.677282 -0.614213 0 0.78914 -0.614213 0 0.789141 -0.475948 0 0.879474 -0.475947 0 0.879474 -0.324699 0 0.945817 -0.3247 0 0.945817 -0.164595 0 0.986361 -0.164595 0 0.986361 1.74846e-07 0 1 -3.01992e-07 0 1 -0.996584 0 -0.0825794 -0.9694 0 -0.245486 -0.9694 0 -0.245486 -0.915773 0 -0.401695 -0.915773 0 -0.401695 -0.837167 0 -0.546948 -0.837167 0 -0.546948 -0.735724 0 -0.677282 -0.735724 0 -0.677282 -0.614213 0 -0.78914 -0.614213 0 -0.78914 -0.475947 0 -0.879474 -0.475947 0 -0.879474 -0.324699 0 -0.945817 -0.324699 0 -0.945817 -0.164595 0 -0.986361 -0.164595 0 -0.986361 0.3247 0 -0.945817 0.164595 0 -0.986361 0.324699 0 -0.945817 0.735724 0 -0.677282 0.614213 0 -0.789141 0.735724 0 -0.677282 0.475947 0 -0.879474 0.475947 0 -0.879474 0.614213 0 -0.78914 0.915773 0 -0.401695 0.9694 0 -0.245485 0.9694 0 -0.245485 0.837166 0 -0.546948 0.915773 0 -0.401695 0.837166 0 -0.546948 0.9694 0 0.245485 0.9694 0 0.245485 0.996584 0 0.0825794 0.996584 0 0.0825794 0.996584 0 -0.0825794 0.996584 0 -0.0825792 0.735724 0 0.677282 0.837166 0 0.546948 0.735724 0 0.677282 0.915773 0 0.401695 0.915773 0 0.401695 0.837166 0 0.546948 0.475947 0 0.879474 0.614213 0 0.789141 0.614213 0 0.789141 0.324699 0 0.945817 0.475947 0 0.879474 0.324699 0 0.945817 0.164595 0 0.986361 0.164595 0 0.986361 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 + + + + + + + + + + + + + + +

0 1 2 3 4 5 6 2 7 1 7 2 8 9 6 6 7 8 9 10 11 10 9 8 12 11 13 10 13 11 14 15 12 12 13 14 15 16 17 16 15 14 18 17 19 16 19 17 20 21 18 18 19 20 22 21 20 22 23 21 1 0 24 25 26 24 24 0 25 26 27 28 27 26 25 29 28 30 27 30 28 31 32 29 29 30 31 32 33 34 33 32 31 35 34 36 33 36 34 37 38 35 35 36 37 38 39 40 39 38 37 39 4 40 41 42 43 40 4 3 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 62 70 69 68 71 72 72 69 68 73 71 74 71 73 72 23 75 74 73 74 75 22 75 23 63 67 64 62 64 70 65 57 66 63 65 67 56 58 59 66 57 56 61 60 52 59 58 60 54 51 50 51 61 52 44 53 55 55 54 50 45 49 46 44 46 53 47 41 48 45 47 49 43 42 5 48 41 43 3 5 42 76 77 78 79 80 81 82 83 81 79 84 80 85 86 87 88 85 87 83 82 88 88 82 85 84 78 80 83 79 81 76 78 84 77 89 90 77 76 89 91 90 92 89 92 90 93 94 91 91 92 93 95 94 93 95 96 94 97 96 98 95 98 96 97 98 99 100 99 101 99 100 97 102 103 101 100 101 103 104 105 106 102 107 108 109 110 111 110 112 113 106 113 112 112 110 109 104 107 105 106 105 113 102 108 103 104 108 107 114 115 116 117 118 119 120 118 121 117 119 122 123 124 125 126 124 123 121 126 120 126 123 120 122 119 115 121 118 117 114 122 115 116 127 128 116 128 114 129 130 127 128 127 130 131 129 132 129 131 130 133 131 132 133 132 134 135 136 134 133 134 136 135 137 136 138 139 137 137 135 138 140 139 141 138 141 139 142 143 144 140 145 146 147 148 149 149 150 151 143 151 150 151 147 149 142 144 146 143 150 144 140 141 145 142 146 145

+
+
+
+
+ + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
diff --git a/src/tsukuba2022/meshes/left_back_wheel.dae b/src/tsukuba2022/meshes/left_back_wheel.dae index 7207948..13de89b 100644 --- a/src/tsukuba2022/meshes/left_back_wheel.dae +++ b/src/tsukuba2022/meshes/left_back_wheel.dae @@ -2,9 +2,9 @@ - 2022-05-02T17:48:25 - 2022-05-02T17:48:25 - + 2022-09-07T14:56:20 + 2022-09-07T14:56:20 + Z_UP @@ -68,9 +68,9 @@ - 0.0265 0 0.03 0.0265 -0.007 0.03 0.0265 -0.007 0.11 0.0265 0 0.11 7.10543e-18 -2.66454e-18 0.0035 5.32907e-18 -0.007 0.0035 0.0265 -0.007 0.03 0.0265 0 0.03 0.03 -2.66454e-18 0.0265 0.03 -0.007 0.0265 0.0035 -0.007 1.06581e-17 0.0035 -2.66454e-18 1.06581e-17 0.0326812 -0.007 0.0277502 0.0322498 -0.007 0.0273188 0.0326812 0 0.0277502 0.0330311 0 0.02825 0.0330311 -0.007 0.02825 0.0332889 0 0.0288029 0.0332889 -0.007 0.0288029 0.0334468 -0.007 0.0293922 0.0334468 0 0.0293922 0.0335 0 0.03 0.0335 -0.007 0.03 0.0322498 0 0.0273188 0.03175 0 0.0269689 0.03175 -0.007 0.0269689 0.0311971 -0.007 0.0267111 0.0311971 0 0.0267111 0.0306078 -0.007 0.0265532 0.0306078 0 0.0265532 0.03 -0.007 0.0265 0.03 -2.66454e-18 0.0265 0.0335 0 0.03 0.0335 0 0.11 0.0335 -0.007 0.11 0.0335 -0.007 0.03 0.0335 0 0.11 0.0265 0 0.11 0.0265 -0.007 0.11 0.0335 -0.007 0.11 0.03175 -0.007 0.0269689 0.0322498 -0.007 0.0273188 0.0335 -0.007 0.03 0.03 -0.007 0.0265 0.0265 -0.007 0.03 0.0035 -0.007 1.06581e-17 0.00345099 -0.007 0.000583691 0.000799228 -0.007 0.00340753 0.000219767 -0.007 0.00349309 5.32907e-18 -0.007 0.0035 0.00187539 -0.007 0.00295515 0.0013563 -0.007 0.00322652 0.00274293 -0.007 0.00217402 0.00234196 -0.007 0.00260101 0.00330532 -0.007 0.00115103 0.00306707 -0.007 0.00168614 0.0330311 -0.007 0.02825 0.0332889 -0.007 0.0288029 0.0306078 -0.007 0.0265532 0.0326812 -0.007 0.0277502 0.0334468 -0.007 0.0293922 0.0311971 -0.007 0.0267111 0.0265 -0.007 0.11 0.0335 -0.007 0.11 -0.00224976 0 -0.00268116 -0.00224976 0 0.00268116 -0.00175 0 -0.00303109 0.0265 0 0.03 0.03 -2.66454e-18 0.0265 0.0035 -2.66454e-18 1.06581e-17 0.0335 0 0.03 0.0265 0 0.11 -0.0035 0 -7.13318e-18 -0.00344683 0 0.000607769 -0.00344683 0 -0.000607769 -0.00328892 0 0.00119707 -0.00328892 0 -0.00119707 -0.00303109 0 -0.00175 -0.00303109 0 0.00175 -0.00268116 0 0.00224976 -0.00268116 0 -0.00224976 -0.00175 0 0.00303109 -0.00119707 0 -0.00328892 -0.000607769 0 -0.00344683 -0.00119707 0 0.00328892 -0.000607769 0 0.00344683 3.05311e-19 0 -0.0035 7.10543e-18 -2.66454e-18 0.0035 0.000607769 0 -0.00344683 0.00175 0 -0.00303109 0.00119707 0 -0.00328892 0.00268116 0 -0.00224976 0.00224976 0 -0.00268116 0.00328892 0 -0.00119707 0.00303109 0 -0.00175 0.00344683 0 -0.000607769 0.0322498 0 0.0273188 0.03175 0 0.0269689 0.0306078 0 0.0265532 0.0332889 0 0.0288029 0.0334468 0 0.0293922 0.0330311 0 0.02825 0.0326812 0 0.0277502 0.0311971 0 0.0267111 0.0335 0 0.11 0.00349827 -0.039 -0.000109938 0.00342851 -0.039 -0.000703773 0.00344683 0 -0.000607769 0.00190624 -0.039 0.00293535 0.00237804 -0.039 0.00256805 0.00234196 -0.007 0.00260101 0.00274293 -0.007 0.00217402 0.0035 -2.66454e-18 1.06581e-17 0.0035 -0.007 1.06581e-17 0.00187539 -0.007 0.00295515 0.0013788 -0.039 0.00321697 0.000811118 -0.039 0.00340472 0.0013563 -0.007 0.00322652 0.000799228 -0.007 0.00340753 0.000219767 -0.039 0.00349309 0.000219767 -0.007 0.00349309 0.00278045 -0.039 0.00212582 0.00310171 -0.039 0.00162154 0.00306707 -0.007 0.00168614 0.00333245 -0.039 0.00106993 0.00330532 -0.007 0.00115103 0.00345099 -0.007 0.000583691 0.00346594 -0.039 0.000487106 0.00328892 0 -0.00119707 0.0032587 -0.039 -0.00127707 0.00303109 0 -0.00175 0.00175 0 -0.00303109 0.00224976 0 -0.00268116 0.0022121 -0.039 -0.00271231 0.00268116 0 -0.00224976 0.00299377 -0.039 -0.00181309 0.00264148 -0.039 -0.00229621 0.000607769 0 -0.00344683 0.000595733 -0.039 -0.00344893 3.05311e-19 0 -0.0035 0.00171816 -0.039 -0.00304925 0.00117408 -0.039 -0.0032972 0.00119707 0 -0.00328892 -0.00169627 -0.039 -0.00306148 -0.00119707 0 -0.00328892 -0.00115832 -0.039 -0.00330277 -0.000607769 0 -0.00344683 -0.000587494 -0.039 -0.00345034 -0.00175 0 -0.00303109 -0.00218609 -0.039 -0.00273331 -0.00224976 0 -0.00268116 -0.00303109 0 -0.00175 -0.00296749 -0.039 -0.00185581 -0.00323689 -0.039 -0.00133137 -0.00261388 -0.039 -0.00232759 -0.00268116 0 -0.00224976 -0.0034951 -0.039 -0.000185102 -0.00347658 -0.039 0.000404196 -0.0035 0 -7.13318e-18 -0.00341444 -0.039 -0.000769148 -0.00344683 0 -0.000607769 -0.00328892 0 -0.00119707 -0.0028451 -0.039 0.00203848 -0.00303109 0 0.00175 -0.00314691 -0.039 0.00153199 -0.00328892 0 0.00119707 -0.00344683 0 0.000607769 -0.00335941 -0.039 0.000982025 -0.00246257 -0.039 0.00248712 -0.00224976 0 0.00268116 -0.00268116 0 0.00224976 -0.00201015 -0.039 0.00286519 -0.00175 0 0.00303109 -0.00119707 0 0.00328892 -0.00150069 -0.039 0.00316195 -0.000948649 -0.039 0.00336899 -0.000607769 0 0.00344683 -0.000369686 -0.039 0.00348042 7.10543e-18 -2.66454e-18 0.0035 5.32907e-18 -0.007 0.0035 1.85962e-18 -0.039 -0.0035 0.0032587 -0.039 -0.00127707 -0.00150069 -0.039 0.00316195 0.00299377 -0.039 -0.00181309 0.0013788 -0.039 0.00321697 0.00333245 -0.039 0.00106993 0.00310171 -0.039 0.00162154 0.00349827 -0.039 -0.000109938 0.00346594 -0.039 0.000487106 0.000219767 -0.039 0.00349309 0.00342851 -0.039 -0.000703773 -0.000369686 -0.039 0.00348042 -0.000948649 -0.039 0.00336899 0.00278045 -0.039 0.00212582 0.00190624 -0.039 0.00293535 0.000811118 -0.039 0.00340472 0.00237804 -0.039 0.00256805 -0.00201015 -0.039 0.00286519 -0.00246257 -0.039 0.00248712 0.00264148 -0.039 -0.00229621 0.0022121 -0.039 -0.00271231 -0.0028451 -0.039 0.00203848 0.00171816 -0.039 -0.00304925 -0.00314691 -0.039 0.00153199 -0.00335941 -0.039 0.000982025 0.00117408 -0.039 -0.0032972 0.000595733 -0.039 -0.00344893 -0.00347658 -0.039 0.000404196 -0.0034951 -0.039 -0.000185102 1.85962e-18 -0.039 -0.0035 -0.00115832 -0.039 -0.00330277 -0.00323689 -0.039 -0.00133137 -0.00169627 -0.039 -0.00306148 -0.00341444 -0.039 -0.000769148 -0.000587494 -0.039 -0.00345034 -0.00218609 -0.039 -0.00273331 -0.00296749 -0.039 -0.00185581 -0.00261388 -0.039 -0.00232759 + 0.0265 0 0.03 0.0265 -0.007 0.03 0.0265 -0.007 0.11 0.0265 0 0.11 7.10543e-18 -2.66454e-18 0.0035 5.32907e-18 -0.007 0.0035 0.0265 -0.007 0.03 0.0265 0 0.03 0.03 -2.66454e-18 0.0265 0.03 -0.007 0.0265 0.0035 -0.007 1.06581e-17 0.0035 -2.66454e-18 1.06581e-17 0.0324749 -0.007 0.0275251 0.0324749 0 0.0275251 0.0328316 0 0.0279428 0.0331185 0 0.028411 0.0328316 -0.007 0.0279428 0.0333287 0 0.0289184 0.0331185 -0.007 0.028411 0.0333287 -0.007 0.0289184 0.0334569 0 0.0294525 0.0335 0 0.03 0.0334569 -0.007 0.0294525 0.0335 -0.007 0.03 0.0320572 -0.007 0.0271684 0.0320572 0 0.0271684 0.031589 -0.007 0.0268815 0.0310816 -0.007 0.0266713 0.031589 0 0.0268815 0.0305475 -0.007 0.0265431 0.0310816 0 0.0266713 0.0305475 0 0.0265431 0.03 -0.007 0.0265 0.03 -2.66454e-18 0.0265 0.0335 0 0.03 0.0335 0 0.11 0.0335 -0.007 0.11 0.0335 -0.007 0.03 0.0335 0 0.11 0.0265 0 0.11 0.0265 -0.007 0.11 0.0335 -0.007 0.11 0.031589 -0.007 0.0268815 0.0320572 -0.007 0.0271684 0.0335 -0.007 0.03 0.03 -0.007 0.0265 0.0265 -0.007 0.03 0.0035 -0.007 1.06581e-17 0.00346024 -0.007 0.000526057 0.000742289 -0.007 0.00342038 0.000219767 -0.007 0.00349309 5.32907e-18 -0.007 0.0035 0.00172518 -0.007 0.00304525 0.00124793 -0.007 0.00326995 0.00255205 -0.007 0.00239512 0.0021632 -0.007 0.0027514 0.00314827 -0.007 0.00152899 0.00288289 -0.007 0.00198453 0.00334218 -0.007 0.00103887 0.0328316 -0.007 0.0279428 0.0331185 -0.007 0.028411 0.0305475 -0.007 0.0265431 0.0333287 -0.007 0.0289184 0.0334569 -0.007 0.0294525 0.0324749 -0.007 0.0275251 0.0310816 -0.007 0.0266713 0.0265 -0.007 0.11 0.0335 -0.007 0.11 -0.00205749 0 -0.00283133 -0.00247409 0 0.00247554 -0.00205644 0 0.00283204 0.0265 0 0.03 0.03 -2.66454e-18 0.0265 0.0035 -2.66454e-18 1.06581e-17 0.0335 0 0.03 0.0265 0 0.11 -0.00349997 0 8.21991e-07 -0.00345672 0 0.000548434 -0.00345699 0 -0.000546838 -0.00332833 0 0.0010825 -0.00332885 0 -0.00108105 -0.00311798 0 0.00158988 -0.00311868 0 -0.00158864 -0.00283167 0 -0.0020571 -0.00283087 0 0.00205806 -0.00247487 0 -0.00247487 -0.00158947 0 -0.00311819 -0.00158822 0 0.00311881 -0.00108229 0 -0.00332838 -0.000548432 0 -0.00345668 -0.00108097 0 0.00332882 -0.000547702 0 0.00345688 -1.02458e-06 0 -0.00349991 7.10543e-18 -2.66454e-18 0.0035 0.000546458 0 -0.003457 0.00158804 0 -0.00311893 0.00108053 0 -0.00332896 0.00247427 0 -0.00247543 0.00205647 0 -0.00283207 0.00283114 0 -0.00205779 0.00332858 0 -0.0010819 0.00311827 0 -0.00158944 0.00345688 0 -0.000547702 0.0320572 0 0.0271684 0.031589 0 0.0268815 0.0305475 0 0.0265431 0.0333287 0 0.0289184 0.0334569 0 0.0294525 0.0331185 0 0.028411 0.0328316 0 0.0279428 0.0324749 0 0.0275251 0.0310816 0 0.0266713 0.0335 0 0.11 0.00349827 -0.039 -0.000109938 0.00343999 -0.039 -0.000645314 0.00345688 0 -0.000547702 0.00219765 -0.039 0.00272397 0.00255205 -0.007 0.00239512 0.0021632 -0.007 0.0027514 0.00258939 -0.039 0.00235469 0.0035 -2.66454e-18 1.06581e-17 0.0035 -0.007 1.06581e-17 0.00172518 -0.007 0.00304525 0.00175385 -0.039 0.00302883 0.00126848 -0.039 0.00326203 0.00124793 -0.007 0.00326995 0.000742289 -0.007 0.00342038 0.000753048 -0.039 0.00341802 0.000219767 -0.007 0.00349309 0.000219767 -0.039 0.00349309 0.00288289 -0.007 0.00198453 0.00314827 -0.007 0.00152899 0.00291982 -0.039 0.00192978 0.00318115 -0.039 0.00145933 0.00334218 -0.007 0.00103887 0.00336724 -0.039 0.000954505 0.00346024 -0.007 0.000526057 0.00347377 -0.039 0.000427257 0.00332858 0 -0.0010819 0.00330027 -0.039 -0.00116539 0.00311827 0 -0.00158944 0.00205647 0 -0.00283207 0.00247427 0 -0.00247543 0.00243486 -0.039 -0.00251415 0.00283114 0 -0.00205779 0.00308242 -0.039 -0.00165784 0.00279165 -0.039 -0.002111 0.00108053 0 -0.00332896 0.0010598 -0.039 -0.0033356 0.000546458 0 -0.003457 0.00202054 -0.039 -0.00285776 0.00155854 -0.039 -0.00313374 0.00158804 0 -0.00311893 -0.000558516 -0.039 -0.00345515 -0.00108229 0 -0.00332838 -0.000548432 0 -0.00345668 1.85962e-18 -0.039 -0.0035 -1.02458e-06 0 -0.00349991 0.000536942 -0.039 -0.00345856 -0.00247487 0 -0.00247487 -0.00205749 0 -0.00283133 -0.00209309 -0.039 -0.00280515 -0.00158947 0 -0.00311819 -0.00110271 -0.039 -0.00332175 -0.00161865 -0.039 -0.00310321 -0.00311868 0 -0.00158864 -0.00315305 -0.039 -0.00151922 -0.00332885 0 -0.00108105 -0.00251388 -0.039 -0.00243521 -0.00287024 -0.039 -0.00200287 -0.00283167 0 -0.0020571 -0.00349817 -0.039 0.000110981 -0.00345672 0 0.000548434 -0.00349997 0 8.21991e-07 -0.00347108 -0.039 -0.000448573 -0.00345699 0 -0.000546838 -0.00335505 -0.039 -0.000996655 -0.00305046 -0.039 0.00171584 -0.00311798 0 0.00158988 -0.00328512 -0.039 0.00120723 -0.00332833 0 0.0010825 -0.00343565 -0.039 0.000667668 -0.00235481 -0.039 0.00258926 -0.00247409 0 0.00247554 -0.00273768 -0.039 0.00218048 -0.00283087 0 0.00205806 -0.00191167 -0.039 0.00293172 -0.00205644 0 0.00283204 -0.00158822 0 0.00311881 -0.0014196 -0.039 0.0031991 -0.000891225 -0.039 0.00338457 -0.00108097 0 0.00332882 -0.000340463 -0.039 0.0034834 -0.000547702 0 0.00345688 5.32907e-18 -0.007 0.0035 7.10543e-18 -2.66454e-18 0.0035 0.00308242 -0.039 -0.00165784 -0.00191167 -0.039 0.00293172 0.00279165 -0.039 -0.002111 0.00318115 -0.039 0.00145933 0.00126848 -0.039 0.00326203 0.00336724 -0.039 0.000954505 0.00349827 -0.039 -0.000109938 0.000219767 -0.039 0.00349309 -0.000340463 -0.039 0.0034834 0.00343999 -0.039 -0.000645314 -0.000891225 -0.039 0.00338457 0.00330027 -0.039 -0.00116539 0.00175385 -0.039 0.00302883 0.000753048 -0.039 0.00341802 0.00347377 -0.039 0.000427257 0.00291982 -0.039 0.00192978 0.00219765 -0.039 0.00272397 0.00258939 -0.039 0.00235469 -0.0014196 -0.039 0.0031991 0.00243486 -0.039 -0.00251415 -0.00235481 -0.039 0.00258926 -0.00273768 -0.039 0.00218048 -0.00305046 -0.039 0.00171584 0.00202054 -0.039 -0.00285776 0.00155854 -0.039 -0.00313374 -0.00328512 -0.039 0.00120723 0.0010598 -0.039 -0.0033356 -0.00343565 -0.039 0.000667668 0.000536942 -0.039 -0.00345856 1.85962e-18 -0.039 -0.0035 -0.00349817 -0.039 0.000110981 -0.000558516 -0.039 -0.00345515 -0.00335505 -0.039 -0.000996655 -0.00110271 -0.039 -0.00332175 -0.00347108 -0.039 -0.000448573 -0.00209309 -0.039 -0.00280515 -0.00287024 -0.039 -0.00200287 -0.00251388 -0.039 -0.00243521 -0.00161865 -0.039 -0.00310321 -0.00315305 -0.039 -0.00151922 - + @@ -78,9 +78,9 @@ - -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.766044 0 -0.642788 0.642788 0 -0.766044 0.766045 0 -0.642788 0.866025 0 -0.5 0.866025 0 -0.5 0.939693 0 -0.34202 0.939693 0 -0.34202 0.984808 0 -0.173648 0.984808 0 -0.173648 1 0 -5.96244e-09 1 0 -5.96244e-09 0.642788 0 -0.766044 0.5 0 -0.866025 0.5 0 -0.866025 0.34202 0 -0.939693 0.34202 0 -0.939693 0.173648 0 -0.984808 0.173648 0 -0.984808 6.95355e-08 0 -1 6.95355e-08 0 -1 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.999507 0 -0.0314108 0.979575 0 -0.201078 0.984808 0 -0.173648 0.544639 0 0.838671 0.679441 0 0.73373 0.669131 0 0.743145 0.783693 0 0.621148 1 0 -1.81211e-08 1 0 1.01088e-07 0.535827 0 0.844328 0.393942 0 0.919135 0.231748 0 0.972776 0.387516 0 0.921863 0.228351 0 0.973579 0.0627905 0 0.998027 0.0627905 0 0.998027 0.794415 0 0.607376 0.886204 0 0.463296 0.876307 0 0.481754 0.952129 0 0.305695 0.944376 0 0.328867 0.985996 0 0.166769 0.990268 0 0.139173 0.939693 0 -0.34202 0.931056 0 -0.364877 0.866026 0 -0.5 0.5 0 -0.866025 0.642788 0 -0.766044 0.632029 0 -0.774945 0.766044 0 -0.642788 0.855364 0 -0.518027 0.754709 0 -0.656059 0.173648 0 -0.984808 0.17021 0 -0.985408 -6.18325e-08 0 -1 0.490904 0 -0.871214 0.335452 0 -0.942057 0.34202 0 -0.939693 -0.484649 0 -0.874709 -0.34202 0 -0.939693 -0.330948 0 -0.943649 -0.173648 0 -0.984808 -0.167856 0 -0.985812 -0.5 0 -0.866025 -0.624597 0 -0.780947 -0.642788 0 -0.766044 -0.866025 0 -0.5 -0.847853 0 -0.530231 -0.924826 0 -0.380391 -0.746822 0 -0.665025 -0.766044 0 -0.642788 -0.998601 0 -0.0528861 -0.993309 0 0.115485 -1 0 -1.36654e-08 -0.975555 0 -0.219757 -0.984808 0 -0.173648 -0.939693 0 -0.34202 -0.812887 0 0.582422 -0.866025 0 0.5 -0.899116 0 0.43771 -0.939693 0 0.34202 -0.984808 0 0.173648 -0.959831 0 0.280579 -0.703591 0 0.710606 -0.642787 0 0.766045 -0.766045 0 0.642788 -0.574329 0 0.818625 -0.5 0 0.866026 -0.34202 0 0.939693 -0.428769 0 0.903414 -0.271043 0 0.962567 -0.173648 0 0.984808 -0.105625 0 0.994406 1.49255e-07 0 1 1.49255e-07 0 1 -6.18325e-08 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 + -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.809017 0 -0.587785 0.891007 0 -0.45399 0.809017 0 -0.587785 0.951057 0 -0.309017 0.891007 0 -0.45399 0.951057 0 -0.309017 0.987688 0 -0.156435 1 0 -5.96244e-09 0.987688 0 -0.156435 1 0 -5.96244e-09 0.587785 0 -0.809017 0.587785 0 -0.809017 0.453991 0 -0.891007 0.309017 0 -0.951057 0.453991 0 -0.891007 0.156435 0 -0.987688 0.309017 0 -0.951057 0.156434 0 -0.987688 6.95355e-08 0 -1 -1.68883e-07 0 -1 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.999507 0 -0.0314108 0.982871 0 -0.184294 0.987688 0 -0.156434 0.627691 0 0.778462 0.728969 0 0.684547 0.61786 0 0.786288 0.739631 0 0.673012 1 0 -1.81211e-08 1 0 -1.81211e-08 0.492727 0 0.870184 0.500907 0 0.865501 0.362275 0 0.932071 0.356412 0 0.934329 0.212007 0 0.977268 0.215076 0 0.976597 0.0627905 0 0.998027 0.0627905 0 0.998027 0.823533 0 0.567269 0.899405 0 0.437116 0.834078 0 0.551646 0.9088 0 0.417233 0.954865 0 0.297042 0.962028 0 0.272952 0.988652 0 0.150226 0.992504 0 0.122216 0.951056 0 -0.309017 0.942991 0 -0.332819 0.891006 0 -0.453991 0.587785 0 -0.809017 0.707107 0 -0.707107 0.695913 0 -0.718126 0.809017 0 -0.587785 0.880808 0 -0.473474 0.797794 0 -0.60293 0.309017 0 -0.951056 0.303035 0 -0.952979 0.156434 0 -0.987688 0.577573 0 -0.816339 0.445573 0 -0.895246 0.45399 0 -0.891007 -0.159537 0 -0.987192 -0.309017 0 -0.951056 -0.156434 0 -0.987688 -6.18325e-08 0 -1 1.76586e-07 0 -1 0.153331 0 -0.988175 -0.707107 0 -0.707107 -0.587785 0 -0.809017 -0.597905 0 -0.801567 -0.453991 0 -0.891007 -0.314987 0 -0.949096 -0.462368 0 -0.886688 -0.891007 0 -0.45399 -0.900774 0 -0.434288 -0.951056 0 -0.309017 -0.718126 0 -0.695913 -0.819952 0 -0.572432 -0.809017 0 -0.587785 -0.999507 0 0.0314108 -0.987688 0 0.156435 -1 0 -1.36654e-08 -0.991716 0 -0.128449 -0.987688 0 -0.156435 -0.958522 0 -0.285019 -0.871727 0 0.489991 -0.891006 0 0.453991 -0.938734 0 0.344643 -0.951056 0 0.309017 -0.981694 0 0.190466 -0.673013 0 0.739631 -0.707107 0 0.707107 -0.782391 0 0.622788 -0.809017 0 0.587785 -0.546394 0 0.837528 -0.587785 0 0.809017 -0.453991 0 0.891007 -0.40578 0 0.913971 -0.254771 0 0.967001 -0.309017 0 0.951057 -0.0972357 0 0.995261 -0.156434 0 0.987688 1.49255e-07 0 1 1.49255e-07 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 - + @@ -91,18 +91,18 @@ - + -

0 1 2 0 2 3 4 5 6 4 6 7 8 9 10 8 10 11 12 13 14 15 16 12 12 14 15 16 17 18 17 16 15 19 18 20 17 20 18 21 22 19 19 20 21 14 13 23 24 23 25 13 25 23 26 27 24 24 25 26 27 28 29 28 27 26 28 30 29 29 30 31 32 33 34 34 35 32 36 37 38 38 39 36 40 41 42 43 44 45 44 46 45 47 44 48 44 49 48 50 44 51 44 47 51 52 44 53 44 50 53 54 44 55 44 52 55 44 54 46 56 57 42 43 58 42 56 42 59 42 57 60 42 61 40 41 59 42 44 43 42 61 42 58 42 62 44 42 63 62 64 65 66 67 68 69 70 67 71 72 73 74 75 76 73 74 73 76 77 75 78 75 77 76 78 79 80 80 77 78 79 64 80 81 66 65 65 64 79 66 81 82 83 82 84 81 84 82 83 85 86 85 83 84 87 88 86 86 85 87 87 89 90 88 87 90 87 91 92 89 87 92 93 94 69 69 94 91 93 69 95 67 69 87 91 87 69 70 96 97 68 70 98 99 70 100 70 99 101 102 96 70 101 102 70 70 103 98 70 97 103 67 70 68 104 70 71 105 106 107 108 109 110 110 109 111 112 113 105 108 114 115 114 108 110 116 115 117 114 117 115 118 119 116 116 117 118 120 119 118 111 109 121 122 123 121 111 121 123 122 124 125 125 123 122 126 124 127 124 126 125 105 113 127 126 127 113 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 139 147 148 149 150 151 152 153 150 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 170 162 168 169 171 172 171 169 168 173 172 174 171 174 172 175 176 173 173 174 175 176 177 178 177 176 175 119 179 177 178 177 179 120 179 119 165 164 163 170 163 162 157 167 166 164 165 167 156 158 160 157 166 158 153 159 161 159 156 160 155 152 151 151 153 161 150 149 154 155 154 152 148 144 143 148 143 149 145 146 147 144 146 145 138 180 139 147 139 180 142 141 137 141 138 137 131 133 140 131 140 142 132 134 136 132 136 133 135 130 129 134 130 135 106 128 107 129 128 106 105 107 112 181 182 183 184 185 186 187 188 189 190 191 192 193 194 186 184 195 185 186 194 184 196 194 193 188 185 195 191 187 189 189 188 195 192 181 190 191 190 187 182 197 183 192 182 181 198 199 197 183 197 199 200 199 198 200 201 202 201 200 198 201 203 202 203 204 205 205 202 203 206 204 207 204 206 205 208 209 207 206 207 209 210 211 212 208 213 214 215 212 216 216 217 215 210 213 211 212 211 216 208 214 209 210 214 213

+

0 1 2 0 2 3 4 5 6 4 6 7 8 9 10 8 10 11 12 13 14 15 16 14 12 14 16 15 17 18 18 16 15 19 17 20 17 19 18 21 22 20 19 20 22 23 22 21 24 13 12 25 24 26 24 25 13 27 28 26 25 26 28 27 29 30 30 28 27 31 29 32 29 31 30 31 32 33 34 35 36 36 37 34 38 39 40 40 41 38 42 43 44 45 46 47 48 47 46 49 46 50 46 51 50 52 46 53 46 49 53 54 46 55 46 52 55 56 46 57 46 54 57 46 58 48 46 56 58 59 60 44 45 61 44 62 44 60 44 62 63 44 43 64 44 64 59 61 65 44 65 42 44 46 44 66 45 44 46 44 67 66 68 69 70 71 72 73 74 71 75 76 77 78 77 79 80 80 78 77 81 82 79 80 79 82 83 81 84 81 83 82 85 83 84 68 85 69 84 69 85 68 70 86 87 88 86 86 70 87 89 88 90 87 90 88 89 91 92 91 89 90 93 94 92 92 91 93 93 95 96 94 93 96 93 97 98 95 93 98 99 97 73 73 100 101 100 73 102 73 101 99 71 73 93 73 97 93 74 103 104 72 74 105 106 74 107 74 108 109 110 74 109 106 108 74 104 111 74 74 110 103 74 72 71 105 74 111 112 74 75 113 114 115 116 117 118 116 119 117 120 121 113 118 122 123 123 116 118 124 122 125 122 124 123 126 127 125 124 125 127 126 128 129 129 127 126 119 130 117 131 130 132 119 132 130 133 134 131 131 132 133 134 135 136 135 134 133 121 136 137 135 137 136 138 139 140 121 137 113 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 179 182 183 184 185 184 183 182 186 187 187 183 182 188 186 189 186 188 187 190 191 189 188 189 191 190 192 193 193 191 190 194 195 192 192 195 193 129 128 194 194 192 129 185 178 177 185 177 184 180 172 181 178 180 179 171 173 174 181 172 171 176 175 167 174 173 175 169 166 165 166 176 167 159 168 170 170 169 165 160 164 161 159 161 168 162 154 163 160 162 164 153 155 156 163 154 153 158 157 149 156 155 157 151 148 147 148 158 149 141 150 152 152 151 147 142 146 143 141 143 150 144 140 145 142 144 146 139 138 114 145 140 139 113 115 120 114 138 115 196 197 198 199 200 201 202 203 204 205 206 207 208 200 199 209 210 201 211 212 208 213 212 211 200 209 201 211 208 199 209 203 210 205 202 204 202 210 203 214 207 206 206 205 204 196 214 197 214 196 207 215 198 216 216 198 197 215 216 217 217 218 219 219 215 217 220 218 221 218 220 219 222 220 221 222 223 224 223 222 221 225 224 226 223 226 224 227 228 229 225 226 230 231 232 233 232 234 235 229 235 234 234 232 231 227 230 228 229 228 235 230 227 225

- -0.0625 -0.016 4.03886e-16 -0.0624198 -0.016 0.00316557 -0.0625 0.016 3.19189e-16 7.65404e-18 -0.016 -0.0625 7.65404e-18 0.016 -0.0625 0.00316557 0.016 -0.0624198 -0.0624198 0.016 0.00316557 -0.0621793 -0.016 0.00632302 -0.0617793 -0.016 0.00946424 -0.0621793 0.016 0.00632302 -0.0612206 -0.016 0.0125812 -0.0617793 0.016 0.00946424 -0.0612206 0.016 0.0125812 -0.0605048 -0.016 0.0156658 -0.0596337 -0.016 0.0187102 -0.0605048 0.016 0.0156658 -0.0586095 -0.016 0.0217066 -0.0596337 0.016 0.0187102 -0.0586095 0.016 0.0217066 -0.0574349 -0.016 0.0246472 -0.0561128 -0.016 0.0275246 -0.0574349 0.016 0.0246472 -0.0546467 -0.016 0.0303314 -0.0561128 0.016 0.0275246 -0.0546467 0.016 0.0303314 -0.0530403 -0.016 0.0330602 -0.0512977 -0.016 0.0357043 -0.0530403 0.016 0.0330602 -0.0494235 -0.016 0.0382566 -0.0512977 0.016 0.0357043 -0.0494235 0.016 0.0382566 -0.0474224 -0.016 0.0407108 -0.0452995 -0.016 0.0430604 -0.0474224 0.016 0.0407108 -0.0430604 -0.016 0.0452995 -0.0452995 0.016 0.0430604 -0.0430604 0.016 0.0452995 -0.0407108 -0.016 0.0474224 -0.0382566 -0.016 0.0494235 -0.0407108 0.016 0.0474224 -0.0357043 -0.016 0.0512977 -0.0382566 0.016 0.0494235 -0.0357043 0.016 0.0512977 -0.0330602 -0.016 0.0530403 -0.0303314 -0.016 0.0546467 -0.0330602 0.016 0.0530403 -0.0275246 -0.016 0.0561128 -0.0303314 0.016 0.0546467 -0.0275246 0.016 0.0561128 -0.0246472 -0.016 0.0574349 -0.0217066 -0.016 0.0586095 -0.0246472 0.016 0.0574349 -0.0187102 -0.016 0.0596337 -0.0217066 0.016 0.0586095 -0.0187102 0.016 0.0596337 -0.0156658 -0.016 0.0605048 -0.0125812 -0.016 0.0612206 -0.0156658 0.016 0.0605048 -0.00946424 -0.016 0.0617793 -0.0125812 0.016 0.0612206 -0.00946424 0.016 0.0617793 -0.00632302 -0.016 0.0621793 -0.00316557 -0.016 0.0624198 -0.00632302 0.016 0.0621793 -1.53081e-17 -0.016 0.0625 -0.00316557 0.016 0.0624198 -1.53081e-17 0.016 0.0625 -0.0624198 0.016 -0.00316557 -0.0621793 0.016 -0.00632302 -0.0624198 -0.016 -0.00316557 -0.0617793 0.016 -0.00946424 -0.0621793 -0.016 -0.00632302 -0.0617793 -0.016 -0.00946424 -0.0612206 0.016 -0.0125812 -0.0605048 0.016 -0.0156658 -0.0612206 -0.016 -0.0125812 -0.0596337 0.016 -0.0187102 -0.0605048 -0.016 -0.0156658 -0.0596337 -0.016 -0.0187102 -0.0586095 0.016 -0.0217066 -0.0574349 0.016 -0.0246472 -0.0586095 -0.016 -0.0217066 -0.0561128 0.016 -0.0275246 -0.0574349 -0.016 -0.0246472 -0.0561128 -0.016 -0.0275246 -0.0546467 0.016 -0.0303314 -0.0530403 0.016 -0.0330602 -0.0546467 -0.016 -0.0303314 -0.0512977 0.016 -0.0357043 -0.0530403 -0.016 -0.0330602 -0.0512977 -0.016 -0.0357043 -0.0494235 0.016 -0.0382566 -0.0474224 0.016 -0.0407108 -0.0494235 -0.016 -0.0382566 -0.0452995 0.016 -0.0430604 -0.0474224 -0.016 -0.0407108 -0.0452995 -0.016 -0.0430604 -0.0430604 0.016 -0.0452995 -0.0407108 0.016 -0.0474224 -0.0430604 -0.016 -0.0452995 -0.0382566 0.016 -0.0494235 -0.0407108 -0.016 -0.0474224 -0.0382566 -0.016 -0.0494235 -0.0357043 0.016 -0.0512977 -0.0330602 0.016 -0.0530403 -0.0357043 -0.016 -0.0512977 -0.0303314 0.016 -0.0546467 -0.0330602 -0.016 -0.0530403 -0.0303314 -0.016 -0.0546467 -0.0275246 0.016 -0.0561128 -0.0246472 0.016 -0.0574349 -0.0275246 -0.016 -0.0561128 -0.0217066 0.016 -0.0586095 -0.0246472 -0.016 -0.0574349 -0.0217066 -0.016 -0.0586095 -0.0187102 0.016 -0.0596337 -0.0156658 0.016 -0.0605048 -0.0187102 -0.016 -0.0596337 -0.0125812 0.016 -0.0612206 -0.0156658 -0.016 -0.0605048 -0.0125812 -0.016 -0.0612206 -0.00946424 0.016 -0.0617793 -0.00632302 0.016 -0.0621793 -0.00946424 -0.016 -0.0617793 -0.00316557 0.016 -0.0624198 -0.00632302 -0.016 -0.0621793 -0.00316557 -0.016 -0.0624198 0.00632302 -0.016 -0.0621793 0.00316557 -0.016 -0.0624198 0.00632302 0.016 -0.0621793 0.0156658 -0.016 -0.0605048 0.0125812 -0.016 -0.0612206 0.0156658 0.016 -0.0605048 0.00946424 -0.016 -0.0617793 0.00946424 0.016 -0.0617793 0.0125812 0.016 -0.0612206 0.0217066 -0.016 -0.0586095 0.0246472 0.016 -0.0574349 0.0246472 -0.016 -0.0574349 0.0187102 0.016 -0.0596337 0.0217066 0.016 -0.0586095 0.0187102 -0.016 -0.0596337 0.0330602 0.016 -0.0530403 0.0330602 -0.016 -0.0530403 0.0303314 -0.016 -0.0546467 0.0303314 0.016 -0.0546467 0.0275246 -0.016 -0.0561128 0.0275246 0.016 -0.0561128 0.0407108 -0.016 -0.0474224 0.0382566 -0.016 -0.0494235 0.0407108 0.016 -0.0474224 0.0357043 -0.016 -0.0512977 0.0357043 0.016 -0.0512977 0.0382566 0.016 -0.0494235 0.0452995 -0.016 -0.0430604 0.0474224 0.016 -0.0407108 0.0474224 -0.016 -0.0407108 0.0430604 0.016 -0.0452995 0.0452995 0.016 -0.0430604 0.0430604 -0.016 -0.0452995 0.0530403 0.016 -0.0330602 0.0530403 -0.016 -0.0330602 0.0512977 -0.016 -0.0357043 0.0512977 0.016 -0.0357043 0.0494235 -0.016 -0.0382566 0.0494235 0.016 -0.0382566 0.0574349 -0.016 -0.0246472 0.0561128 -0.016 -0.0275246 0.0574349 0.016 -0.0246472 0.0546467 -0.016 -0.0303314 0.0546467 0.016 -0.0303314 0.0561128 0.016 -0.0275246 0.0596337 -0.016 -0.0187102 0.0605048 0.016 -0.0156658 0.0605048 -0.016 -0.0156658 0.0586095 0.016 -0.0217066 0.0596337 0.016 -0.0187102 0.0586095 -0.016 -0.0217066 0.0621793 0.016 -0.00632302 0.0621793 -0.016 -0.00632302 0.0617793 -0.016 -0.00946424 0.0617793 0.016 -0.00946424 0.0612206 -0.016 -0.0125812 0.0612206 0.016 -0.0125812 0.0624198 -0.016 0.00316557 0.0625 -0.016 1.57772e-33 0.0624198 0.016 0.00316557 0.0624198 -0.016 -0.00316557 0.0624198 0.016 -0.00316557 0.0625 0.016 1.57772e-33 0.0617793 -0.016 0.00946424 0.0612206 0.016 0.0125812 0.0612206 -0.016 0.0125812 0.0621793 0.016 0.00632302 0.0617793 0.016 0.00946424 0.0621793 -0.016 0.00632302 0.0586095 0.016 0.0217066 0.0586095 -0.016 0.0217066 0.0596337 -0.016 0.0187102 0.0596337 0.016 0.0187102 0.0605048 -0.016 0.0156658 0.0605048 0.016 0.0156658 0.0546467 -0.016 0.0303314 0.0561128 -0.016 0.0275246 0.0546467 0.016 0.0303314 0.0574349 -0.016 0.0246472 0.0574349 0.016 0.0246472 0.0561128 0.016 0.0275246 0.0512977 -0.016 0.0357043 0.0494235 0.016 0.0382566 0.0494235 -0.016 0.0382566 0.0530403 0.016 0.0330602 0.0512977 0.016 0.0357043 0.0530403 -0.016 0.0330602 0.0430604 0.016 0.0452995 0.0430604 -0.016 0.0452995 0.0452995 -0.016 0.0430604 0.0452995 0.016 0.0430604 0.0474224 -0.016 0.0407108 0.0474224 0.016 0.0407108 0.0407108 0.016 0.0474224 0.0407108 -0.016 0.0474224 0.0382566 -0.016 0.0494235 0.0382566 0.016 0.0494235 0.0357043 0.016 0.0512977 0.0357043 -0.016 0.0512977 0.0330602 0.016 0.0530403 0.0330602 -0.016 0.0530403 0.0303314 -0.016 0.0546467 0.0303314 0.016 0.0546467 0.0275246 0.016 0.0561128 0.0275246 -0.016 0.0561128 0.0246472 0.016 0.0574349 0.0246472 -0.016 0.0574349 0.0217066 -0.016 0.0586095 0.0217066 0.016 0.0586095 0.0187102 0.016 0.0596337 0.0187102 -0.016 0.0596337 0.0156658 0.016 0.0605048 0.0156658 -0.016 0.0605048 0.0125812 -0.016 0.0612206 0.0125812 0.016 0.0612206 0.00946424 0.016 0.0617793 0.00946424 -0.016 0.0617793 0.00632302 0.016 0.0621793 0.00632302 -0.016 0.0621793 0.00316557 -0.016 0.0624198 0.00316557 0.016 0.0624198 0.0561128 -0.016 -0.0275246 0.00328892 -0.016 -0.00119707 0.00303109 -0.016 -0.00175 0.00632302 -0.016 0.0621793 0.000607769 -0.016 0.00344683 0.00946424 -0.016 0.0617793 0.0605048 -0.016 -0.0156658 0.00344683 -0.016 -0.000607769 -0.00268116 -0.016 0.00224976 -0.0512977 -0.016 0.0357043 -0.00303109 -0.016 0.00175 0.0035 -0.016 4.31441e-18 0.0621793 -0.016 -0.00632302 0.0624198 -0.016 -0.00316557 -0.0452995 -0.016 0.0430604 -0.0474224 -0.016 0.0407108 0.0617793 -0.016 0.00946424 0.00344683 -0.016 0.000607769 0.0621793 -0.016 0.00632302 -0.00224976 -0.016 0.00268116 -0.0382566 -0.016 0.0494235 -0.0407108 -0.016 0.0474224 0.00328892 -0.016 0.00119707 0.0605048 -0.016 0.0156658 0.0596337 -0.016 0.0187102 -0.00175 -0.016 0.00303109 -0.0303314 -0.016 0.0546467 -0.0330602 -0.016 0.0530403 0.0561128 -0.016 0.0275246 0.0546467 -0.016 0.0303314 0.00303109 -0.016 0.00175 -0.0246472 -0.016 0.0574349 -0.00119707 -0.016 0.00328892 -0.0217066 -0.016 0.0586095 0.0512977 -0.016 0.0357043 0.00268116 -0.016 0.00224976 -0.000607769 -0.016 0.00344683 -0.0125812 -0.016 0.0612206 -0.0156658 -0.016 0.0605048 0.0452995 -0.016 0.0430604 0.00224976 -0.016 0.00268116 0 -0.016 0.0035 -0.00316557 -0.016 0.0624198 -0.00632302 -0.016 0.0621793 0.0357043 -0.016 0.0512977 0.0382566 -0.016 0.0494235 0.00316557 -0.016 0.0624198 0.0187102 -0.016 0.0596337 0.00119707 -0.016 0.00328892 0.0217066 -0.016 0.0586095 0.0156658 -0.016 0.0605048 0.0246472 -0.016 0.0574349 0.00175 -0.016 0.00303109 0.0275246 -0.016 0.0561128 0.0303314 -0.016 0.0546467 0.0330602 -0.016 0.0530403 0.0407108 -0.016 0.0474224 0.0125812 -0.016 0.0612206 -1.53081e-17 -0.016 0.0625 0.0430604 -0.016 0.0452995 0.0494235 -0.016 0.0382566 0.0474224 -0.016 0.0407108 -0.00946424 -0.016 0.0617793 0.0530403 -0.016 0.0330602 -0.0187102 -0.016 0.0596337 0.0586095 -0.016 0.0217066 0.0574349 -0.016 0.0246472 -0.0275246 -0.016 0.0561128 0.0612206 -0.016 0.0125812 -0.0357043 -0.016 0.0512977 0.0625 -0.016 1.57772e-33 0.0624198 -0.016 0.00316557 -0.0430604 -0.016 0.0452995 0.0617793 -0.016 -0.00946424 0.0612206 -0.016 -0.0125812 -0.0494235 -0.016 0.0382566 0.0574349 -0.016 -0.0246472 0.0586095 -0.016 -0.0217066 0.0596337 -0.016 -0.0187102 -0.0546467 -0.016 0.0303314 -0.0561128 -0.016 0.0275246 -0.0530403 -0.016 0.0330602 -0.00328892 -0.016 0.00119707 0.0546467 -0.016 -0.0303314 0.0512977 -0.016 -0.0357043 0.0530403 -0.016 -0.0330602 0.00268116 -0.016 -0.00224976 0.0474224 -0.016 -0.0407108 0.0494235 -0.016 -0.0382566 -0.0586095 -0.016 0.0217066 -0.0596337 -0.016 0.0187102 0.0452995 -0.016 -0.0430604 0.00224976 -0.016 -0.00268116 -0.0605048 -0.016 0.0156658 0.0430604 -0.016 -0.0452995 -0.00344683 -0.016 0.000607769 0.0407108 -0.016 -0.0474224 0.0382566 -0.016 -0.0494235 -0.0612206 -0.016 0.0125812 -0.0617793 -0.016 0.00946424 0.00175 -0.016 -0.00303109 0.0357043 -0.016 -0.0512977 -0.0621793 -0.016 0.00632302 0.0330602 -0.016 -0.0530403 -0.0035 -0.016 -3.53725e-18 -0.0624198 -0.016 0.00316557 -0.0625 -0.016 4.03886e-16 -0.0624198 -0.016 -0.00316557 0.0275246 -0.016 -0.0561128 0.0303314 -0.016 -0.0546467 -0.00344683 -0.016 -0.000607769 0.00119707 -0.016 -0.00328892 -0.0617793 -0.016 -0.00946424 -0.0621793 -0.016 -0.00632302 0.0246472 -0.016 -0.0574349 0.0217066 -0.016 -0.0586095 -0.0612206 -0.016 -0.0125812 0.0187102 -0.016 -0.0596337 -0.0605048 -0.016 -0.0156658 0.000607769 -0.016 -0.00344683 0.0156658 -0.016 -0.0605048 -0.00328892 -0.016 -0.00119707 0.00946424 -0.016 -0.0617793 0.0125812 -0.016 -0.0612206 0.00632302 -0.016 -0.0621793 -0.0586095 -0.016 -0.0217066 -0.0574349 -0.016 -0.0246472 0.00316557 -0.016 -0.0624198 -1.12569e-18 -0.016 -0.0035 -0.00303109 -0.016 -0.00175 7.65404e-18 -0.016 -0.0625 -0.0546467 -0.016 -0.0303314 -0.0530403 -0.016 -0.0330602 -0.00316557 -0.016 -0.0624198 -0.000607769 -0.016 -0.00344683 -0.00268116 -0.016 -0.00224976 -0.0512977 -0.016 -0.0357043 -0.0494235 -0.016 -0.0382566 -0.0125812 -0.016 -0.0612206 -0.00946424 -0.016 -0.0617793 -0.0452995 -0.016 -0.0430604 -0.00224976 -0.016 -0.00268116 -0.0156658 -0.016 -0.0605048 -0.00119707 -0.016 -0.00328892 -0.0187102 -0.016 -0.0596337 -0.0407108 -0.016 -0.0474224 -0.0382566 -0.016 -0.0494235 -0.00175 -0.016 -0.00303109 -0.0246472 -0.016 -0.0574349 -0.0357043 -0.016 -0.0512977 -0.0303314 -0.016 -0.0546467 -0.0330602 -0.016 -0.0530403 -0.0275246 -0.016 -0.0561128 -0.0430604 -0.016 -0.0452995 -0.0217066 -0.016 -0.0586095 -0.0474224 -0.016 -0.0407108 -0.00632302 -0.016 -0.0621793 -0.0561128 -0.016 -0.0275246 -0.0574349 -0.016 0.0246472 -0.0596337 -0.016 -0.0187102 0.0605048 0.016 -0.0156658 0.0596337 0.016 -0.0187102 0.00328892 0.016 -0.00119707 0.0217066 0.016 0.0586095 0.0246472 0.016 0.0574349 0.00119707 0.016 0.00328892 0.00344683 0.016 -0.000607769 0.0621793 0.016 -0.00632302 0.0617793 0.016 -0.00946424 -0.0430604 0.016 0.0452995 -0.00224976 0.016 0.00268116 -0.0452995 0.016 0.0430604 0.0035 0.016 -1.58917e-17 0.0624198 0.016 0.00316557 0.0625 0.016 1.57772e-33 -0.0330602 0.016 0.0530403 -0.00175 0.016 0.00303109 -0.0357043 0.016 0.0512977 0.00344683 0.016 0.000607769 0.0612206 0.016 0.0125812 0.0617793 0.016 0.00946424 -0.0217066 0.016 0.0586095 -0.00119707 0.016 0.00328892 -0.0246472 0.016 0.0574349 0.0586095 0.016 0.0217066 0.0596337 0.016 0.0187102 0.00328892 0.016 0.00119707 -0.00946424 0.016 0.0617793 -0.000607769 0.016 0.00344683 -0.0125812 0.016 0.0612206 0.00303109 0.016 0.00175 0.0561128 0.016 0.0275246 0.0574349 0.016 0.0246472 -1.53081e-17 0.016 0.0625 0 0.016 0.0035 -0.00316557 0.016 0.0624198 0.0530403 0.016 0.0330602 0.0512977 0.016 0.0357043 0.000607769 0.016 0.00344683 0.00316557 0.016 0.0624198 0.00632302 0.016 0.0621793 0.0494235 0.016 0.0382566 0.00268116 0.016 0.00224976 0.0474224 0.016 0.0407108 0.0156658 0.016 0.0605048 0.0125812 0.016 0.0612206 0.0452995 0.016 0.0430604 0.00224976 0.016 0.00268116 0.0430604 0.016 0.0452995 0.0187102 0.016 0.0596337 0.0330602 0.016 0.0530403 0.00175 0.016 0.00303109 0.0303314 0.016 0.0546467 0.0275246 0.016 0.0561128 0.0357043 0.016 0.0512977 0.0382566 0.016 0.0494235 0.0407108 0.016 0.0474224 0.00946424 0.016 0.0617793 0.0546467 0.016 0.0303314 -0.00632302 0.016 0.0621793 0.0605048 0.016 0.0156658 -0.0187102 0.016 0.0596337 -0.0156658 0.016 0.0605048 0.0621793 0.016 0.00632302 -0.0303314 0.016 0.0546467 -0.0275246 0.016 0.0561128 0.0624198 0.016 -0.00316557 -0.0407108 0.016 0.0474224 -0.0382566 0.016 0.0494235 0.0612206 0.016 -0.0125812 -0.0494235 0.016 0.0382566 -0.0474224 0.016 0.0407108 -0.00268116 0.016 0.00224976 -0.0512977 0.016 0.0357043 -0.00303109 0.016 0.00175 -0.0530403 0.016 0.0330602 0.00303109 0.016 -0.00175 0.0561128 0.016 -0.0275246 0.0546467 0.016 -0.0303314 -0.0561128 0.016 0.0275246 -0.0546467 0.016 0.0303314 0.0530403 0.016 -0.0330602 -0.00328892 0.016 0.00119707 0.00268116 0.016 -0.00224976 0.0512977 0.016 -0.0357043 -0.0586095 0.016 0.0217066 -0.0574349 0.016 0.0246472 0.0494235 0.016 -0.0382566 -0.0605048 0.016 0.0156658 -0.0596337 0.016 0.0187102 0.0474224 0.016 -0.0407108 -0.00344683 0.016 0.000607769 0.0452995 0.016 -0.0430604 -0.0612206 0.016 0.0125812 -0.0617793 0.016 0.00946424 -0.0621793 0.016 0.00632302 -0.0035 0.016 5.78862e-18 -0.0624198 0.016 0.00316557 0.0430604 0.016 -0.0452995 0.00224976 0.016 -0.00268116 -0.0625 0.016 3.19189e-16 0.0407108 0.016 -0.0474224 -0.0624198 0.016 -0.00316557 -0.00344683 0.016 -0.000607769 0.0382566 0.016 -0.0494235 -0.0621793 0.016 -0.00632302 -0.0617793 0.016 -0.00946424 0.0357043 0.016 -0.0512977 0.00175 0.016 -0.00303109 -0.0612206 0.016 -0.0125812 0.0330602 0.016 -0.0530403 -0.00328892 0.016 -0.00119707 -0.0605048 0.016 -0.0156658 0.0303314 0.016 -0.0546467 -0.0596337 0.016 -0.0187102 0.0275246 0.016 -0.0561128 -0.0586095 0.016 -0.0217066 -0.0574349 0.016 -0.0246472 0.0246472 0.016 -0.0574349 0.00119707 0.016 -0.00328892 -0.00303109 0.016 -0.00175 0.0217066 0.016 -0.0586095 -0.0512977 0.016 -0.0357043 -0.0530403 0.016 -0.0330602 0.0156658 0.016 -0.0605048 0.000607769 0.016 -0.00344683 -0.0452995 0.016 -0.0430604 -0.0474224 0.016 -0.0407108 -0.00268116 0.016 -0.00224976 0.00632302 0.016 -0.0621793 0.00946424 0.016 -0.0617793 -0.0407108 0.016 -0.0474224 -0.00224976 0.016 -0.00268116 -0.0382566 0.016 -0.0494235 -0.00316557 0.016 -0.0624198 -1.20059e-17 0.016 -0.0035 7.65404e-18 0.016 -0.0625 -0.0330602 0.016 -0.0530403 -0.00175 0.016 -0.00303109 -0.0303314 0.016 -0.0546467 -0.0125812 0.016 -0.0612206 -0.000607769 0.016 -0.00344683 -0.00946424 0.016 -0.0617793 -0.0275246 0.016 -0.0561128 -0.0246472 0.016 -0.0574349 -0.00119707 0.016 -0.00328892 -0.0187102 0.016 -0.0596337 -0.0217066 0.016 -0.0586095 -0.0156658 0.016 -0.0605048 -0.0357043 0.016 -0.0512977 -0.00632302 0.016 -0.0621793 -0.0430604 0.016 -0.0452995 0.00316557 0.016 -0.0624198 -0.0494235 0.016 -0.0382566 0.0125812 0.016 -0.0612206 -0.0546467 0.016 -0.0303314 -0.0561128 0.016 -0.0275246 0.0187102 0.016 -0.0596337 0.0586095 0.016 -0.0217066 0.0574349 0.016 -0.0246472 -0.0035 0.016 5.78862e-18 -0.00344683 -0.016 0.000607769 -0.0035 -0.016 -3.53725e-18 -1.12569e-18 -0.016 -0.0035 0.000607769 0.016 -0.00344683 -1.20059e-17 0.016 -0.0035 -0.00328892 -0.016 0.00119707 -0.00344683 0.016 0.000607769 -0.00328892 0.016 0.00119707 -0.00303109 -0.016 0.00175 -0.00303109 0.016 0.00175 -0.00268116 -0.016 0.00224976 -0.00224976 -0.016 0.00268116 -0.00268116 0.016 0.00224976 -0.00224976 0.016 0.00268116 -0.00175 -0.016 0.00303109 -0.00175 0.016 0.00303109 -0.00119707 -0.016 0.00328892 -0.000607769 -0.016 0.00344683 -0.00119707 0.016 0.00328892 -0.000607769 0.016 0.00344683 0 -0.016 0.0035 0 0.016 0.0035 -0.00344683 0.016 -0.000607769 -0.00344683 -0.016 -0.000607769 -0.00328892 0.016 -0.00119707 -0.00328892 -0.016 -0.00119707 -0.00303109 0.016 -0.00175 -0.00268116 0.016 -0.00224976 -0.00303109 -0.016 -0.00175 -0.00268116 -0.016 -0.00224976 -0.00224976 0.016 -0.00268116 -0.00224976 -0.016 -0.00268116 -0.00175 0.016 -0.00303109 -0.00119707 0.016 -0.00328892 -0.00175 -0.016 -0.00303109 -0.00119707 -0.016 -0.00328892 -0.000607769 0.016 -0.00344683 -0.000607769 -0.016 -0.00344683 0.00119707 -0.016 -0.00328892 0.00119707 0.016 -0.00328892 0.000607769 -0.016 -0.00344683 0.00268116 -0.016 -0.00224976 0.00268116 0.016 -0.00224976 0.00224976 -0.016 -0.00268116 0.00175 -0.016 -0.00303109 0.00224976 0.016 -0.00268116 0.00175 0.016 -0.00303109 0.00328892 -0.016 -0.00119707 0.00344683 -0.016 -0.000607769 0.00344683 0.016 -0.000607769 0.00303109 0.016 -0.00175 0.00303109 -0.016 -0.00175 0.00328892 0.016 -0.00119707 0.00328892 0.016 0.00119707 0.00344683 -0.016 0.000607769 0.00328892 -0.016 0.00119707 0.00344683 0.016 0.000607769 0.0035 0.016 -1.58917e-17 0.0035 -0.016 4.31441e-18 0.00224976 -0.016 0.00268116 0.00224976 0.016 0.00268116 0.00268116 -0.016 0.00224976 0.00303109 -0.016 0.00175 0.00268116 0.016 0.00224976 0.00303109 0.016 0.00175 0.00175 0.016 0.00303109 0.00175 -0.016 0.00303109 0.00119707 -0.016 0.00328892 0.00119707 0.016 0.00328892 0.000607769 -0.016 0.00344683 0.000607769 0.016 0.00344683 + -0.0622865 0.016 -0.00516121 -0.0622865 -0.016 0.00516121 -0.0622865 0.016 0.00516121 7.65404e-18 -0.016 -0.0625 7.65404e-18 0.016 -0.0625 0.0102872 0.016 -0.0616476 -0.0605875 0.016 0.0153428 -0.0605875 -0.016 0.0153428 -0.0572358 -0.016 0.025106 -0.0572358 0.016 0.025106 -0.0523229 -0.016 0.0341843 -0.0523229 0.016 0.0341843 -0.0459827 0.016 0.0423301 -0.0459827 -0.016 0.0423301 -0.0383883 -0.016 0.0493213 -0.0383883 0.016 0.0493213 -0.0297467 -0.016 0.0549671 -0.0297467 0.016 0.0549671 -0.0202937 0.016 0.0591136 -0.0202937 -0.016 0.0591136 -0.0102872 -0.016 0.0616476 -0.0102872 0.016 0.0616476 -1.53081e-17 -0.016 0.0625 -1.53081e-17 0.016 0.0625 -0.0622865 -0.016 -0.00516121 -0.0605875 0.016 -0.0153428 -0.0605875 -0.016 -0.0153428 -0.0572358 0.016 -0.025106 -0.0572358 -0.016 -0.025106 -0.0523229 -0.016 -0.0341843 -0.0523229 0.016 -0.0341843 -0.0459827 0.016 -0.0423301 -0.0459827 -0.016 -0.0423301 -0.0383883 0.016 -0.0493213 -0.0383883 -0.016 -0.0493213 -0.0297467 -0.016 -0.0549671 -0.0297467 0.016 -0.0549671 -0.0202937 0.016 -0.0591136 -0.0202937 -0.016 -0.0591136 -0.0102872 0.016 -0.0616476 -0.0102872 -0.016 -0.0616476 0.0202937 -0.016 -0.0591136 0.0102872 -0.016 -0.0616476 0.0202937 0.016 -0.0591136 0.0459827 -0.016 -0.0423301 0.0383883 -0.016 -0.0493213 0.0459827 0.016 -0.0423301 0.0297467 -0.016 -0.0549671 0.0297467 0.016 -0.0549671 0.0383883 0.016 -0.0493213 0.0572358 -0.016 -0.025106 0.0605875 0.016 -0.0153428 0.0605875 -0.016 -0.0153428 0.0523229 0.016 -0.0341843 0.0572358 0.016 -0.025106 0.0523229 -0.016 -0.0341843 0.0605875 0.016 0.0153428 0.0605875 -0.016 0.0153428 0.0622865 -0.016 0.00516121 0.0622865 0.016 0.00516121 0.0622865 -0.016 -0.00516121 0.0622865 0.016 -0.00516121 0.0459827 -0.016 0.0423301 0.0523229 -0.016 0.0341843 0.0459827 0.016 0.0423301 0.0572358 -0.016 0.025106 0.0572358 0.016 0.025106 0.0523229 0.016 0.0341843 0.0297467 0.016 0.0549671 0.0383883 -0.016 0.0493213 0.0383883 0.016 0.0493213 0.0202937 0.016 0.0591136 0.0297467 -0.016 0.0549671 0.0202937 -0.016 0.0591136 0.0102872 0.016 0.0616476 0.0102872 -0.016 0.0616476 0.0572358 -0.016 0.025106 0.0523229 -0.016 0.0341843 0.00293008 -0.016 0.00191432 0.0297467 -0.016 0.0549671 0.00214974 -0.016 0.00276199 0.0383883 -0.016 0.0493213 0.0202937 -0.016 0.0591136 0.00166582 -0.016 0.00307816 -0.0383883 -0.016 0.0493213 -0.00166582 -0.016 0.00307816 -0.0297467 -0.016 0.0549671 0.000576081 -0.016 0.00345226 0.0102872 -0.016 0.0616476 -1.53081e-17 -0.016 0.0625 0 -0.016 0.0035 -0.0102872 -0.016 0.0616476 -0.0202937 -0.016 0.0591136 -0.000576081 -0.016 0.00345226 0.00113645 -0.016 0.00331036 0.0459827 -0.016 0.0423301 0.00257503 -0.016 0.00237049 -0.00113645 -0.016 0.00331036 -0.00214974 -0.016 0.00276199 -0.00257503 -0.016 0.00237049 0.00320521 -0.016 0.00140593 0.0033929 -0.016 0.000859199 0.0605875 -0.016 0.0153428 -0.0459827 -0.016 0.0423301 -0.00293008 -0.016 0.00191432 0.0622865 -0.016 -0.00516121 0.0622865 -0.016 0.00516121 0.00348805 -0.016 0.000289028 -0.0523229 -0.016 0.0341843 -0.00320521 -0.016 0.00140593 0.00348805 -0.016 -0.000289028 0.0033929 -0.016 -0.000859199 0.0605875 -0.016 -0.0153428 -0.0033929 -0.016 0.000859199 -0.0572358 -0.016 0.025106 -0.0605875 -0.016 0.0153428 -0.00348805 -0.016 0.000289028 -0.0622865 -0.016 0.00516121 -0.00348805 -0.016 -0.000289028 0.0297467 -0.016 -0.0549671 0.0383883 -0.016 -0.0493213 0.00166582 -0.016 -0.00307816 -0.0622865 -0.016 -0.00516121 -0.0033929 -0.016 -0.000859199 -0.00320521 -0.016 -0.00140593 -0.0605875 -0.016 -0.0153428 -0.0572358 -0.016 -0.025106 -0.00293008 -0.016 -0.00191432 0.00113645 -0.016 -0.00331036 0.000576081 -0.016 -0.00345226 0.0202937 -0.016 -0.0591136 -0.0523229 -0.016 -0.0341843 -0.0459827 -0.016 -0.0423301 -1.12569e-18 -0.016 -0.0035 7.65404e-18 -0.016 -0.0625 0.0102872 -0.016 -0.0616476 -0.0102872 -0.016 -0.0616476 -0.000576081 -0.016 -0.00345226 -0.00113645 -0.016 -0.00331036 -0.00166582 -0.016 -0.00307816 -0.0297467 -0.016 -0.0549671 -0.0202937 -0.016 -0.0591136 -0.00214974 -0.016 -0.00276199 -0.00257503 -0.016 -0.00237049 -0.0383883 -0.016 -0.0493213 0.00257503 -0.016 -0.00237049 0.0459827 -0.016 -0.0423301 0.00320521 -0.016 -0.00140593 0.0523229 -0.016 -0.0341843 0.0572358 -0.016 -0.025106 0.00293008 -0.016 -0.00191432 0.00214974 -0.016 -0.00276199 0.00298035 0.016 0.00183508 0.00262735 0.016 0.00231236 0.0523229 0.016 0.0341843 0.00219877 0.016 0.00272313 0.0383883 0.016 0.0493213 0.0459827 0.016 0.0423301 0.00170693 0.016 0.00305555 0.000591503 0.016 0.00344966 -1.53081e-17 0.016 0.0625 0.0102872 0.016 0.0616476 0.0297467 0.016 0.0549671 0.0202937 0.016 0.0591136 0.00116599 0.016 0.00330007 0 0.016 0.0035 0.00324761 0.016 0.001305 0.0572358 0.016 0.025106 -0.0102872 0.016 0.0616476 0.00342144 0.016 0.000737377 0.0605875 0.016 0.0153428 -0.000591503 0.016 0.00344966 -0.00116599 0.016 0.00330007 -0.0202937 0.016 0.0591136 0.00349685 0.016 0.000148544 0.0622865 0.016 0.00516121 -0.00170693 0.016 0.00305555 -0.0383883 0.016 0.0493213 -0.0297467 0.016 0.0549671 -0.00298035 0.016 0.00183508 -0.0572358 0.016 0.025106 -0.0523229 0.016 0.0341843 0.0605875 0.016 -0.0153428 0.00334658 0.016 -0.00102488 0.00347165 0.016 -0.000444562 0.00312524 0.016 -0.00157571 0.0572358 0.016 -0.025106 -0.00324761 0.016 0.001305 -0.00342144 0.016 0.000737377 -0.0605875 0.016 0.0153428 -0.00349685 0.016 0.000148544 -0.0622865 0.016 -0.00516121 -0.0622865 0.016 0.00516121 -0.00347165 0.016 -0.000444562 -0.00334658 0.016 -0.00102488 -0.0605875 0.016 -0.0153428 0.00281399 0.016 -0.00208122 0.0523229 0.016 -0.0341843 -0.00312524 0.016 -0.00157571 -0.0523229 0.016 -0.0341843 -0.0572358 0.016 -0.025106 0.00242179 0.016 -0.00252685 0.0459827 0.016 -0.0423301 0.00144165 0.016 -0.0031893 0.0202937 0.016 -0.0591136 0.000881923 0.016 -0.00338707 -0.00242179 0.016 -0.00252685 -0.0459827 0.016 -0.0423301 -0.00281399 0.016 -0.00208122 7.65404e-18 0.016 -0.0625 -0.0102872 0.016 -0.0616476 -0.000296821 0.016 -0.00348739 -0.0202937 0.016 -0.0591136 -0.000881923 0.016 -0.00338707 0.0102872 0.016 -0.0616476 0.000296821 0.016 -0.00348739 -0.0383883 0.016 -0.0493213 -0.00195991 0.016 -0.00289978 -0.0297467 0.016 -0.0549671 -0.00144165 0.016 -0.0031893 0.0383883 0.016 -0.0493213 0.00195991 0.016 -0.00289978 0.0297467 0.016 -0.0549671 0.0622865 0.016 -0.00516121 -0.00219877 0.016 0.00272313 -0.00262735 0.016 0.00231236 -0.0459827 0.016 0.0423301 -0.00349685 0.016 0.000148544 -0.00348805 -0.016 0.000289028 -0.00348805 -0.016 -0.000289028 0.000296821 0.016 -0.00348739 -0.000296821 0.016 -0.00348739 -1.12569e-18 -0.016 -0.0035 -0.0033929 -0.016 0.000859199 -0.00342144 0.016 0.000737377 -0.00324761 0.016 0.001305 -0.00320521 -0.016 0.00140593 -0.00298035 0.016 0.00183508 -0.00293008 -0.016 0.00191432 -0.00257503 -0.016 0.00237049 -0.00262735 0.016 0.00231236 -0.00219877 0.016 0.00272313 -0.00214974 -0.016 0.00276199 -0.00170693 0.016 0.00305555 -0.00166582 -0.016 0.00307816 -0.00113645 -0.016 0.00331036 -0.00116599 0.016 0.00330007 -0.000591503 0.016 0.00344966 -0.000576081 -0.016 0.00345226 0 0.016 0.0035 0 -0.016 0.0035 -0.00347165 0.016 -0.000444562 -0.0033929 -0.016 -0.000859199 -0.00334658 0.016 -0.00102488 -0.00320521 -0.016 -0.00140593 -0.00312524 0.016 -0.00157571 -0.00281399 0.016 -0.00208122 -0.00293008 -0.016 -0.00191432 -0.00257503 -0.016 -0.00237049 -0.00242179 0.016 -0.00252685 -0.00214974 -0.016 -0.00276199 -0.00195991 0.016 -0.00289978 -0.00144165 0.016 -0.0031893 -0.00166582 -0.016 -0.00307816 -0.00113645 -0.016 -0.00331036 -0.000881923 0.016 -0.00338707 -0.000576081 -0.016 -0.00345226 0.00195991 0.016 -0.00289978 0.00144165 0.016 -0.0031893 0.00166582 -0.016 -0.00307816 0.000881923 0.016 -0.00338707 0.000576081 -0.016 -0.00345226 0.00113645 -0.016 -0.00331036 0.00293008 -0.016 -0.00191432 0.00312524 0.016 -0.00157571 0.00281399 0.016 -0.00208122 0.00214974 -0.016 -0.00276199 0.00257503 -0.016 -0.00237049 0.00242179 0.016 -0.00252685 0.00347165 0.016 -0.000444562 0.00348805 -0.016 -0.000289028 0.00349685 0.016 0.000148544 0.00334658 0.016 -0.00102488 0.00320521 -0.016 -0.00140593 0.0033929 -0.016 -0.000859199 0.00298035 0.016 0.00183508 0.00324761 0.016 0.001305 0.00320521 -0.016 0.00140593 0.0033929 -0.016 0.000859199 0.00342144 0.016 0.000737377 0.00348805 -0.016 0.000289028 0.00214974 -0.016 0.00276199 0.00219877 0.016 0.00272313 0.00257503 -0.016 0.00237049 0.00293008 -0.016 0.00191432 0.00262735 0.016 0.00231236 0.00170693 0.016 0.00305555 0.00166582 -0.016 0.00307816 0.00113645 -0.016 0.00331036 0.00116599 0.016 0.00330007 0.000576081 -0.016 0.00345226 0.000591503 0.016 0.00344966 - + @@ -110,9 +110,9 @@ - -1 0 1.19249e-08 -0.998717 0 0.050649 -1 0 1.19249e-08 -8.74228e-08 0 -1 -8.74228e-08 0 -1 0.0506491 0 -0.998717 -0.998716 0 0.0506494 -0.994869 0 0.101168 -0.988468 0 0.151428 -0.994869 0 0.101168 -0.97953 0 0.201299 -0.988468 0 0.151428 -0.97953 0 0.201299 -0.968077 0 0.250653 -0.954139 0 0.299363 -0.968077 0 0.250652 -0.937752 0 0.347305 -0.954139 0 0.299363 -0.937752 0 0.347306 -0.918958 0 0.394356 -0.897805 0 0.440394 -0.918958 0 0.394356 -0.874347 0 0.485302 -0.897805 0 0.440394 -0.874347 0 0.485302 -0.848644 0 0.528964 -0.820763 0 0.571268 -0.848644 0 0.528964 -0.790776 0 0.612106 -0.820763 0 0.571268 -0.790776 0 0.612106 -0.758758 0 0.651373 -0.724793 0 0.688967 -0.758758 0 0.651372 -0.688967 0 0.724793 -0.724793 0 0.688967 -0.688967 0 0.724793 -0.651372 0 0.758758 -0.612106 0 0.790776 -0.651372 0 0.758758 -0.571268 0 0.820763 -0.612106 0 0.790776 -0.571268 0 0.820763 -0.528964 0 0.848644 -0.485302 0 0.874347 -0.528964 0 0.848644 -0.440394 0 0.897805 -0.485302 0 0.874347 -0.440394 0 0.897804 -0.394356 0 0.918958 -0.347305 0 0.937752 -0.394356 0 0.918958 -0.299363 0 0.954139 -0.347305 0 0.937752 -0.299363 0 0.954139 -0.250653 0 0.968077 -0.201299 0 0.97953 -0.250653 0 0.968077 -0.151427 0 0.988468 -0.201298 0 0.97953 -0.151428 0 0.988468 -0.101168 0 0.994869 -0.0506492 0 0.998716 -0.101169 0 0.994869 1.74846e-07 0 1 -0.0506492 0 0.998716 -3.01992e-07 0 1 -0.998716 0 -0.0506494 -0.994869 0 -0.101168 -0.998717 0 -0.0506489 -0.988468 0 -0.151428 -0.994869 0 -0.101168 -0.988468 0 -0.151428 -0.97953 0 -0.201299 -0.968077 0 -0.250652 -0.97953 0 -0.201299 -0.954139 0 -0.299363 -0.968077 0 -0.250653 -0.954139 0 -0.299363 -0.937752 0 -0.347305 -0.918958 0 -0.394356 -0.937752 0 -0.347305 -0.897804 0 -0.440394 -0.918958 0 -0.394356 -0.897805 0 -0.440394 -0.874347 0 -0.485302 -0.848644 0 -0.528964 -0.874347 0 -0.485302 -0.820763 0 -0.571268 -0.848644 0 -0.528964 -0.820763 0 -0.571268 -0.790776 0 -0.612106 -0.758758 0 -0.651372 -0.790776 0 -0.612106 -0.724793 0 -0.688967 -0.758758 0 -0.651373 -0.724793 0 -0.688967 -0.688967 0 -0.724793 -0.651372 0 -0.758758 -0.688967 0 -0.724793 -0.612106 0 -0.790776 -0.651372 0 -0.758758 -0.612106 0 -0.790776 -0.571268 0 -0.820763 -0.528964 0 -0.848644 -0.571268 0 -0.820763 -0.485302 0 -0.874347 -0.528964 0 -0.848644 -0.485302 0 -0.874347 -0.440394 0 -0.897804 -0.394356 0 -0.918958 -0.440394 0 -0.897805 -0.347305 0 -0.937752 -0.394356 0 -0.918958 -0.347305 0 -0.937752 -0.299363 0 -0.954139 -0.250652 0 -0.968077 -0.299363 0 -0.954139 -0.201298 0 -0.97953 -0.250653 0 -0.968077 -0.201299 0 -0.97953 -0.151428 0 -0.988468 -0.101168 0 -0.994869 -0.151428 0 -0.988468 -0.0506493 0 -0.998716 -0.101168 0 -0.994869 -0.050649 0 -0.998717 0.101168 0 -0.994869 0.0506491 0 -0.998717 0.101168 0 -0.994869 0.250653 0 -0.968077 0.201298 0 -0.97953 0.250653 0 -0.968077 0.151428 0 -0.988468 0.151428 0 -0.988468 0.201298 0 -0.97953 0.347305 0 -0.937752 0.394356 0 -0.918958 0.394356 0 -0.918958 0.299363 0 -0.954139 0.347305 0 -0.937752 0.299363 0 -0.954139 0.528964 0 -0.848644 0.528964 0 -0.848644 0.485302 0 -0.874347 0.485302 0 -0.874347 0.440394 0 -0.897804 0.440394 0 -0.897804 0.651373 0 -0.758758 0.612106 0 -0.790776 0.651372 0 -0.758758 0.571268 0 -0.820763 0.571268 0 -0.820763 0.612106 0 -0.790776 0.724793 0 -0.688967 0.758758 0 -0.651373 0.758758 0 -0.651373 0.688967 0 -0.724793 0.724793 0 -0.688967 0.688967 0 -0.724793 0.848644 0 -0.528964 0.848644 0 -0.528964 0.820763 0 -0.571268 0.820764 0 -0.571268 0.790776 0 -0.612106 0.790776 0 -0.612106 0.918958 0 -0.394356 0.897804 0 -0.440394 0.918958 0 -0.394356 0.874347 0 -0.485302 0.874347 0 -0.485302 0.897804 0 -0.440394 0.954139 0 -0.299363 0.968077 0 -0.250652 0.968077 0 -0.250653 0.937752 0 -0.347305 0.954139 0 -0.299363 0.937752 0 -0.347305 0.994869 0 -0.101168 0.994869 0 -0.101168 0.988468 0 -0.151428 0.988468 0 -0.151428 0.97953 0 -0.201298 0.97953 0 -0.201298 0.998716 0 0.0506493 1 0 -4.37114e-08 0.998717 0 0.0506491 0.998717 0 -0.0506491 0.998717 0 -0.0506491 1 0 7.54979e-08 0.988468 0 0.151428 0.97953 0 0.201299 0.97953 0 0.201299 0.994869 0 0.101168 0.988468 0 0.151428 0.994869 0 0.101168 0.937752 0 0.347305 0.937752 0 0.347305 0.954139 0 0.299363 0.954139 0 0.299363 0.968077 0 0.250653 0.968077 0 0.250653 0.874347 0 0.485302 0.897804 0 0.440394 0.874347 0 0.485302 0.918958 0 0.394356 0.918958 0 0.394356 0.897805 0 0.440394 0.820763 0 0.571268 0.790776 0 0.612106 0.790776 0 0.612106 0.848644 0 0.528964 0.820763 0 0.571268 0.848644 0 0.528964 0.688967 0 0.724793 0.688967 0 0.724793 0.724793 0 0.688967 0.724793 0 0.688967 0.758758 0 0.651372 0.758758 0 0.651372 0.651372 0 0.758758 0.651372 0 0.758758 0.612106 0 0.790776 0.612106 0 0.790776 0.571268 0 0.820763 0.571268 0 0.820763 0.528964 0 0.848644 0.528964 0 0.848644 0.485302 0 0.874347 0.485302 0 0.874347 0.440394 0 0.897805 0.440394 0 0.897805 0.394356 0 0.918958 0.394356 0 0.918958 0.347305 0 0.937752 0.347305 0 0.937752 0.299363 0 0.954139 0.299363 0 0.954139 0.250653 0 0.968077 0.250653 0 0.968077 0.201299 0 0.97953 0.201299 0 0.97953 0.151428 0 0.988468 0.151428 0 0.988468 0.101168 0 0.994869 0.101168 0 0.994869 0.0506492 0 0.998717 0.0506492 0 0.998717 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 -1.19249e-08 0.984808 0 -0.173648 1 0 -1.19249e-08 8.74228e-08 0 1 -0.173648 0 0.984808 8.74228e-08 0 1 0.939693 0 -0.34202 0.984808 0 -0.173648 0.939693 0 -0.34202 0.866025 0 -0.5 0.866025 0 -0.5 0.766044 0 -0.642788 0.642788 0 -0.766044 0.766044 0 -0.642788 0.642788 0 -0.766044 0.5 0 -0.866026 0.5 0 -0.866026 0.34202 0 -0.939693 0.173648 0 -0.984808 0.34202 0 -0.939693 0.173648 0 -0.984808 -1.74846e-07 -0 -1 -1.74846e-07 -0 -1 0.984808 0 0.173648 0.984808 0 0.173648 0.939693 0 0.34202 0.939692 0 0.342021 0.866025 0 0.5 0.766045 0 0.642788 0.866025 0 0.5 0.766045 0 0.642788 0.642788 0 0.766044 0.642788 0 0.766044 0.5 0 0.866026 0.34202 0 0.939693 0.5 0 0.866025 0.34202 0 0.939693 0.173648 0 0.984808 0.173648 0 0.984808 -0.34202 0 0.939693 -0.34202 0 0.939693 -0.173648 0 0.984808 -0.766044 0 0.642788 -0.766044 0 0.642788 -0.642788 0 0.766044 -0.5 0 0.866025 -0.642788 0 0.766044 -0.5 0 0.866025 -0.939693 0 0.34202 -0.984808 0 0.173648 -0.984808 0 0.173648 -0.866025 0 0.5 -0.866025 0 0.5 -0.939693 0 0.34202 -0.939693 -0 -0.34202 -0.984808 -0 -0.173648 -0.939693 -0 -0.34202 -0.984808 -0 -0.173648 -1 -0 -7.54979e-08 -1 0 4.37114e-08 -0.642788 -0 -0.766044 -0.642788 -0 -0.766044 -0.766044 -0 -0.642788 -0.866025 -0 -0.5 -0.766044 -0 -0.642788 -0.866025 -0 -0.5 -0.5 -0 -0.866025 -0.5 -0 -0.866025 -0.34202 -0 -0.939693 -0.34202 -0 -0.939693 -0.173648 -0 -0.984808 -0.173648 -0 -0.984808 + -0.996584 0 -0.0825794 -0.996584 0 0.0825794 -0.996584 0 0.0825794 -8.74228e-08 0 -1 -8.74228e-08 0 -1 0.164595 0 -0.986361 -0.9694 0 0.245485 -0.9694 0 0.245486 -0.915773 0 0.401695 -0.915773 0 0.401695 -0.837166 0 0.546948 -0.837166 0 0.546948 -0.735724 0 0.677282 -0.735724 0 0.677282 -0.614213 0 0.78914 -0.614213 0 0.789141 -0.475948 0 0.879474 -0.475947 0 0.879474 -0.324699 0 0.945817 -0.3247 0 0.945817 -0.164595 0 0.986361 -0.164595 0 0.986361 1.74846e-07 0 1 -3.01992e-07 0 1 -0.996584 0 -0.0825794 -0.9694 0 -0.245486 -0.9694 0 -0.245486 -0.915773 0 -0.401695 -0.915773 0 -0.401695 -0.837167 0 -0.546948 -0.837167 0 -0.546948 -0.735724 0 -0.677282 -0.735724 0 -0.677282 -0.614213 0 -0.78914 -0.614213 0 -0.78914 -0.475947 0 -0.879474 -0.475947 0 -0.879474 -0.324699 0 -0.945817 -0.324699 0 -0.945817 -0.164595 0 -0.986361 -0.164595 0 -0.986361 0.3247 0 -0.945817 0.164595 0 -0.986361 0.324699 0 -0.945817 0.735724 0 -0.677282 0.614213 0 -0.789141 0.735724 0 -0.677282 0.475947 0 -0.879474 0.475947 0 -0.879474 0.614213 0 -0.78914 0.915773 0 -0.401695 0.9694 0 -0.245485 0.9694 0 -0.245485 0.837166 0 -0.546948 0.915773 0 -0.401695 0.837166 0 -0.546948 0.9694 0 0.245485 0.9694 0 0.245485 0.996584 0 0.0825794 0.996584 0 0.0825794 0.996584 0 -0.0825794 0.996584 0 -0.0825792 0.735724 0 0.677282 0.837166 0 0.546948 0.735724 0 0.677282 0.915773 0 0.401695 0.915773 0 0.401695 0.837166 0 0.546948 0.475947 0 0.879474 0.614213 0 0.789141 0.614213 0 0.789141 0.324699 0 0.945817 0.475947 0 0.879474 0.324699 0 0.945817 0.164595 0 0.986361 0.164595 0 0.986361 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.999099 0 -0.042441 0.996584 0 -0.0825794 0.996584 0 0.0825794 -0.0848059 0 0.996397 0.0848059 0 0.996397 8.74228e-08 0 1 0.9694 0 -0.245486 0.977555 0 -0.210679 0.927889 0 -0.372857 0.915773 0 -0.401695 0.851529 0 -0.524307 0.837166 0 -0.546948 0.735724 0 -0.677282 0.750672 0 -0.660675 0.62822 0 -0.778036 0.614213 0 -0.78914 0.487695 0 -0.873014 0.475948 0 -0.879474 0.3247 0 -0.945817 0.33314 0 -0.942877 0.169001 0 -0.985616 0.164595 0 -0.986361 3.01992e-07 0 -1 -1.74846e-07 -0 -1 0.9919 0 0.127018 0.9694 0 0.245486 0.956167 0 0.292823 0.915773 0 0.401695 0.892926 0 0.450204 0.803997 0 0.594633 0.837167 0 0.546948 0.735724 0 0.677282 0.691939 0 0.721956 0.614213 0 0.78914 0.559975 0 0.82851 0.411901 0 0.911228 0.475947 0 0.879474 0.324699 0 0.945817 0.251978 0 0.967733 0.164595 0 0.986361 -0.559975 0 0.82851 -0.411901 0 0.911228 -0.475947 0 0.879474 -0.251978 0 0.967733 -0.164595 0 0.986361 -0.3247 0 0.945817 -0.837166 0 0.546948 -0.892926 0 0.450204 -0.803997 0 0.594633 -0.614213 0 0.789141 -0.735724 0 0.677282 -0.691939 0 0.721956 -0.9919 0 0.127018 -0.996584 0 0.0825794 -0.999099 -0 -0.0424412 -0.956167 0 0.292823 -0.915773 0 0.401695 -0.9694 0 0.245485 -0.851529 -0 -0.524307 -0.927889 -0 -0.372857 -0.915773 -0 -0.401695 -0.9694 -0 -0.245485 -0.977555 -0 -0.210679 -0.996584 -0 -0.0825794 -0.614213 -0 -0.789141 -0.62822 -0 -0.778036 -0.735724 -0 -0.677282 -0.837166 -0 -0.546948 -0.750672 -0 -0.660675 -0.487695 -0 -0.873014 -0.475947 -0 -0.879474 -0.324699 -0 -0.945817 -0.33314 -0 -0.942877 -0.164595 -0 -0.986361 -0.169001 -0 -0.985616 - + @@ -123,9 +123,9 @@ - + -

0 1 2 3 4 5 6 1 7 1 6 2 8 9 7 6 7 9 8 10 11 11 9 8 12 10 13 10 12 11 14 15 13 12 13 15 14 16 17 17 15 14 18 16 19 16 18 17 20 21 19 18 19 21 20 22 23 23 21 20 24 22 25 22 24 23 26 27 25 24 25 27 26 28 29 29 27 26 30 28 31 28 30 29 32 33 31 30 31 33 32 34 35 35 33 32 36 34 37 34 36 35 38 39 37 36 37 39 38 40 41 41 39 38 42 40 43 40 42 41 44 45 43 42 43 45 44 46 47 47 45 44 48 46 49 46 48 47 50 51 49 48 49 51 50 52 53 53 51 50 54 52 55 52 54 53 56 57 55 54 55 57 56 58 59 59 57 56 60 58 61 58 60 59 62 63 61 60 61 63 62 64 65 65 63 62 64 66 65 67 0 2 68 69 67 0 67 69 68 70 71 71 69 68 72 70 73 70 72 71 74 75 73 72 73 75 74 76 77 77 75 74 78 76 79 76 78 77 80 81 79 78 79 81 80 82 83 83 81 80 84 82 85 82 84 83 86 87 85 84 85 87 86 88 89 89 87 86 90 88 91 88 90 89 92 93 91 90 91 93 92 94 95 95 93 92 96 94 97 94 96 95 98 99 97 96 97 99 98 100 101 101 99 98 102 100 103 100 102 101 104 105 103 102 103 105 104 106 107 107 105 104 108 106 109 106 108 107 110 111 109 108 109 111 110 112 113 113 111 110 114 112 115 112 114 113 116 117 115 114 115 117 116 118 119 119 117 116 120 118 121 118 120 119 122 123 121 120 121 123 122 124 125 125 123 122 126 124 4 124 126 125 127 128 129 126 4 3 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 215 220 221 220 215 214 222 221 223 220 223 221 224 225 222 222 223 224 225 226 227 226 225 224 228 227 229 226 229 227 230 231 228 228 229 230 231 232 233 232 231 230 234 233 235 232 235 233 236 237 234 234 235 236 237 238 239 238 237 236 240 239 241 238 241 239 242 243 240 240 241 242 243 244 245 244 243 242 246 245 247 244 247 245 66 64 246 246 247 66 217 216 218 214 216 217 209 219 210 219 218 210 213 212 208 212 209 208 202 204 211 202 211 213 203 205 207 203 207 204 206 197 196 205 197 206 199 198 200 196 198 199 191 201 192 201 200 192 195 194 190 194 191 190 184 186 193 184 193 195 185 187 189 185 189 186 188 179 178 187 179 188 181 180 182 178 180 181 173 183 174 183 182 174 177 176 172 176 173 172 166 168 175 166 175 177 167 169 171 167 171 168 170 161 160 169 161 170 163 162 164 160 162 163 155 165 156 165 164 156 159 158 154 158 155 154 148 150 157 148 157 159 149 151 153 149 153 150 152 143 142 151 143 152 145 144 146 142 144 145 137 147 138 147 146 138 141 140 136 140 137 136 130 132 139 130 139 141 131 133 135 131 135 132 134 127 129 133 127 134 5 128 3 129 128 5 248 249 250 251 252 253 254 255 249 256 257 258 259 260 261 262 263 256 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 278 284 285 286 283 287 288 289 290 291 292 288 293 252 251 294 295 296 297 296 298 252 297 296 299 300 301 299 298 296 295 300 302 301 300 288 292 302 300 303 293 288 304 252 305 253 289 294 306 307 304 288 306 290 289 283 308 309 287 283 309 310 285 284 284 291 310 278 277 311 278 311 282 280 312 281 284 286 280 313 314 270 314 278 270 315 274 273 280 279 315 316 265 264 270 265 271 273 317 267 275 317 273 259 261 318 259 319 265 262 267 320 320 267 269 321 255 322 260 255 321 256 323 257 256 263 323 249 324 325 326 254 249 327 328 258 258 329 327 328 330 258 248 250 331 250 332 333 334 335 336 337 338 330 339 334 340 338 341 330 342 339 340 343 330 341 344 340 345 343 346 347 348 349 340 343 347 350 348 351 349 350 352 343 353 354 352 352 354 355 356 357 348 355 358 352 359 356 348 360 358 361 362 359 363 364 358 360 365 363 359 364 366 358 359 367 368 369 358 366 370 371 367 272 313 270 367 372 370 369 373 374 375 372 376 374 377 369 376 378 375 377 379 380 381 376 382 383 384 385 382 386 387 383 388 389 390 391 392 393 394 389 395 396 391 389 397 395 398 395 399 397 389 394 395 397 399 395 400 396 395 398 400 389 388 401 389 401 393 402 392 391 396 402 391 383 385 403 383 403 388 386 382 390 382 391 390 377 380 384 383 377 384 404 381 382 387 404 382 405 377 374 379 377 405 381 378 376 334 336 332 337 330 406 366 407 369 373 369 407 355 361 358 350 353 352 341 346 343 328 406 330 257 329 258 262 256 267 317 268 267 315 273 280 286 312 280 291 284 289 294 289 252 298 305 252 299 296 300 292 303 300 287 307 288 282 308 283 314 276 278 265 316 271 266 265 319 318 319 259 260 259 255 254 322 255 325 326 249 324 249 248 250 333 331 332 250 334 335 334 339 342 340 344 340 349 345 357 351 348 362 356 359 359 368 365 368 367 371 367 376 372 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 438 445 446 447 448 449 450 451 452 446 453 454 455 456 413 457 411 458 459 460 412 461 459 459 458 462 459 462 455 460 459 461 463 455 462 456 455 464 463 464 455 454 450 455 413 412 459 457 413 452 450 454 451 446 452 413 438 450 445 450 449 445 448 465 446 465 453 446 438 466 439 438 444 466 442 441 447 446 442 447 434 440 432 438 440 434 436 435 467 467 443 442 426 468 427 434 468 426 430 429 469 430 470 436 426 421 420 471 426 428 472 473 424 424 473 430 420 415 414 474 420 422 475 476 418 425 424 418 414 408 410 477 414 416 478 479 480 419 418 480 481 482 483 478 480 481 484 410 485 485 486 484 487 488 482 484 486 489 482 490 487 491 484 492 490 493 494 491 492 495 490 496 497 495 498 491 496 490 499 491 498 500 501 499 502 503 502 499 504 505 503 506 507 500 508 505 504 507 506 509 510 504 511 512 507 509 513 511 514 515 516 507 511 517 514 518 516 515 519 520 511 516 518 521 520 519 522 523 516 521 524 519 525 523 526 527 519 528 525 529 527 526 528 530 531 532 533 527 534 535 536 537 533 538 539 540 541 542 543 544 545 546 547 548 549 550 551 546 552 553 554 555 547 546 551 555 552 553 556 553 549 554 553 556 541 540 557 557 540 546 558 549 542 550 549 558 540 534 536 559 540 539 560 543 537 544 543 560 528 536 530 535 561 536 562 533 532 533 562 538 528 563 564 531 563 528 565 527 529 566 567 410 409 566 410 522 519 524 468 434 433 421 426 471 415 420 474 408 414 477 485 410 567 492 484 489 500 507 491 515 507 512 523 527 516 532 527 565 537 543 533 542 549 543 556 549 548 552 546 553 557 546 545 534 540 559 530 536 561 525 528 564 511 520 517 513 510 511 508 504 510 503 499 504 496 499 501 493 490 497 494 487 490 482 488 483 481 480 482 479 419 480 417 475 418 418 476 425 472 424 423 431 430 473 430 469 470 470 437 436 436 467 442 568 569 570 571 572 573 574 569 575 568 575 569 574 576 577 576 574 575 578 579 577 577 576 578 580 579 581 578 581 579 580 582 583 582 580 581 584 585 583 583 582 584 586 585 587 584 587 585 586 588 589 588 586 587 589 588 590 591 568 570 591 592 593 592 591 570 594 595 593 593 592 594 596 595 597 594 597 595 596 598 599 598 596 597 600 601 599 599 598 600 602 601 603 600 603 601 602 604 605 604 602 603 606 573 605 605 604 606 607 608 609 606 571 573 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 628 635 628 634 629 635 636 637 637 634 635 638 639 636 637 636 639 590 638 589 638 590 639 632 631 630 630 629 632 633 622 624 631 633 624 625 627 623 622 625 623 618 617 626 626 617 627 620 616 621 621 616 618 610 619 611 610 620 619 612 614 613 612 611 614 615 608 607 613 615 607 572 571 609 608 572 609

+

0 1 2 3 4 5 6 2 7 1 7 2 8 9 6 6 7 8 9 10 11 10 9 8 12 11 13 10 13 11 14 15 12 12 13 14 15 16 17 16 15 14 18 17 19 16 19 17 20 21 18 18 19 20 22 21 20 22 23 21 1 0 24 25 26 24 24 0 25 26 27 28 27 26 25 29 28 30 27 30 28 31 32 29 29 30 31 32 33 34 33 32 31 35 34 36 33 36 34 37 38 35 35 36 37 38 39 40 39 38 37 39 4 40 41 42 43 40 4 3 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 62 70 69 68 71 72 72 69 68 73 71 74 71 73 72 23 75 74 73 74 75 22 75 23 63 67 64 62 64 70 65 57 66 63 65 67 56 58 59 66 57 56 61 60 52 59 58 60 54 51 50 51 61 52 44 53 55 55 54 50 45 49 46 44 46 53 47 41 48 45 47 49 43 42 5 48 41 43 3 5 42 76 77 78 79 80 81 82 83 79 84 85 86 87 88 89 90 89 91 91 92 93 82 88 94 95 81 96 92 86 97 98 84 99 100 101 102 103 104 99 105 106 107 108 109 104 110 111 112 113 109 114 113 115 116 117 118 116 119 120 121 122 123 118 124 123 125 126 127 124 128 129 130 127 131 132 133 134 135 136 137 138 77 95 78 139 140 141 140 139 142 136 138 141 138 139 141 143 144 142 142 144 140 134 133 137 137 136 134 145 120 146 147 148 149 143 127 132 143 132 144 131 127 126 126 124 125 125 123 122 122 118 117 117 116 115 115 113 114 114 109 108 108 104 103 103 99 84 98 85 84 85 97 86 97 93 92 93 90 91 90 87 89 87 94 88 94 83 82 83 80 79 80 96 81 96 78 95 78 100 76 102 101 106 76 100 102 105 107 110 106 101 107 149 112 111 112 105 110 150 148 147 147 149 111 146 150 145 150 146 148 145 151 120 121 128 119 151 121 120 130 129 135 119 128 130 133 135 129 152 153 154 155 156 157 156 155 158 159 160 161 162 158 163 164 163 158 161 163 164 162 156 158 155 157 153 164 159 161 159 165 160 166 152 167 160 165 168 169 166 170 171 172 173 174 169 175 176 177 178 179 180 181 182 183 184 185 183 186 187 188 189 190 191 192 193 194 195 196 185 197 198 199 200 201 196 202 203 204 205 206 207 208 209 210 211 210 212 213 214 205 204 215 214 209 216 217 218 212 218 219 220 221 201 222 203 221 223 184 174 224 225 226 207 206 216 157 154 153 154 167 152 167 170 166 170 175 169 175 223 174 223 182 184 182 186 183 186 197 185 197 202 196 202 220 201 220 222 221 222 204 203 205 214 215 215 209 211 211 210 213 213 212 219 219 218 217 217 216 206 208 207 199 198 200 194 208 199 198 195 191 193 200 195 194 192 188 190 191 190 193 180 187 189 189 188 192 225 179 181 179 187 180 224 226 177 225 181 226 176 178 172 224 177 176 173 168 171 178 173 172 165 171 168 227 228 229 230 231 232 233 228 234 227 234 228 233 235 236 235 233 234 237 238 236 236 235 237 239 238 240 237 240 238 239 241 242 241 239 240 243 244 242 242 241 243 245 244 246 243 246 244 245 247 248 247 245 246 248 247 249 248 249 250 229 251 227 251 252 253 252 251 229 254 255 253 253 252 254 256 255 257 254 257 255 256 258 259 258 256 257 260 261 259 259 258 260 262 261 263 260 263 261 262 264 265 264 262 263 266 231 265 265 264 266 266 232 231 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 293 295 296 291 297 291 296 292 297 298 299 299 296 297 300 301 298 299 298 301 249 300 250 300 249 301 294 295 285 293 292 295 287 286 288 294 285 287 289 281 290 286 289 288 279 284 280 281 280 290 274 283 282 282 284 279 277 273 275 273 283 274 276 278 267 277 275 278 269 268 272 276 267 269 270 230 271 268 270 272 232 271 230

diff --git a/src/tsukuba2022/meshes/right_back_wheel.dae b/src/tsukuba2022/meshes/right_back_wheel.dae index d69c6ad..86ec930 100644 --- a/src/tsukuba2022/meshes/right_back_wheel.dae +++ b/src/tsukuba2022/meshes/right_back_wheel.dae @@ -2,9 +2,9 @@ - 2022-05-02T17:48:39 - 2022-05-02T17:48:39 - + 2022-09-07T14:56:31 + 2022-09-07T14:56:31 + Z_UP @@ -68,9 +68,9 @@ - -3.10097e-18 0 0.0035 -0.000607769 0.032 0.00344683 -0.000607769 -0.007 0.00344683 -0.00119707 0.032 0.00328892 -3.10097e-18 -0.007 0.0035 -0.00175 0.032 0.00303109 -0.00119707 -0.007 0.00328892 -0.00175 -0.007 0.00303109 -0.00224976 0.032 0.00268116 -0.00268116 0.032 0.00224976 -0.00224976 -0.007 0.00268116 -0.00303109 0.032 0.00175 -0.00268116 -0.007 0.00224976 -0.00303109 -0.007 0.00175 -0.00328892 0.032 0.00119707 -0.00344683 0.032 0.000607769 -0.00328892 -0.007 0.00119707 -0.0035 0.032 7.10543e-18 -0.00344683 -0.007 0.000607769 -0.0035 -0.007 7.10543e-18 -0.00344683 0.032 -0.000607769 -0.00328892 0.032 -0.00119707 -0.00344683 -0.007 -0.000607769 -0.00303109 0.032 -0.00175 -0.00328892 -0.007 -0.00119707 -0.00303109 -0.007 -0.00175 -0.00268116 0.032 -0.00224976 -0.00224976 0.032 -0.00268116 -0.00268116 -0.007 -0.00224976 -0.00175 0.032 -0.00303109 -0.00224976 -0.007 -0.00268116 -0.00175 -0.007 -0.00303109 -0.00119707 0.032 -0.00328892 -0.000607769 0.032 -0.00344683 -0.00119707 -0.007 -0.00328892 -4.20967e-19 0.032 -0.0035 -0.000607769 -0.007 -0.00344683 -7.49547e-18 -0.007 -0.0035 5.32907e-18 0.032 0.0035 0.000607769 0 0.00344683 0.00119707 0 0.00328892 0.000607769 0.032 0.00344683 0.00119707 0.032 0.00328892 0.00175 0 0.00303109 0.00224976 0.032 0.00268116 0.00175 0.032 0.00303109 0.00224976 0 0.00268116 0.00268116 0 0.00224976 0.00268116 0.032 0.00224976 0.00303109 0 0.00175 0.00303109 0.032 0.00175 0.00344683 0 0.000607769 0.00328892 0.032 0.00119707 0.00328892 0 0.00119707 0.0035 0 -9.5504e-19 0.00344683 0.032 0.000607769 0.00344683 0.032 -0.000607769 0.0035 0.032 0 0.00328892 -0.007 -0.00119707 0.00344683 -0.007 -0.000607769 0.0035 -0.007 -5.61798e-18 0.00328892 0.032 -0.00119707 0.00303109 -0.007 -0.00175 0.00268116 -0.007 -0.00224976 0.00303109 0.032 -0.00175 0.00224976 -0.007 -0.00268116 0.00268116 0.032 -0.00224976 0.00224976 0.032 -0.00268116 0.00175 0.032 -0.00303109 0.00175 -0.007 -0.00303109 0.00119707 -0.007 -0.00328892 0.00119707 0.032 -0.00328892 0.000607769 -0.007 -0.00344683 0.000607769 0.032 -0.00344683 0.00328892 0.032 -0.00119707 0.00303109 0.032 -0.00175 -0.00175 0.032 0.00303109 0.00119707 0.032 0.00328892 0.00303109 0.032 0.00175 0.00328892 0.032 0.00119707 0.0035 0.032 0 5.32907e-18 0.032 0.0035 0.00344683 0.032 0.000607769 0.00344683 0.032 -0.000607769 -0.00119707 0.032 0.00328892 -0.000607769 0.032 0.00344683 0.00268116 0.032 0.00224976 0.00175 0.032 0.00303109 0.000607769 0.032 0.00344683 0.00224976 0.032 0.00268116 -0.00224976 0.032 0.00268116 -0.00268116 0.032 0.00224976 0.00268116 0.032 -0.00224976 0.00224976 0.032 -0.00268116 -0.00303109 0.032 0.00175 0.00175 0.032 -0.00303109 -0.00328892 0.032 0.00119707 0.00119707 0.032 -0.00328892 0.000607769 0.032 -0.00344683 -0.00344683 0.032 0.000607769 -4.20967e-19 0.032 -0.0035 -0.0035 0.032 7.10543e-18 -0.000607769 0.032 -0.00344683 -0.00119707 0.032 -0.00328892 -0.00328892 0.032 -0.00119707 -0.00344683 0.032 -0.000607769 -0.00175 0.032 -0.00303109 -0.00224976 0.032 -0.00268116 -0.00268116 0.032 -0.00224976 -0.00303109 0.032 -0.00175 0.0335 0 0.03 0.0334468 0 0.0293922 0.0332889 0 0.0288029 0.0265 0 0.11 0.0265 0 0.03 0.000607769 0 0.00344683 0.00119707 0 0.00328892 0.00175 0 0.00303109 0.0326812 0 0.0277502 0.0330311 0 0.02825 0.00224976 0 0.00268116 0.00268116 0 0.00224976 0.0322498 0 0.0273188 0.03175 0 0.0269689 0.0311971 0 0.0267111 0.0306078 0 0.0265532 0.03 0 0.0265 0.0335 0 0.11 -3.10097e-18 0 0.0035 0.00303109 0 0.00175 0.00328892 0 0.00119707 0.00344683 0 0.000607769 0.0035 0 -9.5504e-19 0.0265 0 0.03 0.0265 -0.007 0.03 0.0265 -0.007 0.11 0.0265 0 0.11 -3.10097e-18 0 0.0035 -3.10097e-18 -0.007 0.0035 0.0265 -0.007 0.03 0.0265 0 0.03 0.03 0 0.0265 0.03 -0.007 0.0265 0.0035 -0.007 -5.61798e-18 0.0035 0 -9.5504e-19 0.0326812 -0.007 0.0277502 0.0322498 -0.007 0.0273188 0.0326812 0 0.0277502 0.0330311 0 0.02825 0.0330311 -0.007 0.02825 0.0332889 0 0.0288029 0.0332889 -0.007 0.0288029 0.0334468 -0.007 0.0293922 0.0334468 0 0.0293922 0.0335 0 0.03 0.0335 -0.007 0.03 0.0322498 0 0.0273188 0.03175 0 0.0269689 0.03175 -0.007 0.0269689 0.0311971 -0.007 0.0267111 0.0311971 0 0.0267111 0.0306078 -0.007 0.0265532 0.0306078 0 0.0265532 0.03 -0.007 0.0265 0.03 0 0.0265 0.0335 0 0.03 0.0335 0 0.11 0.0335 -0.007 0.11 0.0335 -0.007 0.03 0.0335 0 0.11 0.0265 0 0.11 0.0265 -0.007 0.11 0.0335 -0.007 0.11 0.03175 -0.007 0.0269689 0.0322498 -0.007 0.0273188 0.0335 -0.007 0.03 -0.00224976 -0.007 -0.00268116 -0.00175 -0.007 -0.00303109 -0.00224976 -0.007 0.00268116 0.0265 -0.007 0.03 0.0035 -0.007 -5.61798e-18 0.03 -0.007 0.0265 -0.0035 -0.007 7.10543e-18 -0.00344683 -0.007 -0.000607769 -0.00344683 -0.007 0.000607769 -0.00328892 -0.007 0.00119707 -0.00328892 -0.007 -0.00119707 -0.00303109 -0.007 -0.00175 -0.00303109 -0.007 0.00175 -0.00268116 -0.007 -0.00224976 -0.00268116 -0.007 0.00224976 -0.00175 -0.007 0.00303109 -0.00119707 -0.007 -0.00328892 -0.000607769 -0.007 -0.00344683 -0.00119707 -0.007 0.00328892 -7.49547e-18 -0.007 -0.0035 -0.000607769 -0.007 0.00344683 -3.10097e-18 -0.007 0.0035 0.000607769 -0.007 -0.00344683 0.00119707 -0.007 -0.00328892 0.00175 -0.007 -0.00303109 0.00224976 -0.007 -0.00268116 0.00268116 -0.007 -0.00224976 0.00328892 -0.007 -0.00119707 0.00344683 -0.007 -0.000607769 0.00303109 -0.007 -0.00175 0.0330311 -0.007 0.02825 0.0332889 -0.007 0.0288029 0.0306078 -0.007 0.0265532 0.0326812 -0.007 0.0277502 0.0334468 -0.007 0.0293922 0.0311971 -0.007 0.0267111 0.0265 -0.007 0.11 0.0335 -0.007 0.11 + -3.10097e-18 -0.007 0.0035 -0.000296821 0.032 0.00348739 -0.000576081 -0.007 0.00345226 -0.00113645 -0.007 0.00331036 -0.000881923 0.032 0.00338707 -0.00144165 0.032 0.0031893 -0.00166582 -0.007 0.00307816 -0.00195991 0.032 0.00289978 -0.00214974 -0.007 0.00276199 -0.00257503 -0.007 0.00237049 -0.00242179 0.032 0.00252685 -0.00281399 0.032 0.00208122 -0.00293008 -0.007 0.00191432 -0.00312524 0.032 0.00157571 -0.00320521 -0.007 0.00140593 -0.0033929 -0.007 0.000859199 -0.00334658 0.032 0.00102488 -0.00347165 0.032 0.000444562 -0.00348805 -0.007 0.000289028 -0.00349685 0.032 -0.000148544 -0.00348805 -0.007 -0.000289028 -0.0033929 -0.007 -0.000859199 -0.00342144 0.032 -0.000737377 -0.00324761 0.032 -0.001305 -0.00320521 -0.007 -0.00140593 -0.00298035 0.032 -0.00183508 -0.00293008 -0.007 -0.00191432 -0.00257503 -0.007 -0.00237049 -0.00262735 0.032 -0.00231236 -0.00219877 0.032 -0.00272313 -0.00214974 -0.007 -0.00276199 -0.00170693 0.032 -0.00305555 -0.00166582 -0.007 -0.00307816 -0.00113645 -0.007 -0.00331036 -0.00116599 0.032 -0.00330007 -0.000591503 0.032 -0.00344966 -0.000576081 -0.007 -0.00345226 -4.20967e-19 0.032 -0.0035 -7.49547e-18 -0.007 -0.0035 -3.10097e-18 0 0.0035 0.000607524 0 0.00344687 0.000881923 0.032 0.00338707 0.000296821 0.032 0.00348739 0.00119662 0 0.00328908 0.00144165 0.032 0.0031893 0.00174941 0 0.0030314 0.00195991 0.032 0.00289978 0.00268056 0 0.00225038 0.00242179 0.032 0.00252685 0.00224911 0 0.00268164 0.00303062 0 0.00175069 0.00281399 0.032 0.00208122 0.00334658 0.032 0.00102488 0.00312524 0.032 0.00157571 0.00328863 0 0.0011977 0.00344671 0 0.000608173 0.00347165 0.032 0.000444562 0.0035 0 -9.5504e-19 0.00349685 0.032 -0.000148544 0.0035 -0.007 -5.61798e-18 0.00328863 -0.007 -0.0011977 0.00342144 0.032 -0.000737377 0.00344671 -0.007 -0.000608173 0.00324761 0.032 -0.001305 0.00303062 -0.007 -0.00175069 0.00268056 -0.007 -0.00225038 0.00298035 0.032 -0.00183508 0.00224911 -0.007 -0.00268164 0.00262735 0.032 -0.00231236 0.00219877 0.032 -0.00272313 0.00170693 0.032 -0.00305555 0.00174941 -0.007 -0.0030314 0.00119662 -0.007 -0.00328908 0.00116599 0.032 -0.00330007 0.000607524 -0.007 -0.00344687 0.000591503 0.032 -0.00344966 0.00324761 0.032 -0.001305 0.00298035 0.032 -0.00183508 -0.00144165 0.032 0.0031893 0.00347165 0.032 0.000444562 0.000881923 0.032 0.00338707 0.00334658 0.032 0.00102488 0.00349685 0.032 -0.000148544 0.000296821 0.032 0.00348739 0.00342144 0.032 -0.000737377 -0.000881923 0.032 0.00338707 -0.000296821 0.032 0.00348739 0.00281399 0.032 0.00208122 0.00312524 0.032 0.00157571 0.00195991 0.032 0.00289978 0.00144165 0.032 0.0031893 0.00242179 0.032 0.00252685 -0.00195991 0.032 0.00289978 -0.00242179 0.032 0.00252685 0.00262735 0.032 -0.00231236 0.00219877 0.032 -0.00272313 -0.00281399 0.032 0.00208122 0.00170693 0.032 -0.00305555 -0.00312524 0.032 0.00157571 0.00116599 0.032 -0.00330007 0.000591503 0.032 -0.00344966 -0.00334658 0.032 0.00102488 -4.20967e-19 0.032 -0.0035 -0.00347165 0.032 0.000444562 -0.000591503 0.032 -0.00344966 -0.00342144 0.032 -0.000737377 -0.00349685 0.032 -0.000148544 -0.00219877 0.032 -0.00272313 -0.00262735 0.032 -0.00231236 -0.00298035 0.032 -0.00183508 -0.00324761 0.032 -0.001305 -0.00116599 0.032 -0.00330007 -0.00170693 0.032 -0.00305555 0.0335 0 0.03 0.0334569 0 0.0294525 0.0333287 0 0.0289184 0.0265 0 0.11 0.0265 0 0.03 0.000607524 0 0.00344687 0.00119662 0 0.00328908 0.00174941 0 0.0030314 0.0331185 0 0.028411 0.0328316 0 0.0279428 0.00224911 0 0.00268164 0.00268056 0 0.00225038 0.0324749 0 0.0275251 0.0320572 0 0.0271684 0.0310816 0 0.0266713 0.031589 0 0.0268815 0.0305475 0 0.0265431 0.03 0 0.0265 0.0335 0 0.11 -3.10097e-18 0 0.0035 0.00303062 0 0.00175069 0.00328863 0 0.0011977 0.00344671 0 0.000608173 0.0035 0 -9.5504e-19 0.0265 0 0.03 0.0265 -0.007 0.03 0.0265 -0.007 0.11 0.0265 0 0.11 -3.10097e-18 0 0.0035 -3.10097e-18 -0.007 0.0035 0.0265 -0.007 0.03 0.0265 0 0.03 0.03 0 0.0265 0.03 -0.007 0.0265 0.0035 -0.007 -5.61798e-18 0.0035 0 -9.5504e-19 0.0324749 -0.007 0.0275251 0.0324749 0 0.0275251 0.0328316 0 0.0279428 0.0331185 0 0.028411 0.0328316 -0.007 0.0279428 0.0333287 0 0.0289184 0.0331185 -0.007 0.028411 0.0333287 -0.007 0.0289184 0.0334569 0 0.0294525 0.0335 0 0.03 0.0334569 -0.007 0.0294525 0.0335 -0.007 0.03 0.0320572 -0.007 0.0271684 0.0320572 0 0.0271684 0.031589 -0.007 0.0268815 0.0310816 -0.007 0.0266713 0.031589 0 0.0268815 0.0305475 -0.007 0.0265431 0.0310816 0 0.0266713 0.0305475 0 0.0265431 0.03 -0.007 0.0265 0.03 0 0.0265 0.0335 0 0.03 0.0335 0 0.11 0.0335 -0.007 0.11 0.0335 -0.007 0.03 0.0335 0 0.11 0.0265 0 0.11 0.0265 -0.007 0.11 0.0335 -0.007 0.11 0.031589 -0.007 0.0268815 0.0320572 -0.007 0.0271684 0.0335 -0.007 0.03 -0.00214974 -0.007 -0.00276199 -0.00214974 -0.007 0.00276199 -0.00257503 -0.007 0.00237049 0.0265 -0.007 0.03 0.0035 -0.007 -5.61798e-18 0.03 -0.007 0.0265 -0.00348805 -0.007 -0.000289028 -0.0033929 -0.007 -0.000859199 -0.00348805 -0.007 0.000289028 -0.0033929 -0.007 0.000859199 -0.00320521 -0.007 -0.00140593 -0.00293008 -0.007 -0.00191432 -0.00320521 -0.007 0.00140593 -0.00257503 -0.007 -0.00237049 -0.00293008 -0.007 0.00191432 -0.00166582 -0.007 -0.00307816 -0.00166582 -0.007 0.00307816 -0.00113645 -0.007 0.00331036 -0.00113645 -0.007 -0.00331036 -0.000576081 -0.007 -0.00345226 -0.000576081 -0.007 0.00345226 -7.49547e-18 -0.007 -0.0035 -3.10097e-18 -0.007 0.0035 0.000607524 -0.007 -0.00344687 0.00119662 -0.007 -0.00328908 0.00174941 -0.007 -0.0030314 0.00224911 -0.007 -0.00268164 0.00268056 -0.007 -0.00225038 0.00328863 -0.007 -0.0011977 0.00344671 -0.007 -0.000608173 0.00303062 -0.007 -0.00175069 0.0328316 -0.007 0.0279428 0.0331185 -0.007 0.028411 0.0305475 -0.007 0.0265431 0.0333287 -0.007 0.0289184 0.0334569 -0.007 0.0294525 0.0324749 -0.007 0.0275251 0.0310816 -0.007 0.0266713 0.0265 -0.007 0.11 0.0335 -0.007 0.11 - + @@ -78,9 +78,9 @@ - -8.74228e-08 0 1 -0.173648 0 0.984808 -0.173648 0 0.984808 -0.34202 0 0.939693 -8.74228e-08 0 1 -0.5 0 0.866025 -0.34202 0 0.939693 -0.5 0 0.866026 -0.642788 0 0.766044 -0.766045 0 0.642788 -0.642788 0 0.766044 -0.866025 0 0.5 -0.766045 0 0.642788 -0.866025 0 0.5 -0.939692 0 0.342021 -0.984808 0 0.173648 -0.939693 0 0.34202 -1 0 -1.19249e-08 -0.984808 0 0.173648 -1 0 -1.19249e-08 -0.984808 0 -0.173648 -0.939693 0 -0.34202 -0.984808 0 -0.173648 -0.866025 0 -0.5 -0.939693 0 -0.34202 -0.866025 0 -0.5 -0.766044 0 -0.642788 -0.642788 0 -0.766044 -0.766044 0 -0.642788 -0.5 0 -0.866026 -0.642788 0 -0.766044 -0.5 0 -0.866026 -0.34202 0 -0.939693 -0.173648 0 -0.984808 -0.34202 0 -0.939693 1.74846e-07 0 -1 -0.173648 0 -0.984808 1.74846e-07 0 -1 -8.74228e-08 0 1 0.173648 0 0.984808 0.34202 0 0.939693 0.173648 0 0.984808 0.34202 0 0.939693 0.5 0 0.866025 0.642788 0 0.766044 0.5 0 0.866025 0.642788 0 0.766044 0.766044 0 0.642788 0.766044 0 0.642788 0.866025 0 0.5 0.866025 0 0.5 0.984808 0 0.173648 0.939693 0 0.34202 0.939693 0 0.34202 1 0 4.37114e-08 0.984808 0 0.173648 0.984808 0 -0.173648 1 0 4.37114e-08 0.939693 0 -0.34202 0.984808 0 -0.173648 1 0 -7.54979e-08 0.939693 0 -0.34202 0.866025 0 -0.5 0.766044 0 -0.642788 0.866025 0 -0.5 0.642788 0 -0.766044 0.766044 0 -0.642788 0.642788 0 -0.766044 0.5 0 -0.866025 0.5 0 -0.866025 0.34202 0 -0.939693 0.34202 0 -0.939693 0.173648 0 -0.984808 0.173648 0 -0.984808 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.766044 0 -0.642788 0.642788 0 -0.766044 0.766045 0 -0.642788 0.866025 0 -0.5 0.866025 0 -0.5 0.939693 0 -0.34202 0.939693 0 -0.34202 0.984808 0 -0.173648 0.984808 0 -0.173648 1 0 -5.96244e-09 1 0 -5.96244e-09 0.642788 0 -0.766044 0.5 0 -0.866025 0.5 0 -0.866025 0.34202 0 -0.939693 0.34202 0 -0.939693 0.173648 0 -0.984808 0.173648 0 -0.984808 6.95355e-08 0 -1 6.95355e-08 0 -1 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 + -8.74228e-08 0 1 -0.0848059 0 0.996397 -0.164595 0 0.986361 -0.324699 0 0.945817 -0.251978 0 0.967733 -0.411901 0 0.911228 -0.475947 0 0.879474 -0.559975 0 0.82851 -0.614213 0 0.78914 -0.735724 0 0.677282 -0.691939 0 0.721956 -0.803997 0 0.594633 -0.837167 0 0.546948 -0.892926 0 0.450204 -0.915773 0 0.401695 -0.9694 0 0.245486 -0.956167 0 0.292823 -0.9919 0 0.127018 -0.996584 0 0.0825794 -0.999099 0 -0.0424415 -0.996584 0 -0.0825794 -0.9694 0 -0.245485 -0.977555 0 -0.210679 -0.927889 0 -0.372856 -0.915773 0 -0.401695 -0.851529 0 -0.524307 -0.837166 0 -0.546948 -0.735724 0 -0.677282 -0.750672 0 -0.660675 -0.62822 0 -0.778036 -0.614213 0 -0.789141 -0.487695 0 -0.873014 -0.475947 0 -0.879474 -0.324699 0 -0.945817 -0.33314 0 -0.942877 -0.169001 0 -0.985616 -0.164595 0 -0.986361 1.74846e-07 0 -1 -3.01992e-07 0 -1 1.50996e-07 0 1 0.173648 0 0.984808 0.251978 0 0.967733 0.0848059 0 0.996397 0.34202 0 0.939693 0.411901 0 0.911229 0.5 0 0.866026 0.559975 0 0.82851 0.766044 0 0.642788 0.691939 0 0.721956 0.642788 0 0.766044 0.866025 0 0.5 0.803997 0 0.594633 0.956167 0 0.292823 0.892926 0 0.450204 0.939693 0 0.34202 0.984808 0 0.173648 0.9919 0 0.127018 1 0 -7.54979e-08 0.999099 0 -0.0424412 1 0 4.37114e-08 0.939693 0 -0.34202 0.977555 0 -0.210679 0.984808 0 -0.173648 0.927889 0 -0.372856 0.866025 0 -0.5 0.766044 0 -0.642788 0.851529 0 -0.524307 0.642788 0 -0.766044 0.750672 0 -0.660675 0.62822 0 -0.778036 0.487695 0 -0.873014 0.5 0 -0.866025 0.34202 0 -0.939693 0.33314 0 -0.942877 0.173648 0 -0.984808 0.169001 0 -0.985616 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.809017 0 -0.587785 0.891007 0 -0.45399 0.809017 0 -0.587785 0.951057 0 -0.309017 0.891007 0 -0.45399 0.951057 0 -0.309017 0.987688 0 -0.156435 1 0 -5.96244e-09 0.987688 0 -0.156435 1 0 -5.96244e-09 0.587785 0 -0.809017 0.587785 0 -0.809017 0.453991 0 -0.891007 0.309017 0 -0.951057 0.453991 0 -0.891007 0.156435 0 -0.987688 0.309017 0 -0.951057 0.156434 0 -0.987688 6.95355e-08 0 -1 -1.68883e-07 0 -1 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 - + @@ -91,18 +91,18 @@ - + -

0 1 2 3 2 1 0 2 4 3 5 6 6 2 3 7 5 8 5 7 6 9 10 8 7 8 10 9 11 12 12 10 9 13 11 14 11 13 12 15 16 14 13 14 16 15 17 18 18 16 15 19 17 20 17 19 18 21 22 20 19 20 22 21 23 24 24 22 21 25 23 26 23 25 24 27 28 26 25 26 28 27 29 30 30 28 27 31 29 32 29 31 30 33 34 32 31 32 34 33 35 36 36 34 33 35 37 36 38 0 39 39 40 41 38 39 41 42 40 43 40 42 41 44 45 46 45 42 43 47 48 44 44 46 47 48 49 50 49 48 47 51 52 53 50 49 53 51 54 55 55 52 51 56 57 54 54 57 55 58 56 59 54 60 59 38 1 0 46 45 43 59 56 54 53 52 50 61 58 62 58 61 56 63 64 62 61 62 64 65 66 63 66 64 63 65 67 66 68 67 69 65 69 67 70 71 68 68 69 70 71 72 73 72 71 70 72 37 73 73 37 35 74 75 76 77 78 79 80 81 82 83 84 85 86 78 87 77 79 88 78 77 87 89 86 87 82 88 79 85 81 80 81 88 82 84 83 74 85 80 83 76 75 90 84 74 76 91 90 92 75 92 90 91 93 94 93 91 92 95 96 94 94 93 95 97 96 95 97 98 99 99 96 97 100 101 98 99 98 101 102 103 104 100 105 101 106 107 108 108 109 106 109 104 103 109 103 106 100 102 105 105 102 104 110 111 112 113 110 114 115 114 116 114 117 116 118 110 119 110 112 119 114 120 117 121 120 114 122 123 110 122 110 118 110 124 125 123 124 110 110 125 126 127 110 113 114 115 128 110 126 114 114 129 121 130 114 131 130 129 114 114 126 132 132 131 114 133 134 135 133 135 136 137 138 139 137 139 140 141 142 143 141 143 144 145 146 147 148 149 145 145 147 148 149 150 151 150 149 148 152 151 153 150 153 151 154 155 152 152 153 154 147 146 156 157 156 158 146 158 156 159 160 157 157 158 159 160 161 162 161 160 159 161 163 162 162 163 164 165 166 167 167 168 165 169 170 171 171 172 169 173 174 175 176 177 178 179 180 181 182 183 184 185 184 186 183 186 184 187 188 185 185 186 187 188 189 190 189 188 187 190 189 176 191 178 177 178 190 176 177 192 191 193 194 192 191 192 194 193 195 196 196 194 193 195 197 196 197 198 199 195 198 197 197 200 201 199 200 197 201 202 197 180 203 204 203 180 205 202 205 180 179 197 180 202 180 197 206 207 175 181 208 175 206 175 209 175 207 210 175 211 173 174 209 175 179 181 175 211 175 208 175 212 179 175 213 212

+

0 1 2 3 2 4 1 4 2 5 6 3 3 4 5 6 7 8 7 6 5 9 8 10 7 10 8 11 12 9 9 10 11 12 13 14 13 12 11 15 14 16 13 16 14 17 18 15 15 16 17 18 19 20 19 18 17 21 20 22 19 22 20 23 24 21 21 22 23 24 25 26 25 24 23 27 26 28 25 28 26 29 30 27 27 28 29 30 31 32 31 30 29 33 32 34 31 34 32 35 36 33 33 34 35 37 36 35 37 38 36 1 0 39 40 41 42 39 40 42 41 43 44 43 41 40 45 46 44 43 45 44 47 48 49 46 49 48 47 50 51 51 48 47 52 53 54 51 50 53 55 56 52 52 54 55 56 57 58 57 56 55 57 59 58 60 61 62 59 62 58 42 1 39 49 46 45 61 58 62 50 54 53 63 60 64 60 63 61 65 66 64 63 64 66 67 68 65 68 66 65 67 69 68 70 69 71 67 71 69 72 73 70 70 71 72 73 74 75 74 73 72 74 38 75 75 38 37 76 77 78 79 80 81 82 83 79 84 85 86 87 88 89 90 81 80 88 90 89 91 87 89 81 90 88 86 83 82 83 80 79 85 84 76 86 82 84 78 77 92 85 76 78 93 92 94 77 94 92 93 95 96 95 93 94 97 98 96 96 95 97 97 99 98 99 100 101 101 98 99 102 103 100 101 100 103 104 105 106 102 106 103 107 108 109 110 111 112 109 110 112 112 107 109 105 104 111 105 111 110 104 106 102 113 114 115 116 113 117 118 117 119 117 120 119 121 122 113 121 113 115 117 123 120 124 123 117 113 125 126 122 125 113 127 113 128 113 126 128 129 130 113 129 113 127 131 113 116 117 118 132 113 130 117 117 133 124 134 117 135 134 133 117 117 130 136 136 135 117 137 138 139 137 139 140 141 142 143 141 143 144 145 146 147 145 147 148 149 150 151 152 153 151 149 151 153 152 154 155 155 153 152 156 154 157 154 156 155 158 159 157 156 157 159 160 159 158 161 150 149 162 161 163 161 162 150 164 165 163 162 163 165 164 166 167 167 165 164 168 166 169 166 168 167 168 169 170 171 172 173 173 174 171 175 176 177 177 178 175 179 180 181 182 183 184 185 186 187 188 189 190 191 189 192 189 191 190 193 194 192 191 192 194 193 195 196 196 194 193 196 195 184 183 182 197 184 195 182 198 183 197 199 198 200 197 200 198 201 202 199 199 200 201 202 203 204 203 202 201 204 205 206 203 205 204 204 207 208 206 207 204 208 209 204 186 210 211 210 186 212 209 212 186 185 204 186 209 186 204 213 214 181 187 215 181 216 181 214 181 216 217 181 180 218 181 218 213 215 219 181 219 179 181 185 181 220 187 181 185 181 221 220

- -0.0625 -0.016 4.03886e-16 -0.0624198 -0.016 0.00316557 -0.0625 0.016 3.19189e-16 7.65404e-18 -0.016 -0.0625 7.65404e-18 0.016 -0.0625 0.00316557 0.016 -0.0624198 -0.0624198 0.016 0.00316557 -0.0621793 -0.016 0.00632302 -0.0617793 -0.016 0.00946424 -0.0621793 0.016 0.00632302 -0.0612206 -0.016 0.0125812 -0.0617793 0.016 0.00946424 -0.0612206 0.016 0.0125812 -0.0605048 -0.016 0.0156658 -0.0596337 -0.016 0.0187102 -0.0605048 0.016 0.0156658 -0.0586095 -0.016 0.0217066 -0.0596337 0.016 0.0187102 -0.0586095 0.016 0.0217066 -0.0574349 -0.016 0.0246472 -0.0561128 -0.016 0.0275246 -0.0574349 0.016 0.0246472 -0.0546467 -0.016 0.0303314 -0.0561128 0.016 0.0275246 -0.0546467 0.016 0.0303314 -0.0530403 -0.016 0.0330602 -0.0512977 -0.016 0.0357043 -0.0530403 0.016 0.0330602 -0.0494235 -0.016 0.0382566 -0.0512977 0.016 0.0357043 -0.0494235 0.016 0.0382566 -0.0474224 -0.016 0.0407108 -0.0452995 -0.016 0.0430604 -0.0474224 0.016 0.0407108 -0.0430604 -0.016 0.0452995 -0.0452995 0.016 0.0430604 -0.0430604 0.016 0.0452995 -0.0407108 -0.016 0.0474224 -0.0382566 -0.016 0.0494235 -0.0407108 0.016 0.0474224 -0.0357043 -0.016 0.0512977 -0.0382566 0.016 0.0494235 -0.0357043 0.016 0.0512977 -0.0330602 -0.016 0.0530403 -0.0303314 -0.016 0.0546467 -0.0330602 0.016 0.0530403 -0.0275246 -0.016 0.0561128 -0.0303314 0.016 0.0546467 -0.0275246 0.016 0.0561128 -0.0246472 -0.016 0.0574349 -0.0217066 -0.016 0.0586095 -0.0246472 0.016 0.0574349 -0.0187102 -0.016 0.0596337 -0.0217066 0.016 0.0586095 -0.0187102 0.016 0.0596337 -0.0156658 -0.016 0.0605048 -0.0125812 -0.016 0.0612206 -0.0156658 0.016 0.0605048 -0.00946424 -0.016 0.0617793 -0.0125812 0.016 0.0612206 -0.00946424 0.016 0.0617793 -0.00632302 -0.016 0.0621793 -0.00316557 -0.016 0.0624198 -0.00632302 0.016 0.0621793 -1.53081e-17 -0.016 0.0625 -0.00316557 0.016 0.0624198 -1.53081e-17 0.016 0.0625 -0.0624198 0.016 -0.00316557 -0.0621793 0.016 -0.00632302 -0.0624198 -0.016 -0.00316557 -0.0617793 0.016 -0.00946424 -0.0621793 -0.016 -0.00632302 -0.0617793 -0.016 -0.00946424 -0.0612206 0.016 -0.0125812 -0.0605048 0.016 -0.0156658 -0.0612206 -0.016 -0.0125812 -0.0596337 0.016 -0.0187102 -0.0605048 -0.016 -0.0156658 -0.0596337 -0.016 -0.0187102 -0.0586095 0.016 -0.0217066 -0.0574349 0.016 -0.0246472 -0.0586095 -0.016 -0.0217066 -0.0561128 0.016 -0.0275246 -0.0574349 -0.016 -0.0246472 -0.0561128 -0.016 -0.0275246 -0.0546467 0.016 -0.0303314 -0.0530403 0.016 -0.0330602 -0.0546467 -0.016 -0.0303314 -0.0512977 0.016 -0.0357043 -0.0530403 -0.016 -0.0330602 -0.0512977 -0.016 -0.0357043 -0.0494235 0.016 -0.0382566 -0.0474224 0.016 -0.0407108 -0.0494235 -0.016 -0.0382566 -0.0452995 0.016 -0.0430604 -0.0474224 -0.016 -0.0407108 -0.0452995 -0.016 -0.0430604 -0.0430604 0.016 -0.0452995 -0.0407108 0.016 -0.0474224 -0.0430604 -0.016 -0.0452995 -0.0382566 0.016 -0.0494235 -0.0407108 -0.016 -0.0474224 -0.0382566 -0.016 -0.0494235 -0.0357043 0.016 -0.0512977 -0.0330602 0.016 -0.0530403 -0.0357043 -0.016 -0.0512977 -0.0303314 0.016 -0.0546467 -0.0330602 -0.016 -0.0530403 -0.0303314 -0.016 -0.0546467 -0.0275246 0.016 -0.0561128 -0.0246472 0.016 -0.0574349 -0.0275246 -0.016 -0.0561128 -0.0217066 0.016 -0.0586095 -0.0246472 -0.016 -0.0574349 -0.0217066 -0.016 -0.0586095 -0.0187102 0.016 -0.0596337 -0.0156658 0.016 -0.0605048 -0.0187102 -0.016 -0.0596337 -0.0125812 0.016 -0.0612206 -0.0156658 -0.016 -0.0605048 -0.0125812 -0.016 -0.0612206 -0.00946424 0.016 -0.0617793 -0.00632302 0.016 -0.0621793 -0.00946424 -0.016 -0.0617793 -0.00316557 0.016 -0.0624198 -0.00632302 -0.016 -0.0621793 -0.00316557 -0.016 -0.0624198 0.00632302 -0.016 -0.0621793 0.00316557 -0.016 -0.0624198 0.00632302 0.016 -0.0621793 0.0156658 -0.016 -0.0605048 0.0125812 -0.016 -0.0612206 0.0156658 0.016 -0.0605048 0.00946424 -0.016 -0.0617793 0.00946424 0.016 -0.0617793 0.0125812 0.016 -0.0612206 0.0217066 -0.016 -0.0586095 0.0246472 0.016 -0.0574349 0.0246472 -0.016 -0.0574349 0.0187102 0.016 -0.0596337 0.0217066 0.016 -0.0586095 0.0187102 -0.016 -0.0596337 0.0330602 0.016 -0.0530403 0.0330602 -0.016 -0.0530403 0.0303314 -0.016 -0.0546467 0.0303314 0.016 -0.0546467 0.0275246 -0.016 -0.0561128 0.0275246 0.016 -0.0561128 0.0407108 -0.016 -0.0474224 0.0382566 -0.016 -0.0494235 0.0407108 0.016 -0.0474224 0.0357043 -0.016 -0.0512977 0.0357043 0.016 -0.0512977 0.0382566 0.016 -0.0494235 0.0452995 -0.016 -0.0430604 0.0474224 0.016 -0.0407108 0.0474224 -0.016 -0.0407108 0.0430604 0.016 -0.0452995 0.0452995 0.016 -0.0430604 0.0430604 -0.016 -0.0452995 0.0530403 0.016 -0.0330602 0.0530403 -0.016 -0.0330602 0.0512977 -0.016 -0.0357043 0.0512977 0.016 -0.0357043 0.0494235 -0.016 -0.0382566 0.0494235 0.016 -0.0382566 0.0574349 -0.016 -0.0246472 0.0561128 -0.016 -0.0275246 0.0574349 0.016 -0.0246472 0.0546467 -0.016 -0.0303314 0.0546467 0.016 -0.0303314 0.0561128 0.016 -0.0275246 0.0596337 -0.016 -0.0187102 0.0605048 0.016 -0.0156658 0.0605048 -0.016 -0.0156658 0.0586095 0.016 -0.0217066 0.0596337 0.016 -0.0187102 0.0586095 -0.016 -0.0217066 0.0621793 0.016 -0.00632302 0.0621793 -0.016 -0.00632302 0.0617793 -0.016 -0.00946424 0.0617793 0.016 -0.00946424 0.0612206 -0.016 -0.0125812 0.0612206 0.016 -0.0125812 0.0624198 -0.016 0.00316557 0.0625 -0.016 1.57772e-33 0.0624198 0.016 0.00316557 0.0624198 -0.016 -0.00316557 0.0624198 0.016 -0.00316557 0.0625 0.016 1.57772e-33 0.0617793 -0.016 0.00946424 0.0612206 0.016 0.0125812 0.0612206 -0.016 0.0125812 0.0621793 0.016 0.00632302 0.0617793 0.016 0.00946424 0.0621793 -0.016 0.00632302 0.0586095 0.016 0.0217066 0.0586095 -0.016 0.0217066 0.0596337 -0.016 0.0187102 0.0596337 0.016 0.0187102 0.0605048 -0.016 0.0156658 0.0605048 0.016 0.0156658 0.0546467 -0.016 0.0303314 0.0561128 -0.016 0.0275246 0.0546467 0.016 0.0303314 0.0574349 -0.016 0.0246472 0.0574349 0.016 0.0246472 0.0561128 0.016 0.0275246 0.0512977 -0.016 0.0357043 0.0494235 0.016 0.0382566 0.0494235 -0.016 0.0382566 0.0530403 0.016 0.0330602 0.0512977 0.016 0.0357043 0.0530403 -0.016 0.0330602 0.0430604 0.016 0.0452995 0.0430604 -0.016 0.0452995 0.0452995 -0.016 0.0430604 0.0452995 0.016 0.0430604 0.0474224 -0.016 0.0407108 0.0474224 0.016 0.0407108 0.0407108 0.016 0.0474224 0.0407108 -0.016 0.0474224 0.0382566 -0.016 0.0494235 0.0382566 0.016 0.0494235 0.0357043 0.016 0.0512977 0.0357043 -0.016 0.0512977 0.0330602 0.016 0.0530403 0.0330602 -0.016 0.0530403 0.0303314 -0.016 0.0546467 0.0303314 0.016 0.0546467 0.0275246 0.016 0.0561128 0.0275246 -0.016 0.0561128 0.0246472 0.016 0.0574349 0.0246472 -0.016 0.0574349 0.0217066 -0.016 0.0586095 0.0217066 0.016 0.0586095 0.0187102 0.016 0.0596337 0.0187102 -0.016 0.0596337 0.0156658 0.016 0.0605048 0.0156658 -0.016 0.0605048 0.0125812 -0.016 0.0612206 0.0125812 0.016 0.0612206 0.00946424 0.016 0.0617793 0.00946424 -0.016 0.0617793 0.00632302 0.016 0.0621793 0.00632302 -0.016 0.0621793 0.00316557 -0.016 0.0624198 0.00316557 0.016 0.0624198 0.0561128 -0.016 -0.0275246 0.00328892 -0.016 -0.00119707 0.00303109 -0.016 -0.00175 0.00632302 -0.016 0.0621793 0.000607769 -0.016 0.00344683 0.00946424 -0.016 0.0617793 0.0605048 -0.016 -0.0156658 0.00344683 -0.016 -0.000607769 -0.00268116 -0.016 0.00224976 -0.0512977 -0.016 0.0357043 -0.00303109 -0.016 0.00175 0.0035 -0.016 4.31441e-18 0.0621793 -0.016 -0.00632302 0.0624198 -0.016 -0.00316557 -0.0452995 -0.016 0.0430604 -0.0474224 -0.016 0.0407108 0.0617793 -0.016 0.00946424 0.00344683 -0.016 0.000607769 0.0621793 -0.016 0.00632302 -0.00224976 -0.016 0.00268116 -0.0382566 -0.016 0.0494235 -0.0407108 -0.016 0.0474224 0.00328892 -0.016 0.00119707 0.0605048 -0.016 0.0156658 0.0596337 -0.016 0.0187102 -0.00175 -0.016 0.00303109 -0.0303314 -0.016 0.0546467 -0.0330602 -0.016 0.0530403 0.0561128 -0.016 0.0275246 0.0546467 -0.016 0.0303314 0.00303109 -0.016 0.00175 -0.0246472 -0.016 0.0574349 -0.00119707 -0.016 0.00328892 -0.0217066 -0.016 0.0586095 0.0512977 -0.016 0.0357043 0.00268116 -0.016 0.00224976 -0.000607769 -0.016 0.00344683 -0.0125812 -0.016 0.0612206 -0.0156658 -0.016 0.0605048 0.0452995 -0.016 0.0430604 0.00224976 -0.016 0.00268116 0 -0.016 0.0035 -0.00316557 -0.016 0.0624198 -0.00632302 -0.016 0.0621793 0.0357043 -0.016 0.0512977 0.0382566 -0.016 0.0494235 0.00316557 -0.016 0.0624198 0.0187102 -0.016 0.0596337 0.00119707 -0.016 0.00328892 0.0217066 -0.016 0.0586095 0.0156658 -0.016 0.0605048 0.0246472 -0.016 0.0574349 0.00175 -0.016 0.00303109 0.0275246 -0.016 0.0561128 0.0303314 -0.016 0.0546467 0.0330602 -0.016 0.0530403 0.0407108 -0.016 0.0474224 0.0125812 -0.016 0.0612206 -1.53081e-17 -0.016 0.0625 0.0430604 -0.016 0.0452995 0.0494235 -0.016 0.0382566 0.0474224 -0.016 0.0407108 -0.00946424 -0.016 0.0617793 0.0530403 -0.016 0.0330602 -0.0187102 -0.016 0.0596337 0.0586095 -0.016 0.0217066 0.0574349 -0.016 0.0246472 -0.0275246 -0.016 0.0561128 0.0612206 -0.016 0.0125812 -0.0357043 -0.016 0.0512977 0.0625 -0.016 1.57772e-33 0.0624198 -0.016 0.00316557 -0.0430604 -0.016 0.0452995 0.0617793 -0.016 -0.00946424 0.0612206 -0.016 -0.0125812 -0.0494235 -0.016 0.0382566 0.0574349 -0.016 -0.0246472 0.0586095 -0.016 -0.0217066 0.0596337 -0.016 -0.0187102 -0.0546467 -0.016 0.0303314 -0.0561128 -0.016 0.0275246 -0.0530403 -0.016 0.0330602 -0.00328892 -0.016 0.00119707 0.0546467 -0.016 -0.0303314 0.0512977 -0.016 -0.0357043 0.0530403 -0.016 -0.0330602 0.00268116 -0.016 -0.00224976 0.0474224 -0.016 -0.0407108 0.0494235 -0.016 -0.0382566 -0.0586095 -0.016 0.0217066 -0.0596337 -0.016 0.0187102 0.0452995 -0.016 -0.0430604 0.00224976 -0.016 -0.00268116 -0.0605048 -0.016 0.0156658 0.0430604 -0.016 -0.0452995 -0.00344683 -0.016 0.000607769 0.0407108 -0.016 -0.0474224 0.0382566 -0.016 -0.0494235 -0.0612206 -0.016 0.0125812 -0.0617793 -0.016 0.00946424 0.00175 -0.016 -0.00303109 0.0357043 -0.016 -0.0512977 -0.0621793 -0.016 0.00632302 0.0330602 -0.016 -0.0530403 -0.0035 -0.016 -3.53725e-18 -0.0624198 -0.016 0.00316557 -0.0625 -0.016 4.03886e-16 -0.0624198 -0.016 -0.00316557 0.0275246 -0.016 -0.0561128 0.0303314 -0.016 -0.0546467 -0.00344683 -0.016 -0.000607769 0.00119707 -0.016 -0.00328892 -0.0617793 -0.016 -0.00946424 -0.0621793 -0.016 -0.00632302 0.0246472 -0.016 -0.0574349 0.0217066 -0.016 -0.0586095 -0.0612206 -0.016 -0.0125812 0.0187102 -0.016 -0.0596337 -0.0605048 -0.016 -0.0156658 0.000607769 -0.016 -0.00344683 0.0156658 -0.016 -0.0605048 -0.00328892 -0.016 -0.00119707 0.00946424 -0.016 -0.0617793 0.0125812 -0.016 -0.0612206 0.00632302 -0.016 -0.0621793 -0.0586095 -0.016 -0.0217066 -0.0574349 -0.016 -0.0246472 0.00316557 -0.016 -0.0624198 -1.12569e-18 -0.016 -0.0035 -0.00303109 -0.016 -0.00175 7.65404e-18 -0.016 -0.0625 -0.0546467 -0.016 -0.0303314 -0.0530403 -0.016 -0.0330602 -0.00316557 -0.016 -0.0624198 -0.000607769 -0.016 -0.00344683 -0.00268116 -0.016 -0.00224976 -0.0512977 -0.016 -0.0357043 -0.0494235 -0.016 -0.0382566 -0.0125812 -0.016 -0.0612206 -0.00946424 -0.016 -0.0617793 -0.0452995 -0.016 -0.0430604 -0.00224976 -0.016 -0.00268116 -0.0156658 -0.016 -0.0605048 -0.00119707 -0.016 -0.00328892 -0.0187102 -0.016 -0.0596337 -0.0407108 -0.016 -0.0474224 -0.0382566 -0.016 -0.0494235 -0.00175 -0.016 -0.00303109 -0.0246472 -0.016 -0.0574349 -0.0357043 -0.016 -0.0512977 -0.0303314 -0.016 -0.0546467 -0.0330602 -0.016 -0.0530403 -0.0275246 -0.016 -0.0561128 -0.0430604 -0.016 -0.0452995 -0.0217066 -0.016 -0.0586095 -0.0474224 -0.016 -0.0407108 -0.00632302 -0.016 -0.0621793 -0.0561128 -0.016 -0.0275246 -0.0574349 -0.016 0.0246472 -0.0596337 -0.016 -0.0187102 0.0605048 0.016 -0.0156658 0.0596337 0.016 -0.0187102 0.00328892 0.016 -0.00119707 0.0217066 0.016 0.0586095 0.0246472 0.016 0.0574349 0.00119707 0.016 0.00328892 0.00344683 0.016 -0.000607769 0.0621793 0.016 -0.00632302 0.0617793 0.016 -0.00946424 -0.0430604 0.016 0.0452995 -0.00224976 0.016 0.00268116 -0.0452995 0.016 0.0430604 0.0035 0.016 -1.58917e-17 0.0624198 0.016 0.00316557 0.0625 0.016 1.57772e-33 -0.0330602 0.016 0.0530403 -0.00175 0.016 0.00303109 -0.0357043 0.016 0.0512977 0.00344683 0.016 0.000607769 0.0612206 0.016 0.0125812 0.0617793 0.016 0.00946424 -0.0217066 0.016 0.0586095 -0.00119707 0.016 0.00328892 -0.0246472 0.016 0.0574349 0.0586095 0.016 0.0217066 0.0596337 0.016 0.0187102 0.00328892 0.016 0.00119707 -0.00946424 0.016 0.0617793 -0.000607769 0.016 0.00344683 -0.0125812 0.016 0.0612206 0.00303109 0.016 0.00175 0.0561128 0.016 0.0275246 0.0574349 0.016 0.0246472 -1.53081e-17 0.016 0.0625 0 0.016 0.0035 -0.00316557 0.016 0.0624198 0.0530403 0.016 0.0330602 0.0512977 0.016 0.0357043 0.000607769 0.016 0.00344683 0.00316557 0.016 0.0624198 0.00632302 0.016 0.0621793 0.0494235 0.016 0.0382566 0.00268116 0.016 0.00224976 0.0474224 0.016 0.0407108 0.0156658 0.016 0.0605048 0.0125812 0.016 0.0612206 0.0452995 0.016 0.0430604 0.00224976 0.016 0.00268116 0.0430604 0.016 0.0452995 0.0187102 0.016 0.0596337 0.0330602 0.016 0.0530403 0.00175 0.016 0.00303109 0.0303314 0.016 0.0546467 0.0275246 0.016 0.0561128 0.0357043 0.016 0.0512977 0.0382566 0.016 0.0494235 0.0407108 0.016 0.0474224 0.00946424 0.016 0.0617793 0.0546467 0.016 0.0303314 -0.00632302 0.016 0.0621793 0.0605048 0.016 0.0156658 -0.0187102 0.016 0.0596337 -0.0156658 0.016 0.0605048 0.0621793 0.016 0.00632302 -0.0303314 0.016 0.0546467 -0.0275246 0.016 0.0561128 0.0624198 0.016 -0.00316557 -0.0407108 0.016 0.0474224 -0.0382566 0.016 0.0494235 0.0612206 0.016 -0.0125812 -0.0494235 0.016 0.0382566 -0.0474224 0.016 0.0407108 -0.00268116 0.016 0.00224976 -0.0512977 0.016 0.0357043 -0.00303109 0.016 0.00175 -0.0530403 0.016 0.0330602 0.00303109 0.016 -0.00175 0.0561128 0.016 -0.0275246 0.0546467 0.016 -0.0303314 -0.0561128 0.016 0.0275246 -0.0546467 0.016 0.0303314 0.0530403 0.016 -0.0330602 -0.00328892 0.016 0.00119707 0.00268116 0.016 -0.00224976 0.0512977 0.016 -0.0357043 -0.0586095 0.016 0.0217066 -0.0574349 0.016 0.0246472 0.0494235 0.016 -0.0382566 -0.0605048 0.016 0.0156658 -0.0596337 0.016 0.0187102 0.0474224 0.016 -0.0407108 -0.00344683 0.016 0.000607769 0.0452995 0.016 -0.0430604 -0.0612206 0.016 0.0125812 -0.0617793 0.016 0.00946424 -0.0621793 0.016 0.00632302 -0.0035 0.016 5.78862e-18 -0.0624198 0.016 0.00316557 0.0430604 0.016 -0.0452995 0.00224976 0.016 -0.00268116 -0.0625 0.016 3.19189e-16 0.0407108 0.016 -0.0474224 -0.0624198 0.016 -0.00316557 -0.00344683 0.016 -0.000607769 0.0382566 0.016 -0.0494235 -0.0621793 0.016 -0.00632302 -0.0617793 0.016 -0.00946424 0.0357043 0.016 -0.0512977 0.00175 0.016 -0.00303109 -0.0612206 0.016 -0.0125812 0.0330602 0.016 -0.0530403 -0.00328892 0.016 -0.00119707 -0.0605048 0.016 -0.0156658 0.0303314 0.016 -0.0546467 -0.0596337 0.016 -0.0187102 0.0275246 0.016 -0.0561128 -0.0586095 0.016 -0.0217066 -0.0574349 0.016 -0.0246472 0.0246472 0.016 -0.0574349 0.00119707 0.016 -0.00328892 -0.00303109 0.016 -0.00175 0.0217066 0.016 -0.0586095 -0.0512977 0.016 -0.0357043 -0.0530403 0.016 -0.0330602 0.0156658 0.016 -0.0605048 0.000607769 0.016 -0.00344683 -0.0452995 0.016 -0.0430604 -0.0474224 0.016 -0.0407108 -0.00268116 0.016 -0.00224976 0.00632302 0.016 -0.0621793 0.00946424 0.016 -0.0617793 -0.0407108 0.016 -0.0474224 -0.00224976 0.016 -0.00268116 -0.0382566 0.016 -0.0494235 -0.00316557 0.016 -0.0624198 -1.20059e-17 0.016 -0.0035 7.65404e-18 0.016 -0.0625 -0.0330602 0.016 -0.0530403 -0.00175 0.016 -0.00303109 -0.0303314 0.016 -0.0546467 -0.0125812 0.016 -0.0612206 -0.000607769 0.016 -0.00344683 -0.00946424 0.016 -0.0617793 -0.0275246 0.016 -0.0561128 -0.0246472 0.016 -0.0574349 -0.00119707 0.016 -0.00328892 -0.0187102 0.016 -0.0596337 -0.0217066 0.016 -0.0586095 -0.0156658 0.016 -0.0605048 -0.0357043 0.016 -0.0512977 -0.00632302 0.016 -0.0621793 -0.0430604 0.016 -0.0452995 0.00316557 0.016 -0.0624198 -0.0494235 0.016 -0.0382566 0.0125812 0.016 -0.0612206 -0.0546467 0.016 -0.0303314 -0.0561128 0.016 -0.0275246 0.0187102 0.016 -0.0596337 0.0586095 0.016 -0.0217066 0.0574349 0.016 -0.0246472 -0.0035 0.016 5.78862e-18 -0.00344683 -0.016 0.000607769 -0.0035 -0.016 -3.53725e-18 -1.12569e-18 -0.016 -0.0035 0.000607769 0.016 -0.00344683 -1.20059e-17 0.016 -0.0035 -0.00328892 -0.016 0.00119707 -0.00344683 0.016 0.000607769 -0.00328892 0.016 0.00119707 -0.00303109 -0.016 0.00175 -0.00303109 0.016 0.00175 -0.00268116 -0.016 0.00224976 -0.00224976 -0.016 0.00268116 -0.00268116 0.016 0.00224976 -0.00224976 0.016 0.00268116 -0.00175 -0.016 0.00303109 -0.00175 0.016 0.00303109 -0.00119707 -0.016 0.00328892 -0.000607769 -0.016 0.00344683 -0.00119707 0.016 0.00328892 -0.000607769 0.016 0.00344683 0 -0.016 0.0035 0 0.016 0.0035 -0.00344683 0.016 -0.000607769 -0.00344683 -0.016 -0.000607769 -0.00328892 0.016 -0.00119707 -0.00328892 -0.016 -0.00119707 -0.00303109 0.016 -0.00175 -0.00268116 0.016 -0.00224976 -0.00303109 -0.016 -0.00175 -0.00268116 -0.016 -0.00224976 -0.00224976 0.016 -0.00268116 -0.00224976 -0.016 -0.00268116 -0.00175 0.016 -0.00303109 -0.00119707 0.016 -0.00328892 -0.00175 -0.016 -0.00303109 -0.00119707 -0.016 -0.00328892 -0.000607769 0.016 -0.00344683 -0.000607769 -0.016 -0.00344683 0.00119707 -0.016 -0.00328892 0.00119707 0.016 -0.00328892 0.000607769 -0.016 -0.00344683 0.00268116 -0.016 -0.00224976 0.00268116 0.016 -0.00224976 0.00224976 -0.016 -0.00268116 0.00175 -0.016 -0.00303109 0.00224976 0.016 -0.00268116 0.00175 0.016 -0.00303109 0.00328892 -0.016 -0.00119707 0.00344683 -0.016 -0.000607769 0.00344683 0.016 -0.000607769 0.00303109 0.016 -0.00175 0.00303109 -0.016 -0.00175 0.00328892 0.016 -0.00119707 0.00328892 0.016 0.00119707 0.00344683 -0.016 0.000607769 0.00328892 -0.016 0.00119707 0.00344683 0.016 0.000607769 0.0035 0.016 -1.58917e-17 0.0035 -0.016 4.31441e-18 0.00224976 -0.016 0.00268116 0.00224976 0.016 0.00268116 0.00268116 -0.016 0.00224976 0.00303109 -0.016 0.00175 0.00268116 0.016 0.00224976 0.00303109 0.016 0.00175 0.00175 0.016 0.00303109 0.00175 -0.016 0.00303109 0.00119707 -0.016 0.00328892 0.00119707 0.016 0.00328892 0.000607769 -0.016 0.00344683 0.000607769 0.016 0.00344683 + -0.0622865 0.016 -0.00516121 -0.0622865 -0.016 0.00516121 -0.0622865 0.016 0.00516121 7.65404e-18 -0.016 -0.0625 7.65404e-18 0.016 -0.0625 0.0102872 0.016 -0.0616476 -0.0605875 0.016 0.0153428 -0.0605875 -0.016 0.0153428 -0.0572358 -0.016 0.025106 -0.0572358 0.016 0.025106 -0.0523229 -0.016 0.0341843 -0.0523229 0.016 0.0341843 -0.0459827 0.016 0.0423301 -0.0459827 -0.016 0.0423301 -0.0383883 -0.016 0.0493213 -0.0383883 0.016 0.0493213 -0.0297467 -0.016 0.0549671 -0.0297467 0.016 0.0549671 -0.0202937 0.016 0.0591136 -0.0202937 -0.016 0.0591136 -0.0102872 -0.016 0.0616476 -0.0102872 0.016 0.0616476 -1.53081e-17 -0.016 0.0625 -1.53081e-17 0.016 0.0625 -0.0622865 -0.016 -0.00516121 -0.0605875 0.016 -0.0153428 -0.0605875 -0.016 -0.0153428 -0.0572358 0.016 -0.025106 -0.0572358 -0.016 -0.025106 -0.0523229 -0.016 -0.0341843 -0.0523229 0.016 -0.0341843 -0.0459827 0.016 -0.0423301 -0.0459827 -0.016 -0.0423301 -0.0383883 0.016 -0.0493213 -0.0383883 -0.016 -0.0493213 -0.0297467 -0.016 -0.0549671 -0.0297467 0.016 -0.0549671 -0.0202937 0.016 -0.0591136 -0.0202937 -0.016 -0.0591136 -0.0102872 0.016 -0.0616476 -0.0102872 -0.016 -0.0616476 0.0202937 -0.016 -0.0591136 0.0102872 -0.016 -0.0616476 0.0202937 0.016 -0.0591136 0.0459827 -0.016 -0.0423301 0.0383883 -0.016 -0.0493213 0.0459827 0.016 -0.0423301 0.0297467 -0.016 -0.0549671 0.0297467 0.016 -0.0549671 0.0383883 0.016 -0.0493213 0.0572358 -0.016 -0.025106 0.0605875 0.016 -0.0153428 0.0605875 -0.016 -0.0153428 0.0523229 0.016 -0.0341843 0.0572358 0.016 -0.025106 0.0523229 -0.016 -0.0341843 0.0605875 0.016 0.0153428 0.0605875 -0.016 0.0153428 0.0622865 -0.016 0.00516121 0.0622865 0.016 0.00516121 0.0622865 -0.016 -0.00516121 0.0622865 0.016 -0.00516121 0.0459827 -0.016 0.0423301 0.0523229 -0.016 0.0341843 0.0459827 0.016 0.0423301 0.0572358 -0.016 0.025106 0.0572358 0.016 0.025106 0.0523229 0.016 0.0341843 0.0297467 0.016 0.0549671 0.0383883 -0.016 0.0493213 0.0383883 0.016 0.0493213 0.0202937 0.016 0.0591136 0.0297467 -0.016 0.0549671 0.0202937 -0.016 0.0591136 0.0102872 0.016 0.0616476 0.0102872 -0.016 0.0616476 0.0572358 -0.016 0.025106 0.0523229 -0.016 0.0341843 0.00293008 -0.016 0.00191432 0.0297467 -0.016 0.0549671 0.00214974 -0.016 0.00276199 0.0383883 -0.016 0.0493213 0.0202937 -0.016 0.0591136 0.00166582 -0.016 0.00307816 -0.0383883 -0.016 0.0493213 -0.00166582 -0.016 0.00307816 -0.0297467 -0.016 0.0549671 0.000576081 -0.016 0.00345226 0.0102872 -0.016 0.0616476 -1.53081e-17 -0.016 0.0625 0 -0.016 0.0035 -0.0102872 -0.016 0.0616476 -0.0202937 -0.016 0.0591136 -0.000576081 -0.016 0.00345226 0.00113645 -0.016 0.00331036 0.0459827 -0.016 0.0423301 0.00257503 -0.016 0.00237049 -0.00113645 -0.016 0.00331036 -0.00214974 -0.016 0.00276199 -0.00257503 -0.016 0.00237049 0.00320521 -0.016 0.00140593 0.0033929 -0.016 0.000859199 0.0605875 -0.016 0.0153428 -0.0459827 -0.016 0.0423301 -0.00293008 -0.016 0.00191432 0.0622865 -0.016 -0.00516121 0.0622865 -0.016 0.00516121 0.00348805 -0.016 0.000289028 -0.0523229 -0.016 0.0341843 -0.00320521 -0.016 0.00140593 0.00348805 -0.016 -0.000289028 0.0033929 -0.016 -0.000859199 0.0605875 -0.016 -0.0153428 -0.0033929 -0.016 0.000859199 -0.0572358 -0.016 0.025106 -0.0605875 -0.016 0.0153428 -0.00348805 -0.016 0.000289028 -0.0622865 -0.016 0.00516121 -0.00348805 -0.016 -0.000289028 0.0297467 -0.016 -0.0549671 0.0383883 -0.016 -0.0493213 0.00166582 -0.016 -0.00307816 -0.0622865 -0.016 -0.00516121 -0.0033929 -0.016 -0.000859199 -0.00320521 -0.016 -0.00140593 -0.0605875 -0.016 -0.0153428 -0.0572358 -0.016 -0.025106 -0.00293008 -0.016 -0.00191432 0.00113645 -0.016 -0.00331036 0.000576081 -0.016 -0.00345226 0.0202937 -0.016 -0.0591136 -0.0523229 -0.016 -0.0341843 -0.0459827 -0.016 -0.0423301 -1.12569e-18 -0.016 -0.0035 7.65404e-18 -0.016 -0.0625 0.0102872 -0.016 -0.0616476 -0.0102872 -0.016 -0.0616476 -0.000576081 -0.016 -0.00345226 -0.00113645 -0.016 -0.00331036 -0.00166582 -0.016 -0.00307816 -0.0297467 -0.016 -0.0549671 -0.0202937 -0.016 -0.0591136 -0.00214974 -0.016 -0.00276199 -0.00257503 -0.016 -0.00237049 -0.0383883 -0.016 -0.0493213 0.00257503 -0.016 -0.00237049 0.0459827 -0.016 -0.0423301 0.00320521 -0.016 -0.00140593 0.0523229 -0.016 -0.0341843 0.0572358 -0.016 -0.025106 0.00293008 -0.016 -0.00191432 0.00214974 -0.016 -0.00276199 0.00298035 0.016 0.00183508 0.00262735 0.016 0.00231236 0.0523229 0.016 0.0341843 0.00219877 0.016 0.00272313 0.0383883 0.016 0.0493213 0.0459827 0.016 0.0423301 0.00170693 0.016 0.00305555 0.000591503 0.016 0.00344966 -1.53081e-17 0.016 0.0625 0.0102872 0.016 0.0616476 0.0297467 0.016 0.0549671 0.0202937 0.016 0.0591136 0.00116599 0.016 0.00330007 0 0.016 0.0035 0.00324761 0.016 0.001305 0.0572358 0.016 0.025106 -0.0102872 0.016 0.0616476 0.00342144 0.016 0.000737377 0.0605875 0.016 0.0153428 -0.000591503 0.016 0.00344966 -0.00116599 0.016 0.00330007 -0.0202937 0.016 0.0591136 0.00349685 0.016 0.000148544 0.0622865 0.016 0.00516121 -0.00170693 0.016 0.00305555 -0.0383883 0.016 0.0493213 -0.0297467 0.016 0.0549671 -0.00298035 0.016 0.00183508 -0.0572358 0.016 0.025106 -0.0523229 0.016 0.0341843 0.0605875 0.016 -0.0153428 0.00334658 0.016 -0.00102488 0.00347165 0.016 -0.000444562 0.00312524 0.016 -0.00157571 0.0572358 0.016 -0.025106 -0.00324761 0.016 0.001305 -0.00342144 0.016 0.000737377 -0.0605875 0.016 0.0153428 -0.00349685 0.016 0.000148544 -0.0622865 0.016 -0.00516121 -0.0622865 0.016 0.00516121 -0.00347165 0.016 -0.000444562 -0.00334658 0.016 -0.00102488 -0.0605875 0.016 -0.0153428 0.00281399 0.016 -0.00208122 0.0523229 0.016 -0.0341843 -0.00312524 0.016 -0.00157571 -0.0523229 0.016 -0.0341843 -0.0572358 0.016 -0.025106 0.00242179 0.016 -0.00252685 0.0459827 0.016 -0.0423301 0.00144165 0.016 -0.0031893 0.0202937 0.016 -0.0591136 0.000881923 0.016 -0.00338707 -0.00242179 0.016 -0.00252685 -0.0459827 0.016 -0.0423301 -0.00281399 0.016 -0.00208122 7.65404e-18 0.016 -0.0625 -0.0102872 0.016 -0.0616476 -0.000296821 0.016 -0.00348739 -0.0202937 0.016 -0.0591136 -0.000881923 0.016 -0.00338707 0.0102872 0.016 -0.0616476 0.000296821 0.016 -0.00348739 -0.0383883 0.016 -0.0493213 -0.00195991 0.016 -0.00289978 -0.0297467 0.016 -0.0549671 -0.00144165 0.016 -0.0031893 0.0383883 0.016 -0.0493213 0.00195991 0.016 -0.00289978 0.0297467 0.016 -0.0549671 0.0622865 0.016 -0.00516121 -0.00219877 0.016 0.00272313 -0.00262735 0.016 0.00231236 -0.0459827 0.016 0.0423301 -0.00349685 0.016 0.000148544 -0.00348805 -0.016 0.000289028 -0.00348805 -0.016 -0.000289028 0.000296821 0.016 -0.00348739 -0.000296821 0.016 -0.00348739 -1.12569e-18 -0.016 -0.0035 -0.0033929 -0.016 0.000859199 -0.00342144 0.016 0.000737377 -0.00324761 0.016 0.001305 -0.00320521 -0.016 0.00140593 -0.00298035 0.016 0.00183508 -0.00293008 -0.016 0.00191432 -0.00257503 -0.016 0.00237049 -0.00262735 0.016 0.00231236 -0.00219877 0.016 0.00272313 -0.00214974 -0.016 0.00276199 -0.00170693 0.016 0.00305555 -0.00166582 -0.016 0.00307816 -0.00113645 -0.016 0.00331036 -0.00116599 0.016 0.00330007 -0.000591503 0.016 0.00344966 -0.000576081 -0.016 0.00345226 0 0.016 0.0035 0 -0.016 0.0035 -0.00347165 0.016 -0.000444562 -0.0033929 -0.016 -0.000859199 -0.00334658 0.016 -0.00102488 -0.00320521 -0.016 -0.00140593 -0.00312524 0.016 -0.00157571 -0.00281399 0.016 -0.00208122 -0.00293008 -0.016 -0.00191432 -0.00257503 -0.016 -0.00237049 -0.00242179 0.016 -0.00252685 -0.00214974 -0.016 -0.00276199 -0.00195991 0.016 -0.00289978 -0.00144165 0.016 -0.0031893 -0.00166582 -0.016 -0.00307816 -0.00113645 -0.016 -0.00331036 -0.000881923 0.016 -0.00338707 -0.000576081 -0.016 -0.00345226 0.00195991 0.016 -0.00289978 0.00144165 0.016 -0.0031893 0.00166582 -0.016 -0.00307816 0.000881923 0.016 -0.00338707 0.000576081 -0.016 -0.00345226 0.00113645 -0.016 -0.00331036 0.00293008 -0.016 -0.00191432 0.00312524 0.016 -0.00157571 0.00281399 0.016 -0.00208122 0.00214974 -0.016 -0.00276199 0.00257503 -0.016 -0.00237049 0.00242179 0.016 -0.00252685 0.00347165 0.016 -0.000444562 0.00348805 -0.016 -0.000289028 0.00349685 0.016 0.000148544 0.00334658 0.016 -0.00102488 0.00320521 -0.016 -0.00140593 0.0033929 -0.016 -0.000859199 0.00298035 0.016 0.00183508 0.00324761 0.016 0.001305 0.00320521 -0.016 0.00140593 0.0033929 -0.016 0.000859199 0.00342144 0.016 0.000737377 0.00348805 -0.016 0.000289028 0.00214974 -0.016 0.00276199 0.00219877 0.016 0.00272313 0.00257503 -0.016 0.00237049 0.00293008 -0.016 0.00191432 0.00262735 0.016 0.00231236 0.00170693 0.016 0.00305555 0.00166582 -0.016 0.00307816 0.00113645 -0.016 0.00331036 0.00116599 0.016 0.00330007 0.000576081 -0.016 0.00345226 0.000591503 0.016 0.00344966 - + @@ -110,9 +110,9 @@ - -1 0 1.19249e-08 -0.998717 0 0.050649 -1 0 1.19249e-08 -8.74228e-08 0 -1 -8.74228e-08 0 -1 0.0506491 0 -0.998717 -0.998716 0 0.0506494 -0.994869 0 0.101168 -0.988468 0 0.151428 -0.994869 0 0.101168 -0.97953 0 0.201299 -0.988468 0 0.151428 -0.97953 0 0.201299 -0.968077 0 0.250653 -0.954139 0 0.299363 -0.968077 0 0.250652 -0.937752 0 0.347305 -0.954139 0 0.299363 -0.937752 0 0.347306 -0.918958 0 0.394356 -0.897805 0 0.440394 -0.918958 0 0.394356 -0.874347 0 0.485302 -0.897805 0 0.440394 -0.874347 0 0.485302 -0.848644 0 0.528964 -0.820763 0 0.571268 -0.848644 0 0.528964 -0.790776 0 0.612106 -0.820763 0 0.571268 -0.790776 0 0.612106 -0.758758 0 0.651373 -0.724793 0 0.688967 -0.758758 0 0.651372 -0.688967 0 0.724793 -0.724793 0 0.688967 -0.688967 0 0.724793 -0.651372 0 0.758758 -0.612106 0 0.790776 -0.651372 0 0.758758 -0.571268 0 0.820763 -0.612106 0 0.790776 -0.571268 0 0.820763 -0.528964 0 0.848644 -0.485302 0 0.874347 -0.528964 0 0.848644 -0.440394 0 0.897805 -0.485302 0 0.874347 -0.440394 0 0.897804 -0.394356 0 0.918958 -0.347305 0 0.937752 -0.394356 0 0.918958 -0.299363 0 0.954139 -0.347305 0 0.937752 -0.299363 0 0.954139 -0.250653 0 0.968077 -0.201299 0 0.97953 -0.250653 0 0.968077 -0.151427 0 0.988468 -0.201298 0 0.97953 -0.151428 0 0.988468 -0.101168 0 0.994869 -0.0506492 0 0.998716 -0.101169 0 0.994869 1.74846e-07 0 1 -0.0506492 0 0.998716 -3.01992e-07 0 1 -0.998716 0 -0.0506494 -0.994869 0 -0.101168 -0.998717 0 -0.0506489 -0.988468 0 -0.151428 -0.994869 0 -0.101168 -0.988468 0 -0.151428 -0.97953 0 -0.201299 -0.968077 0 -0.250652 -0.97953 0 -0.201299 -0.954139 0 -0.299363 -0.968077 0 -0.250653 -0.954139 0 -0.299363 -0.937752 0 -0.347305 -0.918958 0 -0.394356 -0.937752 0 -0.347305 -0.897804 0 -0.440394 -0.918958 0 -0.394356 -0.897805 0 -0.440394 -0.874347 0 -0.485302 -0.848644 0 -0.528964 -0.874347 0 -0.485302 -0.820763 0 -0.571268 -0.848644 0 -0.528964 -0.820763 0 -0.571268 -0.790776 0 -0.612106 -0.758758 0 -0.651372 -0.790776 0 -0.612106 -0.724793 0 -0.688967 -0.758758 0 -0.651373 -0.724793 0 -0.688967 -0.688967 0 -0.724793 -0.651372 0 -0.758758 -0.688967 0 -0.724793 -0.612106 0 -0.790776 -0.651372 0 -0.758758 -0.612106 0 -0.790776 -0.571268 0 -0.820763 -0.528964 0 -0.848644 -0.571268 0 -0.820763 -0.485302 0 -0.874347 -0.528964 0 -0.848644 -0.485302 0 -0.874347 -0.440394 0 -0.897804 -0.394356 0 -0.918958 -0.440394 0 -0.897805 -0.347305 0 -0.937752 -0.394356 0 -0.918958 -0.347305 0 -0.937752 -0.299363 0 -0.954139 -0.250652 0 -0.968077 -0.299363 0 -0.954139 -0.201298 0 -0.97953 -0.250653 0 -0.968077 -0.201299 0 -0.97953 -0.151428 0 -0.988468 -0.101168 0 -0.994869 -0.151428 0 -0.988468 -0.0506493 0 -0.998716 -0.101168 0 -0.994869 -0.050649 0 -0.998717 0.101168 0 -0.994869 0.0506491 0 -0.998717 0.101168 0 -0.994869 0.250653 0 -0.968077 0.201298 0 -0.97953 0.250653 0 -0.968077 0.151428 0 -0.988468 0.151428 0 -0.988468 0.201298 0 -0.97953 0.347305 0 -0.937752 0.394356 0 -0.918958 0.394356 0 -0.918958 0.299363 0 -0.954139 0.347305 0 -0.937752 0.299363 0 -0.954139 0.528964 0 -0.848644 0.528964 0 -0.848644 0.485302 0 -0.874347 0.485302 0 -0.874347 0.440394 0 -0.897804 0.440394 0 -0.897804 0.651373 0 -0.758758 0.612106 0 -0.790776 0.651372 0 -0.758758 0.571268 0 -0.820763 0.571268 0 -0.820763 0.612106 0 -0.790776 0.724793 0 -0.688967 0.758758 0 -0.651373 0.758758 0 -0.651373 0.688967 0 -0.724793 0.724793 0 -0.688967 0.688967 0 -0.724793 0.848644 0 -0.528964 0.848644 0 -0.528964 0.820763 0 -0.571268 0.820764 0 -0.571268 0.790776 0 -0.612106 0.790776 0 -0.612106 0.918958 0 -0.394356 0.897804 0 -0.440394 0.918958 0 -0.394356 0.874347 0 -0.485302 0.874347 0 -0.485302 0.897804 0 -0.440394 0.954139 0 -0.299363 0.968077 0 -0.250652 0.968077 0 -0.250653 0.937752 0 -0.347305 0.954139 0 -0.299363 0.937752 0 -0.347305 0.994869 0 -0.101168 0.994869 0 -0.101168 0.988468 0 -0.151428 0.988468 0 -0.151428 0.97953 0 -0.201298 0.97953 0 -0.201298 0.998716 0 0.0506493 1 0 -4.37114e-08 0.998717 0 0.0506491 0.998717 0 -0.0506491 0.998717 0 -0.0506491 1 0 7.54979e-08 0.988468 0 0.151428 0.97953 0 0.201299 0.97953 0 0.201299 0.994869 0 0.101168 0.988468 0 0.151428 0.994869 0 0.101168 0.937752 0 0.347305 0.937752 0 0.347305 0.954139 0 0.299363 0.954139 0 0.299363 0.968077 0 0.250653 0.968077 0 0.250653 0.874347 0 0.485302 0.897804 0 0.440394 0.874347 0 0.485302 0.918958 0 0.394356 0.918958 0 0.394356 0.897805 0 0.440394 0.820763 0 0.571268 0.790776 0 0.612106 0.790776 0 0.612106 0.848644 0 0.528964 0.820763 0 0.571268 0.848644 0 0.528964 0.688967 0 0.724793 0.688967 0 0.724793 0.724793 0 0.688967 0.724793 0 0.688967 0.758758 0 0.651372 0.758758 0 0.651372 0.651372 0 0.758758 0.651372 0 0.758758 0.612106 0 0.790776 0.612106 0 0.790776 0.571268 0 0.820763 0.571268 0 0.820763 0.528964 0 0.848644 0.528964 0 0.848644 0.485302 0 0.874347 0.485302 0 0.874347 0.440394 0 0.897805 0.440394 0 0.897805 0.394356 0 0.918958 0.394356 0 0.918958 0.347305 0 0.937752 0.347305 0 0.937752 0.299363 0 0.954139 0.299363 0 0.954139 0.250653 0 0.968077 0.250653 0 0.968077 0.201299 0 0.97953 0.201299 0 0.97953 0.151428 0 0.988468 0.151428 0 0.988468 0.101168 0 0.994869 0.101168 0 0.994869 0.0506492 0 0.998717 0.0506492 0 0.998717 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 -1.19249e-08 0.984808 0 -0.173648 1 0 -1.19249e-08 8.74228e-08 0 1 -0.173648 0 0.984808 8.74228e-08 0 1 0.939693 0 -0.34202 0.984808 0 -0.173648 0.939693 0 -0.34202 0.866025 0 -0.5 0.866025 0 -0.5 0.766044 0 -0.642788 0.642788 0 -0.766044 0.766044 0 -0.642788 0.642788 0 -0.766044 0.5 0 -0.866026 0.5 0 -0.866026 0.34202 0 -0.939693 0.173648 0 -0.984808 0.34202 0 -0.939693 0.173648 0 -0.984808 -1.74846e-07 -0 -1 -1.74846e-07 -0 -1 0.984808 0 0.173648 0.984808 0 0.173648 0.939693 0 0.34202 0.939692 0 0.342021 0.866025 0 0.5 0.766045 0 0.642788 0.866025 0 0.5 0.766045 0 0.642788 0.642788 0 0.766044 0.642788 0 0.766044 0.5 0 0.866026 0.34202 0 0.939693 0.5 0 0.866025 0.34202 0 0.939693 0.173648 0 0.984808 0.173648 0 0.984808 -0.34202 0 0.939693 -0.34202 0 0.939693 -0.173648 0 0.984808 -0.766044 0 0.642788 -0.766044 0 0.642788 -0.642788 0 0.766044 -0.5 0 0.866025 -0.642788 0 0.766044 -0.5 0 0.866025 -0.939693 0 0.34202 -0.984808 0 0.173648 -0.984808 0 0.173648 -0.866025 0 0.5 -0.866025 0 0.5 -0.939693 0 0.34202 -0.939693 -0 -0.34202 -0.984808 -0 -0.173648 -0.939693 -0 -0.34202 -0.984808 -0 -0.173648 -1 -0 -7.54979e-08 -1 0 4.37114e-08 -0.642788 -0 -0.766044 -0.642788 -0 -0.766044 -0.766044 -0 -0.642788 -0.866025 -0 -0.5 -0.766044 -0 -0.642788 -0.866025 -0 -0.5 -0.5 -0 -0.866025 -0.5 -0 -0.866025 -0.34202 -0 -0.939693 -0.34202 -0 -0.939693 -0.173648 -0 -0.984808 -0.173648 -0 -0.984808 + -0.996584 0 -0.0825794 -0.996584 0 0.0825794 -0.996584 0 0.0825794 -8.74228e-08 0 -1 -8.74228e-08 0 -1 0.164595 0 -0.986361 -0.9694 0 0.245485 -0.9694 0 0.245486 -0.915773 0 0.401695 -0.915773 0 0.401695 -0.837166 0 0.546948 -0.837166 0 0.546948 -0.735724 0 0.677282 -0.735724 0 0.677282 -0.614213 0 0.78914 -0.614213 0 0.789141 -0.475948 0 0.879474 -0.475947 0 0.879474 -0.324699 0 0.945817 -0.3247 0 0.945817 -0.164595 0 0.986361 -0.164595 0 0.986361 1.74846e-07 0 1 -3.01992e-07 0 1 -0.996584 0 -0.0825794 -0.9694 0 -0.245486 -0.9694 0 -0.245486 -0.915773 0 -0.401695 -0.915773 0 -0.401695 -0.837167 0 -0.546948 -0.837167 0 -0.546948 -0.735724 0 -0.677282 -0.735724 0 -0.677282 -0.614213 0 -0.78914 -0.614213 0 -0.78914 -0.475947 0 -0.879474 -0.475947 0 -0.879474 -0.324699 0 -0.945817 -0.324699 0 -0.945817 -0.164595 0 -0.986361 -0.164595 0 -0.986361 0.3247 0 -0.945817 0.164595 0 -0.986361 0.324699 0 -0.945817 0.735724 0 -0.677282 0.614213 0 -0.789141 0.735724 0 -0.677282 0.475947 0 -0.879474 0.475947 0 -0.879474 0.614213 0 -0.78914 0.915773 0 -0.401695 0.9694 0 -0.245485 0.9694 0 -0.245485 0.837166 0 -0.546948 0.915773 0 -0.401695 0.837166 0 -0.546948 0.9694 0 0.245485 0.9694 0 0.245485 0.996584 0 0.0825794 0.996584 0 0.0825794 0.996584 0 -0.0825794 0.996584 0 -0.0825792 0.735724 0 0.677282 0.837166 0 0.546948 0.735724 0 0.677282 0.915773 0 0.401695 0.915773 0 0.401695 0.837166 0 0.546948 0.475947 0 0.879474 0.614213 0 0.789141 0.614213 0 0.789141 0.324699 0 0.945817 0.475947 0 0.879474 0.324699 0 0.945817 0.164595 0 0.986361 0.164595 0 0.986361 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.999099 0 -0.042441 0.996584 0 -0.0825794 0.996584 0 0.0825794 -0.0848059 0 0.996397 0.0848059 0 0.996397 8.74228e-08 0 1 0.9694 0 -0.245486 0.977555 0 -0.210679 0.927889 0 -0.372857 0.915773 0 -0.401695 0.851529 0 -0.524307 0.837166 0 -0.546948 0.735724 0 -0.677282 0.750672 0 -0.660675 0.62822 0 -0.778036 0.614213 0 -0.78914 0.487695 0 -0.873014 0.475948 0 -0.879474 0.3247 0 -0.945817 0.33314 0 -0.942877 0.169001 0 -0.985616 0.164595 0 -0.986361 3.01992e-07 0 -1 -1.74846e-07 -0 -1 0.9919 0 0.127018 0.9694 0 0.245486 0.956167 0 0.292823 0.915773 0 0.401695 0.892926 0 0.450204 0.803997 0 0.594633 0.837167 0 0.546948 0.735724 0 0.677282 0.691939 0 0.721956 0.614213 0 0.78914 0.559975 0 0.82851 0.411901 0 0.911228 0.475947 0 0.879474 0.324699 0 0.945817 0.251978 0 0.967733 0.164595 0 0.986361 -0.559975 0 0.82851 -0.411901 0 0.911228 -0.475947 0 0.879474 -0.251978 0 0.967733 -0.164595 0 0.986361 -0.3247 0 0.945817 -0.837166 0 0.546948 -0.892926 0 0.450204 -0.803997 0 0.594633 -0.614213 0 0.789141 -0.735724 0 0.677282 -0.691939 0 0.721956 -0.9919 0 0.127018 -0.996584 0 0.0825794 -0.999099 -0 -0.0424412 -0.956167 0 0.292823 -0.915773 0 0.401695 -0.9694 0 0.245485 -0.851529 -0 -0.524307 -0.927889 -0 -0.372857 -0.915773 -0 -0.401695 -0.9694 -0 -0.245485 -0.977555 -0 -0.210679 -0.996584 -0 -0.0825794 -0.614213 -0 -0.789141 -0.62822 -0 -0.778036 -0.735724 -0 -0.677282 -0.837166 -0 -0.546948 -0.750672 -0 -0.660675 -0.487695 -0 -0.873014 -0.475947 -0 -0.879474 -0.324699 -0 -0.945817 -0.33314 -0 -0.942877 -0.164595 -0 -0.986361 -0.169001 -0 -0.985616 - + @@ -123,9 +123,9 @@ - + -

0 1 2 3 4 5 6 1 7 1 6 2 8 9 7 6 7 9 8 10 11 11 9 8 12 10 13 10 12 11 14 15 13 12 13 15 14 16 17 17 15 14 18 16 19 16 18 17 20 21 19 18 19 21 20 22 23 23 21 20 24 22 25 22 24 23 26 27 25 24 25 27 26 28 29 29 27 26 30 28 31 28 30 29 32 33 31 30 31 33 32 34 35 35 33 32 36 34 37 34 36 35 38 39 37 36 37 39 38 40 41 41 39 38 42 40 43 40 42 41 44 45 43 42 43 45 44 46 47 47 45 44 48 46 49 46 48 47 50 51 49 48 49 51 50 52 53 53 51 50 54 52 55 52 54 53 56 57 55 54 55 57 56 58 59 59 57 56 60 58 61 58 60 59 62 63 61 60 61 63 62 64 65 65 63 62 64 66 65 67 0 2 68 69 67 0 67 69 68 70 71 71 69 68 72 70 73 70 72 71 74 75 73 72 73 75 74 76 77 77 75 74 78 76 79 76 78 77 80 81 79 78 79 81 80 82 83 83 81 80 84 82 85 82 84 83 86 87 85 84 85 87 86 88 89 89 87 86 90 88 91 88 90 89 92 93 91 90 91 93 92 94 95 95 93 92 96 94 97 94 96 95 98 99 97 96 97 99 98 100 101 101 99 98 102 100 103 100 102 101 104 105 103 102 103 105 104 106 107 107 105 104 108 106 109 106 108 107 110 111 109 108 109 111 110 112 113 113 111 110 114 112 115 112 114 113 116 117 115 114 115 117 116 118 119 119 117 116 120 118 121 118 120 119 122 123 121 120 121 123 122 124 125 125 123 122 126 124 4 124 126 125 127 128 129 126 4 3 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 215 220 221 220 215 214 222 221 223 220 223 221 224 225 222 222 223 224 225 226 227 226 225 224 228 227 229 226 229 227 230 231 228 228 229 230 231 232 233 232 231 230 234 233 235 232 235 233 236 237 234 234 235 236 237 238 239 238 237 236 240 239 241 238 241 239 242 243 240 240 241 242 243 244 245 244 243 242 246 245 247 244 247 245 66 64 246 246 247 66 217 216 218 214 216 217 209 219 210 219 218 210 213 212 208 212 209 208 202 204 211 202 211 213 203 205 207 203 207 204 206 197 196 205 197 206 199 198 200 196 198 199 191 201 192 201 200 192 195 194 190 194 191 190 184 186 193 184 193 195 185 187 189 185 189 186 188 179 178 187 179 188 181 180 182 178 180 181 173 183 174 183 182 174 177 176 172 176 173 172 166 168 175 166 175 177 167 169 171 167 171 168 170 161 160 169 161 170 163 162 164 160 162 163 155 165 156 165 164 156 159 158 154 158 155 154 148 150 157 148 157 159 149 151 153 149 153 150 152 143 142 151 143 152 145 144 146 142 144 145 137 147 138 147 146 138 141 140 136 140 137 136 130 132 139 130 139 141 131 133 135 131 135 132 134 127 129 133 127 134 5 128 3 129 128 5 248 249 250 251 252 253 254 255 249 256 257 258 259 260 261 262 263 256 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 278 284 285 286 283 287 288 289 290 291 292 288 293 252 251 294 295 296 297 296 298 252 297 296 299 300 301 299 298 296 295 300 302 301 300 288 292 302 300 303 293 288 304 252 305 253 289 294 306 307 304 288 306 290 289 283 308 309 287 283 309 310 285 284 284 291 310 278 277 311 278 311 282 280 312 281 284 286 280 313 314 270 314 278 270 315 274 273 280 279 315 316 265 264 270 265 271 273 317 267 275 317 273 259 261 318 259 319 265 262 267 320 320 267 269 321 255 322 260 255 321 256 323 257 256 263 323 249 324 325 326 254 249 327 328 258 258 329 327 328 330 258 248 250 331 250 332 333 334 335 336 337 338 330 339 334 340 338 341 330 342 339 340 343 330 341 344 340 345 343 346 347 348 349 340 343 347 350 348 351 349 350 352 343 353 354 352 352 354 355 356 357 348 355 358 352 359 356 348 360 358 361 362 359 363 364 358 360 365 363 359 364 366 358 359 367 368 369 358 366 370 371 367 272 313 270 367 372 370 369 373 374 375 372 376 374 377 369 376 378 375 377 379 380 381 376 382 383 384 385 382 386 387 383 388 389 390 391 392 393 394 389 395 396 391 389 397 395 398 395 399 397 389 394 395 397 399 395 400 396 395 398 400 389 388 401 389 401 393 402 392 391 396 402 391 383 385 403 383 403 388 386 382 390 382 391 390 377 380 384 383 377 384 404 381 382 387 404 382 405 377 374 379 377 405 381 378 376 334 336 332 337 330 406 366 407 369 373 369 407 355 361 358 350 353 352 341 346 343 328 406 330 257 329 258 262 256 267 317 268 267 315 273 280 286 312 280 291 284 289 294 289 252 298 305 252 299 296 300 292 303 300 287 307 288 282 308 283 314 276 278 265 316 271 266 265 319 318 319 259 260 259 255 254 322 255 325 326 249 324 249 248 250 333 331 332 250 334 335 334 339 342 340 344 340 349 345 357 351 348 362 356 359 359 368 365 368 367 371 367 376 372 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 438 445 446 447 448 449 450 451 452 446 453 454 455 456 413 457 411 458 459 460 412 461 459 459 458 462 459 462 455 460 459 461 463 455 462 456 455 464 463 464 455 454 450 455 413 412 459 457 413 452 450 454 451 446 452 413 438 450 445 450 449 445 448 465 446 465 453 446 438 466 439 438 444 466 442 441 447 446 442 447 434 440 432 438 440 434 436 435 467 467 443 442 426 468 427 434 468 426 430 429 469 430 470 436 426 421 420 471 426 428 472 473 424 424 473 430 420 415 414 474 420 422 475 476 418 425 424 418 414 408 410 477 414 416 478 479 480 419 418 480 481 482 483 478 480 481 484 410 485 485 486 484 487 488 482 484 486 489 482 490 487 491 484 492 490 493 494 491 492 495 490 496 497 495 498 491 496 490 499 491 498 500 501 499 502 503 502 499 504 505 503 506 507 500 508 505 504 507 506 509 510 504 511 512 507 509 513 511 514 515 516 507 511 517 514 518 516 515 519 520 511 516 518 521 520 519 522 523 516 521 524 519 525 523 526 527 519 528 525 529 527 526 528 530 531 532 533 527 534 535 536 537 533 538 539 540 541 542 543 544 545 546 547 548 549 550 551 546 552 553 554 555 547 546 551 555 552 553 556 553 549 554 553 556 541 540 557 557 540 546 558 549 542 550 549 558 540 534 536 559 540 539 560 543 537 544 543 560 528 536 530 535 561 536 562 533 532 533 562 538 528 563 564 531 563 528 565 527 529 566 567 410 409 566 410 522 519 524 468 434 433 421 426 471 415 420 474 408 414 477 485 410 567 492 484 489 500 507 491 515 507 512 523 527 516 532 527 565 537 543 533 542 549 543 556 549 548 552 546 553 557 546 545 534 540 559 530 536 561 525 528 564 511 520 517 513 510 511 508 504 510 503 499 504 496 499 501 493 490 497 494 487 490 482 488 483 481 480 482 479 419 480 417 475 418 418 476 425 472 424 423 431 430 473 430 469 470 470 437 436 436 467 442 568 569 570 571 572 573 574 569 575 568 575 569 574 576 577 576 574 575 578 579 577 577 576 578 580 579 581 578 581 579 580 582 583 582 580 581 584 585 583 583 582 584 586 585 587 584 587 585 586 588 589 588 586 587 589 588 590 591 568 570 591 592 593 592 591 570 594 595 593 593 592 594 596 595 597 594 597 595 596 598 599 598 596 597 600 601 599 599 598 600 602 601 603 600 603 601 602 604 605 604 602 603 606 573 605 605 604 606 607 608 609 606 571 573 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 628 635 628 634 629 635 636 637 637 634 635 638 639 636 637 636 639 590 638 589 638 590 639 632 631 630 630 629 632 633 622 624 631 633 624 625 627 623 622 625 623 618 617 626 626 617 627 620 616 621 621 616 618 610 619 611 610 620 619 612 614 613 612 611 614 615 608 607 613 615 607 572 571 609 608 572 609

+

0 1 2 3 4 5 6 2 7 1 7 2 8 9 6 6 7 8 9 10 11 10 9 8 12 11 13 10 13 11 14 15 12 12 13 14 15 16 17 16 15 14 18 17 19 16 19 17 20 21 18 18 19 20 22 21 20 22 23 21 1 0 24 25 26 24 24 0 25 26 27 28 27 26 25 29 28 30 27 30 28 31 32 29 29 30 31 32 33 34 33 32 31 35 34 36 33 36 34 37 38 35 35 36 37 38 39 40 39 38 37 39 4 40 41 42 43 40 4 3 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 62 70 69 68 71 72 72 69 68 73 71 74 71 73 72 23 75 74 73 74 75 22 75 23 63 67 64 62 64 70 65 57 66 63 65 67 56 58 59 66 57 56 61 60 52 59 58 60 54 51 50 51 61 52 44 53 55 55 54 50 45 49 46 44 46 53 47 41 48 45 47 49 43 42 5 48 41 43 3 5 42 76 77 78 79 80 81 82 83 79 84 85 86 87 88 89 90 89 91 91 92 93 82 88 94 95 81 96 92 86 97 98 84 99 100 101 102 103 104 99 105 106 107 108 109 104 110 111 112 113 109 114 113 115 116 117 118 116 119 120 121 122 123 118 124 123 125 126 127 124 128 129 130 127 131 132 133 134 135 136 137 138 77 95 78 139 140 141 140 139 142 136 138 141 138 139 141 143 144 142 142 144 140 134 133 137 137 136 134 145 120 146 147 148 149 143 127 132 143 132 144 131 127 126 126 124 125 125 123 122 122 118 117 117 116 115 115 113 114 114 109 108 108 104 103 103 99 84 98 85 84 85 97 86 97 93 92 93 90 91 90 87 89 87 94 88 94 83 82 83 80 79 80 96 81 96 78 95 78 100 76 102 101 106 76 100 102 105 107 110 106 101 107 149 112 111 112 105 110 150 148 147 147 149 111 146 150 145 150 146 148 145 151 120 121 128 119 151 121 120 130 129 135 119 128 130 133 135 129 152 153 154 155 156 157 156 155 158 159 160 161 162 158 163 164 163 158 161 163 164 162 156 158 155 157 153 164 159 161 159 165 160 166 152 167 160 165 168 169 166 170 171 172 173 174 169 175 176 177 178 179 180 181 182 183 184 185 183 186 187 188 189 190 191 192 193 194 195 196 185 197 198 199 200 201 196 202 203 204 205 206 207 208 209 210 211 210 212 213 214 205 204 215 214 209 216 217 218 212 218 219 220 221 201 222 203 221 223 184 174 224 225 226 207 206 216 157 154 153 154 167 152 167 170 166 170 175 169 175 223 174 223 182 184 182 186 183 186 197 185 197 202 196 202 220 201 220 222 221 222 204 203 205 214 215 215 209 211 211 210 213 213 212 219 219 218 217 217 216 206 208 207 199 198 200 194 208 199 198 195 191 193 200 195 194 192 188 190 191 190 193 180 187 189 189 188 192 225 179 181 179 187 180 224 226 177 225 181 226 176 178 172 224 177 176 173 168 171 178 173 172 165 171 168 227 228 229 230 231 232 233 228 234 227 234 228 233 235 236 235 233 234 237 238 236 236 235 237 239 238 240 237 240 238 239 241 242 241 239 240 243 244 242 242 241 243 245 244 246 243 246 244 245 247 248 247 245 246 248 247 249 248 249 250 229 251 227 251 252 253 252 251 229 254 255 253 253 252 254 256 255 257 254 257 255 256 258 259 258 256 257 260 261 259 259 258 260 262 261 263 260 263 261 262 264 265 264 262 263 266 231 265 265 264 266 266 232 231 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 293 295 296 291 297 291 296 292 297 298 299 299 296 297 300 301 298 299 298 301 249 300 250 300 249 301 294 295 285 293 292 295 287 286 288 294 285 287 289 281 290 286 289 288 279 284 280 281 280 290 274 283 282 282 284 279 277 273 275 273 283 274 276 278 267 277 275 278 269 268 272 276 267 269 270 230 271 268 270 272 232 271 230

diff --git a/src/tsukuba2022/meshes/velodyne.dae b/src/tsukuba2022/meshes/velodyne.dae index 1394586..541020f 100644 --- a/src/tsukuba2022/meshes/velodyne.dae +++ b/src/tsukuba2022/meshes/velodyne.dae @@ -2,9 +2,9 @@ - 2022-05-02T18:24:22 - 2022-05-02T18:24:22 - + 2022-09-07T14:59:10 + 2022-09-07T14:59:10 + Z_UP @@ -12,17 +12,14 @@ - - + + - - + + - - - - - + + @@ -32,7 +29,7 @@ - 0 0 0 1 + 0.25098 0.25098 0.25098 1 1 1 1 1 @@ -49,12 +46,12 @@ - + - 0.647059 0.647059 0.647059 1 + 0.25098 0.278431 0.270588 1 1 1 1 1 @@ -71,12 +68,12 @@ - + - 0.968627 0.52549 0.00392157 1 + 0.741176 0.733333 0.72549 1 1 1 1 1 @@ -93,34 +90,12 @@ - + - 0.231373 0.376471 0.705882 1 - - - 1 1 1 1 - - - 1 - - - - - - 1 - - - - - - - - - - 0.00784314 0.00784314 0.00784314 1 + 0.898039 0.898039 0.898039 1 1 1 1 1 @@ -143,9 +118,9 @@ - -0.04998 -0.00141494 -0.019 -0.04998 -0.00141494 0.019 -0.04998 0.00141494 0.019 -0.0498199 -0.0042403 -0.019 -0.0498199 -0.0042403 0.019 -0.0495002 -0.00705207 0.019 -0.0495002 -0.00705207 -0.019 -0.0490219 -0.00984125 -0.019 -0.0490219 -0.00984125 0.019 -0.0483866 -0.0125989 -0.019 -0.0483866 -0.0125989 0.019 -0.0475964 -0.0153162 0.019 -0.0475964 -0.0153162 -0.019 -0.0466536 -0.0179844 -0.019 -0.0466536 -0.0179844 0.019 -0.0455614 -0.0205951 -0.019 -0.0455614 -0.0205951 0.019 -0.0443233 -0.0231397 0.019 -0.0443233 -0.0231397 -0.019 -0.0429432 -0.0256102 -0.019 -0.0429432 -0.0256102 0.019 -0.0414255 -0.0279987 -0.019 -0.0414255 -0.0279987 0.019 -0.0397751 -0.0302975 0.019 -0.0397751 -0.0302975 -0.019 -0.0379973 -0.0324993 -0.019 -0.0379973 -0.0324993 0.019 -0.0360978 -0.0345969 -0.019 -0.0360978 -0.0345969 0.019 -0.0340827 -0.0365838 0.019 -0.0340827 -0.0365838 -0.019 -0.0319583 -0.0384534 -0.019 -0.0319583 -0.0384534 0.019 -0.0297317 -0.0401999 -0.019 -0.0297317 -0.0401999 0.019 -0.0274097 -0.0418175 0.019 -0.0274097 -0.0418175 -0.019 -0.025 -0.0433013 -0.019 -0.025 -0.0433013 0.019 -0.0225102 -0.0446463 -0.019 -0.0225102 -0.0446463 0.019 -0.0199483 -0.0458483 0.019 -0.0199483 -0.0458483 -0.019 -0.0173224 -0.0469034 -0.019 -0.0173224 -0.0469034 0.019 -0.0146411 -0.0478083 -0.019 -0.0146411 -0.0478083 0.019 -0.0119129 -0.0485601 0.019 -0.0119129 -0.0485601 -0.019 -0.00914656 -0.0491563 -0.019 -0.00914656 -0.0491563 0.019 -0.00635089 -0.049595 -0.019 -0.00635089 -0.049595 0.019 -0.00353488 -0.0498749 0.019 -0.00353488 -0.0498749 -0.019 -0.000707542 -0.049995 -0.019 -0.000707542 -0.049995 0.019 0.00212206 -0.0499549 -0.019 0.00212206 -0.0499549 0.019 0.00494487 -0.0497549 0.019 0.00494487 -0.0497549 -0.019 0.00775183 -0.0493954 -0.019 0.00775183 -0.0493954 0.019 0.010534 -0.0488778 -0.019 0.010534 -0.0488778 0.019 0.0132824 -0.0482035 0.019 0.0132824 -0.0482035 -0.019 0.0159882 -0.0473749 -0.019 0.0159882 -0.0473749 0.019 0.0186428 -0.0463945 -0.019 0.0186428 -0.0463945 0.019 0.0212377 -0.0452654 0.019 0.0212377 -0.0452654 -0.019 0.0237646 -0.0439914 -0.019 0.0237646 -0.0439914 0.019 0.0262154 -0.0425765 -0.019 0.0262154 -0.0425765 0.019 0.0285821 -0.0410251 0.019 0.0285821 -0.0410251 -0.019 0.0308574 -0.0393424 -0.019 0.0308574 -0.0393424 0.019 0.0330337 -0.0375336 -0.019 0.0330337 -0.0375336 0.019 0.0351043 -0.0356046 0.019 0.0351043 -0.0356046 -0.019 0.0370624 -0.0335616 -0.019 0.0370624 -0.0335616 0.019 0.0389018 -0.031411 -0.019 0.0389018 -0.031411 0.019 0.0406166 -0.0291598 0.019 0.0406166 -0.0291598 -0.019 0.0422012 -0.0268152 -0.019 0.0422012 -0.0268152 0.019 0.0436507 -0.0243847 -0.019 0.0436507 -0.0243847 0.019 0.0449604 -0.0218762 0.019 0.0449604 -0.0218762 -0.019 0.046126 -0.0192975 -0.019 0.046126 -0.0192975 0.019 0.0471439 -0.016657 -0.019 0.0471439 -0.016657 0.019 0.0480107 -0.0139631 0.019 0.0480107 -0.0139631 -0.019 0.0487238 -0.0112246 -0.019 0.0487238 -0.0112246 0.019 0.0492808 -0.00845004 -0.019 0.0492808 -0.00845004 0.019 0.0496799 -0.00564844 0.019 0.0496799 -0.00564844 -0.019 0.0499199 -0.00282875 -0.019 0.0499199 -0.00282875 0.019 0.05 0 -0.019 0.05 -1.22465e-17 0.019 -0.04998 0.00141494 -0.019 -0.0498199 0.0042403 -0.019 -0.0498199 0.0042403 0.019 -0.0495002 0.00705207 0.019 -0.0495002 0.00705207 -0.019 -0.0490219 0.00984125 0.019 -0.0490219 0.00984125 -0.019 -0.0483866 0.0125989 -0.019 -0.0483866 0.0125989 0.019 -0.0475964 0.0153162 0.019 -0.0475964 0.0153162 -0.019 -0.0466536 0.0179844 0.019 -0.0466536 0.0179844 -0.019 -0.0455614 0.0205951 -0.019 -0.0455614 0.0205951 0.019 -0.0443233 0.0231397 0.019 -0.0443233 0.0231397 -0.019 -0.0429432 0.0256102 0.019 -0.0429432 0.0256102 -0.019 -0.0414255 0.0279987 -0.019 -0.0414255 0.0279987 0.019 -0.0397751 0.0302975 0.019 -0.0397751 0.0302975 -0.019 -0.0379973 0.0324993 0.019 -0.0379973 0.0324993 -0.019 -0.0360978 0.0345969 -0.019 -0.0360978 0.0345969 0.019 -0.0340827 0.0365838 0.019 -0.0340827 0.0365838 -0.019 -0.0319583 0.0384534 0.019 -0.0319583 0.0384534 -0.019 -0.0297317 0.0401999 -0.019 -0.0297317 0.0401999 0.019 -0.0274097 0.0418175 0.019 -0.0274097 0.0418175 -0.019 -0.025 0.0433013 0.019 -0.025 0.0433013 -0.019 -0.0225102 0.0446463 -0.019 -0.0225102 0.0446463 0.019 -0.0199483 0.0458483 0.019 -0.0199483 0.0458483 -0.019 -0.0173224 0.0469034 0.019 -0.0173224 0.0469034 -0.019 -0.0146411 0.0478083 -0.019 -0.0146411 0.0478083 0.019 -0.0119129 0.0485601 0.019 -0.0119129 0.0485601 -0.019 -0.00914656 0.0491563 0.019 -0.00914656 0.0491563 -0.019 -0.00635089 0.049595 -0.019 -0.00635089 0.049595 0.019 -0.00353488 0.0498749 0.019 -0.00353488 0.0498749 -0.019 -0.000707542 0.049995 0.019 -0.000707542 0.049995 -0.019 0.00212206 0.0499549 -0.019 0.00212206 0.0499549 0.019 0.00494487 0.0497549 0.019 0.00494487 0.0497549 -0.019 0.00775183 0.0493954 0.019 0.00775183 0.0493954 -0.019 0.010534 0.0488778 -0.019 0.010534 0.0488778 0.019 0.0132824 0.0482035 0.019 0.0132824 0.0482035 -0.019 0.0159882 0.0473749 0.019 0.0159882 0.0473749 -0.019 0.0186428 0.0463945 -0.019 0.0186428 0.0463945 0.019 0.0212377 0.0452654 0.019 0.0212377 0.0452654 -0.019 0.0237646 0.0439914 0.019 0.0237646 0.0439914 -0.019 0.0262154 0.0425765 -0.019 0.0262154 0.0425765 0.019 0.0285821 0.0410251 0.019 0.0285821 0.0410251 -0.019 0.0308574 0.0393424 0.019 0.0308574 0.0393424 -0.019 0.0330337 0.0375336 -0.019 0.0330337 0.0375336 0.019 0.0351043 0.0356046 0.019 0.0351043 0.0356046 -0.019 0.0370624 0.0335616 0.019 0.0370624 0.0335616 -0.019 0.0389018 0.031411 -0.019 0.0389018 0.031411 0.019 0.0406166 0.0291598 0.019 0.0406166 0.0291598 -0.019 0.0422012 0.0268152 0.019 0.0422012 0.0268152 -0.019 0.0436507 0.0243847 -0.019 0.0436507 0.0243847 0.019 0.0449604 0.0218762 0.019 0.0449604 0.0218762 -0.019 0.046126 0.0192975 0.019 0.046126 0.0192975 -0.019 0.0471439 0.016657 -0.019 0.0471439 0.016657 0.019 0.0480107 0.0139631 0.019 0.0480107 0.0139631 -0.019 0.0487238 0.0112246 0.019 0.0487238 0.0112246 -0.019 0.0492808 0.00845004 -0.019 0.0492808 0.00845004 0.019 0.0496799 0.00564844 0.019 0.0496799 0.00564844 -0.019 0.0499199 0.00282875 0.019 0.0499199 0.00282875 -0.019 + 0.051064 0.00357724 -0.00121981 0.0514893 0.00366458 -0.00143037 0.0514664 0.00347563 -0.000901916 0.051064 0.0038323 -0.00177799 0.051512 0.00392297 -0.00192922 0.051064 0.004178 -0.00228507 0.0515342 0.0042583 -0.00237932 0.051556 0.00465706 -0.0027745 0.051064 0.0046044 -0.00272644 0.051064 0.00509923 -0.00308944 0.0515784 0.00511506 -0.00309853 0.0516013 0.00561695 -0.00335054 0.051064 0.00564828 -0.00336362 0.051064 0.00623576 -0.0035411 0.0516242 0.00615239 -0.00352052 0.051064 0.00684477 -0.00361678 0.0516465 0.00670542 -0.0036088 0.0516683 0.0072667 -0.00360849 0.051064 0.00745782 -0.00358848 0.051064 0.00805728 -0.00345702 0.0516905 0.00782134 -0.00352151 0.051064 0.00862591 -0.00322617 0.051713 0.00835572 -0.0033498 0.051736 0.00885717 -0.00309782 0.051064 0.00914736 -0.00290258 0.051064 0.00960665 -0.00249554 0.0517584 0.00931309 -0.00277087 0.051064 0.00999057 -0.00201676 0.0517801 0.00971361 -0.00237778 0.0518024 0.0100485 -0.00192761 0.051064 0.0102881 -0.00147999 0.0510646 0.0104814 -0.000897752 0.0518252 0.0103096 -0.00143106 0.0518482 0.0104908 -0.000900151 0.051064 0.00342014 -0.000626552 0.0514439 0.00338322 -0.000348647 0.051064 0.00336553 -1.52856e-05 0.0513773 0.00361101 0.0013046 0.051064 0.0038174 0.0017513 0.051064 0.00356706 0.00119098 0.0514223 0.00337168 0.000212131 0.0514001 0.00344803 0.00076784 0.051064 0.00341498 0.000596421 0.0513544 0.00385549 0.00181124 0.0513102 0.00455491 0.00268224 0.051064 0.00458145 0.00270624 0.051064 0.0041588 0.00226128 0.0513323 0.00416922 0.00227413 0.0512878 0.00499872 0.00302577 0.0512423 0.00601822 0.00348761 0.051064 0.00561992 0.00335221 0.0512652 0.00549057 0.00329657 0.051064 0.0050732 0.0030734 0.0512198 0.00656866 0.00359564 0.051064 0.00620587 0.00353465 0.051198 0.0071293 0.00361681 0.051064 0.00681423 0.00361547 0.051064 0.0074275 0.00359235 0.0511303 0.00873865 0.00316613 0.051064 0.00912277 0.00292074 0.051064 0.0085986 0.00323992 0.051064 0.00802804 0.00346595 0.0511761 0.0076858 0.00354991 0.0511533 0.00822637 0.00339759 0.051064 0.00958548 0.00251759 0.0511077 0.009207 0.00285882 0.051064 0.00997343 0.00204207 0.051086 0.00962074 0.00247871 0.0513773 0.00361101 0.0013046 0.0510939 0.0040663 0.00112634 0.0513544 0.00385549 0.00181124 0.0511193 0.00391596 0.000607015 0.0514001 0.00344803 0.00076784 0.0510683 0.00430439 0.00161301 0.0514223 0.00337168 0.000212131 0.0510437 0.00461835 0.00204608 0.0513323 0.00416922 0.00227413 0.0514439 0.00338322 -0.000348647 0.0511435 0.00385749 7.86532e-05 0.0511924 0.00401159 -0.000972781 0.0511672 0.00388878 -0.000448226 0.0514664 0.00347563 -0.000901916 0.0514893 0.00366458 -0.00143037 0.051218 0.00422425 -0.00147164 0.051512 0.00392297 -0.00192922 0.0512431 0.00451708 -0.00192272 0.051556 0.00465706 -0.0027745 0.0515784 0.00511506 -0.00309853 0.051291 0.00529744 -0.00263432 0.0515342 0.0042583 -0.00237932 0.0512666 0.00487472 -0.00230959 0.0513421 0.0062923 -0.00305084 0.0516465 0.00670542 -0.0036088 0.0513665 0.00682081 -0.00312418 0.0513165 0.0057767 -0.00288574 0.0516013 0.00561695 -0.00335054 0.0516242 0.00615239 -0.00352052 0.0516683 0.0072667 -0.00360849 0.0516905 0.00782134 -0.00352151 0.05139 0.00734714 -0.00310746 0.051713 0.00835572 -0.0033498 0.051415 0.00787362 -0.00299964 0.0514407 0.00837825 -0.00280113 0.051736 0.00885717 -0.00309782 0.0517584 0.00931309 -0.00277087 0.0514659 0.00883843 -0.00252037 0.0517801 0.00971361 -0.00237778 0.0514896 0.00923607 -0.0021726 0.0515137 0.00957107 -0.0017606 0.0518024 0.0100485 -0.00192761 0.0518252 0.0103096 -0.00143106 0.0515391 0.00983548 -0.00128928 0.0518482 0.0104908 -0.000900151 0.0515647 0.0100152 -0.000778037 0.0510202 0.00499473 0.00241377 0.0513102 0.00455491 0.00268224 0.0509954 0.00543624 0.00271824 0.0512878 0.00499872 0.00302577 0.0509697 0.00592874 0.00294479 0.0509606 0.00640957 0.00310042 0.0512423 0.00601822 0.00348761 0.0512652 0.00549057 0.00329657 0.0512198 0.00656866 0.00359564 0.0509556 0.00690959 0.0031827 0.0511077 0.009207 0.00285882 0.0509916 0.0093085 0.0025336 0.051086 0.00962074 0.00247871 0.051198 0.0071293 0.00361681 0.050955 0.00741692 0.00319232 0.0509588 0.00792018 0.00313032 0.0511761 0.0076858 0.00354991 0.0511303 0.00873865 0.00316613 0.0509666 0.00841014 0.00299843 0.0509778 0.00887589 0.00279877 0.0511533 0.00822637 0.00339759 0.0510065 0.00969829 0.00220952 0.0510214 0.0100376 0.00183218 0.051064 0.00997343 0.00204207 0.0510347 0.0103186 0.00141002 0.0510493 0.0101619 0.0017343 0.0515647 0.0100152 -0.000778037 0.0518482 0.0104908 -0.000900151 0.0510646 0.0104814 -0.000897752 0.0513379 0.0100152 -0.000778041 0.0510347 0.0103186 0.00141002 0.051064 0.0104431 0.00106865 0.051064 0.0102448 0.00157297 0.0510493 0.0101619 0.0017343 0.051064 0.00997343 0.00204207 0.0510451 0.010476 0.0009554 0.051064 0.0105639 0.000540382 0.051064 0.0105945 -3.16414e-18 0.0510518 0.010572 0.000481418 0.055626 0.00174495 -0.00313543 0.061341 0.00174495 -0.00313543 0.055626 0.00186332 -0.00328376 0.061341 0.00186332 -0.00328376 0.055626 0.00200205 -0.0034125 0.055626 0.002159 -0.00351953 0.061341 0.00200205 -0.0034125 0.061341 0.002159 -0.00351953 0.061341 0.00164996 -0.00297105 0.055626 0.00164996 -0.00297105 0.061341 0.00158052 -0.00279429 0.055626 0.00158052 -0.00279429 0.055626 0.00153821 -0.00260911 0.061341 0.00153821 -0.00260911 0.061341 0.001524 -0.00241967 0.055626 0.001524 -0.00241967 0.061341 0.00689009 -0.0061058 0.061341 0.00707991 -0.0061058 0.055626 0.00707991 -0.0061058 0.061341 0.0072676 -0.00607751 0.055626 0.0072676 -0.00607751 0.055626 0.00744898 -0.00602156 0.061341 0.00744898 -0.00602156 0.055626 0.00762 -0.0059392 0.061341 0.00762 -0.0059392 0.055626 0.00689009 -0.0061058 0.061341 0.0067024 -0.00607751 0.055626 0.0067024 -0.00607751 0.055626 0.00652102 -0.00602156 0.061341 0.00652102 -0.00602156 0.061341 0.00635 -0.0059392 0.055626 0.00635 -0.0059392 0.061341 0.0122255 -0.00313475 0.061341 0.0123204 -0.00297031 0.055626 0.0123204 -0.00297031 0.061341 0.0123897 -0.00279363 0.055626 0.0123897 -0.00279363 0.055626 0.0124318 -0.00260911 0.061341 0.0124318 -0.00260911 0.055626 0.012446 -0.00241967 0.061341 0.012446 -0.00241967 0.055626 0.0122255 -0.00313475 0.061341 0.0121072 -0.00328327 0.055626 0.0121072 -0.00328327 0.055626 0.011968 -0.0034125 0.061341 0.011968 -0.0034125 0.061341 0.011811 -0.00351953 0.055626 0.011811 -0.00351953 0.055626 0.0122251 0.00313543 0.061341 0.0122251 0.00313543 0.055626 0.0121067 0.00328376 0.061341 0.0121067 0.00328376 0.055626 0.011968 0.0034125 0.055626 0.011811 0.00351953 0.061341 0.011968 0.0034125 0.061341 0.011811 0.00351953 0.061341 0.01232 0.00297105 0.055626 0.01232 0.00297105 0.061341 0.0123895 0.00279429 0.055626 0.0123895 0.00279429 0.055626 0.0124318 0.00260911 0.061341 0.0124318 0.00260911 0.061341 0.012446 0.00241967 0.055626 0.012446 0.00241967 0.055626 0.00689009 0.0061058 0.061341 0.00689009 0.0061058 0.055626 0.0067024 0.00607751 0.061341 0.0067024 0.00607751 0.055626 0.00652102 0.00602156 0.055626 0.00635 0.0059392 0.061341 0.00652102 0.00602156 0.061341 0.00635 0.0059392 0.061341 0.00707991 0.0061058 0.055626 0.00707991 0.0061058 0.061341 0.0072676 0.00607751 0.055626 0.0072676 0.00607751 0.055626 0.00744898 0.00602156 0.061341 0.00744898 0.00602156 0.061341 0.00762 0.0059392 0.055626 0.00762 0.0059392 0.055626 0.00164961 0.00297031 0.061341 0.00164961 0.00297031 0.055626 0.00158034 0.00279363 0.061341 0.00158034 0.00279363 0.055626 0.00153821 0.00260911 0.055626 0.001524 0.00241967 0.061341 0.00153821 0.00260911 0.061341 0.001524 0.00241967 0.061341 0.00174447 0.00313475 0.055626 0.00174447 0.00313475 0.061341 0.00186283 0.00328327 0.055626 0.00186283 0.00328327 0.055626 0.00200205 0.0034125 0.061341 0.00200205 0.0034125 0.061341 0.002159 0.00351953 0.055626 0.002159 0.00351953 0.053594 0.00237984 0.00490776 0.053594 0.00224328 0.00477587 0.051064 0.00224328 0.00477587 0.053594 0.00212795 0.00462516 0.051064 0.00212795 0.00462516 0.051064 0.00203655 0.00445943 0.053594 0.00203655 0.00445943 0.051059 0.00197062 0.00428127 0.053594 0.00197062 0.00428127 0.051064 0.00237984 0.00490776 0.053594 0.00253458 0.00501785 0.051064 0.00253458 0.00501785 0.051064 0.00270405 0.00510365 0.053594 0.00270405 0.00510365 0.053594 0.00288444 0.00516321 0.051064 0.00288444 0.00516321 0.053594 0.000432091 -0.00153392 0.053594 0.000477956 -0.00171811 0.051064 0.000477956 -0.00171811 0.053594 0.000550761 -0.00189341 0.051064 0.000550761 -0.00189341 0.051064 0.000648879 -0.0020559 0.053594 0.000648879 -0.0020559 0.051059 0.000770119 -0.00220195 0.053594 0.000770119 -0.00220195 0.051064 0.000432091 -0.00153392 0.053594 0.000414191 -0.00134496 0.051064 0.000414191 -0.00134496 0.051064 0.000424654 -0.00115543 0.053594 0.000424654 -0.00115543 0.053594 0.000463249 -0.000969581 0.051064 0.000463249 -0.000969581 0.053594 0.00893304 0.00644195 0.053594 0.00875059 0.00649432 0.051064 0.00875059 0.00649432 0.053594 0.00856238 0.00651892 0.051064 0.00856238 0.00651892 0.051064 0.0083726 0.00651519 0.053594 0.0083726 0.00651519 0.051064 0.0081855 0.00648322 0.053594 0.0081855 0.00648322 0.051064 0.00893304 0.00644195 0.053594 0.00910564 0.00636297 0.051064 0.00910564 0.00636297 0.051064 0.00926454 0.00625914 0.053594 0.00926454 0.00625914 0.053594 0.0094062 0.00613279 0.051064 0.0094062 0.00613279 0.053594 0.0135379 0.00153392 0.053594 0.013492 0.00171811 0.051064 0.013492 0.00171811 0.053594 0.0134192 0.00189341 0.051064 0.0134192 0.00189341 0.051064 0.0133211 0.0020559 0.053594 0.0133211 0.0020559 0.051064 0.0131999 0.00220195 0.053594 0.0131999 0.00220195 0.051064 0.0135379 0.00153392 0.053594 0.0135558 0.00134496 0.051064 0.0135558 0.00134496 0.051064 0.0135453 0.00115543 0.053594 0.0135453 0.00115543 0.053594 0.0135068 0.000969581 0.051064 0.0135068 0.000969581 0.053594 0.0115902 -0.00490776 0.053594 0.0117267 -0.00477587 0.051064 0.0117267 -0.00477587 0.053594 0.011842 -0.00462516 0.051064 0.011842 -0.00462516 0.051064 0.0119335 -0.00445943 0.053594 0.0119335 -0.00445943 0.051064 0.0119994 -0.00428127 0.053594 0.0119994 -0.00428127 0.051064 0.0115902 -0.00490776 0.053594 0.0114354 -0.00501785 0.051064 0.0114354 -0.00501785 0.051064 0.0112659 -0.00510365 0.053594 0.0112659 -0.00510365 0.053594 0.0110856 -0.00516321 0.051064 0.0110856 -0.00516321 0.053594 0.00503696 -0.00644195 0.053594 0.00521941 -0.00649432 0.051064 0.00521941 -0.00649432 0.053594 0.00540762 -0.00651892 0.051064 0.00540762 -0.00651892 0.051064 0.0055974 -0.00651519 0.053594 0.0055974 -0.00651519 0.051059 0.0057845 -0.00648322 0.053594 0.0057845 -0.00648322 0.051064 0.00503696 -0.00644195 0.053594 0.00486436 -0.00636297 0.051064 0.00486436 -0.00636297 0.051064 0.00470546 -0.00625914 0.053594 0.00470546 -0.00625914 0.053594 0.00456381 -0.00613279 0.051064 0.00456381 -0.00613279 0.059055 0.00494285 -0.00151037 0.059055 0.00471697 -0.00114352 0.059055 0.00822375 0.00221746 0.059055 0.00538932 0.00197621 0.059055 0.00574625 0.00221746 0.059055 0.00482212 0.00133174 0.059055 0.00507829 0.00167811 0.059055 0.00613882 0.00239491 0.059055 0.00462816 0.000947055 0.059055 0.00450201 0.000535125 0.059055 0.00655574 0.00250346 0.059055 0.006985 0.00254 0.059055 0.00444729 0.000107801 0.059055 0.00455634 -0.00074377 0.059055 0.00741426 0.00250346 0.059055 0.00783117 0.00239491 0.059055 0.00446557 -0.000322625 0.059055 0.00556266 -0.00210441 0.059055 0.00914788 0.00133174 0.059055 0.00593877 -0.00231452 0.059055 0.00889171 0.00167811 0.059055 0.00522747 -0.00183377 0.059055 0.00858068 0.00197621 0.059055 0.00634498 -0.00245804 0.059055 0.00934184 0.000947055 0.059055 0.00946799 0.000535125 0.059055 0.00762502 -0.00245804 0.059055 0.00950443 -0.000322625 0.059055 0.00941366 -0.00074377 0.059055 0.00720041 -0.00253085 0.059055 0.00676959 -0.00253085 0.059055 0.00952271 0.000107801 0.059055 0.00840734 -0.00210441 0.059055 0.00902715 -0.00151037 0.059055 0.00874253 -0.00183377 0.059055 0.00925303 -0.00114352 0.059055 0.00803123 -0.00231452 0.063119 0.00656693 0.00250536 0.059055 0.006985 0.00254 0.059055 0.00655574 0.00250346 0.059055 0.00538932 0.00197621 0.063119 0.0054249 0.00200442 0.059055 0.00574625 0.00221746 0.059055 0.00613882 0.00239491 0.063119 0.00577609 0.00223386 0.063119 0.00616026 0.00240238 0.063119 0.00465894 0.00102031 0.059055 0.00482212 0.00133174 0.059055 0.00462816 0.000947055 0.063119 0.00511626 0.0017203 0.059055 0.00507829 0.00167811 0.063119 0.0048586 0.00138925 0.059055 0.00444729 0.000107801 0.059055 0.00446557 -0.000322625 0.063119 0.00445368 -0.000209752 0.059055 0.00450201 0.000535125 0.063119 0.00445368 0.000209752 0.063119 0.00452272 0.000623533 0.059055 0.00494285 -0.00151037 0.063119 0.0048586 -0.00138925 0.059055 0.00471697 -0.00114352 0.063119 0.00465894 -0.00102031 0.063119 0.00452272 -0.000623533 0.059055 0.00455634 -0.00074377 0.063119 0.00577609 -0.00223386 0.059055 0.00556266 -0.00210441 0.059055 0.00593877 -0.00231452 0.063119 0.00511626 -0.0017203 0.059055 0.00522747 -0.00183377 0.063119 0.0054249 -0.00200442 0.059055 0.00676959 -0.00253085 0.059055 0.00720041 -0.00253085 0.063119 0.006985 -0.00254 0.059055 0.00634498 -0.00245804 0.063119 0.00656693 -0.00250536 0.063119 0.00616026 -0.00240238 0.059055 0.00840734 -0.00210441 0.063119 0.00819391 -0.00223386 0.059055 0.00803123 -0.00231452 0.063119 0.00780974 -0.00240238 0.063119 0.00740307 -0.00250536 0.059055 0.00762502 -0.00245804 0.063119 0.0091114 -0.00138925 0.059055 0.00902715 -0.00151037 0.059055 0.00925303 -0.00114352 0.063119 0.0085451 -0.00200442 0.059055 0.00874253 -0.00183377 0.063119 0.00885374 -0.0017203 0.059055 0.00950443 -0.000322625 0.059055 0.00952271 0.000107801 0.063119 0.00951632 -0.000209752 0.059055 0.00941366 -0.00074377 0.063119 0.00944728 -0.000623533 0.063119 0.00931107 -0.00102031 0.063119 0.00951632 0.000209752 0.059055 0.00946799 0.000535125 0.063119 0.00944728 0.000623533 0.063119 0.00931107 0.00102031 0.059055 0.00934184 0.000947055 0.059055 0.00914788 0.00133174 0.063119 0.0091114 0.00138925 0.059055 0.00889171 0.00167811 0.063119 0.00885374 0.0017203 0.063119 0.0085451 0.00200442 0.059055 0.00858068 0.00197621 0.059055 0.00822375 0.00221746 0.063119 0.00819391 0.00223386 0.059055 0.00783117 0.00239491 0.063119 0.00780974 0.00240238 0.063119 0.00740307 0.00250536 0.059055 0.00741426 0.00250346 0.063119 0.006985 0.00254 0.053594 0.0135379 0.00153392 0.053594 0.0135558 0.00134496 0.053594 0.0110314 0.00131418 0.053594 0.00278291 -0.000665708 0.053594 0.00293862 -0.00131418 0.053594 0.000463249 -0.000969581 0.053594 0.000432091 -0.00153392 0.053594 0.000414191 -0.00134496 0.053594 0.000424654 -0.00115543 0.053594 0.000477956 -0.00171811 0.053594 0.000550761 -0.00189341 0.053594 0.00237984 0.00490776 0.053594 0.00253458 0.00501785 0.053594 0.00288444 0.00516321 0.053594 0.00270405 0.00510365 0.053594 0.00397716 0.0030089 0.053594 0.00224328 0.00477587 0.053594 0.00203655 0.00445943 0.053594 0.00212795 0.00462516 0.053594 0.0131999 0.00220195 0.053594 0.0107761 0.0019308 0.053594 0.0104274 0.00249994 0.053594 0.00632059 0.00420224 0.053594 0.00567133 0.00404655 0.053594 0.0081855 0.00648322 0.053594 0.00856238 0.00651892 0.053594 0.00830085 0.0040458 0.053594 0.0083726 0.00651519 0.053594 0.00893304 0.00644195 0.053594 0.00875059 0.00649432 0.053594 0.00926454 0.00625914 0.053594 0.00910564 0.00636297 0.053594 0.0094062 0.00613279 0.053594 0.0119994 -0.00428127 0.053594 0.0104266 -0.00250122 0.053594 0.0107756 -0.00193192 0.053594 0.0135068 0.000969581 0.053594 0.0111871 0.000665708 0.053594 0.0027305 -8.30277e-18 0.053594 0.0135453 0.00115543 0.053594 0.013492 0.00171811 0.053594 0.0134192 0.00189341 0.053594 0.00829867 -0.00404655 0.053594 0.0110856 -0.00516321 0.053594 0.0057845 -0.00648322 0.053594 0.000770119 -0.00220195 0.053594 0.00319394 -0.0019308 0.053594 0.00354257 -0.00249994 0.053594 0.0112659 -0.00510365 0.053594 0.0114354 -0.00501785 0.053594 0.0117267 -0.00477587 0.053594 0.0115902 -0.00490776 0.053594 0.00999284 -0.0030089 0.053594 0.0119335 -0.00445943 0.053594 0.011842 -0.00462516 0.053594 0.00397594 -0.00300758 0.053594 0.00456381 -0.00613279 0.053594 0.00566915 -0.0040458 0.053594 0.0055974 -0.00651519 0.053594 0.00540762 -0.00651892 0.053594 0.00764941 -0.00420224 0.053594 0.0069838 -0.00425443 0.053594 0.00521941 -0.00649432 0.053594 0.00503696 -0.00644195 0.053594 0.00486436 -0.00636297 0.053594 0.00470546 -0.00625914 0.053594 0.00999406 0.00300758 0.053594 0.00293883 0.00131501 0.053594 0.00197062 0.00428127 0.053594 0.00319443 0.00193192 0.053594 0.0110312 -0.00131501 0.053594 0.0111871 -0.000665708 0.053594 0.000648879 -0.0020559 0.053594 0.00448341 -0.00344121 0.053594 0.00505247 -0.00379016 0.053594 0.00631825 -0.00420185 0.053594 0.00891561 -0.0037912 0.053594 0.00948501 -0.00344245 0.053594 0.0112395 -7.73623e-18 0.053594 0.0133211 0.0020559 0.053594 0.0069862 0.00425443 0.053594 0.0094866 0.00344121 0.053594 0.00891753 0.00379016 0.053594 0.00765175 0.00420185 0.053594 0.00505439 0.0037912 0.053594 0.00448499 0.00344245 0.053594 0.00354341 0.00250122 0.053594 0.00278291 0.000665708 0.053594 0.0135068 0.000969581 0.051064 0.0119994 -0.00428127 0.053594 0.0119994 -0.00428127 0.051064 0.0135068 0.000969581 0.053594 0.0094062 0.00613279 0.051064 0.0131999 0.00220195 0.053594 0.0131999 0.00220195 0.051064 0.0094062 0.00613279 0.053594 0.00288444 0.00516321 0.051064 0.0081855 0.00648322 0.053594 0.0081855 0.00648322 0.051064 0.00288444 0.00516321 0.051059 0.00197062 0.00428127 0.053594 0.00197062 0.00428127 0.053594 0.000463249 -0.000969581 0.051064 0.000463249 -0.000969581 0.051059 0.000770119 -0.00220195 0.053594 0.000770119 -0.00220195 0.053594 0.00456381 -0.00613279 0.051064 0.00456381 -0.00613279 0.053594 0.0110856 -0.00516321 0.051059 0.0057845 -0.00648322 0.053594 0.0057845 -0.00648322 0.051064 0.0110856 -0.00516321 0.054864 0.0104266 0.00250122 0.054864 0.0118074 0.00256248 0.054864 0.0114035 0.00320919 0.054864 0.00603807 0.00537814 0.054864 0.00529912 0.00519412 0.054864 0.00566915 0.0040458 0.054864 0.00393211 0.00452792 0.054864 0.00505247 0.00379016 0.054864 0.00459248 0.00490892 0.054864 0.00631825 0.00420185 0.054864 0.0033311 0.00405851 0.054864 0.00448341 0.00344121 0.054864 0.00354257 0.00249994 0.054864 0.00397594 0.00300758 0.054864 0.00280223 0.00351083 0.054864 0.0069838 0.00425443 0.054864 0.00679478 0.00545764 0.054864 0.00199692 0.00222269 0.054864 0.00319394 0.0019308 0.054864 0.00235475 0.00289514 0.054864 0.00764941 0.00420224 0.054864 0.00755641 0.00543101 0.054864 0.00293862 0.00131418 0.054864 0.00173599 0.00150657 0.054864 0.00278291 0.000665708 0.054864 0.00829867 0.00404655 0.054864 0.00830734 0.00529843 0.054864 0.0103479 0.00430258 0.054864 0.00948501 0.00344245 0.054864 0.00999284 0.0030089 0.054864 0.00891561 0.0037912 0.054864 0.00903222 0.00506264 0.054864 0.0111871 0.000665708 0.054864 0.0123268 0.00113391 0.054864 0.0110312 0.00131501 0.054864 0.00199556 -0.00221967 0.054864 0.00293883 -0.00131501 0.054864 0.00173522 -0.00150361 0.054864 0.00354341 -0.00250122 0.054864 0.00280132 -0.00350988 0.054864 0.00397716 -0.0030089 0.054864 0.00505439 -0.0037912 0.054864 0.00458958 -0.00490745 0.054864 0.00567133 -0.00404655 0.054864 0.0111871 -0.000665708 0.054864 0.0110314 -0.00131418 0.054864 0.0123264 -0.00113648 0.054864 0.00679422 -0.00545767 0.054864 0.0069862 -0.00425443 0.054864 0.00632059 -0.00420224 0.054864 0.0109132 -0.00379365 0.054864 0.0114022 -0.00321085 0.054864 0.0104274 -0.00249994 0.054864 0.00891753 -0.00379016 0.054864 0.00830085 -0.0040458 0.054864 0.00902913 -0.00506388 0.054864 0.00830454 -0.00529904 0.054864 0.00765175 -0.00420185 0.054864 0.0094866 -0.00344121 0.054864 0.0103466 -0.00430373 0.054864 0.00999406 -0.00300758 0.054864 0.00971433 -0.00472998 0.054864 0.00755487 -0.00543108 0.054864 0.00529606 -0.00519319 0.054864 0.00603579 -0.00537785 0.054864 0.0118059 -0.00256521 0.054864 0.0107761 -0.0019308 0.054864 0.00448499 -0.00344245 0.054864 0.00393013 -0.00452646 0.054864 0.012116 -0.00186923 0.054864 0.0124327 -0.000381331 0.054864 0.0112395 -6.8957e-18 0.054864 0.00333053 -0.00405791 0.054864 0.00319443 -0.00193192 0.054864 0.00235322 -0.00289287 0.054864 0.0124327 0.000380252 0.054864 0.0107756 0.00193192 0.054864 0.0121171 0.00186613 0.054864 0.00278291 -0.000665708 0.054864 0.0109134 0.00379346 0.054864 0.00157727 -0.00076078 0.054864 0.001524 -8.2868e-18 0.054864 0.0027305 -8.30956e-18 0.054864 0.00157727 0.00076078 0.054864 0.00971685 0.00472842 0.055626 0.0123991 0.000713921 0.054864 0.0123268 0.00113391 0.054864 0.0124327 0.000380252 0.054864 0.0121171 0.00186613 0.055626 0.0122603 0.00141163 0.055626 0.0120307 0.00208877 0.054864 0.0118074 0.00256248 0.055626 0.0117144 0.0027305 0.054864 0.0114035 0.00320919 0.054864 0.0109134 0.00379346 0.055626 0.0113183 0.0033231 0.055626 0.0108477 0.00386015 0.054864 0.0103479 0.00430258 0.055626 0.0103103 0.00433178 0.054864 0.00971685 0.00472842 0.055626 0.0097155 0.00472936 0.055626 0.00907449 0.00504544 0.055626 0.00839935 0.00527458 0.054864 0.00903222 0.00506264 0.055626 0.00769894 0.00541405 0.054864 0.00830734 0.00529843 0.054864 0.00755641 0.00543101 0.055626 0.00698614 0.00546094 0.055626 0.00627317 0.00541437 0.054864 0.00679478 0.00545764 0.055626 0.00557228 0.00527509 0.054864 0.00603807 0.00537814 0.054864 0.00529912 0.00519412 0.055626 0.00489551 0.00504544 0.055626 0.0042545 0.00472936 0.054864 0.00459248 0.00490892 0.055626 0.00365968 0.00433178 0.054864 0.00393211 0.00452792 0.054864 0.0033311 0.00405851 0.055626 0.00312485 0.0038627 0.055626 0.00265322 0.00332532 0.054864 0.00280223 0.00351083 0.055626 0.00225564 0.0027305 0.054864 0.00235475 0.00289514 0.054864 0.00199692 0.00222269 0.055626 0.00194044 0.00209123 0.055626 0.00171066 0.00141513 0.054864 0.00173599 0.00150657 0.055626 0.0015709 0.000713921 0.054864 0.00157727 0.00076078 0.054864 0.001524 -8.2868e-18 0.055626 0.001524 -8.29088e-18 0.055626 0.012446 -7.59289e-18 0.054864 0.0124327 -0.000381331 0.055626 0.0123991 -0.000713921 0.055626 0.0122593 -0.00141513 0.054864 0.0123264 -0.00113648 0.054864 0.012116 -0.00186923 0.055626 0.0120296 -0.00209123 0.054864 0.0118059 -0.00256521 0.055626 0.0117144 -0.0027305 0.055626 0.0113168 -0.00332532 0.054864 0.0114022 -0.00321085 0.054864 0.0109132 -0.00379365 0.055626 0.0108451 -0.0038627 0.054864 0.0103466 -0.00430373 0.055626 0.0103103 -0.00433178 0.055626 0.0097155 -0.00472936 0.054864 0.00971433 -0.00472998 0.055626 0.00907449 -0.00504544 0.054864 0.00902913 -0.00506388 0.054864 0.00830454 -0.00529904 0.055626 0.00839772 -0.00527509 0.054864 0.00755487 -0.00543108 0.055626 0.00769683 -0.00541437 0.055626 0.00698386 -0.00546094 0.054864 0.00679422 -0.00545767 0.054864 0.00603579 -0.00537785 0.055626 0.00627106 -0.00541405 0.054864 0.00529606 -0.00519319 0.055626 0.00557065 -0.00527458 0.055626 0.00489551 -0.00504544 0.054864 0.00458958 -0.00490745 0.054864 0.00393013 -0.00452646 0.055626 0.0042545 -0.00472936 0.054864 0.00333053 -0.00405791 0.055626 0.00365968 -0.00433178 0.055626 0.0031223 -0.00386015 0.054864 0.00280132 -0.00350988 0.054864 0.00235322 -0.00289287 0.055626 0.00265166 -0.0033231 0.054864 0.00199556 -0.00221967 0.055626 0.00225564 -0.0027305 0.055626 0.00193929 -0.00208877 0.054864 0.00173522 -0.00150361 0.054864 0.00157727 -0.00076078 0.055626 0.00170973 -0.00141163 0.055626 0.0015709 -0.000713921 0.061341 0.002159 -0.00351953 0.061341 0.00365968 -0.00433178 0.061341 0.0042545 -0.00472936 0.061341 0.00225564 -0.0027305 0.061341 0.00174495 -0.00313543 0.061341 0.00193929 -0.00208877 0.061341 0.001524 -0.00241967 0.061341 0.00153821 -0.00260911 0.061341 0.00200205 -0.0034125 0.061341 0.00186332 -0.00328376 0.061341 0.0031223 -0.00386015 0.061341 0.00265166 -0.0033231 0.061341 0.00164996 -0.00297105 0.061341 0.00158052 -0.00279429 0.061341 0.00170973 -0.00141163 0.061341 0.0015709 -0.000713921 0.061341 0.001524 -9.68821e-18 0.055626 0.00164961 0.00297031 0.055626 0.00158034 0.00279363 0.055626 0.00194044 0.00209123 0.055626 0.00225564 0.0027305 0.055626 0.00174447 0.00313475 0.055626 0.002159 0.00351953 0.055626 0.00200205 0.0034125 0.055626 0.00186283 0.00328327 0.055626 0.00265322 0.00332532 0.055626 0.00365968 0.00433178 0.055626 0.0042545 0.00472936 0.055626 0.00312485 0.0038627 0.055626 0.00153821 0.00260911 0.055626 0.00171066 0.00141513 0.055626 0.001524 0.00241967 0.055626 0.001524 -8.29088e-18 0.055626 0.0015709 0.000713921 0.061341 0.0097155 -0.00472936 0.055626 0.00762 -0.0059392 0.061341 0.00762 -0.0059392 0.055626 0.0097155 -0.00472936 0.061341 0.011811 -0.00351953 0.055626 0.011811 -0.00351953 0.061341 0.012446 -0.00241967 0.055626 0.012446 -7.59289e-18 0.055626 0.012446 -0.00241967 0.061341 0.012446 -8.43769e-18 0.061341 0.012446 0.00241967 0.055626 0.012446 0.00241967 0.061341 0.0097155 0.00472936 0.055626 0.011811 0.00351953 0.061341 0.011811 0.00351953 0.055626 0.0097155 0.00472936 0.061341 0.00762 0.0059392 0.055626 0.00762 0.0059392 0.061341 0.0042545 0.00472936 0.055626 0.00635 0.0059392 0.061341 0.00635 0.0059392 0.055626 0.0042545 0.00472936 0.061341 0.002159 0.00351953 0.055626 0.002159 0.00351953 0.055626 0.001524 -0.00241967 0.061341 0.001524 -9.68821e-18 0.061341 0.001524 -0.00241967 0.055626 0.001524 -8.29088e-18 0.055626 0.001524 0.00241967 0.061341 0.001524 0.00241967 0.061341 0.0042545 -0.00472936 0.055626 0.002159 -0.00351953 0.061341 0.002159 -0.00351953 0.055626 0.0042545 -0.00472936 0.061341 0.00635 -0.0059392 0.055626 0.00635 -0.0059392 0.061341 0.00744898 -0.00602156 0.061341 0.0067024 -0.00607751 0.061341 0.00652102 -0.00602156 0.061341 0.0072676 -0.00607751 0.061341 0.00627106 -0.00541405 0.061341 0.00698386 -0.00546094 0.061341 0.00635 -0.0059392 0.061341 0.00689009 -0.0061058 0.061341 0.00769683 -0.00541437 0.061341 0.00839772 -0.00527509 0.061341 0.00762 -0.0059392 0.061341 0.00907449 -0.00504544 0.061341 0.0097155 -0.00472936 0.061341 0.00707991 -0.0061058 0.061341 0.00557065 -0.00527458 0.061341 0.00489551 -0.00504544 0.061341 0.0042545 -0.00472936 0.061341 0.0113168 -0.00332532 0.061341 0.0117144 -0.0027305 0.061341 0.011811 -0.00351953 0.061341 0.0123204 -0.00297031 0.061341 0.0120296 -0.00209123 0.061341 0.0123897 -0.00279363 0.061341 0.0122255 -0.00313475 0.061341 0.0124318 -0.00260911 0.061341 0.012446 -0.00241967 0.061341 0.0123991 -0.000713921 0.061341 0.012446 -8.43769e-18 0.061341 0.0122593 -0.00141513 0.061341 0.0121072 -0.00328327 0.061341 0.011968 -0.0034125 0.061341 0.0108451 -0.0038627 0.061341 0.0103103 -0.00433178 0.061341 0.0097155 -0.00472936 0.061341 0.0122251 0.00313543 0.061341 0.0120307 0.00208877 0.061341 0.0117144 0.0027305 0.061341 0.012446 0.00241967 0.061341 0.0124318 0.00260911 0.061341 0.011811 0.00351953 0.061341 0.011968 0.0034125 0.061341 0.0121067 0.00328376 0.061341 0.0113183 0.0033231 0.061341 0.0108477 0.00386015 0.061341 0.0103103 0.00433178 0.061341 0.0097155 0.00472936 0.061341 0.01232 0.00297105 0.061341 0.0123895 0.00279429 0.061341 0.0122603 0.00141163 0.061341 0.0123991 0.000713921 0.061341 0.012446 -8.43769e-18 0.061341 0.0072676 0.00607751 0.061341 0.00652102 0.00602156 0.061341 0.0067024 0.00607751 0.061341 0.00769894 0.00541405 0.061341 0.00698614 0.00546094 0.061341 0.00762 0.0059392 0.061341 0.00707991 0.0061058 0.061341 0.00689009 0.0061058 0.061341 0.00744898 0.00602156 0.061341 0.00635 0.0059392 0.061341 0.00557228 0.00527509 0.061341 0.00489551 0.00504544 0.061341 0.00627317 0.00541437 0.061341 0.0042545 0.00472936 0.061341 0.00839935 0.00527458 0.061341 0.00907449 0.00504544 0.061341 0.0097155 0.00472936 0.061341 0.00194044 0.00209123 0.061341 0.001524 0.00241967 0.061341 0.00153821 0.00260911 0.061341 0.002159 0.00351953 0.061341 0.00265322 0.00332532 0.061341 0.00225564 0.0027305 0.061341 0.00158034 0.00279363 0.061341 0.00164961 0.00297031 0.061341 0.00174447 0.00313475 0.061341 0.00171066 0.00141513 0.061341 0.0015709 0.000713921 0.061341 0.001524 -9.68821e-18 0.061341 0.00186283 0.00328327 0.061341 0.00200205 0.0034125 0.061341 0.00312485 0.0038627 0.061341 0.00365968 0.00433178 0.061341 0.0042545 0.00472936 0.063119 0.00951632 -0.000209752 0.062103 0.0123904 -0.000777495 0.063119 0.00944728 -0.000623533 0.062103 0.00661197 0.00544824 0.062103 0.00735705 0.00544824 0.063119 0.006985 0.00254 0.062103 0.012225 -0.00153761 0.063119 0.00931107 -0.00102031 0.063119 0.0091114 -0.00138925 0.062103 0.0119529 -0.00226744 0.062103 0.0115797 -0.00295127 0.062103 0.011113 -0.00357512 0.062103 0.0105621 -0.00412627 0.063119 0.00885374 -0.0017203 0.063119 0.0085451 -0.00200442 0.062103 0.00993835 -0.00459344 0.062103 0.00925438 -0.00496711 0.063119 0.00819391 -0.00223386 0.062103 0.00852413 -0.0052396 0.063119 0.00780974 -0.00240238 0.063119 0.00740307 -0.00250536 0.062103 0.00776249 -0.00540537 0.063119 0.006985 -0.00254 0.062103 0.006985 -0.005461 0.062103 0.012446 -7.32235e-18 0.062103 0.012395 0.00074429 0.063119 0.00951632 0.000209752 0.063119 0.00944728 0.000623533 0.062103 0.0122431 0.00147455 0.063119 0.00931107 0.00102031 0.062103 0.0119932 0.00217706 0.063119 0.0091114 0.00138925 0.062103 0.0116501 0.00283864 0.062103 0.0112205 0.00344698 0.063119 0.00885374 0.0017203 0.062103 0.0107123 0.00399122 0.063119 0.0085451 0.00200442 0.062103 0.0101335 0.00446194 0.062103 0.00949618 0.00484931 0.063119 0.00819391 0.00223386 0.063119 0.00780974 0.00240238 0.062103 0.00881226 0.00514611 0.063119 0.00740307 0.00250536 0.062103 0.0080947 0.00534693 0.062103 0.00447125 0.00484791 0.062103 0.00515489 0.00514513 0.063119 0.00616026 0.00240238 0.063119 0.00656693 0.00250536 0.062103 0.00587296 0.00534654 0.063119 0.00511626 0.0017203 0.062103 0.00325736 0.00399084 0.063119 0.0054249 0.00200442 0.063119 0.00577609 0.00223386 0.062103 0.00383481 0.00446066 0.063119 0.00465894 0.00102031 0.062103 0.00197559 0.00217425 0.062103 0.00231846 0.00283646 0.062103 0.00274851 0.00344596 0.063119 0.0048586 0.00138925 0.062103 0.001524 -6.6864e-17 0.063119 0.00445368 0.000209752 0.063119 0.00445368 -0.000209752 0.062103 0.00157497 0.00074429 0.062103 0.00172621 0.00147185 0.063119 0.00452272 0.000623533 0.062103 0.00201839 -0.00227021 0.062103 0.00174571 -0.00153998 0.063119 0.00465894 -0.00102031 0.063119 0.00452272 -0.000623533 0.062103 0.00157973 -0.000778019 0.062103 0.00239194 -0.00295374 0.063119 0.0048586 -0.00138925 0.062103 0.00285842 -0.00357671 0.063119 0.00511626 -0.0017203 0.062103 0.00340914 -0.00412743 0.062103 0.00403361 -0.00459471 0.063119 0.0054249 -0.00200442 0.063119 0.00577609 -0.00223386 0.062103 0.00471804 -0.00496813 0.063119 0.00616026 -0.00240238 0.062103 0.00544825 -0.00524016 0.062103 0.00620698 -0.00540527 0.063119 0.00656693 -0.00250536 0.062103 0.00620698 -0.00540527 0.062103 0.006985 -0.005461 0.061341 0.00627106 -0.00541405 0.062103 0.012446 -7.32235e-18 0.061341 0.0123991 0.000713921 0.061341 0.012446 -8.43769e-18 0.061341 0.00557065 -0.00527458 0.062103 0.00544825 -0.00524016 0.061341 0.00489551 -0.00504544 0.062103 0.00471804 -0.00496813 0.062103 0.00403361 -0.00459471 0.061341 0.0042545 -0.00472936 0.061341 0.00365968 -0.00433178 0.062103 0.00340914 -0.00412743 0.061341 0.0031223 -0.00386015 0.061341 0.00265166 -0.0033231 0.062103 0.00285842 -0.00357671 0.062103 0.00239194 -0.00295374 0.061341 0.00225564 -0.0027305 0.061341 0.00193929 -0.00208877 0.062103 0.00201839 -0.00227021 0.061341 0.00170973 -0.00141163 0.062103 0.00174571 -0.00153998 0.062103 0.00157973 -0.000778019 0.061341 0.0015709 -0.000713921 0.062103 0.001524 -6.6864e-17 0.061341 0.001524 -9.68821e-18 0.061341 0.00698386 -0.00546094 0.062103 0.00776249 -0.00540537 0.061341 0.00769683 -0.00541437 0.062103 0.00852413 -0.0052396 0.061341 0.00839772 -0.00527509 0.061341 0.00907449 -0.00504544 0.062103 0.00925438 -0.00496711 0.062103 0.00993835 -0.00459344 0.061341 0.0097155 -0.00472936 0.062103 0.0105621 -0.00412627 0.061341 0.0103103 -0.00433178 0.061341 0.0108451 -0.0038627 0.062103 0.011113 -0.00357512 0.062103 0.0115797 -0.00295127 0.061341 0.0113168 -0.00332532 0.062103 0.0119529 -0.00226744 0.061341 0.0117144 -0.0027305 0.061341 0.0120296 -0.00209123 0.062103 0.012225 -0.00153761 0.062103 0.0123904 -0.000777495 0.061341 0.0122593 -0.00141513 0.061341 0.0123991 -0.000713921 0.062103 0.0122431 0.00147455 0.061341 0.0122603 0.00141163 0.062103 0.012395 0.00074429 0.062103 0.0112205 0.00344698 0.061341 0.0113183 0.0033231 0.062103 0.0116501 0.00283864 0.062103 0.0119932 0.00217706 0.061341 0.0117144 0.0027305 0.061341 0.0120307 0.00208877 0.062103 0.0101335 0.00446194 0.062103 0.00949618 0.00484931 0.061341 0.0097155 0.00472936 0.061341 0.0108477 0.00386015 0.062103 0.0107123 0.00399122 0.061341 0.0103103 0.00433178 0.061341 0.00769894 0.00541405 0.062103 0.0080947 0.00534693 0.062103 0.00735705 0.00544824 0.061341 0.00839935 0.00527458 0.061341 0.00907449 0.00504544 0.062103 0.00881226 0.00514611 0.062103 0.00661197 0.00544824 0.061341 0.00627317 0.00541437 0.061341 0.00698614 0.00546094 0.062103 0.00447125 0.00484791 0.061341 0.0042545 0.00472936 0.061341 0.00489551 0.00504544 0.062103 0.00587296 0.00534654 0.062103 0.00515489 0.00514513 0.061341 0.00557228 0.00527509 0.062103 0.00325736 0.00399084 0.062103 0.00274851 0.00344596 0.061341 0.00312485 0.0038627 0.061341 0.00365968 0.00433178 0.062103 0.00383481 0.00446066 0.062103 0.00231846 0.00283646 0.061341 0.00265322 0.00332532 0.061341 0.00225564 0.0027305 0.062103 0.00197559 0.00217425 0.062103 0.00172621 0.00147185 0.061341 0.00194044 0.00209123 0.062103 0.00157497 0.00074429 0.061341 0.00171066 0.00141513 0.061341 0.0015709 0.000713921 0.055626 0.0067024 0.00607751 0.055626 0.00707991 0.0061058 0.055626 0.00689009 0.0061058 0.055626 0.00652102 0.00602156 0.055626 0.0072676 0.00607751 0.055626 0.00744898 0.00602156 0.055626 0.00635 0.0059392 0.055626 0.00762 0.0059392 0.055626 0.00839935 0.00527458 0.055626 0.00907449 0.00504544 0.055626 0.00698614 0.00546094 0.055626 0.00769894 0.00541405 0.055626 0.0097155 0.00472936 0.055626 0.00627317 0.00541437 0.055626 0.00489551 0.00504544 0.055626 0.00557228 0.00527509 0.055626 0.0042545 0.00472936 0.055626 0.0124318 0.00260911 0.055626 0.0120307 0.00208877 0.055626 0.012446 0.00241967 0.055626 0.0123895 0.00279429 0.055626 0.0122603 0.00141163 0.055626 0.01232 0.00297105 0.055626 0.0122251 0.00313543 0.055626 0.0117144 0.0027305 0.055626 0.0121067 0.00328376 0.055626 0.011968 0.0034125 0.055626 0.0123991 0.000713921 0.055626 0.012446 -7.59289e-18 0.055626 0.0113183 0.0033231 0.055626 0.011811 0.00351953 0.055626 0.0103103 0.00433178 0.055626 0.0108477 0.00386015 0.055626 0.0097155 0.00472936 0.055626 0.0117144 -0.0027305 0.055626 0.0122255 -0.00313475 0.055626 0.0120296 -0.00209123 0.055626 0.0123204 -0.00297031 0.055626 0.0123897 -0.00279363 0.055626 0.011968 -0.0034125 0.055626 0.011811 -0.00351953 0.055626 0.0121072 -0.00328327 0.055626 0.0113168 -0.00332532 0.055626 0.0108451 -0.0038627 0.055626 0.0103103 -0.00433178 0.055626 0.0097155 -0.00472936 0.055626 0.0124318 -0.00260911 0.055626 0.0122593 -0.00141513 0.055626 0.012446 -0.00241967 0.055626 0.012446 -7.59289e-18 0.055626 0.0123991 -0.000713921 0.055626 0.0072676 -0.00607751 0.055626 0.00689009 -0.0061058 0.055626 0.00707991 -0.0061058 0.055626 0.00744898 -0.00602156 0.055626 0.0067024 -0.00607751 0.055626 0.00652102 -0.00602156 0.055626 0.00762 -0.0059392 0.055626 0.00635 -0.0059392 0.055626 0.00489551 -0.00504544 0.055626 0.0042545 -0.00472936 0.055626 0.00698386 -0.00546094 0.055626 0.00627106 -0.00541405 0.055626 0.00557065 -0.00527458 0.055626 0.00769683 -0.00541437 0.055626 0.00907449 -0.00504544 0.055626 0.00839772 -0.00527509 0.055626 0.0097155 -0.00472936 0.055626 0.00193929 -0.00208877 0.055626 0.001524 -0.00241967 0.055626 0.00153821 -0.00260911 0.055626 0.00164996 -0.00297105 0.055626 0.00158052 -0.00279429 0.055626 0.00174495 -0.00313543 0.055626 0.00170973 -0.00141163 0.055626 0.0015709 -0.000713921 0.055626 0.001524 -8.29088e-18 0.055626 0.00225564 -0.0027305 0.055626 0.00186332 -0.00328376 0.055626 0.00200205 -0.0034125 0.055626 0.00265166 -0.0033231 0.055626 0.002159 -0.00351953 0.055626 0.00365968 -0.00433178 0.055626 0.0031223 -0.00386015 0.055626 0.0042545 -0.00472936 0.053594 0.0069838 -0.00425443 0.054864 0.0069862 -0.00425443 0.053594 0.00764941 -0.00420224 0.053594 0.0027305 -8.30277e-18 0.054864 0.00278291 0.000665708 0.054864 0.0027305 -8.30956e-18 0.054864 0.00765175 -0.00420185 0.053594 0.00829867 -0.00404655 0.053594 0.00891561 -0.0037912 0.054864 0.00830085 -0.0040458 0.054864 0.00891753 -0.00379016 0.053594 0.00948501 -0.00344245 0.054864 0.0094866 -0.00344121 0.053594 0.00999284 -0.0030089 0.053594 0.0104266 -0.00250122 0.054864 0.00999406 -0.00300758 0.054864 0.0104274 -0.00249994 0.053594 0.0107756 -0.00193192 0.054864 0.0107761 -0.0019308 0.053594 0.0110312 -0.00131501 0.053594 0.0111871 -0.000665708 0.054864 0.0110314 -0.00131418 0.054864 0.0111871 -0.000665708 0.053594 0.0112395 -7.73623e-18 0.054864 0.0112395 -6.8957e-18 0.054864 0.00632059 -0.00420224 0.054864 0.00567133 -0.00404655 0.053594 0.00631825 -0.00420185 0.053594 0.00566915 -0.0040458 0.054864 0.00505439 -0.0037912 0.053594 0.00505247 -0.00379016 0.054864 0.00448499 -0.00344245 0.054864 0.00397716 -0.0030089 0.053594 0.00448341 -0.00344121 0.053594 0.00397594 -0.00300758 0.054864 0.00354341 -0.00250122 0.053594 0.00354257 -0.00249994 0.054864 0.00319443 -0.00193192 0.054864 0.00293883 -0.00131501 0.053594 0.00319394 -0.0019308 0.053594 0.00293862 -0.00131418 0.054864 0.00278291 -0.000665708 0.053594 0.00278291 -0.000665708 0.053594 0.00293883 0.00131501 0.054864 0.00293862 0.00131418 0.053594 0.00278291 0.000665708 0.053594 0.00397716 0.0030089 0.054864 0.00397594 0.00300758 0.053594 0.00354341 0.00250122 0.053594 0.00319443 0.00193192 0.054864 0.00354257 0.00249994 0.054864 0.00319394 0.0019308 0.053594 0.00505439 0.0037912 0.053594 0.00567133 0.00404655 0.054864 0.00566915 0.0040458 0.054864 0.00448341 0.00344121 0.053594 0.00448499 0.00344245 0.054864 0.00505247 0.00379016 0.054864 0.00764941 0.00420224 0.053594 0.0069862 0.00425443 0.053594 0.00765175 0.00420185 0.054864 0.0069838 0.00425443 0.054864 0.00631825 0.00420185 0.053594 0.00632059 0.00420224 0.053594 0.0094866 0.00344121 0.054864 0.00948501 0.00344245 0.053594 0.00891753 0.00379016 0.053594 0.00830085 0.0040458 0.054864 0.00891561 0.0037912 0.054864 0.00829867 0.00404655 0.053594 0.0104274 0.00249994 0.054864 0.0104266 0.00250122 0.053594 0.00999406 0.00300758 0.054864 0.00999284 0.0030089 0.054864 0.0107756 0.00193192 0.053594 0.0107761 0.0019308 0.053594 0.0110314 0.00131418 0.054864 0.0110312 0.00131501 0.053594 0.0111871 0.000665708 0.054864 0.0111871 0.000665708 0.051064 0.0114354 -0.00501785 0.051064 0.0110856 -0.00516321 0.051064 0.0112659 -0.00510365 0.051064 0.0081855 0.00648322 0.051064 0.00856238 0.00651892 0.051064 0.0083726 0.00651519 0.051064 0.0117267 -0.00477587 0.051064 0.0115902 -0.00490776 0.051064 0.011842 -0.00462516 0.051064 0.0119335 -0.00445943 0.051064 0.0119994 -0.00428127 0.051059 0.000770119 -0.00220195 0.051064 0.0046044 -0.00272644 0.051064 0.004178 -0.00228507 0.051064 0.00357724 -0.00121981 0.051064 0.0038323 -0.00177799 0.051064 0.00540762 -0.00651892 0.051059 0.0057845 -0.00648322 0.051064 0.00521941 -0.00649432 0.051064 0.0055974 -0.00651519 0.051064 0.00503696 -0.00644195 0.051064 0.00486436 -0.00636297 0.051064 0.00470546 -0.00625914 0.051064 0.00456381 -0.00613279 0.051064 0.00623576 -0.0035411 0.051064 0.00684477 -0.00361678 0.051064 0.00356706 0.00119098 0.051059 0.00197062 0.00428127 0.051064 0.000463249 -0.000969581 0.051064 0.000477956 -0.00171811 0.051064 0.000550761 -0.00189341 0.051064 0.000414191 -0.00134496 0.051064 0.000432091 -0.00153392 0.051064 0.000424654 -0.00115543 0.051064 0.000648879 -0.0020559 0.051064 0.0038174 0.0017513 0.051064 0.0041588 0.00226128 0.051064 0.00288444 0.00516321 0.051064 0.00270405 0.00510365 0.051064 0.00253458 0.00501785 0.051064 0.0131999 0.00220195 0.051064 0.0094062 0.00613279 0.051064 0.00958548 0.00251759 0.051064 0.00237984 0.00490776 0.051064 0.00224328 0.00477587 0.051064 0.00212795 0.00462516 0.051064 0.00203655 0.00445943 0.051064 0.00912277 0.00292074 0.051064 0.00875059 0.00649432 0.051064 0.00681423 0.00361547 0.051064 0.0074275 0.00359235 0.051064 0.00893304 0.00644195 0.051064 0.00910564 0.00636297 0.051064 0.00926454 0.00625914 0.051064 0.00997343 0.00204207 0.051064 0.0133211 0.0020559 0.051064 0.0135068 0.000969581 0.051064 0.00960665 -0.00249554 0.051064 0.00914736 -0.00290258 0.051064 0.013492 0.00171811 0.051064 0.0134192 0.00189341 0.051064 0.0135558 0.00134496 0.051064 0.0135379 0.00153392 0.051064 0.0135453 0.00115543 0.051064 0.0105639 0.000540382 0.051064 0.0105945 -3.16414e-18 0.051064 0.00620587 0.00353465 0.051064 0.00805728 -0.00345702 0.051064 0.00745782 -0.00358848 0.051064 0.00802804 0.00346595 0.051064 0.0085986 0.00323992 0.051064 0.0050732 0.0030734 0.051064 0.00561992 0.00335221 0.051064 0.00458145 0.00270624 0.051064 0.00336553 -1.52856e-05 0.051064 0.00341498 0.000596421 0.051064 0.00342014 -0.000626552 0.051064 0.00509923 -0.00308944 0.051064 0.00564828 -0.00336362 0.051064 0.00862591 -0.00322617 0.051064 0.0102881 -0.00147999 0.051064 0.00999057 -0.00201676 0.0510646 0.0104814 -0.000897752 0.051064 0.010566 -0.000452671 0.051064 0.0104431 0.00106865 0.051064 0.0102448 0.00157297 0.0510522 0.0105677 -0.000435651 0.0510467 0.0104885 -0.000866505 0.051064 0.010566 -0.000452671 0.0510646 0.0104814 -0.000897752 0.051064 0.0105945 -3.16414e-18 0.0510437 0.0103586 -0.00128336 0.0512394 0.00884437 -0.002516 0.0509895 0.00949108 -0.0025767 0.0509718 0.00908777 -0.00290905 0.0512631 0.00923986 -0.00216866 0.0512143 0.00838665 -0.00279693 0.050956 0.00863671 -0.00317593 0.0512871 0.00957318 -0.0017575 0.0510075 0.00984213 -0.0021878 0.0510241 0.0101355 -0.00175515 0.0509438 0.00814985 -0.00336757 0.0511887 0.00788445 -0.00299641 0.0513124 0.00983626 -0.00128756 0.0510437 0.0103586 -0.00128336 0.0513379 0.0100152 -0.000778041 0.0510646 0.0104814 -0.000897752 0.0509365 0.00763742 -0.00347785 0.0511638 0.00736003 -0.00310593 0.0511404 0.00683542 -0.00312492 0.0509348 0.00711465 -0.00350248 0.0510174 0.00453192 -0.00194162 0.0510408 0.00489098 -0.00232434 0.0509995 0.00483474 -0.00236872 0.0509393 0.00659394 -0.00343858 0.051116 0.00630867 -0.00305451 0.050949 0.006093 -0.00328701 0.0509635 0.00562438 -0.00305159 0.0510906 0.0057941 -0.00289296 0.0510652 0.00531484 -0.00264538 0.0509809 0.00520201 -0.00274233 0.0512666 0.00487472 -0.00230959 0.0510408 0.00489098 -0.00232434 0.0510174 0.00453192 -0.00194162 0.051291 0.00529744 -0.00263432 0.051218 0.00422425 -0.00147164 0.0510443 0.00402011 -0.000998435 0.0511924 0.00401159 -0.000972781 0.0512431 0.00451708 -0.00192272 0.0513165 0.0057767 -0.00288574 0.0510652 0.00531484 -0.00264538 0.0510518 0.00389302 -0.000474555 0.051054 0.00385714 6.26998e-05 0.0511435 0.00385749 7.86532e-05 0.0511672 0.00388878 -0.000448226 0.0510324 0.00423549 -0.00149192 0.0510505 0.00391404 0.000597199 0.0511193 0.00391596 0.000607015 0.0510939 0.0040663 0.00112634 0.0510419 0.00406219 0.00111477 0.0510291 0.00429668 0.00160012 0.0510137 0.00461105 0.00203714 0.0510683 0.00430439 0.00161301 0.0510437 0.00461835 0.00204608 0.0509974 0.00499561 0.0024145 0.0509821 0.00543932 0.00271963 0.0509954 0.00543624 0.00271824 0.0510202 0.00499473 0.00241377 0.0509697 0.00592874 0.00294479 0.0513421 0.0062923 -0.00305084 0.0510906 0.0057941 -0.00289296 0.051116 0.00630867 -0.00305451 0.0513665 0.00682081 -0.00312418 0.05139 0.00734714 -0.00310746 0.0511404 0.00683542 -0.00312492 0.051415 0.00787362 -0.00299964 0.0511638 0.00736003 -0.00310593 0.0511887 0.00788445 -0.00299641 0.0514407 0.00837825 -0.00280113 0.0514659 0.00883843 -0.00252037 0.0512143 0.00838665 -0.00279693 0.0514896 0.00923607 -0.0021726 0.0512394 0.00884437 -0.002516 0.0512631 0.00923986 -0.00216866 0.0515137 0.00957107 -0.0017606 0.0515391 0.00983548 -0.00128928 0.0512871 0.00957318 -0.0017575 0.0515647 0.0100152 -0.000778037 0.0513124 0.00983626 -0.00128756 0.0513379 0.0100152 -0.000778041 0.0197968 -2.70738e-34 -0.0473548 0.00115753 7.39554e-37 -0.0422019 0.021909 -2.3148e-34 -0.0463938 -0.00238269 0 -0.00156377 -0.043418 -1.43537e-33 -0.0283826 -0.00261911 0 -0.00121397 -0.00209055 0 0.00186857 -0.0360405 -1.28476e-33 0.0372183 -0.0343342 -1.25287e-33 0.0387792 0.0176603 -3.10425e-34 -0.0482117 -0.00279301 0 -0.000829252 -0.0500862 -1.55548e-33 -0.0137127 -0.0506504 -1.56542e-33 -0.0114738 0.0014759 2.57434e-36 -0.0427902 0.0154821 -3.50861e-34 -0.0489738 0.0132624 -3.92044e-34 -0.0496411 -0.00053224 0 0.0424198 -0.000129827 0 0.00246904 -0.000551645 0 0.00248696 -0.0028994 0 -0.000420677 -0.0518924 -1.5864e-33 -0.00232366 -0.0029352 -3.06818e-35 4.07341e-20 -0.0511167 -1.57355e-33 -0.00920124 -0.0514788 -1.57975e-33 -0.00691987 -0.0517366 -1.58402e-33 -0.00463028 0.00155829 3.01163e-36 -0.0431155 -0.0376607 -1.33049e-33 -0.0355985 -0.0392188 -1.35893e-33 -0.0338939 -0.0446485 -1.4577e-33 -0.0264247 -0.0477949 -1.51453e-33 -0.020254 -0.0376793 -1.31541e-33 0.0355783 -0.00238269 0 0.00156377 -0.002478 -3.44605e-35 -0.04345 -0.0118971 -8.57328e-34 -0.0502098 -0.00245029 -2.16951e-35 -0.0431155 -0.0511189 -1.56961e-33 0.00919243 -0.0028994 0 0.000420677 -0.0514788 -1.57675e-33 0.00691987 0.0110191 -4.33643e-34 -0.0502075 0.00876262 -4.75461e-34 -0.0506693 0.001586 1.56321e-35 -0.04345 -0.051946 -6.34787e-34 7.02783e-18 -0.0486576 -1.53002e-33 -0.0181048 -0.026849 -1.13247e-33 -0.0442155 -0.0288163 -1.16857e-33 -0.0429811 -0.00182224 -1.75727e-35 -0.041955 -0.0407068 -1.38605e-33 -0.0321132 -0.0421059 -1.41152e-33 -0.0302768 -0.0468412 -1.49735e-33 -0.022354 -0.0023679 -2.11168e-35 -0.0427902 -0.0163478 -9.39349e-34 -0.0489828 -0.00223309 -2.02193e-35 -0.0424829 -0.0227838 -1.05778e-33 -0.0464031 -0.00204953 -1.90271e-35 -0.0422019 -0.0141422 -8.98713e-34 -0.0496453 -0.0360325 -1.30074e-33 -0.0372269 -0.00209055 0 -0.00186857 -0.0307082 -1.20326e-33 -0.0416703 -0.0015574 -1.58957e-35 -0.0417489 -0.0206829 -1.01915e-33 -0.0473568 -0.0457964 -1.47848e-33 -0.0244047 -0.0494242 -1.54372e-33 -0.015918 -0.0248372 -1.09552e-33 -0.0453567 -0.0185281 -9.79493e-34 -0.04822 -0.00245029 -2.22733e-35 -0.0457845 -0.0023679 -2.1836e-35 -0.0461098 -0.00734809 -7.73403e-34 -0.051035 -0.002478 -3.48939e-35 -0.04545 -0.00962686 -8.15455e-34 -0.050674 -0.000431499 -6.45626e-34 -0.0514991 -0.000944826 -1.33488e-35 -0.0474198 -0.000613801 -1.13205e-35 -0.0474751 -0.00204953 -2.00013e-35 -0.0466981 -0.00182224 -1.86538e-35 -0.046945 -0.00506077 -7.3117e-34 -0.0512928 0.00187291 -6.0301e-34 -0.0514475 0.000665399 -3.36603e-36 -0.0471511 0.000930236 -1.68905e-36 -0.046945 -0.0518924 -1.5854e-33 0.00232366 -0.0468507 -1.48785e-33 0.0223323 -0.00261911 0 0.00121397 -0.00279301 0 0.000829252 -0.0517366 -1.58202e-33 0.00463028 -0.042116 -1.39859e-33 0.0302613 -0.0434338 -1.42337e-33 0.0283584 0.00134109 1.81003e-36 -0.0424829 -0.0392365 -1.34457e-33 0.0338747 -0.0325659 -1.21986e-33 0.0402553 -0.00151139 0 0.0427197 -0.00137411 0 0.0023097 -0.00175111 0 0.00211963 -0.0307274 -1.18557e-33 0.0416553 -0.00120364 0 0.0425645 -0.0008741 0 0.0424636 -0.000970423 0 0.00243333 0.000930236 -6.07888e-37 -0.041955 0.0239707 -1.93134e-34 -0.0453429 -0.0288188 -1.14999e-33 0.0429792 -0.0268678 -1.11366e-33 0.0442053 0.0259758 -1.55817e-34 -0.0442053 -0.00178849 0 0.0429246 0.0279268 -1.19479e-34 -0.0429792 0.000665399 -2.19554e-36 -0.0417489 -0.022801 -1.03799e-33 0.0463938 -0.0248627 -1.07634e-33 0.0453429 0.0298354 -8.3906e-35 -0.0416553 -0.0206888 -9.98734e-34 0.0473548 -0.00202697 0 0.0431735 -0.000613801 -1.00097e-35 -0.0414249 -0.000970423 0 -0.00243333 -0.000551645 0 -0.00248696 -0.00126225 -1.40419e-35 -0.0415891 -0.00137411 0 -0.0023097 -0.000944826 -1.20619e-35 -0.0414802 -0.00221996 0 0.043459 -0.0185523 -9.59047e-34 0.0482117 -0.0163741 -9.18612e-34 0.0489738 -0.000278199 -7.94119e-36 -0.0414249 -0.000129827 0 -0.00246904 0.000282894 0 -0.00238009 5.28265e-05 -5.91289e-36 -0.0414802 -0.00175111 0 -0.00211963 0.000370245 -3.9801e-36 -0.0415891 -0.0141544 -8.77428e-34 0.0496411 -0.00236193 0 0.0437731 -0.0119111 -8.3583e-34 0.0502075 -0.00244877 0 0.0441066 0.000674647 0 -0.00222267 0.00103416 0 -0.00200131 -0.002478 -1.54155e-35 0.04445 -0.00965462 -7.94011e-34 0.0506693 0.0316739 -4.96121e-35 -0.0402553 -0.040712 -1.37224e-33 0.0321076 0.0334422 -1.65977e-35 -0.0387792 -0.00737275 -7.51744e-34 0.0510308 -0.00236193 0 0.0451269 -0.00244877 0 0.0447934 -0.00276491 -6.66462e-34 0.0514475 -0.000460501 -6.23846e-34 0.0514991 -0.0008741 0 0.0464364 0.0351485 1.52862e-35 -0.0372183 0.00135109 0 -0.00172237 0.0367873 4.59414e-35 -0.0355783 0.00157868 0 0.0442777 0.00157868 0 0.0446223 0.00873486 -4.54017e-34 0.050674 0.000282894 0 0.00238009 -0.0001879 0 0.0424345 0.000149016 0 0.0425071 0.03982 1.02763e-34 -0.0321076 0.0383445 7.51003e-35 -0.0338747 0.00152043 0 0.043938 0.0110051 -4.12145e-34 0.0502098 0.00140562 0 0.043613 0.0154558 -3.30124e-34 0.0489828 0.00123753 0 0.0433121 0.00161633 0 -0.00139389 0.0239452 -1.73954e-34 0.0453567 0.000762295 0 0.0428163 0.00102101 0 0.043044 -0.0015574 -1.70662e-35 -0.0471511 -0.00126225 -1.52816e-35 -0.0473109 -0.00274446 -6.88378e-34 -0.0514475 0.00182223 0 0.0010253 0.0449044 2.0901e-34 0.0244047 0.0459492 2.27881e-34 0.022354 0.0398148 1.16581e-34 0.0321132 0.0412139 1.4205e-34 0.0302768 0.00161633 0 0.00139389 0.0469029 2.45059e-34 0.020254 -0.0486642 -1.5223e-33 0.0180897 -0.0478064 -1.50597e-33 0.0202278 0.0437565 1.88225e-34 0.0264247 0.042526 1.65899e-34 0.0283826 0.0508446 3.14551e-34 0.00463028 0.00203423 0 0.000211099 0.0505868 3.1028e-34 0.00691987 0.0510004 3.1693e-34 0.00232366 0.0485322 2.74243e-34 0.015918 0.00196288 0 0.000627224 0.00135109 0 0.00172237 0.00103416 0 0.00200131 0.0334301 -1.54661e-38 0.0387886 0.0502247 3.0408e-34 0.00920124 0.00203423 0 -0.000211099 0.051054 6.34787e-34 -7.08517e-19 0.0510004 3.15923e-34 -0.00232366 0.0508446 3.12544e-34 -0.00463028 0.0505868 3.07282e-34 -0.00691987 0.0491942 2.86005e-34 0.0137127 0.0497584 2.95951e-34 0.0114738 0.0316514 -3.25788e-35 0.0402728 0.00196288 0 -0.000627224 0.0502269 3.00135e-34 -0.00919243 0.0497649 2.91106e-34 -0.011448 -0.0457971 -1.46792e-33 0.0244032 0.0492009 2.80192e-34 -0.0136864 0.00182223 0 -0.0010253 0.0477722 2.52824e-34 -0.0180897 0.0485347 2.67395e-34 -0.0159079 -0.0325434 -1.23689e-33 -0.0402728 -0.0500929 -1.54966e-33 0.0136864 0.0469144 2.36501e-34 -0.0202278 0.0459587 2.18375e-34 -0.0223323 0.0351405 3.1269e-35 0.0372269 0.0449051 1.98447e-34 -0.0244032 0.0437686 1.77002e-34 -0.0264062 0.025957 -1.37006e-34 0.0442155 0.0279243 -1.00902e-34 0.0429811 0.041224 1.29121e-34 -0.0302613 0.0425418 1.53897e-34 -0.0283584 0.0132502 -3.70759e-34 0.0496453 0.0176361 -2.89979e-34 0.04822 0.0197909 -2.50327e-34 0.0473568 0.0014759 1.85509e-36 -0.0461098 0.00648075 -5.17728e-34 -0.0510308 0.00417347 -5.60443e-34 -0.051292 0.0218918 -2.11691e-34 0.0464031 -0.00506547 -7.0903e-34 0.051292 -0.00178849 0 0.0459754 -0.00202697 0 0.0457265 -0.0446606 -1.44647e-33 0.0264062 -0.00223309 -2.10717e-35 -0.0464171 -0.000278199 -9.25205e-36 -0.0474751 5.28265e-05 -7.19982e-36 -0.0474198 0.000370245 -5.21981e-36 -0.0473109 0.00115753 -2.34616e-37 -0.0466981 0.00134109 9.57606e-37 -0.0464171 0.00155829 2.43336e-36 -0.0457845 0.001586 1.51988e-35 -0.04545 0.00185245 -5.81094e-34 0.0514475 0.00416877 -5.38303e-34 0.0512928 0.000762295 0 0.0460837 0.00645609 -4.9607e-34 0.051035 0.00152043 0 0.044962 0.00140562 0 0.045287 0.00123753 0 0.0455879 0.00102101 0 0.045856 -0.0494267 -1.53687e-33 0.0159079 0.0298162 -6.62075e-35 0.0416703 -0.050657 -1.56058e-33 0.011448 -0.0343221 -1.26946e-33 -0.0387886 0.0477656 2.60544e-34 0.0181048 0.000468814 0 0.0462644 0.000149016 0 0.0463929 -0.0001879 0 0.0464655 -0.00053224 0 0.0464802 -0.00120364 0 0.0463355 -0.00151139 0 0.0461803 -0.00221996 0 0.045441 0.000468814 0 0.0426356 0.0383268 8.94563e-35 0.0338939 0.0367687 6.10188e-35 0.0355985 0.000674647 0 0.00222267 0.0266226 0.0188 -0.0437527 0.0279243 0.0188 -0.0429811 0.0285669 0.0188 -0.0424892 -0.034055 0.0188 -0.0389549 -0.0357782 0.0188 -0.0373994 -0.0343342 0.0188 -0.0387792 -0.0514224 0.0188 0.00696368 -0.0511167 0.0188 0.00920124 -0.0514788 0.0188 0.00691987 0.0246159 0.0188 -0.0449318 0.025957 0.0188 -0.0442155 -0.0457971 0.0188 -0.0244032 -0.0456643 0.0188 -0.0245439 -0.0467226 0.0188 -0.0224839 0.0161252 0.0188 -0.048707 0.0176361 0.0188 -0.04822 0.0183138 0.0188 -0.0479067 -0.0494242 0.0188 0.015918 -0.0493437 0.0188 0.0160005 -0.0486576 0.0188 0.0181048 -0.0505827 0.0188 -0.0115444 -0.0500929 0.0188 -0.0136864 -0.0500108 0.0188 -0.0137971 -0.0485644 0.0188 -0.0182105 -0.04934 0.0188 -0.0160148 -0.0486642 0.0188 -0.0180897 -0.0476893 0.0188 -0.0203728 -0.0468507 0.0188 -0.0223323 -0.0494267 0.0188 -0.0159079 0.0154558 0.0188 -0.0489828 0.0139004 0.0188 -0.0494093 -0.0264982 0.0188 -0.0443654 -0.0284789 0.0188 -0.0431422 -0.0268678 0.0188 -0.0442053 -0.0360405 0.0188 -0.0372183 -0.0374267 0.0188 -0.0357692 -0.0405152 0.0188 -0.0322732 -0.0419262 0.0188 -0.0304377 -0.040712 0.0188 -0.0321076 0.0132502 0.0188 -0.0496453 0.011662 0.0188 -0.0500044 -0.00911184 0.0188 -0.0507136 -0.00737275 0.0188 -0.0510308 -0.00680969 0.0188 -0.051054 -0.0516836 0.0188 -0.00466018 -0.0518415 0.0188 -0.00233895 -0.0517366 0.0188 -0.00463028 0.00939289 0.0188 -0.0504992 0.00709309 0.0188 -0.0508937 0.00873486 0.0188 -0.050674 -0.0510558 0.0188 -0.00925682 -0.050657 0.0188 -0.011448 -0.042116 0.0188 -0.0302613 -0.0432557 0.0188 -0.0285363 -0.022801 0.0188 -0.0463938 -0.0223827 0.0188 -0.0465385 -0.02446 0.0188 -0.0455006 -0.0303926 0.0188 -0.0418357 -0.0322513 0.0188 -0.04044 -0.0307274 0.0188 -0.0416553 -0.0390059 0.0188 -0.0340602 -0.0392365 0.0188 -0.0338747 -0.0119111 0.0188 -0.0502075 -0.0114077 0.0188 -0.0502687 -0.013658 0.0188 -0.0497243 -0.0180924 0.0188 -0.0483279 -0.0202662 0.0188 -0.047479 -0.0185523 0.0188 -0.0482117 -0.00965462 0.0188 -0.0506693 -0.0434338 0.0188 -0.0283584 -0.0445035 0.0188 -0.0265691 -0.0248627 0.0188 -0.0453429 -0.0163741 0.0188 -0.0489738 -0.0158863 0.0188 -0.0490773 -0.0376793 0.0188 -0.0355783 -0.0325659 0.0188 -0.0402553 -0.0446606 0.0188 -0.0264062 -0.0288188 0.0188 -0.0429792 -0.0206888 0.0188 -0.0473548 -0.0478064 0.0188 -0.0202278 -0.0141544 0.0188 -0.0496411 -0.00450308 0.0188 -0.0512896 -0.00276491 0.0188 -0.0514475 -0.00218603 0.0188 -0.0514201 -0.00506547 0.0188 -0.051292 0.000150602 0.0188 -0.0514452 0.00185245 0.0188 -0.0514475 0.00247392 0.0188 -0.0513663 -0.000460501 0.0188 -0.0514991 0.00416877 0.0188 -0.0512928 0.00478391 0.0188 -0.0511834 -0.0514224 0.0188 -0.00696368 -0.0511189 0.0188 -0.00919243 0.00645609 0.0188 -0.051035 -0.0514788 0.0188 -0.00691987 0.0110051 0.0188 -0.0502098 -0.051896 0.0188 7.20202e-19 -0.0518924 0.0188 -0.00232366 0.0204551 0.0188 -0.0470128 0.0197909 0.0188 -0.0473568 -0.051946 0.0188 1.72846e-17 -0.0518924 0.0188 0.00232366 0.0218918 0.0188 -0.0464031 0.0225493 0.0188 -0.0460252 -0.0510577 0.0188 0.00924946 -0.0506504 0.0188 0.0114738 -0.0500184 0.0188 0.0137678 -0.0500862 0.0188 0.0137127 -0.0505898 0.0188 0.0115175 -0.0485702 0.0188 0.0181976 -0.0477949 0.0188 0.020254 0.0239452 0.0188 -0.0453567 -0.0477016 0.0188 0.0203454 -0.0468412 0.0188 0.022354 0.0298162 0.0188 -0.0416703 0.0304527 0.0188 -0.0411379 0.0316514 0.0188 -0.0402728 0.0322885 0.0188 -0.0396915 -0.0467341 0.0188 0.0224583 -0.0457964 0.0188 0.0244047 -0.0456678 0.0188 0.0245363 -0.0446485 0.0188 0.0264247 0.0340486 0.0188 -0.0381725 0.0334301 0.0188 -0.0387886 -0.0445145 0.0188 0.0265528 -0.043418 0.0188 0.0283826 0.0351405 0.0188 -0.0372269 0.035733 0.0188 -0.036581 0.0367687 0.0188 -0.0355985 0.0373493 0.0188 -0.0349075 -0.0421059 0.0188 0.0302768 -0.0432731 0.0188 0.0285105 0.0383268 0.0188 -0.0338939 0.0388931 0.0188 -0.0331573 -0.0419402 0.0188 0.0304171 -0.0407068 0.0188 0.0321132 -0.0405157 0.0188 0.0322725 -0.0392188 0.0188 0.0338939 0.0398148 0.0188 -0.0321132 0.04035 0.0188 -0.0313484 0.0417201 0.0188 -0.0294808 0.0412139 0.0188 -0.0302768 -0.0374484 0.0188 0.0357466 -0.0360325 0.0188 0.0372269 -0.0376607 0.0188 0.0355985 -0.0390226 0.0188 0.0340428 -0.0357926 0.0188 0.0373844 -0.0343221 0.0188 0.0387886 0.042526 0.0188 -0.0283826 0.043012 0.0188 -0.0275388 0.0442146 0.0188 -0.0255425 0.0437565 0.0188 -0.0264247 0.0449044 0.0188 -0.0244047 0.0459492 0.0188 -0.022354 0.0453216 0.0188 -0.0235029 -0.0340604 0.0188 0.0389509 -0.0325434 0.0188 0.0402728 -0.0288163 0.0188 0.0429811 -0.0307082 0.0188 0.0416703 -0.030417 0.0188 0.0418177 -0.0322734 0.0188 0.0404236 0.0472566 0.0188 -0.0192727 0.0469029 0.0188 -0.020254 0.0477656 0.0188 -0.0181048 0.0463331 0.0188 -0.0214201 0.0485322 0.0188 -0.015918 0.0480798 0.0188 -0.0170953 -0.0284913 0.0188 0.043133 -0.026849 0.0188 0.0442155 -0.0265103 0.0188 0.0443593 -0.0248372 0.0188 0.0453567 0.0491942 0.0188 -0.0137127 0.0488015 0.0188 -0.0148915 -0.0227838 0.0188 0.0464031 -0.0244866 0.0188 0.0454871 0.0497584 0.0188 -0.0114738 0.0494225 0.0188 -0.0126571 -0.022408 0.0188 0.0465257 -0.0206829 0.0188 0.0473568 -0.0185281 0.0188 0.04822 -0.0202744 0.0188 0.0474749 0.0502247 0.0188 -0.00920124 0.049945 0.0188 -0.0103786 0.0505868 0.0188 -0.00691987 0.0508446 0.0188 -0.00463028 0.0506764 0.0188 -0.00579512 0.050363 0.0188 -0.00809133 -0.015916 0.0188 0.0490682 -0.0141422 0.0188 0.0496453 -0.0163478 0.0188 0.0489828 -0.0181107 0.0188 0.0483223 0.0509899 0.0188 -0.00114687 0.0510004 0.0188 -0.00232366 0.051054 0.0188 -7.08517e-19 -0.0136823 0.0188 0.0497169 -0.0118971 0.0188 0.0502098 -0.00734809 0.0188 0.051035 -0.00962686 0.0188 0.050674 -0.00913529 0.0188 0.0507106 0.0509899 0.0188 0.00117602 0.0510004 0.0188 0.00232366 -0.00219203 0.0188 0.0514203 -0.000431499 0.0188 0.0514991 -0.00274446 0.0188 0.0514475 -0.00506077 0.0188 0.0512928 -0.00452416 0.0188 0.0512869 0.0132624 0.0188 0.0496411 0.0110191 0.0188 0.0502075 0.011634 0.0188 0.0500104 0.00648075 0.0188 0.0510308 0.00417347 0.0188 0.051292 0.00476783 0.0188 0.0511841 0.0138907 0.0188 0.0494114 0.0154821 0.0188 0.0489738 0.0459587 0.0188 0.0223323 0.0449051 0.0188 0.0244032 0.0453089 0.0188 0.0235256 0.00876262 0.0188 0.0506693 0.00936394 0.0188 0.0505054 0.00708059 0.0188 0.0508964 0.0265959 0.0188 0.0437691 0.0279268 0.0188 0.0429792 0.0259758 0.0188 0.0442053 0.0285484 0.0188 0.0425006 0.0298354 0.0188 0.0416553 0.0197968 0.0188 0.0473548 0.0176603 0.0188 0.0482117 0.018285 0.0188 0.0479183 0.016108 0.0188 0.048714 0.0239707 0.0188 0.0453429 0.0245962 0.0188 0.044944 0.0316739 0.0188 0.0402553 0.0322684 0.0188 0.0397092 0.0334422 0.0188 0.0387792 0.0367873 0.0188 0.0355783 0.0351485 0.0188 0.0372183 0.0357205 0.0188 0.036592 0.021909 0.0188 0.0463938 0.0225468 0.0188 0.0460262 0.0304488 0.0188 0.0411414 0.0340256 0.0188 0.0381928 0.0373417 0.0188 0.0349169 0.0383445 0.0188 0.0338747 0.0388746 0.0188 0.0331802 0.03982 0.0188 0.0321076 0.0430032 0.0188 0.0275545 0.0437686 0.0188 0.0264062 0.0425418 0.0188 0.0283584 0.0403319 0.0188 0.0313709 0.041224 0.0188 0.0302613 0.0441995 0.0188 0.0255694 0.0417134 0.0188 0.0294891 0.0469144 0.0188 0.0202278 0.047249 0.0188 0.0192941 0.0477722 0.0188 0.0180897 0.0204313 0.0188 0.0470224 0.0480693 0.0188 0.0171249 0.0485347 0.0188 0.0159079 0.0463314 0.0188 0.0214231 0.0487941 0.0188 0.0149125 0.0492009 0.0188 0.0136864 0.0494217 0.0188 0.0126613 0.0497649 0.0188 0.011448 0.00244342 0.0188 0.0513676 0.00187291 0.0188 0.0514475 0.0502269 0.0188 0.00919243 0.0499405 0.0188 0.0104047 0.0503578 0.0188 0.00812168 0.0505868 0.0188 0.00691987 0.000123471 0.0188 0.0514464 0.0508446 0.0188 0.00463028 0.0508854 0.0188 0.00349002 0.0506735 0.0188 0.0058122 -0.0114094 0.0188 0.0502682 -0.00684077 0.0188 0.05105 0.0508854 0.0188 -0.00347865 -0.0517366 0.0188 0.00463028 -0.0516836 0.0188 0.00466018 -0.0518415 0.0188 0.00233895 0.0509899 0.058 0.00114687 0.0509899 0.058 -0.00117602 0.0509899 0.0188 -0.00114687 0.0508854 0.058 -0.00349002 0.0508854 0.0188 -0.00347865 0.0506764 0.0188 -0.00579512 0.0506735 0.058 -0.0058122 0.0503578 0.058 -0.00812168 0.050363 0.0188 -0.00809133 0.0499405 0.058 -0.0104047 0.049945 0.0188 -0.0103786 0.0494225 0.0188 -0.0126571 0.0494217 0.058 -0.0126613 0.0487941 0.058 -0.0149125 0.0488015 0.0188 -0.0148915 0.0480693 0.058 -0.0171249 0.0480798 0.0188 -0.0170953 0.0472566 0.0188 -0.0192727 0.047249 0.058 -0.0192941 0.0463314 0.058 -0.0214231 0.0463331 0.0188 -0.0214201 0.0453089 0.058 -0.0235256 0.0453216 0.0188 -0.0235029 0.0442146 0.0188 -0.0255425 0.0441995 0.058 -0.0255694 0.0430032 0.058 -0.0275545 0.043012 0.0188 -0.0275388 0.0417134 0.058 -0.0294891 0.0417201 0.0188 -0.0294808 0.04035 0.0188 -0.0313484 0.0403319 0.058 -0.0313709 0.0388746 0.058 -0.0331802 0.0388931 0.0188 -0.0331573 0.0373417 0.058 -0.0349169 0.0373493 0.0188 -0.0349075 0.035733 0.0188 -0.036581 0.0357205 0.058 -0.036592 0.0340256 0.058 -0.0381928 0.0340486 0.0188 -0.0381725 0.0322684 0.058 -0.0397092 0.0322885 0.0188 -0.0396915 0.0304527 0.0188 -0.0411379 0.0304488 0.058 -0.0411414 0.0285484 0.058 -0.0425006 0.0285669 0.0188 -0.0424892 0.0265959 0.058 -0.0437691 0.0266226 0.0188 -0.0437527 0.0246159 0.0188 -0.0449318 0.0245962 0.058 -0.044944 0.0225468 0.058 -0.0460262 0.0225493 0.0188 -0.0460252 0.0204313 0.058 -0.0470224 0.0204551 0.0188 -0.0470128 0.0183138 0.0188 -0.0479067 0.018285 0.058 -0.0479183 0.016108 0.058 -0.048714 0.0161252 0.0188 -0.048707 0.0138907 0.058 -0.0494114 0.0139004 0.0188 -0.0494093 0.011662 0.0188 -0.0500044 0.011634 0.058 -0.0500104 0.00936394 0.058 -0.0505054 0.00939289 0.0188 -0.0504992 0.00708059 0.058 -0.0508964 0.00709309 0.0188 -0.0508937 0.00478391 0.0188 -0.0511834 0.00476783 0.058 -0.0511841 0.00244342 0.058 -0.0513676 0.00247392 0.0188 -0.0513663 0.000123471 0.058 -0.0514464 0.000150602 0.0188 -0.0514452 -0.00218603 0.0188 -0.0514201 -0.00219203 0.058 -0.0514203 -0.00452416 0.058 -0.0512869 -0.00450308 0.0188 -0.0512896 -0.00684077 0.058 -0.05105 -0.00680969 0.0188 -0.051054 -0.00911184 0.0188 -0.0507136 -0.00913529 0.058 -0.0507106 -0.0114094 0.058 -0.0502682 -0.0114077 0.0188 -0.0502687 -0.0136823 0.058 -0.0497169 -0.013658 0.0188 -0.0497243 -0.0158863 0.0188 -0.0490773 -0.015916 0.058 -0.0490682 -0.0181107 0.058 -0.0483223 -0.0180924 0.0188 -0.0483279 -0.0202744 0.058 -0.0474749 -0.0202662 0.0188 -0.047479 -0.0223827 0.0188 -0.0465385 -0.022408 0.058 -0.0465257 -0.0244866 0.058 -0.0454871 -0.02446 0.0188 -0.0455006 -0.0265103 0.058 -0.0443593 -0.0264982 0.0188 -0.0443654 -0.0284789 0.0188 -0.0431422 -0.0284913 0.058 -0.043133 -0.030417 0.058 -0.0418177 -0.0303926 0.0188 -0.0418357 -0.0322734 0.058 -0.0404236 -0.0322513 0.0188 -0.04044 -0.034055 0.0188 -0.0389549 -0.0340604 0.058 -0.0389509 -0.0357926 0.058 -0.0373844 -0.0357782 0.0188 -0.0373994 -0.0374484 0.058 -0.0357466 -0.0374267 0.0188 -0.0357692 -0.0390059 0.0188 -0.0340602 -0.0390226 0.058 -0.0340428 -0.0405157 0.058 -0.0322725 -0.0405152 0.0188 -0.0322732 -0.0419402 0.058 -0.0304171 -0.0419262 0.0188 -0.0304377 -0.0432557 0.0188 -0.0285363 -0.0432731 0.058 -0.0285105 -0.0445145 0.058 -0.0265528 -0.0445035 0.0188 -0.0265691 -0.0456678 0.058 -0.0245363 -0.0456643 0.0188 -0.0245439 -0.0467226 0.0188 -0.0224839 -0.0467341 0.058 -0.0224583 -0.0477016 0.058 -0.0203454 -0.0476893 0.0188 -0.0203728 -0.0485702 0.058 -0.0181976 -0.0485644 0.0188 -0.0182105 -0.04934 0.0188 -0.0160148 -0.0493437 0.058 -0.0160005 -0.0500184 0.058 -0.0137678 -0.0500108 0.0188 -0.0137971 -0.0505898 0.058 -0.0115175 -0.0505827 0.0188 -0.0115444 -0.0510558 0.0188 -0.00925682 -0.0510577 0.058 -0.00924946 -0.0514224 0.058 -0.00696368 -0.0514224 0.0188 -0.00696368 -0.0516836 0.058 -0.00466018 -0.0516836 0.0188 -0.00466018 -0.0518415 0.0188 -0.00233895 -0.0518415 0.058 -0.00233895 -0.051896 0.0188 7.20202e-19 -0.051896 0.058 -1.18814e-17 0.0509899 0.0188 0.00117602 0.0508854 0.058 0.00347865 0.0508854 0.0188 0.00349002 0.0506735 0.0188 0.0058122 0.0506764 0.058 0.00579512 0.0503578 0.0188 0.00812168 0.050363 0.058 0.00809133 0.049945 0.058 0.0103786 0.0499405 0.0188 0.0104047 0.0494217 0.0188 0.0126613 0.0494225 0.058 0.0126571 0.0487941 0.0188 0.0149125 0.0488015 0.058 0.0148915 0.0480798 0.058 0.0170953 0.0480693 0.0188 0.0171249 0.047249 0.0188 0.0192941 0.0472566 0.058 0.0192727 0.0463314 0.0188 0.0214231 0.0463331 0.058 0.0214201 0.0453216 0.058 0.0235029 0.0453089 0.0188 0.0235256 0.0441995 0.0188 0.0255694 0.0442146 0.058 0.0255425 0.0430032 0.0188 0.0275545 0.043012 0.058 0.0275388 0.0417201 0.058 0.0294808 0.0417134 0.0188 0.0294891 0.0403319 0.0188 0.0313709 0.04035 0.058 0.0313484 0.0388746 0.0188 0.0331802 0.0388931 0.058 0.0331573 0.0373493 0.058 0.0349075 0.0373417 0.0188 0.0349169 0.0357205 0.0188 0.036592 0.035733 0.058 0.036581 0.0340256 0.0188 0.0381928 0.0340486 0.058 0.0381725 0.0322885 0.058 0.0396915 0.0322684 0.0188 0.0397092 0.0304488 0.0188 0.0411414 0.0304527 0.058 0.0411379 0.0285484 0.0188 0.0425006 0.0285669 0.058 0.0424892 0.0266226 0.058 0.0437527 0.0265959 0.0188 0.0437691 0.0245962 0.0188 0.044944 0.0246159 0.058 0.0449318 0.0225468 0.0188 0.0460262 0.0225493 0.058 0.0460252 0.0204551 0.058 0.0470128 0.0204313 0.0188 0.0470224 0.018285 0.0188 0.0479183 0.0183138 0.058 0.0479067 0.016108 0.0188 0.048714 0.0161252 0.058 0.048707 0.0139004 0.058 0.0494093 0.0138907 0.0188 0.0494114 0.011634 0.0188 0.0500104 0.011662 0.058 0.0500044 0.00936394 0.0188 0.0505054 0.00939289 0.058 0.0504992 0.00709309 0.058 0.0508937 0.00708059 0.0188 0.0508964 0.00476783 0.0188 0.0511841 0.00478391 0.058 0.0511834 0.00244342 0.0188 0.0513676 0.00247392 0.058 0.0513663 0.000150602 0.058 0.0514452 0.000123471 0.0188 0.0514464 -0.00219203 0.0188 0.0514203 -0.00218603 0.058 0.0514201 -0.00452416 0.0188 0.0512869 -0.00450308 0.058 0.0512896 -0.00680969 0.058 0.051054 -0.00684077 0.0188 0.05105 -0.00913529 0.0188 0.0507106 -0.00911184 0.058 0.0507136 -0.0114094 0.0188 0.0502682 -0.0114077 0.058 0.0502687 -0.013658 0.058 0.0497243 -0.0136823 0.0188 0.0497169 -0.015916 0.0188 0.0490682 -0.0158863 0.058 0.0490773 -0.0181107 0.0188 0.0483223 -0.0180924 0.058 0.0483279 -0.0202662 0.058 0.047479 -0.0202744 0.0188 0.0474749 -0.022408 0.0188 0.0465257 -0.0223827 0.058 0.0465385 -0.0244866 0.0188 0.0454871 -0.02446 0.058 0.0455006 -0.0264982 0.058 0.0443654 -0.0265103 0.0188 0.0443593 -0.0284913 0.0188 0.043133 -0.0284789 0.058 0.0431422 -0.030417 0.0188 0.0418177 -0.0303926 0.058 0.0418357 -0.0322513 0.058 0.04044 -0.0322734 0.0188 0.0404236 -0.0340604 0.0188 0.0389509 -0.034055 0.058 0.0389549 -0.0357926 0.0188 0.0373844 -0.0357782 0.058 0.0373994 -0.0374267 0.058 0.0357692 -0.0374484 0.0188 0.0357466 -0.0390226 0.0188 0.0340428 -0.0390059 0.058 0.0340602 -0.0405157 0.0188 0.0322725 -0.0405152 0.058 0.0322732 -0.0419262 0.058 0.0304377 -0.0419402 0.0188 0.0304171 -0.0432731 0.0188 0.0285105 -0.0432557 0.058 0.0285363 -0.0445145 0.0188 0.0265528 -0.0445035 0.058 0.0265691 -0.0456643 0.058 0.0245439 -0.0456678 0.0188 0.0245363 -0.0467341 0.0188 0.0224583 -0.0467226 0.058 0.0224839 -0.0477016 0.0188 0.0203454 -0.0476893 0.058 0.0203728 -0.0485644 0.058 0.0182105 -0.0485702 0.0188 0.0181976 -0.0493437 0.0188 0.0160005 -0.04934 0.058 0.0160148 -0.0500184 0.0188 0.0137678 -0.0500108 0.058 0.0137971 -0.0505827 0.058 0.0115444 -0.0505898 0.0188 0.0115175 -0.0510577 0.0188 0.00924946 -0.0510558 0.058 0.00925682 -0.0514224 0.0188 0.00696368 -0.0514224 0.058 0.00696368 -0.0516836 0.058 0.00466018 -0.0516836 0.0188 0.00466018 -0.0518415 0.0188 0.00233895 -0.0518415 0.058 0.00233895 -0.0518415 0.058 -0.00233895 -0.051946 0.058 6.18949e-21 -0.051896 0.058 -1.18814e-17 -0.0518914 0.058 0.00234122 -0.0518914 0.058 -0.00234122 -0.0516836 0.058 -0.00466018 -0.0517334 0.058 -0.00466471 -0.0514224 0.058 -0.00696368 -0.0514719 0.058 -0.00697045 -0.0510577 0.058 -0.00924946 -0.051105 0.058 -0.00926581 -0.0505898 0.058 -0.0115175 -0.0506315 0.058 -0.0115556 -0.0500184 0.058 -0.0137678 -0.050059 0.058 -0.0138105 -0.0493437 0.058 -0.0160005 -0.0493875 0.058 -0.0160304 -0.0485702 0.058 -0.0181976 -0.0486112 0.058 -0.0182282 -0.0477016 0.058 -0.0203454 -0.0477352 0.058 -0.0203926 -0.0467341 0.058 -0.0224583 -0.0467675 0.058 -0.0225058 -0.0456678 0.058 -0.0245363 -0.0457083 0.058 -0.0245678 -0.0445145 0.058 -0.0265528 -0.0445463 0.058 -0.0265949 -0.0432731 0.058 -0.0285105 -0.0432973 0.058 -0.0285641 -0.0419402 0.058 -0.0304171 -0.0419665 0.058 -0.0304673 -0.0405157 0.058 -0.0322725 -0.0405542 0.058 -0.0323046 -0.0390226 0.058 -0.0340428 -0.0390434 0.058 -0.0340933 -0.0374484 0.058 -0.0357466 -0.0374627 0.058 -0.0358039 -0.0357926 0.058 -0.0373844 -0.0358125 0.058 -0.0374357 -0.0340604 0.058 -0.0389509 -0.0340876 0.058 -0.0389928 -0.0322734 0.058 -0.0404236 -0.0322822 0.058 -0.0404793 -0.030417 0.058 -0.0418177 -0.0304217 0.058 -0.0418764 -0.0284913 0.058 -0.043133 -0.0285062 0.058 -0.0431841 -0.0265103 0.058 -0.0443593 -0.0265236 0.058 -0.0444085 -0.0244866 0.058 -0.0454871 -0.0244833 0.058 -0.0455448 -0.022408 0.058 -0.0465257 -0.022404 0.058 -0.0465837 -0.0202744 0.058 -0.0474749 -0.0202855 0.058 -0.0475252 -0.0181107 0.058 -0.0483223 -0.0181096 0.058 -0.0483748 -0.015916 0.058 -0.0490682 -0.0159013 0.058 -0.049125 -0.0136823 0.058 -0.0497169 -0.0136709 0.058 -0.0497726 -0.0114094 0.058 -0.0502682 -0.0114184 0.058 -0.0503176 -0.00913529 0.058 -0.0507106 -0.00912026 0.058 -0.0507629 -0.00684077 0.058 -0.05105 -0.00681587 0.058 -0.0511036 -0.00452416 0.058 -0.0512869 -0.00450703 0.058 -0.0513394 -0.00219203 0.058 -0.0514203 -0.00218773 0.058 -0.0514701 0.000123471 0.058 -0.0514464 0.000151182 0.058 -0.0514952 0.00244342 0.058 -0.0513676 0.00247676 0.058 -0.0514162 0.00476783 0.058 -0.0511841 0.004789 0.058 -0.0512331 0.00708059 0.058 -0.0508964 0.00710041 0.058 -0.0509432 0.00936394 0.058 -0.0505054 0.00940245 0.058 -0.0505483 0.011634 0.058 -0.0500104 0.0116737 0.058 -0.050053 0.0138907 0.058 -0.0494114 0.0139143 0.058 -0.0494573 0.016108 0.058 -0.048714 0.0161413 0.058 -0.0487544 0.018285 0.058 -0.0479183 0.018332 0.058 -0.0479533 0.0204313 0.058 -0.0470224 0.0204754 0.058 -0.0470585 0.0225468 0.058 -0.0460262 0.0225716 0.058 -0.0460699 0.0245962 0.058 -0.044944 0.0246403 0.058 -0.0449755 0.0265959 0.058 -0.0437691 0.0266489 0.058 -0.0437952 0.0285484 0.058 -0.0425006 0.0285951 0.058 -0.0425305 0.0304488 0.058 -0.0411414 0.0304827 0.058 -0.0411779 0.0322684 0.058 -0.0397092 0.0323203 0.058 -0.0397301 0.0340256 0.058 -0.0381928 0.0340821 0.058 -0.0382096 0.0357205 0.058 -0.036592 0.0357682 0.058 -0.0366165 0.0373417 0.058 -0.0349169 0.037386 0.058 -0.0349414 0.0388746 0.058 -0.0331802 0.0389313 0.058 -0.0331895 0.0403319 0.058 -0.0313709 0.0403897 0.058 -0.0313789 0.0417134 0.058 -0.0294891 0.0417611 0.058 -0.0295095 0.0430032 0.058 -0.0275545 0.0430542 0.058 -0.0275656 0.0441995 0.058 -0.0255694 0.044258 0.058 -0.0255673 0.0453089 0.058 -0.0235256 0.0453661 0.058 -0.0235257 0.0463314 0.058 -0.0214231 0.0463785 0.058 -0.0214409 0.047249 0.058 -0.0192941 0.0473029 0.058 -0.0192914 0.0480693 0.058 -0.0171249 0.0481269 0.058 -0.0171119 0.0487941 0.058 -0.0149125 0.0488494 0.058 -0.014906 0.0494217 0.058 -0.0126613 0.0494709 0.058 -0.0126694 0.0499405 0.058 -0.0104047 0.0499939 0.058 -0.0103887 0.0503578 0.058 -0.00812168 0.0504123 0.058 -0.00809919 0.0506735 0.058 -0.0058122 0.0507261 0.058 -0.00580075 0.0508854 0.058 -0.00349002 0.0509353 0.058 -0.00348203 0.0509899 0.058 -0.00117602 0.0510399 0.058 -0.00114798 0.0509899 0.058 0.00114687 0.0510399 0.058 0.00117717 0.0508854 0.058 0.00347865 0.0509353 0.058 0.00349341 0.0506764 0.058 0.00579512 0.0507232 0.058 0.00581785 0.050363 0.058 0.00809133 0.0504071 0.058 0.00812957 0.049945 0.058 0.0103786 0.0499895 0.058 0.0104148 0.0494225 0.058 0.0126571 0.0494702 0.058 0.0126737 0.0488015 0.058 0.0148915 0.0488419 0.058 0.014927 0.0480798 0.058 0.0170953 0.0481165 0.058 0.0171415 0.0472566 0.058 0.0192727 0.0472953 0.058 0.0193128 0.0463331 0.058 0.0214201 0.0463768 0.058 0.021444 0.0453216 0.058 0.0235029 0.0453533 0.058 0.0235485 0.0442146 0.058 0.0255425 0.0442429 0.058 0.0255943 0.043012 0.058 0.0275388 0.0430455 0.058 0.0275813 0.0417201 0.058 0.0294808 0.0417544 0.058 0.0295178 0.04035 0.058 0.0313484 0.0403715 0.058 0.0314014 0.0388931 0.058 0.0331573 0.0389128 0.058 0.0332124 0.0373493 0.058 0.0349075 0.0373784 0.058 0.0349508 0.035733 0.058 0.036581 0.0357556 0.058 0.0366276 0.0340486 0.058 0.0381725 0.0340591 0.058 0.0382299 0.0322885 0.058 0.0396915 0.0323002 0.058 0.0397478 0.0304527 0.058 0.0411379 0.0304788 0.058 0.0411813 0.0285669 0.058 0.0424892 0.0285765 0.058 0.0425419 0.0266226 0.058 0.0437527 0.0266222 0.058 0.0438116 0.0246159 0.058 0.0449318 0.0246205 0.058 0.0449877 0.0225493 0.058 0.0460252 0.0225691 0.058 0.0460709 0.0204551 0.058 0.0470128 0.0204515 0.058 0.0470681 0.0183138 0.058 0.0479067 0.0183032 0.058 0.0479649 0.0161252 0.058 0.048707 0.0161241 0.058 0.0487613 0.0139004 0.058 0.0494093 0.0139046 0.058 0.0494594 0.011662 0.058 0.0500044 0.0116457 0.058 0.050059 0.00939289 0.058 0.0504992 0.00937347 0.058 0.0505545 0.00709309 0.058 0.0508937 0.0070879 0.058 0.0509459 0.00478391 0.058 0.0511834 0.0047729 0.058 0.0512338 0.00247392 0.058 0.0513663 0.00244623 0.058 0.0514175 0.000150602 0.058 0.0514452 0.000124024 0.058 0.0514964 -0.00218603 0.058 0.0514201 -0.00219373 0.058 0.0514703 -0.00450308 0.058 0.0512896 -0.00452812 0.058 0.0513367 -0.00680969 0.058 0.051054 -0.00684699 0.058 0.0510996 -0.00911184 0.058 0.0507136 -0.00914374 0.058 0.0507599 -0.0114077 0.058 0.0502687 -0.0114201 0.058 0.050317 -0.013658 0.058 0.0497243 -0.0136951 0.058 0.0497652 -0.0158863 0.058 0.0490773 -0.0159311 0.058 0.0491159 -0.0180924 0.058 0.0483279 -0.0181278 0.058 0.0483692 -0.0202662 0.058 0.047479 -0.0202937 0.058 0.047521 -0.0223827 0.058 0.0465385 -0.0224293 0.058 0.0465709 -0.02446 0.058 0.0455006 -0.02451 0.058 0.0455314 -0.0264982 0.058 0.0443654 -0.0265356 0.058 0.0444024 -0.0284789 0.058 0.0431422 -0.0285186 0.058 0.0431749 -0.0303926 0.058 0.0418357 -0.0304461 0.058 0.0418583 -0.0322513 0.058 0.04044 -0.0323043 0.058 0.0404629 -0.034055 0.058 0.0389549 -0.0340931 0.058 0.0389887 -0.0357782 0.058 0.0373994 -0.0358269 0.058 0.0374208 -0.0374267 0.058 0.0357692 -0.0374843 0.058 0.0357813 -0.0390059 0.058 0.0340602 -0.0390601 0.058 0.0340759 -0.0405152 0.058 0.0322732 -0.0405547 0.058 0.0323038 -0.0419262 0.058 0.0304377 -0.0419805 0.058 0.0304466 -0.0432557 0.058 0.0285363 -0.0433147 0.058 0.0285382 -0.0445035 0.058 0.0265691 -0.0445573 0.058 0.0265786 -0.0456643 0.058 0.0245439 -0.0457117 0.058 0.0245601 -0.0467226 0.058 0.0224839 -0.0467791 0.058 0.0224801 -0.0476893 0.058 0.0203728 -0.0477476 0.058 0.0203652 -0.0485644 0.058 0.0182105 -0.048617 0.058 0.0182153 -0.04934 0.058 0.0160148 -0.0493912 0.058 0.016016 -0.0500108 0.058 0.0137971 -0.0500666 0.058 0.0137812 -0.0505827 0.058 0.0115444 -0.0506385 0.058 0.0115287 -0.0510558 0.058 0.00925682 -0.0511069 0.058 0.00925845 -0.0514224 0.058 0.00696368 -0.0514719 0.058 0.00697045 -0.0516836 0.058 0.00466018 -0.0517334 0.058 0.00466471 -0.0518415 0.058 0.00233895 0.0329768 0.0727 -0.0365123 -0.0415085 0.0727 0.027642 0.0312617 0.0727 -0.0380107 -0.0202143 0.0727 -0.0453801 -0.0137695 0.0727 -0.0476726 -0.0222788 0.0727 -0.0444246 -0.044946 0.0727 0.0216793 -0.0458992 0.0727 0.0196007 0.0257216 0.0727 -0.0420178 -0.0401894 0.0727 0.0295078 -0.0497708 0.0727 0.00415454 -0.049909 0.0727 0.00188187 0.00430006 0.0727 -0.049271 0.0237549 0.0727 -0.0431794 0.03619 0.0727 -0.0332855 0.0376944 0.0727 -0.0315525 -0.0357116 0.0727 0.0347357 -0.0498728 0.0727 -0.00268859 -0.0496968 0.0727 -0.00495364 0.00203294 0.0727 -0.0494377 0.00656554 0.0727 -0.0489995 -0.00480877 0.0727 -0.0493066 -0.00253445 0.0727 -0.0494546 0.0110488 0.0727 -0.0481465 -0.0487337 0.0727 0.0108839 -0.0491832 0.0727 0.00865557 -0.0455858 0.0727 -0.020313 -0.0410996 0.0727 -0.0282397 -0.0472638 0.0727 -0.0160689 -0.0464699 0.0727 -0.0182222 -0.0485435 0.0727 -0.0116987 -0.00706669 0.0727 -0.0490551 -0.0467583 0.0727 0.017473 -0.0481804 0.0727 0.0130975 0.0196758 0.0727 -0.0452251 -0.0180993 0.0727 -0.0462438 -0.0159421 0.0727 -0.0470119 -0.0300487 0.0727 -0.0396725 -0.0352368 0.0727 -0.0352105 -0.0335787 0.0727 -0.0367742 -0.0423524 0.0727 -0.0263457 -0.0446041 0.0727 -0.0223652 0.0132486 0.0727 -0.0475668 -0.0242928 0.0727 -0.0433772 -0.026277 0.0727 -0.0422241 -0.0499433 0.0727 -0.000405572 -0.047955 0.0727 -0.0138945 -0.0281956 0.0727 -0.0409892 0.00882938 0.0727 -0.0486232 -0.00932248 0.0727 -0.0486966 -0.011563 0.0727 -0.0482342 -0.00024373 0.0727 -0.049499 -0.031842 0.0727 -0.0382685 -0.0397574 0.0727 -0.0300789 -0.0368163 0.0727 -0.0335774 -0.0383258 0.0727 -0.0318633 -0.043525 0.0727 -0.0243788 -0.0494159 0.0727 -0.0072154 -0.0490303 0.0727 -0.00947387 -0.0495289 0.0727 0.00641244 0.0175806 0.0727 -0.0461009 0.0154288 0.0727 -0.0468841 -0.0475233 0.0727 0.0152963 0.0217339 0.0727 -0.0442513 -0.0438925 0.0727 0.0237186 0.0276217 0.0727 -0.0407723 -0.0427428 0.0727 0.0257123 0.0294684 0.0727 -0.0394366 -0.0387723 0.0727 0.0313246 0.0346174 0.0727 -0.0349387 -0.0372784 0.0727 0.0330687 -0.0340664 0.0727 0.03633 0.0391006 0.0727 -0.0297704 -0.0305528 0.0727 0.0392909 -0.0323392 0.0727 0.0378545 0.0404261 0.0727 -0.0279215 0.0416708 0.0727 -0.0260058 0.0428295 0.0727 -0.0240307 -0.0287072 0.0727 0.0406393 0.0438857 0.0727 -0.0220205 -0.0267879 0.0727 0.0419077 -0.0248141 0.0727 0.0430854 -0.0227965 0.0727 0.0441665 0.0448507 0.0727 -0.0199582 0.0457247 0.0727 -0.0178441 0.0464996 0.0727 -0.0156954 -0.0186079 0.0727 0.0460465 -0.0207334 0.0727 0.0451515 -0.0164551 0.0727 0.046839 0.0471698 0.0727 -0.0135246 0.0477413 0.0727 -0.0113183 -0.0142753 0.0727 0.0475289 0.0485805 0.0727 -0.00682867 0.0482141 0.0727 -0.00907649 -0.00980705 0.0727 0.0486057 -0.0120555 0.0727 0.0481184 0.0488416 0.0727 -0.00457047 -0.0075488 0.0727 0.0489873 0.0489994 0.0727 -0.00229425 -0.00528076 0.0727 0.0492633 -0.00298188 0.0727 0.0494338 0.0489991 0.0727 0.00230656 -0.000687006 0.0727 0.0494986 0.0488395 0.0727 0.00459556 0.0485752 0.0727 0.00686699 0.0482064 0.0727 0.00912085 0.00160004 0.0727 0.0494575 0.0477329 0.0727 0.0113571 0.0471547 0.0727 0.0135759 0.0456924 0.0727 0.0179296 0.00617645 0.0727 0.0490539 0.00388768 0.0727 0.0493093 0.041598 0.0727 0.0261248 0.0448139 0.0727 0.0200424 0.0427593 0.0727 0.0241568 0.046472 0.0727 0.015777 0.0235011 0.0727 0.0433211 0.0172616 0.0727 0.0462241 0.0106783 0.0727 0.0482338 0.0151059 0.0727 0.0469925 0.0129083 0.0727 0.0476635 0.0214686 0.0727 0.0443834 0.0193785 0.0727 0.0453565 0.0375682 0.0727 0.0317042 0.0403434 0.0727 0.0280421 0.0389958 0.0727 0.0299086 0.0254761 0.0727 0.0421697 0.0310748 0.0727 0.0381661 0.0292756 0.0727 0.0395825 0.0274049 0.0727 0.0409204 0.0360627 0.0727 0.0334259 0.0344737 0.0727 0.035082 0.0328025 0.0727 0.0366713 0.0438352 0.0727 0.0221205 0.00843999 0.0727 0.0486953 0.049054 0.0727 -2.26632e-17 0.0510411 0.0707 -0.001088 0.0510399 0.058 -0.00114798 0.0510399 0.058 0.00117717 0.0509353 0.058 -0.00348203 0.0509395 0.0707 -0.00342696 0.0507329 0.0707 -0.00573937 0.0507261 0.058 -0.00580075 0.0504214 0.0707 -0.0080405 0.0504123 0.058 -0.00809919 0.0499939 0.058 -0.0103887 0.0500052 0.0707 -0.0103341 0.0494848 0.0707 -0.0126162 0.0494709 0.058 -0.0126694 0.0488659 0.0707 -0.0148506 0.0488494 0.058 -0.014906 0.0481269 0.058 -0.0171119 0.0481451 0.0707 -0.0170597 0.0473223 0.0707 -0.0192436 0.0473029 0.058 -0.0192914 0.0464016 0.0707 -0.0213904 0.0463785 0.058 -0.0214409 0.0453661 0.058 -0.0235257 0.0453906 0.0707 -0.0234776 0.0442833 0.0707 -0.0255227 0.044258 0.058 -0.0255673 0.0430798 0.0707 -0.0275257 0.0430542 0.058 -0.0275656 0.0417611 0.058 -0.0295095 0.0417906 0.0707 -0.029467 0.04042 0.0707 -0.0313391 0.0403897 0.058 -0.0313789 0.0389616 0.0707 -0.0331534 0.0389313 0.058 -0.0331895 0.037386 0.058 -0.0349414 0.0374156 0.0707 -0.0349098 0.0358022 0.0707 -0.0365827 0.0357682 0.058 -0.0366165 0.0341162 0.0707 -0.0381786 0.0340821 0.058 -0.0382096 0.0323203 0.058 -0.0397301 0.0323536 0.0707 -0.0397027 0.0305151 0.0707 -0.0411541 0.0304827 0.058 -0.0411779 0.0286315 0.0707 -0.0425054 0.0285951 0.058 -0.0425305 0.0266489 0.058 -0.0437952 0.0266846 0.0707 -0.0437729 0.0246744 0.0707 -0.0449565 0.0246403 0.058 -0.0449755 0.0226089 0.0707 -0.0460513 0.0225716 0.058 -0.0460699 0.0204754 0.058 -0.0470585 0.0205122 0.0707 -0.047042 0.0183675 0.0707 -0.0479393 0.018332 0.058 -0.0479533 0.0161746 0.0707 -0.0487432 0.0161413 0.058 -0.0487544 0.0139143 0.058 -0.0494573 0.0139507 0.0707 -0.0494467 0.0117091 0.0707 -0.0500443 0.0116737 0.058 -0.050053 0.00943601 0.0707 -0.0505417 0.00940245 0.058 -0.0505483 0.00710041 0.058 -0.0509432 0.0071313 0.0707 -0.0509388 0.004823 0.0707 -0.0512296 0.004789 0.058 -0.0512331 0.0025093 0.0707 -0.0514142 0.00247676 0.058 -0.0514162 0.000151182 0.058 -0.0514952 0.000181499 0.0707 -0.0514948 -0.00216041 0.0707 -0.0514713 -0.00218773 0.058 -0.0514701 -0.00447669 0.0707 -0.0513417 -0.00450703 0.058 -0.0513394 -0.00681587 0.058 -0.0511036 -0.00678731 0.0707 -0.051107 -0.00909415 0.0707 -0.0507674 -0.00912026 0.058 -0.0507629 -0.0113912 0.0707 -0.0503235 -0.0114184 0.058 -0.0503176 -0.0136709 0.058 -0.0497726 -0.0136451 0.0707 -0.0497794 -0.0158775 0.0707 -0.0491324 -0.0159013 0.058 -0.049125 -0.0180883 0.0707 -0.0483827 -0.0181096 0.058 -0.0483748 -0.0202855 0.058 -0.0475252 -0.0202632 0.0707 -0.0475344 -0.0223832 0.0707 -0.0465934 -0.022404 0.058 -0.0465837 -0.0244646 0.0707 -0.0455546 -0.0244833 0.058 -0.0455448 -0.0265236 0.058 -0.0444085 -0.0265072 0.0707 -0.0444182 -0.0284891 0.0707 -0.0431952 -0.0285062 0.058 -0.0431841 -0.0304061 0.0707 -0.0418875 -0.0304217 0.058 -0.0418764 -0.0322822 0.058 -0.0404793 -0.0322684 0.0707 -0.04049 -0.0340876 0.058 -0.0389928 -0.0340761 0.0707 -0.0390029 -0.0358004 0.0707 -0.0374471 -0.0358125 0.058 -0.0374357 -0.0374519 0.0707 -0.035815 -0.0374627 0.058 -0.0358039 -0.0390434 0.058 -0.0340933 -0.0390342 0.0707 -0.0341037 -0.0405454 0.0707 -0.0323154 -0.0405542 0.058 -0.0323046 -0.0419588 0.0707 -0.0304777 -0.0419665 0.058 -0.0304673 -0.0432973 0.058 -0.0285641 -0.0432907 0.0707 -0.0285738 -0.044541 0.0707 -0.0266036 -0.0445463 0.058 -0.0265949 -0.0457034 0.0707 -0.0245767 -0.0457083 0.058 -0.0245678 -0.0467675 0.058 -0.0225058 -0.0467635 0.0707 -0.0225141 -0.0477319 0.0707 -0.0204 -0.0477352 0.058 -0.0203926 -0.0486088 0.0707 -0.0182344 -0.0486112 0.058 -0.0182282 -0.0493875 0.058 -0.0160304 -0.0493854 0.0707 -0.0160366 -0.0500574 0.0707 -0.0138159 -0.050059 0.058 -0.0138105 -0.0506304 0.0707 -0.01156 -0.0506315 0.058 -0.0115556 -0.051105 0.058 -0.00926581 -0.0511044 0.0707 -0.00926907 -0.0514715 0.0707 -0.00697329 -0.0514719 0.058 -0.00697045 -0.0517332 0.0707 -0.00466669 -0.0517334 0.058 -0.00466471 -0.0518914 0.058 -0.00234122 -0.0518914 0.0707 -0.00234226 -0.051946 0.058 6.18949e-21 -0.051946 0.0707 -6.39411e-17 0.0510382 0.0707 0.00124061 0.0509353 0.058 0.00349341 0.0509307 0.0707 0.00355885 0.0507232 0.058 0.00581785 0.0507168 0.0707 0.00587708 0.0503968 0.0707 0.00819297 0.0504071 0.058 0.00812957 0.0499895 0.058 0.0104148 0.0499755 0.0707 0.0104809 0.0494702 0.058 0.0126737 0.049453 0.0707 0.0127409 0.0488236 0.0707 0.0149883 0.0488419 0.058 0.014927 0.0481165 0.058 0.0171415 0.0480934 0.0707 0.017206 0.0472953 0.058 0.0193128 0.0472683 0.0707 0.019379 0.046348 0.0707 0.0215073 0.0463768 0.058 0.021444 0.0453533 0.058 0.0235485 0.0453221 0.0707 0.0236093 0.0442429 0.058 0.0255943 0.0442065 0.0707 0.0256572 0.0430048 0.0707 0.0276449 0.0430455 0.058 0.0275813 0.0417544 0.058 0.0295178 0.0417165 0.0707 0.0295731 0.0403715 0.058 0.0314014 0.040327 0.0707 0.031459 0.038863 0.0707 0.033271 0.0389128 0.058 0.0332124 0.0373784 0.058 0.0349508 0.0373244 0.0707 0.035009 0.0357556 0.058 0.0366276 0.0357049 0.0707 0.0366783 0.0340017 0.0707 0.0382815 0.0340591 0.058 0.0382299 0.0323002 0.058 0.0397478 0.0322374 0.0707 0.0397991 0.0304788 0.058 0.0411813 0.0304122 0.0707 0.0412312 0.0285137 0.0707 0.042585 0.0285765 0.058 0.0425419 0.0266222 0.058 0.0438116 0.0265526 0.0707 0.0438543 0.0246205 0.058 0.0449877 0.024546 0.0707 0.0450288 0.0224937 0.0707 0.0461087 0.0225691 0.058 0.0460709 0.0204515 0.058 0.0470681 0.0203777 0.0707 0.047101 0.0183032 0.058 0.0479649 0.018223 0.0707 0.0479958 0.0160396 0.0707 0.0487897 0.0161241 0.058 0.0487613 0.0139046 0.058 0.0494594 0.0138272 0.0707 0.0494826 0.0116457 0.058 0.050059 0.0115626 0.0707 0.050079 0.0092848 0.0707 0.0505713 0.00937347 0.058 0.0505545 0.0070879 0.058 0.0509459 0.00699569 0.0707 0.0509593 0.0047729 0.058 0.0512338 0.00468976 0.0707 0.0512428 0.00235633 0.0707 0.0514223 0.00244623 0.058 0.0514175 0.000124024 0.058 0.0514964 2.94977e-05 0.0707 0.051497 -0.00219373 0.058 0.0514703 -0.00229074 0.0707 0.0514668 -0.00461631 0.0707 0.05133 -0.00452812 0.058 0.0513367 -0.00684699 0.058 0.0510996 -0.0069408 0.0707 0.0510875 -0.00914374 0.058 0.0507599 -0.00924099 0.0707 0.0507428 -0.0115169 0.0707 0.0502959 -0.0114201 0.058 0.050317 -0.0136951 0.058 0.0497652 -0.0137853 0.0707 0.0497413 -0.0159311 0.058 0.0491159 -0.0160255 0.0707 0.0490857 -0.0182243 0.0707 0.0483336 -0.0181278 0.058 0.0483692 -0.0202937 0.058 0.047521 -0.0203819 0.0707 0.0474848 -0.0224293 0.058 0.0465709 -0.022518 0.0707 0.046529 -0.0246013 0.0707 0.0454826 -0.02451 0.058 0.0455314 -0.0265356 0.058 0.0444024 -0.0266276 0.0707 0.044348 -0.0285186 0.058 0.0431749 -0.028599 0.0707 0.0431234 -0.0305295 0.0707 0.0417982 -0.0304461 0.058 0.0418583 -0.0323043 0.058 0.0404629 -0.0323888 0.0707 0.0403958 -0.0340931 0.058 0.0389887 -0.0341769 0.0707 0.0389161 -0.0359002 0.0707 0.037352 -0.0358269 0.058 0.0374208 -0.0374843 0.058 0.0357813 -0.0375588 0.0707 0.0357037 -0.0390601 0.058 0.0340759 -0.039134 0.0707 0.0339914 -0.0406259 0.0707 0.0322151 -0.0405547 0.058 0.0323038 -0.0419805 0.058 0.0304466 -0.0420431 0.0707 0.0303616 -0.0433147 0.058 0.0285382 -0.0433765 0.0707 0.0284445 -0.0446171 0.0707 0.0264786 -0.0445573 0.058 0.0265786 -0.0457117 0.058 0.0245601 -0.0457646 0.0707 0.0244636 -0.0467791 0.058 0.0224801 -0.0468193 0.0707 0.0223997 -0.0477809 0.0707 0.0202869 -0.0477476 0.058 0.0203652 -0.048617 0.058 0.0182153 -0.0486496 0.0707 0.0181251 -0.0493912 0.058 0.016016 -0.0494254 0.0707 0.0159144 -0.0500922 0.0707 0.0136895 -0.0500666 0.058 0.0137812 -0.0506385 0.058 0.0115287 -0.0506568 0.0707 0.0114484 -0.0511069 0.058 0.00925845 -0.0511191 0.0707 0.00919109 -0.0514792 0.0707 0.00691761 -0.0514719 0.058 0.00697045 -0.0517334 0.058 0.00466471 -0.0517371 0.0707 0.00462793 -0.0518914 0.058 0.00234122 -0.0518926 0.0707 0.00232206 -0.0447308 0.0710129 -0.0262407 -0.0432907 0.0707 -0.0285738 -0.0396591 0.0710129 -0.0333474 -0.0513136 0.071318 0.00739382 -0.0513861 0.0710129 0.00740436 -0.0518314 0.071318 -0.00130919 -0.0467635 0.0707 -0.0225141 -0.0485285 0.0710129 -0.0183791 0.0213104 0.0721142 0.0460317 0.013154 0.072318 0.0488165 0.0212084 0.072318 0.0458159 -0.0506568 0.0707 0.0114484 -0.0511191 0.0707 0.00919109 -0.0514792 0.0707 0.00691761 -0.00993928 0.0718756 -0.0502288 -0.0182914 0.0718756 -0.0479019 -0.0183487 0.071608 -0.0480556 -0.0500574 0.0707 -0.0138159 -0.0493854 0.0707 -0.0160366 -0.049402 0.0710129 0.0159068 -0.0500922 0.0707 0.0136895 -0.0383926 0.0726754 -0.0322704 -0.032393 0.0726754 -0.0382192 -0.0352368 0.0727 -0.0352105 -0.018137 0.072318 -0.0474873 -0.0259079 0.072318 -0.0438144 -0.0260278 0.0721142 -0.0440208 -0.0261302 0.0718756 -0.044197 -0.0182203 0.0721142 -0.0477109 -0.0494254 0.0707 0.0159144 -0.0519047 0.0710129 -0.00131106 -0.0517371 0.0707 0.00462793 -0.0518926 0.0707 0.00232206 -0.0493323 0.071318 0.0158841 -0.0469755 0.0726754 -0.0177855 -0.0455858 0.0727 -0.020313 -0.0464699 0.0727 -0.0182222 -0.00990143 0.0721142 -0.0500285 -0.049909 0.0727 0.00188187 -0.0497708 0.0727 0.00415454 -0.0497408 0.0726754 0.00716522 -0.049312 0.0726754 -0.00966615 -0.0502427 0.0726754 -0.00126871 -0.0505478 0.0726021 -0.00127649 -0.0481804 0.0727 0.0130975 -0.0478209 0.0726754 0.015393 -0.0487337 0.0727 0.0108839 -0.0491832 0.0727 0.00865557 -0.0495289 0.0727 0.00641244 -0.0475233 0.0727 0.0152963 -0.0500428 0.0726021 0.00720912 -0.0496968 0.0727 -0.00495364 -0.0494159 0.0727 -0.0072154 -0.0498728 0.0727 -0.00268859 -0.0496114 0.0726021 -0.00972537 -0.0472606 0.0726021 -0.0178945 -0.047955 0.0727 -0.0138945 -0.0475314 0.072482 -0.017998 -0.0438125 0.072482 -0.0256966 -0.043563 0.0726021 -0.0255488 -0.0386251 0.0726021 -0.0324681 -0.0388459 0.072482 -0.0326559 -0.0440427 0.072318 -0.025833 -0.0390498 0.072318 -0.0328293 -0.044248 0.0721142 -0.0259546 -0.0444233 0.0718756 -0.0260585 -0.0392316 0.0721142 -0.0329839 -0.0433005 0.0726754 -0.0253932 -0.0446041 0.0727 -0.0223652 -0.0330994 0.0721142 -0.0390642 -0.0329463 0.072318 -0.0388811 -0.0410996 0.0727 -0.0282397 -0.0423524 0.0727 -0.0263457 -0.0325888 0.0726021 -0.0384534 -0.00985711 0.072318 -0.049794 -0.00130651 0.072318 -0.0506683 -0.00131056 0.0721142 -0.0509069 -0.0419588 0.0707 -0.0304777 -0.0405454 0.0707 -0.0323154 -0.0374519 0.0707 -0.035815 -0.0358004 0.0707 -0.0374471 -0.0334593 0.0710129 -0.0394948 -0.0179423 0.0726021 -0.0469648 -0.0256278 0.0726021 -0.0433324 -0.0257734 0.072482 -0.0435831 0.00726885 0.072318 -0.0500849 0.00730518 0.0721142 -0.0503207 0.0156223 0.072318 -0.0480606 -0.00932248 0.0727 -0.0486966 -0.0096969 0.0726754 -0.0489463 -0.00706669 0.0727 -0.0490551 0.0156979 0.0721142 -0.048287 0.0235134 0.072318 -0.0446538 -0.00131402 0.0718756 -0.0511107 0.00733621 0.0718756 -0.0505222 0.0238001 0.071608 -0.0451882 0.0309874 0.0718756 -0.0403112 0.0237226 0.0718756 -0.0450437 0.0236262 0.0721142 -0.0448641 0.0308621 0.0721142 -0.0401505 -0.0136451 0.0707 -0.0497794 -0.0113912 0.0707 -0.0503235 -0.0100056 0.0710129 -0.0505799 0.0110488 0.0727 -0.0481465 0.00713751 0.0726754 -0.0492322 0.0153487 0.0726754 -0.0472424 -0.00132009 0.0710129 -0.051468 -0.00678731 0.0707 -0.051107 -0.00447669 0.0707 -0.0513417 0.0303725 0.0726021 -0.0395226 0.0233869 0.072482 -0.044418 0.0305508 0.072482 -0.0397513 0.0371972 0.0721142 -0.0342819 0.0422483 0.072318 -0.0272985 0.0370207 0.072318 -0.0341212 0.0231055 0.0726754 -0.0438936 0.0257216 0.0727 -0.0420178 0.0237549 0.0727 -0.0431794 0.00739061 0.0710129 -0.0508754 0.00943601 0.0707 -0.0505417 0.0117091 0.0707 -0.0500443 0.0373479 0.0718756 -0.0344191 0.0462477 0.072318 -0.0196904 0.0464676 0.0721142 -0.0197832 0.0489037 0.072318 -0.0115159 0.0466554 0.0718756 -0.0198624 0.0491361 0.0721142 -0.0115702 0.0415215 0.0726754 -0.0268338 0.0428295 0.0727 -0.0240307 0.0416708 0.0727 -0.0260058 0.0158759 0.0710129 -0.0488192 0.0183675 0.0707 -0.0479393 0.0205122 0.0707 -0.047042 0.0493346 0.0718756 -0.0116165 0.0501401 0.072318 -0.00301016 0.0503609 0.0718756 0.00563097 0.0484826 0.0721142 0.01408 0.0501584 0.0721142 0.00560852 0.0469846 0.0710129 -0.0200012 0.0429222 0.0710129 -0.0277293 0.0453906 0.0707 -0.0234776 0.0482533 0.072318 0.014014 0.0499212 0.072318 0.00558223 0.0505239 0.071608 0.00564904 0.0486785 0.0718756 0.0141364 0.0451844 0.072318 0.0220427 0.0453993 0.0721142 0.0221465 0.041163 0.0718756 0.0296942 0.0455828 0.0718756 0.0222351 0.0457305 0.071608 0.0223065 0.0409971 0.0721142 0.0295758 0.0412965 0.071608 0.0297895 0.0355461 0.0718756 0.036299 0.0490637 0.0726754 0.0054872 0.0474242 0.0726754 0.0137755 0.0482064 0.0727 0.00912085 0.0504214 0.0707 -0.0080405 0.0507329 0.0707 -0.00573937 0.0509385 0.0710129 -0.00305767 0.0496552 0.072482 0.00555276 0.0477175 0.0726021 0.0138598 0.049367 0.0726021 0.00552082 0.0286399 0.072318 0.0414973 0.0352346 0.072318 0.0359848 0.0354026 0.0721142 0.0361543 0.0427593 0.0727 0.0241568 0.0438352 0.0727 0.0221205 0.0444076 0.0726754 0.0216674 0.0287769 0.0721142 0.0416927 0.0213975 0.0718756 0.046216 0.0214676 0.071608 0.0463642 0.0132728 0.0718756 0.0492428 0.0132181 0.0721142 0.0490464 0.00475338 0.0718756 0.0508529 0.0133168 0.071608 0.0494007 0.0281447 0.0726754 0.0407908 0.0310748 0.0727 0.0381661 0.0346272 0.0726754 0.0353722 0.0414538 0.0710129 0.0299018 0.0442065 0.0707 0.0256572 0.0430048 0.0707 0.0276449 0.0235011 0.0727 0.0433211 0.0254761 0.0727 0.0421697 -0.0124367 0.0721142 0.0494821 -0.00390176 0.0721142 0.0507968 -0.00391559 0.0718756 0.0510001 0.038863 0.0707 0.033271 0.040327 0.0707 0.031459 0.00462063 0.0726754 0.0495545 0.00843999 0.0727 0.0486953 0.0129225 0.0726754 0.0479855 -0.00392672 0.071608 0.0511637 -0.0124848 0.0718756 0.0496802 -0.000687006 0.0727 0.0494986 0.00160004 0.0727 0.0494575 0.0322374 0.0707 0.0397991 0.0304122 0.0707 0.0412312 0.029099 0.0710129 0.0421522 -0.0207076 0.0718756 0.046931 -0.0207726 0.071608 0.0470816 -0.0283475 0.0718756 0.0428317 0.0215502 0.0710129 0.046539 0.0265526 0.0707 0.0438543 0.024546 0.0707 0.0450288 0.00478973 0.0710129 0.0512084 2.94977e-05 0.0707 0.051497 -0.00393985 0.0710129 0.0513567 0.0133687 0.0710129 0.049587 0.018223 0.0707 0.0479958 0.0160396 0.0707 0.0487897 -0.028106 0.072318 0.042461 -0.0205322 0.072318 0.0465248 -0.0206268 0.0721142 0.0467439 -0.0122492 0.0726021 0.0487083 -0.0203112 0.0726021 0.0460129 -0.0201903 0.0726754 0.0457328 -0.028437 0.071608 0.0429691 -0.0351848 0.0718756 0.0375003 -0.0348841 0.072318 0.0371757 -0.0282363 0.0721142 0.042661 -0.00384772 0.0726021 0.0500025 -0.0038674 0.072482 0.0502917 0.0092848 0.0707 0.0505713 0.00699569 0.0707 0.0509593 -0.0227965 0.0727 0.0441665 -0.0207334 0.0727 0.0451515 -0.0410227 0.0718756 0.03109 -0.0352962 0.071608 0.0376206 0.00235633 0.0707 0.0514223 -0.0248141 0.0727 0.0430854 -0.00229074 0.0707 0.0514668 -0.0408609 0.0721142 0.030966 -0.0455128 0.0721142 0.0236905 -0.0287072 0.0727 0.0406393 -0.0276351 0.0726754 0.0417382 -0.0305528 0.0727 0.0392909 -0.0411528 0.071608 0.0311897 -0.0456932 0.0718756 0.0237853 -0.00924099 0.0707 0.0507428 -0.0125689 0.0710129 0.0500275 -0.0069408 0.0707 0.0510875 -0.0453016 0.072318 0.0235794 -0.0406715 0.072318 0.0308209 -0.0285426 0.0710129 0.0431312 -0.0323888 0.0707 0.0403958 -0.0354276 0.0710129 0.0377624 -0.0486496 0.0707 0.0181251 -0.0203819 0.0707 0.0474848 -0.0208492 0.0710129 0.0472591 -0.0182243 0.0707 0.0483336 -0.0160255 0.0707 0.0490857 -0.0413063 0.0710129 0.0313073 -0.0375588 0.0707 0.0357037 -0.0477809 0.0707 0.0202869 -0.0246013 0.0707 0.0454826 -0.0266276 0.0707 0.044348 -0.0460095 0.0710129 0.0239516 -0.0468193 0.0707 0.0223997 -0.0457646 0.0707 0.0244636 -0.0459447 0.071318 0.0239175 -0.0492181 0.071608 0.015847 -0.0341769 0.0707 0.0389161 -0.0420431 0.0707 0.0303616 -0.0433765 0.0707 0.0284445 -0.0446171 0.0707 0.0264786 -0.039134 0.0707 0.0339914 -0.0359002 0.0707 0.037352 -0.0458384 0.071608 0.0238616 -0.0305295 0.0707 0.0417982 -0.0342978 0.0726754 0.0365428 -0.0490621 0.0718756 0.0157963 -0.0488683 0.0721142 0.0157334 -0.0345052 0.0726021 0.0367667 -0.0278017 0.0726021 0.0419938 -0.02796 0.072482 0.0422368 -0.0402289 0.0726021 0.0304818 -0.0399867 0.0726754 0.0302962 -0.0486413 0.072318 0.0156596 -0.0372784 0.0727 0.0330687 -0.0483868 0.072482 0.0155769 -0.0450647 0.072482 0.0234549 -0.0415085 0.0727 0.027642 -0.0401894 0.0727 0.0295078 -0.0427428 0.0727 0.0257123 -0.0481111 0.0726021 0.0154873 -0.0448081 0.0726021 0.02332 -0.044538 0.0726754 0.023178 -0.0458992 0.0727 0.0196007 -0.044946 0.0727 0.0216793 -0.0467583 0.0727 0.017473 -0.0350463 0.0721142 0.0373508 0.0115626 0.0707 0.050079 -0.003827 0.0726754 0.049698 -0.0121774 0.0726754 0.0484117 -0.0075488 0.0727 0.0489873 -0.00528076 0.0727 0.0492633 -0.0125234 0.071608 0.0498396 -0.0123805 0.072318 0.0492502 0.00388768 0.0727 0.0493093 -0.00388556 0.072318 0.0505587 0.0357977 0.0710129 0.0365528 0.0340017 0.0707 0.0382815 0.0130044 0.0726021 0.0482794 0.00465167 0.0726021 0.0498581 0.0209702 0.0726021 0.0453119 0.0210941 0.072482 0.045574 0.00470838 0.072318 0.0504128 0.00473265 0.0721142 0.0506502 0.0373244 0.0707 0.035009 0.0193785 0.0727 0.0453565 0.0208398 0.0726754 0.045036 0.0172616 0.0727 0.0462241 0.00477006 0.071608 0.0510161 0.0274049 0.0727 0.0409204 0.0472683 0.0707 0.019379 0.0459046 0.0710129 0.0223906 0.0480934 0.0707 0.017206 0.0468065 0.071608 -0.0199261 0.0283199 0.0726021 0.0410407 0.034842 0.0726021 0.0355889 0.040585 0.072482 0.0292817 0.040349 0.0726021 0.0291133 0.0499755 0.0707 0.0104809 0.0507161 0.0710129 0.00567034 0.0503968 0.0707 0.00819297 0.049453 0.0707 0.0127409 0.0490219 0.0710129 0.0142352 0.0401006 0.0726754 0.028936 0.0375682 0.0727 0.0317042 0.0389958 0.0727 0.0299086 0.0509307 0.0707 0.00355885 0.0510382 0.0707 0.00124061 0.028988 0.071608 0.0419939 0.0288938 0.0718756 0.0418596 0.041598 0.0727 0.0261248 0.0356616 0.071608 0.0364155 0.0510411 0.0707 -0.001088 0.0456924 0.0727 0.0179296 0.0408028 0.072318 0.0294372 0.0446824 0.0726021 0.0218002 0.0481451 0.0707 -0.0170597 0.0488659 0.0707 -0.0148506 0.0496826 0.0710129 -0.0116977 0.0485752 0.0727 0.00686699 0.0442833 0.0707 -0.0255227 0.0464016 0.0707 -0.0213904 0.0489994 0.0727 -0.00229425 0.0492789 0.0726754 -0.00295891 0.049054 0.0727 -2.26632e-17 0.0489991 0.0727 0.00230656 0.04042 0.0707 -0.0313391 0.0417906 0.0707 -0.029467 0.0488361 0.071608 0.0141817 0.0483608 0.0726021 -0.0113892 0.045734 0.0726021 -0.0194738 0.0460011 0.072482 -0.0195865 0.0480636 0.0726754 -0.0113199 0.0485805 0.0727 -0.00682867 0.0495835 0.0726021 -0.00297704 0.0376121 0.0710129 -0.0346597 0.0389616 0.0707 -0.0331534 0.0503783 0.0721142 -0.00302433 0.0341162 0.0707 -0.0381786 0.0358022 0.0707 -0.0365827 0.0464996 0.0727 -0.0156954 0.0457247 0.0727 -0.0178441 0.0454528 0.0726754 -0.0193552 0.0312071 0.0710129 -0.040593 0.0266846 0.0707 -0.0437729 0.0286315 0.0707 -0.0425054 0.0505818 0.0718756 -0.00303644 0.0507455 0.071608 -0.00304618 0.0438857 0.0727 -0.0220205 0.0226089 0.0707 -0.0460513 0.0238916 0.0710129 -0.0453585 0.0494943 0.071608 -0.0116538 0.0366085 0.0726021 -0.0337458 0.0363829 0.0726754 -0.0335403 0.0426211 0.0718756 -0.0275368 0.0139507 0.0707 -0.0494467 0.0417786 0.0726021 -0.0269981 0.0329768 0.0727 -0.0365123 0.0301848 0.0726754 -0.039282 0.0424494 0.0721142 -0.027427 0.0427593 0.071608 -0.0276252 0.0232498 0.0726021 -0.0441625 0.0025093 0.0707 -0.0514142 0.004823 0.0707 -0.0512296 0.0276217 0.0727 -0.0407723 0.0374691 0.071608 -0.0345295 0.0307153 0.072318 -0.0399623 0.0154288 0.0727 -0.0468841 0.0175806 0.0727 -0.0461009 0.0310882 0.071608 -0.0404405 -0.0158775 0.0707 -0.0491324 -0.00129704 0.0726021 -0.0501108 -0.00130197 0.072482 -0.0504007 0.00718397 0.0726021 -0.0495338 -0.0184162 0.0710129 -0.0482368 -0.0223832 0.0707 -0.0465934 -0.0202632 0.0707 -0.0475344 0.0157626 0.0718756 -0.0484803 0.00430006 0.0727 -0.049271 0.00203294 0.0727 -0.0494377 -0.00129186 0.0726754 -0.0498057 -0.0244646 0.0707 -0.0455546 -0.0263098 0.0710129 -0.044506 0.0158146 0.071608 -0.0486358 -0.00024373 0.0727 -0.049499 -0.0284891 0.0707 -0.0431952 -0.0304061 0.0707 -0.0418875 0.00722811 0.072482 -0.0498204 0.00736117 0.071608 -0.0506842 -0.0137695 0.0727 -0.0476726 -0.0178358 0.0726754 -0.0466789 -0.00131681 0.071608 -0.0512746 -0.0254744 0.0726754 -0.0430685 -0.0202143 0.0727 -0.0453801 -0.0222788 0.0727 -0.0444246 -0.00996974 0.071608 -0.0503899 -0.0242928 0.0727 -0.0433772 -0.0457034 0.0707 -0.0245767 -0.0300487 0.0727 -0.0396725 -0.0281956 0.0727 -0.0409892 -0.0477319 0.0707 -0.0204 -0.031842 0.0727 -0.0382685 -0.0262126 0.071608 -0.0443388 -0.0333353 0.071608 -0.0393464 -0.0332301 0.0718756 -0.0392206 -0.0511044 0.0707 -0.00926907 -0.0509429 0.0710129 -0.00998876 -0.0514715 0.0707 -0.00697329 -0.0395118 0.071608 -0.0332222 -0.0393868 0.0718756 -0.0331159 -0.0517332 0.0707 -0.00466669 -0.0518914 0.0707 -0.00234226 -0.0445644 0.071608 -0.0261421 -0.0505924 0.0718756 -0.00991942 -0.0517114 0.071608 -0.00130613 -0.0507532 0.071608 -0.00995124 -0.051946 0.0707 -6.39411e-17 -0.0406259 0.0707 0.0322151 -0.028599 0.0707 0.0431234 -0.0412482 0.071318 0.0312628 -0.0115169 0.0707 0.0502959 -0.040459 0.072482 0.0306581 -0.0438925 0.0727 0.0237186 -0.022518 0.0707 0.046529 -0.0353778 0.071318 0.0377087 -0.0347022 0.072482 0.0369794 -0.0323392 0.0727 0.0378545 -0.0357116 0.0727 0.0347357 -0.0387723 0.0727 0.0313246 -0.0137853 0.0707 0.0497413 -0.0285026 0.071318 0.0430698 -0.0164551 0.0727 0.046839 -0.0340664 0.0727 0.03633 -0.00461631 0.0707 0.05133 -0.0208202 0.071318 0.0471918 -0.0204261 0.072482 0.0462791 -0.0267879 0.0727 0.0419077 0.00468976 0.0707 0.0512428 -0.0125517 0.071318 0.0499563 0.0224937 0.0707 0.0461087 -0.0123175 0.072482 0.0489901 -0.00980705 0.0727 0.0486057 -0.0142753 0.0727 0.0475289 -0.0186079 0.0727 0.0460465 0.0138272 0.0707 0.0494826 -0.00393487 0.071318 0.0512836 -0.0120555 0.0727 0.0481184 0.0203777 0.0707 0.047101 0.00478228 0.071318 0.0511355 0.00468116 0.072482 0.0501466 -0.00298188 0.0727 0.0494338 0.0285137 0.0707 0.042585 0.013349 0.071318 0.0495164 0.0130822 0.072482 0.0485587 0.0151059 0.0727 0.0469925 0.0106783 0.0727 0.0482338 0.00617645 0.0727 0.0490539 0.0357049 0.0707 0.0366783 0.0215189 0.071318 0.0464728 0.046348 0.0707 0.0215073 0.0129083 0.0727 0.0476635 0.0417165 0.0707 0.0295731 0.0290569 0.071318 0.0420922 0.0284863 0.072482 0.0412782 0.0214686 0.0727 0.0443834 0.0453221 0.0707 0.0236093 0.0357461 0.071318 0.0365008 0.0350462 0.072482 0.0357948 0.0360627 0.0727 0.0334259 0.0328025 0.0727 0.0366713 0.0292756 0.0727 0.0395825 0.0488236 0.0707 0.0149883 0.0413942 0.071318 0.0298592 0.0344737 0.0727 0.035082 0.0507168 0.0707 0.00587708 0.0458386 0.071318 0.0223587 0.0494848 0.0707 -0.0126162 0.0449435 0.072482 0.0219263 0.0403434 0.0727 0.0280421 0.0509395 0.0707 -0.00342696 0.0489515 0.071318 0.014215 0.0479961 0.072482 0.01394 0.0477329 0.0727 0.0113571 0.046472 0.0727 0.015777 0.0448139 0.0727 0.0200424 0.0500052 0.0707 -0.0103341 0.0506433 0.071318 0.00566227 0.0471547 0.0727 0.0135759 0.0473223 0.0707 -0.0192436 0.0508653 0.071318 -0.00305331 0.049873 0.072482 -0.00299426 0.0488395 0.0727 0.00459556 0.0430798 0.0707 -0.0275257 0.0496113 0.071318 -0.0116811 0.0305151 0.0707 -0.0411541 0.0486431 0.072482 -0.0114551 0.0471698 0.0727 -0.0135246 0.0482141 0.0727 -0.00907649 0.0488416 0.0727 -0.00457047 0.0374156 0.0707 -0.0349098 0.0469171 0.071318 -0.0199728 0.0391006 0.0727 -0.0297704 0.0477413 0.0727 -0.0113183 0.0323536 0.0707 -0.0397027 0.0428604 0.071318 -0.0276899 0.0420229 0.072482 -0.0271543 0.0448507 0.0727 -0.0199582 0.0246744 0.0707 -0.0449565 0.0375579 0.071318 -0.0346104 0.0368229 0.072482 -0.033941 0.0346174 0.0727 -0.0349387 0.0376944 0.0727 -0.0315525 0.0404261 0.0727 -0.0279215 0.0161746 0.0707 -0.0487432 0.0311621 0.071318 -0.0405353 -0.00216041 0.0707 -0.0514713 0.0196758 0.0727 -0.0452251 0.0312617 0.0727 -0.0380107 0.03619 0.0727 -0.0332855 0.0071313 0.0707 -0.0509388 0.0238569 0.071318 -0.045294 0.0154455 0.0726021 -0.0475319 0.0294684 0.0727 -0.0394366 0.000181499 0.0707 -0.0514948 0.0158526 0.071318 -0.0487497 0.0155374 0.072482 -0.0478069 0.0217339 0.0727 -0.0442513 -0.00909415 0.0707 -0.0507674 0.00737945 0.071318 -0.0508029 -0.00480877 0.0727 -0.0493066 0.00882938 0.0727 -0.0486232 0.0132486 0.0727 -0.0475668 -0.0180883 0.0707 -0.0483827 -0.00131885 0.071318 -0.0513947 -0.0340761 0.0707 -0.0390029 -0.00975357 0.0726021 -0.0492462 0.00656554 0.0727 -0.0489995 -0.0265072 0.0707 -0.0444182 -0.00999204 0.071318 -0.0505079 -0.00980742 0.072482 -0.0495311 -0.00253445 0.0727 -0.0494546 -0.0322684 0.0707 -0.04049 -0.0183906 0.071318 -0.0481681 -0.0180436 0.072482 -0.0472365 -0.0159421 0.0727 -0.0470119 -0.011563 0.0727 -0.0482342 -0.0390342 0.0707 -0.0341037 -0.0262729 0.071318 -0.0444426 -0.0180993 0.0727 -0.0462438 -0.044541 0.0707 -0.0266036 -0.0334123 0.071318 -0.0394386 -0.0327747 0.072482 -0.0386758 -0.026277 0.0727 -0.0422241 -0.0486088 0.0707 -0.0182344 -0.0396032 0.071318 -0.0333 -0.0397574 0.0727 -0.0300789 -0.0368163 0.0727 -0.0335774 -0.0335787 0.0727 -0.0367742 -0.0506304 0.0707 -0.01156 -0.0446677 0.071318 -0.0262034 -0.0508376 0.072482 -0.00128387 -0.0383258 0.0727 -0.0318633 -0.0483478 0.071608 -0.0183101 -0.04846 0.071318 -0.0183529 -0.0481947 0.0718756 -0.0182515 -0.0480043 0.0721142 -0.0181787 -0.0477814 0.072318 -0.0180935 -0.043525 0.0727 -0.0243788 -0.0508711 0.071318 -0.00997454 -0.0503924 0.0721142 -0.00987987 -0.0501583 0.072318 -0.00983356 -0.0498958 0.072482 -0.00978163 -0.0485435 0.0727 -0.0116987 -0.0472638 0.0727 -0.0160689 -0.0515475 0.0718756 -0.00130196 -0.0513437 0.0721142 -0.00129677 -0.0511051 0.072318 -0.00129069 -0.0490303 0.0727 -0.00947387 -0.0511947 0.071608 0.00737655 -0.0510324 0.0718756 0.00735296 -0.0508307 0.0721142 0.00732364 -0.0505946 0.072318 0.00728931 -0.0503298 0.072482 0.00725082 -0.0499433 0.0727 -0.000405572 0.00103416 0.0071 -0.00200131 0.000674647 0.0071 -0.00222267 -0.00261911 0.0071 0.00121397 -0.00238269 0.0071 -0.00156377 -0.00261911 0.0071 -0.00121397 -0.00175111 0.0071 -0.00211963 -0.00209055 0.0071 -0.00186857 -0.00279301 0.0071 -0.000829252 -0.00137411 0.0071 -0.0023097 -0.000970423 0.0071 -0.00243333 -0.0028994 0.0071 -0.000420677 -0.0029352 0.0071 4.07341e-20 -0.000551645 0.0071 -0.00248696 0.000282894 0.0071 -0.00238009 -0.0028994 0.0071 0.000420677 -0.00279301 0.0071 0.000829252 -0.000129827 0.0071 -0.00246904 0.00161633 0.0071 -0.00139389 -0.00175111 0.0071 0.00211963 0.00182223 0.0071 -0.0010253 -0.00209055 0.0071 0.00186857 0.00135109 0.0071 -0.00172237 -0.00238269 0.0071 0.00156377 0.00196288 0.0071 -0.000627224 -0.00137411 0.0071 0.0023097 -0.000970423 0.0071 0.00243333 0.00196288 0.0071 0.000627224 -0.000129827 0.0071 0.00246904 0.000282894 0.0071 0.00238009 0.00203423 0.0071 0.000211099 0.00203423 0.0071 -0.000211099 -0.000551645 0.0071 0.00248696 0.00161633 0.0071 0.00139389 0.00103416 0.0071 0.00200131 0.00135109 0.0071 0.00172237 0.000674647 0.0071 0.00222267 0.00182223 0.0071 0.0010253 -0.00279301 0 0.000829252 -0.00279301 0.0071 0.000829252 -0.0028994 0.0071 0.000420677 -0.0029352 0.0071 4.07341e-20 -0.0029352 -3.06818e-35 4.07341e-20 -0.0028994 0 0.000420677 -0.00238269 0.0071 0.00156377 -0.00209055 0 0.00186857 -0.00209055 0.0071 0.00186857 -0.00238269 0 0.00156377 -0.00261911 0.0071 0.00121397 -0.00261911 0 0.00121397 -0.000970423 0 0.00243333 -0.000970423 0.0071 0.00243333 -0.00137411 0.0071 0.0023097 -0.00137411 0 0.0023097 -0.00175111 0.0071 0.00211963 -0.00175111 0 0.00211963 0.000282894 0.0071 0.00238009 -0.000129827 0.0071 0.00246904 0.000282894 0 0.00238009 -0.000551645 0.0071 0.00248696 -0.000551645 0 0.00248696 -0.000129827 0 0.00246904 0.00103416 0.0071 0.00200131 0.00135109 0 0.00172237 0.00135109 0.0071 0.00172237 0.000674647 0 0.00222267 0.00103416 0 0.00200131 0.000674647 0.0071 0.00222267 0.00196288 0 0.000627224 0.00196288 0.0071 0.000627224 0.00182223 0.0071 0.0010253 0.00182223 0 0.0010253 0.00161633 0.0071 0.00139389 0.00161633 0 0.00139389 0.00196288 0.0071 -0.000627224 0.00203423 0.0071 -0.000211099 0.00196288 0 -0.000627224 0.00203423 0.0071 0.000211099 0.00203423 0 0.000211099 0.00203423 0 -0.000211099 0.00161633 0.0071 -0.00139389 0.00135109 0 -0.00172237 0.00135109 0.0071 -0.00172237 0.00182223 0 -0.0010253 0.00161633 0 -0.00139389 0.00182223 0.0071 -0.0010253 0.000282894 0 -0.00238009 0.000282894 0.0071 -0.00238009 0.000674647 0.0071 -0.00222267 0.000674647 0 -0.00222267 0.00103416 0.0071 -0.00200131 0.00103416 0 -0.00200131 -0.000970423 0 -0.00243333 -0.000551645 0.0071 -0.00248696 -0.000551645 0 -0.00248696 -0.000129827 0.0071 -0.00246904 -0.000129827 0 -0.00246904 -0.00137411 0 -0.0023097 -0.000970423 0.0071 -0.00243333 -0.00137411 0.0071 -0.0023097 -0.00175111 0 -0.00211963 -0.00209055 0 -0.00186857 -0.00175111 0.0071 -0.00211963 -0.00238269 0 -0.00156377 -0.00209055 0.0071 -0.00186857 -0.00238269 0.0071 -0.00156377 -0.00261911 0 -0.00121397 -0.00279301 0 -0.000829252 -0.00261911 0.0071 -0.00121397 -0.0028994 0 -0.000420677 -0.00279301 0.0071 -0.000829252 -0.0028994 0.0071 -0.000420677 0.0014759 0.0055 -0.0461098 0.001586 0.0055 -0.04545 0.00155829 0.0055 -0.0457845 -0.002478 0.0055 -0.04545 -0.0023679 0.0055 -0.0461098 -0.00245029 0.0055 -0.0457845 -0.00223309 0.0055 -0.0464171 -0.00204953 0.0055 -0.0466981 -0.00182224 0.0055 -0.046945 -0.0015574 0.0055 -0.0471511 -0.00126225 0.0055 -0.0473109 -0.000944826 0.0055 -0.0474198 -0.002478 0.0055 -0.04345 -0.000613801 0.0055 -0.0474751 0.001586 0.0055 -0.04345 5.28265e-05 0.0055 -0.0414802 0.000370245 0.0055 -0.0415891 5.28265e-05 0.0055 -0.0474198 -0.000278199 0.0055 -0.0414249 0.00134109 0.0055 -0.0464171 0.000665399 0.0055 -0.0471511 0.000930236 0.0055 -0.046945 0.00115753 0.0055 -0.0466981 0.000370245 0.0055 -0.0473109 0.000665399 0.0055 -0.0417489 0.000930236 0.0055 -0.041955 0.0014759 0.0055 -0.0427902 0.00134109 0.0055 -0.0424829 0.00155829 0.0055 -0.0431155 0.00115753 0.0055 -0.0422019 -0.000278199 0.0055 -0.0474751 -0.000613801 0.0055 -0.0414249 -0.000944826 0.0055 -0.0414802 -0.0015574 0.0055 -0.0417489 -0.00126225 0.0055 -0.0415891 -0.00204953 0.0055 -0.0422019 -0.00182224 0.0055 -0.041955 -0.0023679 0.0055 -0.0427902 -0.00223309 0.0055 -0.0424829 -0.00245029 0.0055 -0.0431155 0.000762295 0.0055 0.0428163 0.000468814 0.0055 0.0426356 -0.00221996 0.0055 0.045441 -0.00202697 0.0055 0.0431735 -0.00221996 0.0055 0.043459 -0.00151139 0.0055 0.0427197 -0.00178849 0.0055 0.0429246 -0.00236193 0.0055 0.0437731 -0.00120364 0.0055 0.0425645 -0.0008741 0.0055 0.0424636 -0.00244877 0.0055 0.0441066 -0.002478 0.0055 0.04445 -0.00053224 0.0055 0.0424198 0.000149016 0.0055 0.0425071 -0.00244877 0.0055 0.0447934 -0.00236193 0.0055 0.0451269 -0.0001879 0.0055 0.0424345 0.00123753 0.0055 0.0433121 -0.00151139 0.0055 0.0461803 0.00140562 0.0055 0.043613 -0.00178849 0.0055 0.0459754 0.00102101 0.0055 0.043044 -0.00202697 0.0055 0.0457265 0.00152043 0.0055 0.043938 -0.00120364 0.0055 0.0463355 -0.0008741 0.0055 0.0464364 0.00152043 0.0055 0.044962 -0.0001879 0.0055 0.0464655 0.000149016 0.0055 0.0463929 0.00157868 0.0055 0.0446223 0.00157868 0.0055 0.0442777 -0.00053224 0.0055 0.0464802 0.00123753 0.0055 0.0455879 0.000762295 0.0055 0.0460837 0.00102101 0.0055 0.045856 0.000468814 0.0055 0.0462644 0.00140562 0.0055 0.045287 -0.00236193 0 0.0451269 -0.00236193 0.0055 0.0451269 -0.00244877 0.0055 0.0447934 -0.002478 0.0055 0.04445 -0.002478 -1.54155e-35 0.04445 -0.00244877 0 0.0447934 -0.00202697 0.0055 0.0457265 -0.00178849 0 0.0459754 -0.00178849 0.0055 0.0459754 -0.00202697 0 0.0457265 -0.00221996 0.0055 0.045441 -0.00221996 0 0.045441 -0.0008741 0 0.0464364 -0.0008741 0.0055 0.0464364 -0.00120364 0.0055 0.0463355 -0.00120364 0 0.0463355 -0.00151139 0.0055 0.0461803 -0.00151139 0 0.0461803 0.000149016 0.0055 0.0463929 -0.0001879 0.0055 0.0464655 0.000149016 0 0.0463929 -0.00053224 0.0055 0.0464802 -0.00053224 0 0.0464802 -0.0001879 0 0.0464655 0.000762295 0.0055 0.0460837 0.00102101 0 0.045856 0.00102101 0.0055 0.045856 0.000468814 0 0.0462644 0.000762295 0 0.0460837 0.000468814 0.0055 0.0462644 0.00152043 0 0.044962 0.00152043 0.0055 0.044962 0.00140562 0.0055 0.045287 0.00140562 0 0.045287 0.00123753 0.0055 0.0455879 0.00123753 0 0.0455879 0.00152043 0.0055 0.043938 0.00157868 0.0055 0.0442777 0.00152043 0 0.043938 0.00157868 0.0055 0.0446223 0.00157868 0 0.0446223 0.00157868 0 0.0442777 0.00123753 0.0055 0.0433121 0.00102101 0 0.043044 0.00102101 0.0055 0.043044 0.00140562 0 0.043613 0.00123753 0 0.0433121 0.00140562 0.0055 0.043613 0.000149016 0 0.0425071 0.000149016 0.0055 0.0425071 0.000468814 0.0055 0.0426356 0.000468814 0 0.0426356 0.000762295 0.0055 0.0428163 0.000762295 0 0.0428163 -0.0008741 0 0.0424636 -0.00053224 0.0055 0.0424198 -0.00053224 0 0.0424198 -0.0001879 0.0055 0.0424345 -0.0001879 0 0.0424345 -0.00120364 0 0.0425645 -0.0008741 0.0055 0.0424636 -0.00120364 0.0055 0.0425645 -0.00151139 0 0.0427197 -0.00178849 0 0.0429246 -0.00151139 0.0055 0.0427197 -0.00202697 0 0.0431735 -0.00178849 0.0055 0.0429246 -0.00202697 0.0055 0.0431735 -0.00221996 0 0.043459 -0.00236193 0 0.0437731 -0.00221996 0.0055 0.043459 -0.00244877 0 0.0441066 -0.00236193 0.0055 0.0437731 -0.00244877 0.0055 0.0441066 -0.00245029 -2.16951e-35 -0.0431155 -0.002478 0.0055 -0.04345 -0.002478 -3.44605e-35 -0.04345 -0.00204953 -1.90271e-35 -0.0422019 -0.00223309 0.0055 -0.0424829 -0.00223309 -2.02193e-35 -0.0424829 -0.0023679 -2.11168e-35 -0.0427902 -0.0023679 0.0055 -0.0427902 -0.00245029 0.0055 -0.0431155 -0.0015574 0.0055 -0.0417489 -0.0015574 -1.58957e-35 -0.0417489 -0.00126225 -1.40419e-35 -0.0415891 -0.00204953 0.0055 -0.0422019 -0.00182224 -1.75727e-35 -0.041955 -0.00182224 0.0055 -0.041955 -0.000613801 -1.00097e-35 -0.0414249 -0.000278199 -7.94119e-36 -0.0414249 -0.000613801 0.0055 -0.0414249 -0.000944826 -1.20619e-35 -0.0414802 -0.000944826 0.0055 -0.0414802 -0.00126225 0.0055 -0.0415891 0.000665399 -2.19554e-36 -0.0417489 0.000370245 0.0055 -0.0415891 0.000370245 -3.9801e-36 -0.0415891 5.28265e-05 0.0055 -0.0414802 -0.000278199 0.0055 -0.0414249 5.28265e-05 -5.91289e-36 -0.0414802 0.00115753 0.0055 -0.0422019 0.000930236 0.0055 -0.041955 0.00115753 7.39554e-37 -0.0422019 0.000665399 0.0055 -0.0417489 0.000930236 -6.07888e-37 -0.041955 0.00134109 1.81003e-36 -0.0424829 0.00134109 0.0055 -0.0424829 0.0014759 2.57434e-36 -0.0427902 0.0014759 0.0055 -0.0427902 0.00155829 0.0055 -0.0431155 0.00155829 3.01163e-36 -0.0431155 0.001586 1.56321e-35 -0.04345 0.001586 0.0055 -0.04345 -0.002478 0.0055 -0.04545 -0.002478 -3.44605e-35 -0.04345 -0.002478 0.0055 -0.04345 -0.002478 -3.48939e-35 -0.04545 0.001586 0.0055 -0.04345 0.001586 1.51988e-35 -0.04545 0.001586 0.0055 -0.04545 0.001586 1.56321e-35 -0.04345 0.00155829 2.43336e-36 -0.0457845 0.001586 0.0055 -0.04545 0.001586 1.51988e-35 -0.04545 0.00115753 -2.34616e-37 -0.0466981 0.00134109 0.0055 -0.0464171 0.00134109 9.57606e-37 -0.0464171 0.0014759 1.85509e-36 -0.0461098 0.0014759 0.0055 -0.0461098 0.00155829 0.0055 -0.0457845 0.000665399 0.0055 -0.0471511 0.000665399 -3.36603e-36 -0.0471511 0.000370245 -5.21981e-36 -0.0473109 0.00115753 0.0055 -0.0466981 0.000930236 -1.68905e-36 -0.046945 0.000930236 0.0055 -0.046945 -0.000278199 -9.25205e-36 -0.0474751 -0.000613801 -1.13205e-35 -0.0474751 -0.000278199 0.0055 -0.0474751 5.28265e-05 -7.19982e-36 -0.0474198 5.28265e-05 0.0055 -0.0474198 0.000370245 0.0055 -0.0473109 -0.0015574 -1.70662e-35 -0.0471511 -0.00126225 0.0055 -0.0473109 -0.00126225 -1.52816e-35 -0.0473109 -0.000944826 0.0055 -0.0474198 -0.000613801 0.0055 -0.0474751 -0.000944826 -1.33488e-35 -0.0474198 -0.00204953 0.0055 -0.0466981 -0.00182224 0.0055 -0.046945 -0.00204953 -2.00013e-35 -0.0466981 -0.0015574 0.0055 -0.0471511 -0.00182224 -1.86538e-35 -0.046945 -0.00223309 -2.10717e-35 -0.0464171 -0.00223309 0.0055 -0.0464171 -0.0023679 -2.1836e-35 -0.0461098 -0.0023679 0.0055 -0.0461098 -0.00245029 0.0055 -0.0457845 -0.00245029 -2.22733e-35 -0.0457845 -0.002478 -3.48939e-35 -0.04545 -0.002478 0.0055 -0.04545 -0.000460501 -6.23846e-34 0.0514991 -0.00274446 0.0188 0.0514475 -0.000431499 0.0188 0.0514991 0.0510324 0.00423549 -0.00149192 0.0510174 0.00453192 -0.00194162 0.0510004 3.15923e-34 -0.00232366 -0.00506077 0.0188 0.0512928 -0.00276491 -6.66462e-34 0.0514475 -0.00506547 -7.0903e-34 0.051292 -0.00734809 0.0188 0.051035 -0.00737275 -7.51744e-34 0.0510308 -0.00962686 0.0188 0.050674 -0.0118971 0.0188 0.0502098 -0.00965462 -7.94011e-34 0.0506693 -0.0119111 -8.3583e-34 0.0502075 -0.0141422 0.0188 0.0496453 -0.0141544 -8.77428e-34 0.0496411 -0.0163478 0.0188 0.0489828 -0.0185281 0.0188 0.04822 -0.0163741 -9.18612e-34 0.0489738 -0.0185523 -9.59047e-34 0.0482117 -0.0206829 0.0188 0.0473568 -0.0206888 -9.98734e-34 0.0473548 -0.0227838 0.0188 0.0464031 -0.0248372 0.0188 0.0453567 -0.022801 -1.03799e-33 0.0463938 -0.0248627 -1.07634e-33 0.0453429 -0.026849 0.0188 0.0442155 -0.0268678 -1.11366e-33 0.0442053 -0.0288163 0.0188 0.0429811 -0.0307082 0.0188 0.0416703 -0.0288188 -1.14999e-33 0.0429792 -0.0307274 -1.18557e-33 0.0416553 -0.0325434 0.0188 0.0402728 -0.0325659 -1.21986e-33 0.0402553 -0.0343221 0.0188 0.0387886 -0.0360325 0.0188 0.0372269 -0.0343342 -1.25287e-33 0.0387792 -0.0360405 -1.28476e-33 0.0372183 -0.0376607 0.0188 0.0355985 -0.0376793 -1.31541e-33 0.0355783 -0.0392188 0.0188 0.0338939 -0.0407068 0.0188 0.0321132 -0.0392365 -1.34457e-33 0.0338747 -0.040712 -1.37224e-33 0.0321076 -0.0421059 0.0188 0.0302768 -0.042116 -1.39859e-33 0.0302613 -0.043418 0.0188 0.0283826 -0.0446485 0.0188 0.0264247 -0.0434338 -1.42337e-33 0.0283584 -0.0446606 -1.44647e-33 0.0264062 -0.0457964 0.0188 0.0244047 -0.0457971 -1.46792e-33 0.0244032 -0.0468412 0.0188 0.022354 -0.0477949 0.0188 0.020254 -0.0468507 -1.48785e-33 0.0223323 -0.0478064 -1.50597e-33 0.0202278 -0.0486576 0.0188 0.0181048 -0.0486642 -1.5223e-33 0.0180897 -0.0494242 0.0188 0.015918 -0.0500862 0.0188 0.0137127 -0.0494267 -1.53687e-33 0.0159079 -0.0500929 -1.54966e-33 0.0136864 -0.0506504 0.0188 0.0114738 -0.050657 -1.56058e-33 0.011448 -0.0511167 0.0188 0.00920124 -0.0514788 0.0188 0.00691987 -0.0511189 -1.56961e-33 0.00919243 -0.0514788 -1.57675e-33 0.00691987 -0.0517366 0.0188 0.00463028 -0.0517366 -1.58202e-33 0.00463028 -0.0518924 0.0188 0.00232366 -0.051946 0.0188 1.72846e-17 -0.0518924 -1.5854e-33 0.00232366 -0.051946 -6.34787e-34 7.02783e-18 0.00185245 -5.81094e-34 0.0514475 0.00187291 0.0188 0.0514475 0.00416877 -5.38303e-34 0.0512928 0.00645609 -4.9607e-34 0.051035 0.00417347 0.0188 0.051292 0.00648075 0.0188 0.0510308 0.00873486 -4.54017e-34 0.050674 0.00876262 0.0188 0.0506693 0.0110051 -4.12145e-34 0.0502098 0.0132502 -3.70759e-34 0.0496453 0.0110191 0.0188 0.0502075 0.0132624 0.0188 0.0496411 0.0154558 -3.30124e-34 0.0489828 0.0154821 0.0188 0.0489738 0.0176361 -2.89979e-34 0.04822 0.0197909 -2.50327e-34 0.0473568 0.0176603 0.0188 0.0482117 0.0197968 0.0188 0.0473548 0.0218918 -2.11691e-34 0.0464031 0.021909 0.0188 0.0463938 0.0239452 -1.73954e-34 0.0453567 0.025957 -1.37006e-34 0.0442155 0.0239707 0.0188 0.0453429 0.0259758 0.0188 0.0442053 0.0279243 -1.00902e-34 0.0429811 0.0279268 0.0188 0.0429792 0.0298162 -6.62075e-35 0.0416703 0.0316514 -3.25788e-35 0.0402728 0.0298354 0.0188 0.0416553 0.0316739 0.0188 0.0402553 0.0334301 -1.54661e-38 0.0387886 0.0334422 0.0188 0.0387792 0.0351405 3.1269e-35 0.0372269 0.0367687 6.10188e-35 0.0355985 0.0351485 0.0188 0.0372183 0.0367873 0.0188 0.0355783 0.0383268 8.94563e-35 0.0338939 0.0383445 0.0188 0.0338747 0.0398148 1.16581e-34 0.0321132 0.0412139 1.4205e-34 0.0302768 0.03982 0.0188 0.0321076 0.041224 0.0188 0.0302613 0.042526 1.65899e-34 0.0283826 0.0425418 0.0188 0.0283584 0.0437565 1.88225e-34 0.0264247 0.0449044 2.0901e-34 0.0244047 0.0437686 0.0188 0.0264062 0.0449051 0.0188 0.0244032 0.0459492 2.27881e-34 0.022354 0.0459587 0.0188 0.0223323 0.0469029 2.45059e-34 0.020254 0.0477656 2.60544e-34 0.0181048 0.0469144 0.0188 0.0202278 0.0477722 0.0188 0.0180897 0.0485322 2.74243e-34 0.015918 0.0485347 0.0188 0.0159079 0.0491942 2.86005e-34 0.0137127 0.0497584 2.95951e-34 0.0114738 0.0492009 0.0188 0.0136864 0.0497649 0.0188 0.011448 0.0502247 3.0408e-34 0.00920124 0.0502269 0.0188 0.00919243 0.0505868 3.1028e-34 0.00691987 0.0508446 3.14551e-34 0.00463028 0.0505868 0.0188 0.00691987 0.0509974 0.00499561 0.0024145 0.0510004 3.1693e-34 0.00232366 0.0509821 0.00543932 0.00271963 0.0508446 0.0188 0.00463028 0.051054 6.34787e-34 -7.08517e-19 0.0510505 0.00391404 0.000597199 0.051054 0.00385714 6.26998e-05 0.0510137 0.00461105 0.00203714 0.0510518 0.00389302 -0.000474555 0.0502269 3.00135e-34 -0.00919243 0.0505868 3.07282e-34 -0.00691987 0.0505868 0.0188 -0.00691987 0.0510004 0.0188 -0.00232366 0.0509895 0.00949108 -0.0025767 0.0510075 0.00984213 -0.0021878 0.0491942 0.0188 -0.0137127 0.0485347 2.67395e-34 -0.0159079 0.0492009 2.80192e-34 -0.0136864 0.0502247 0.0188 -0.00920124 0.0497584 0.0188 -0.0114738 0.0497649 2.91106e-34 -0.011448 0.0469144 2.36501e-34 -0.0202278 0.0469029 0.0188 -0.020254 0.0459587 2.18375e-34 -0.0223323 0.0477722 2.52824e-34 -0.0180897 0.0485322 0.0188 -0.015918 0.0477656 0.0188 -0.0181048 0.0425418 1.53897e-34 -0.0283584 0.0437686 1.77002e-34 -0.0264062 0.0437565 0.0188 -0.0264247 0.0449044 0.0188 -0.0244047 0.0449051 1.98447e-34 -0.0244032 0.0459492 0.0188 -0.022354 0.0398148 0.0188 -0.0321132 0.0383445 7.51003e-35 -0.0338747 0.03982 1.02763e-34 -0.0321076 0.042526 0.0188 -0.0283826 0.0412139 0.0188 -0.0302768 0.041224 1.29121e-34 -0.0302613 0.0351485 1.52862e-35 -0.0372183 0.0351405 0.0188 -0.0372269 0.0334422 -1.65977e-35 -0.0387792 0.0367873 4.59414e-35 -0.0355783 0.0383268 0.0188 -0.0338939 0.0367687 0.0188 -0.0355985 0.0279268 -1.19479e-34 -0.0429792 0.0298354 -8.3906e-35 -0.0416553 0.0298162 0.0188 -0.0416703 0.0316514 0.0188 -0.0402728 0.0316739 -4.96121e-35 -0.0402553 0.0334301 0.0188 -0.0387886 0.0239452 0.0188 -0.0453567 0.021909 -2.3148e-34 -0.0463938 0.0239707 -1.93134e-34 -0.0453429 0.0279243 0.0188 -0.0429811 0.025957 0.0188 -0.0442155 0.0259758 -1.55817e-34 -0.0442053 0.0176603 -3.10425e-34 -0.0482117 0.0176361 0.0188 -0.04822 0.0154821 -3.50861e-34 -0.0489738 0.0197968 -2.70738e-34 -0.0473548 0.0218918 0.0188 -0.0464031 0.0197909 0.0188 -0.0473568 0.00876262 -4.75461e-34 -0.0506693 0.0110191 -4.33643e-34 -0.0502075 0.0110051 0.0188 -0.0502098 0.0132502 0.0188 -0.0496453 0.0132624 -3.92044e-34 -0.0496411 0.0154558 0.0188 -0.0489828 0.00416877 0.0188 -0.0512928 0.00187291 -6.0301e-34 -0.0514475 0.00417347 -5.60443e-34 -0.051292 0.00873486 0.0188 -0.050674 0.00645609 0.0188 -0.051035 0.00648075 -5.17728e-34 -0.0510308 -0.00274446 -6.88378e-34 -0.0514475 -0.00276491 0.0188 -0.0514475 -0.00506077 -7.3117e-34 -0.0512928 -0.000431499 -6.45626e-34 -0.0514991 0.00185245 0.0188 -0.0514475 -0.000460501 0.0188 -0.0514991 -0.0118971 -8.57328e-34 -0.0502098 -0.00962686 -8.15455e-34 -0.050674 -0.00965462 0.0188 -0.0506693 -0.00737275 0.0188 -0.0510308 -0.00734809 -7.73403e-34 -0.051035 -0.00506547 0.0188 -0.051292 -0.0163741 0.0188 -0.0489738 -0.0185281 -9.79493e-34 -0.04822 -0.0163478 -9.39349e-34 -0.0489828 -0.0119111 0.0188 -0.0502075 -0.0141544 0.0188 -0.0496411 -0.0141422 -8.98713e-34 -0.0496453 -0.0227838 -1.05778e-33 -0.0464031 -0.022801 0.0188 -0.0463938 -0.0248372 -1.09552e-33 -0.0453567 -0.0206829 -1.01915e-33 -0.0473568 -0.0185523 0.0188 -0.0482117 -0.0206888 0.0188 -0.0473548 -0.0307082 -1.20326e-33 -0.0416703 -0.0288163 -1.16857e-33 -0.0429811 -0.0288188 0.0188 -0.0429792 -0.0268678 0.0188 -0.0442053 -0.026849 -1.13247e-33 -0.0442155 -0.0248627 0.0188 -0.0453429 -0.0343342 0.0188 -0.0387792 -0.0360325 -1.30074e-33 -0.0372269 -0.0343221 -1.26946e-33 -0.0387886 -0.0307274 0.0188 -0.0416553 -0.0325659 0.0188 -0.0402553 -0.0325434 -1.23689e-33 -0.0402728 -0.0376793 0.0188 -0.0355783 -0.0392188 -1.35893e-33 -0.0338939 -0.0376607 -1.33049e-33 -0.0355985 -0.0360405 0.0188 -0.0372183 -0.0407068 -1.38605e-33 -0.0321132 -0.0392365 0.0188 -0.0338747 -0.040712 0.0188 -0.0321076 -0.0421059 -1.41152e-33 -0.0302768 -0.042116 0.0188 -0.0302613 -0.043418 -1.43537e-33 -0.0283826 -0.0446485 -1.4577e-33 -0.0264247 -0.0434338 0.0188 -0.0283584 -0.0446606 0.0188 -0.0264062 -0.0457964 -1.47848e-33 -0.0244047 -0.0457971 0.0188 -0.0244032 -0.0468412 -1.49735e-33 -0.022354 -0.0477949 -1.51453e-33 -0.020254 -0.0468507 0.0188 -0.0223323 -0.0478064 0.0188 -0.0202278 -0.0486576 -1.53002e-33 -0.0181048 -0.0486642 0.0188 -0.0180897 -0.0494242 -1.54372e-33 -0.015918 -0.0500862 -1.55548e-33 -0.0137127 -0.0494267 0.0188 -0.0159079 -0.0500929 0.0188 -0.0136864 -0.0506504 -1.56542e-33 -0.0114738 -0.050657 0.0188 -0.011448 -0.0511167 -1.57355e-33 -0.00920124 -0.0514788 -1.57975e-33 -0.00691987 -0.0511189 0.0188 -0.00919243 -0.0514788 0.0188 -0.00691987 -0.0517366 -1.58402e-33 -0.00463028 -0.0517366 0.0188 -0.00463028 -0.0518924 -1.5864e-33 -0.00232366 -0.0518924 0.0188 -0.00232366 0.0508446 3.12544e-34 -0.00463028 0.0508446 0.0188 -0.00463028 0.0510241 0.0101355 -0.00175515 0.0509718 0.00908777 -0.00290905 0.051054 0.0188 -7.08517e-19 0.0510467 0.0104885 -0.000866505 0.0510522 0.0105677 -0.000435651 0.0510443 0.00402011 -0.000998435 0.0510437 0.0103586 -0.00128336 0.0510004 0.0188 0.00232366 0.0510347 0.0103186 0.00141002 0.0510214 0.0100376 0.00183218 0.0510419 0.00406219 0.00111477 0.0510451 0.010476 0.0009554 0.0510518 0.010572 0.000481418 0.0510291 0.00429668 0.00160012 0.0510065 0.00969829 0.00220952 0.0509916 0.0093085 0.0025336 0.050955 0.00741692 0.00319232 0.0509697 0.00592874 0.00294479 0.0509666 0.00841014 0.00299843 0.0509778 0.00887589 0.00279877 0.0509606 0.00640957 0.00310042 0.0509588 0.00792018 0.00313032 0.0509556 0.00690959 0.0031827 0.051064 0.0105945 -3.16414e-18 0.0509348 0.00711465 -0.00350248 0.0509809 0.00520201 -0.00274233 0.0509635 0.00562438 -0.00305159 0.050956 0.00863671 -0.00317593 0.050949 0.006093 -0.00328701 0.0509365 0.00763742 -0.00347785 0.0509438 0.00814985 -0.00336757 0.0509393 0.00659394 -0.00343858 0.0509995 0.00483474 -0.00236872 - + @@ -153,9 +128,9 @@ - -0.9996 -0.0282987 0 -0.9996 -0.0282987 0 -0.9996 0.028299 0 -0.996397 -0.0848059 0 -0.996397 -0.0848059 0 -0.990004 -0.141042 0 -0.990004 -0.141041 0 -0.980439 -0.196825 0 -0.980439 -0.196825 0 -0.967733 -0.251978 0 -0.967733 -0.251978 0 -0.951927 -0.306324 0 -0.951927 -0.306324 0 -0.933072 -0.359689 0 -0.933072 -0.359689 0 -0.911228 -0.411901 0 -0.911228 -0.411901 0 -0.886466 -0.462794 0 -0.886466 -0.462794 0 -0.858863 -0.512205 0 -0.858863 -0.512205 0 -0.82851 -0.559975 0 -0.82851 -0.559975 0 -0.795502 -0.605951 0 -0.795502 -0.605951 0 -0.759946 -0.649986 0 -0.759946 -0.649986 0 -0.721956 -0.691939 0 -0.721956 -0.691939 0 -0.681653 -0.731675 0 -0.681653 -0.731675 0 -0.639167 -0.769068 0 -0.639167 -0.769068 0 -0.594633 -0.803997 0 -0.594633 -0.803997 0 -0.548195 -0.836351 0 -0.548195 -0.836351 0 -0.5 -0.866025 0 -0.5 -0.866025 0 -0.450204 -0.892926 0 -0.450204 -0.892926 0 -0.398966 -0.916966 0 -0.398965 -0.916966 0 -0.346449 -0.938069 0 -0.346449 -0.938069 0 -0.292823 -0.956167 0 -0.292823 -0.956167 0 -0.238259 -0.971202 0 -0.238259 -0.971202 0 -0.182931 -0.983126 0 -0.182931 -0.983126 0 -0.127018 -0.9919 0 -0.127018 -0.9919 0 -0.0706974 -0.997498 0 -0.0706979 -0.997498 0 -0.0141511 -0.9999 0 -0.0141506 -0.9999 0 0.0424415 -0.999099 0 0.042441 -0.999099 0 0.0988972 -0.995098 0 0.0988977 -0.995098 0 0.155037 -0.987909 0 0.155037 -0.987909 0 0.210679 -0.977555 0 0.210679 -0.977555 0 0.265647 -0.96407 0 0.265647 -0.96407 0 0.319764 -0.947497 0 0.319764 -0.947497 0 0.372856 -0.927889 0 0.372856 -0.927889 0 0.424755 -0.905309 0 0.424755 -0.905309 0 0.475292 -0.879828 0 0.475293 -0.879828 0 0.524307 -0.851529 0 0.524307 -0.851529 0 0.571643 -0.820503 0 0.571643 -0.820503 0 0.617147 -0.786848 0 0.617147 -0.786848 0 0.660675 -0.750672 0 0.660675 -0.750672 0 0.702086 -0.712092 0 0.702086 -0.712092 0 0.741248 -0.671231 0 0.741248 -0.671231 0 0.778036 -0.62822 0 0.778036 -0.62822 0 0.812331 -0.583196 0 0.812331 -0.583196 0 0.844024 -0.536305 0 0.844024 -0.536305 0 0.873014 -0.487695 0 0.873014 -0.487695 0 0.899207 -0.437523 0 0.899207 -0.437523 0 0.92252 -0.38595 0 0.92252 -0.385949 0 0.942877 -0.33314 0 0.942878 -0.33314 0 0.960215 -0.279263 0 0.960215 -0.279263 0 0.974476 -0.224491 0 0.974476 -0.224491 0 0.985616 -0.169001 0 0.985616 -0.169001 0 0.993599 -0.112969 0 0.993599 -0.112969 0 0.998398 -0.0565749 0 0.998398 -0.0565749 0 1 1.74846e-07 0 1 -3.01992e-07 0 -0.9996 0.0282988 0 -0.996397 0.0848059 0 -0.996397 0.0848059 0 -0.990004 0.141041 0 -0.990004 0.141041 0 -0.980439 0.196825 0 -0.980439 0.196825 0 -0.967733 0.251978 0 -0.967733 0.251978 0 -0.951927 0.306324 0 -0.951927 0.306324 0 -0.933072 0.359689 0 -0.933072 0.359689 0 -0.911229 0.411901 0 -0.911229 0.411901 0 -0.886466 0.462794 0 -0.886466 0.462794 0 -0.858863 0.512205 0 -0.858863 0.512205 0 -0.82851 0.559975 0 -0.82851 0.559975 0 -0.795502 0.605951 0 -0.795502 0.605951 0 -0.759946 0.649986 0 -0.759946 0.649986 0 -0.721956 0.691939 0 -0.721956 0.691939 0 -0.681653 0.731675 0 -0.681653 0.731675 0 -0.639167 0.769068 0 -0.639167 0.769068 0 -0.594633 0.803997 0 -0.594633 0.803997 0 -0.548195 0.836351 0 -0.548195 0.836351 0 -0.5 0.866025 0 -0.5 0.866025 0 -0.450204 0.892926 0 -0.450204 0.892926 0 -0.398965 0.916966 0 -0.398965 0.916966 0 -0.346449 0.938069 0 -0.346449 0.938069 0 -0.292823 0.956167 0 -0.292823 0.956167 0 -0.238259 0.971202 0 -0.238259 0.971202 0 -0.182931 0.983126 0 -0.182931 0.983126 0 -0.127018 0.9919 0 -0.127018 0.9919 0 -0.0706976 0.997498 0 -0.0706976 0.997498 0 -0.0141509 0.9999 0 -0.0141508 0.9999 0 0.0424412 0.999099 0 0.0424412 0.999099 0 0.0988973 0.995098 0 0.0988974 0.995098 0 0.155037 0.987909 0 0.155037 0.987909 0 0.210679 0.977555 0 0.210679 0.977555 0 0.265647 0.96407 0 0.265647 0.96407 0 0.319764 0.947497 0 0.319764 0.947497 0 0.372856 0.927889 0 0.372856 0.927889 0 0.424755 0.905308 0 0.424755 0.905308 0 0.475292 0.879828 0 0.475292 0.879828 0 0.524307 0.851529 0 0.524307 0.851529 0 0.571643 0.820503 0 0.571643 0.820503 0 0.617147 0.786848 0 0.617147 0.786848 0 0.660675 0.750672 0 0.660675 0.750672 0 0.702086 0.712092 0 0.702086 0.712092 0 0.741248 0.671231 0 0.741248 0.671231 0 0.778036 0.62822 0 0.778036 0.62822 0 0.812331 0.583196 0 0.812331 0.583196 0 0.844024 0.536305 0 0.844024 0.536305 0 0.873014 0.487695 0 0.873014 0.487695 0 0.899207 0.437523 0 0.899207 0.437523 0 0.92252 0.38595 0 0.92252 0.38595 0 0.942877 0.33314 0 0.942877 0.33314 0 0.960215 0.279263 0 0.960215 0.279263 0 0.974476 0.224491 0 0.974476 0.224491 0 0.985616 0.169001 0 0.985616 0.169001 0 0.993599 0.112969 0 0.993599 0.112969 0 0.998398 0.056575 0 0.998398 0.0565751 0 + 1.13847e-16 0.941501 0.33701 1.11424e-16 0.918517 0.395382 1.166e-16 0.968611 0.248581 1.06286e-16 0.871032 0.491226 1.0355e-16 0.846174 0.532906 9.56687e-17 0.775522 0.631321 9.31992e-17 0.753602 0.657331 8.06244e-17 0.643062 0.765814 8.23013e-17 0.657717 0.753266 6.65678e-17 0.521003 0.853555 6.60968e-17 0.516933 0.856026 4.99572e-17 0.378181 0.925732 4.89207e-17 0.369311 0.929306 2.98671e-17 0.207002 0.978341 3.26096e-17 0.230281 0.973124 9.9549e-18 0.0387417 0.999249 1.45279e-17 0.0772685 0.99701 -3.92085e-18 -0.0777526 0.996973 -1.02435e-17 -0.130632 0.991431 -3.01474e-17 -0.29625 0.95511 -2.22788e-17 -0.230934 0.972969 -4.91846e-17 -0.453352 0.891332 -4.01006e-17 -0.378559 0.925577 -5.69577e-17 -0.517078 0.855938 -6.68078e-17 -0.59742 0.801928 -8.25104e-17 -0.724314 0.689471 -7.24379e-17 -0.643104 0.765779 -9.58409e-17 -0.830384 0.557192 -8.6191e-17 -0.753787 0.657119 -9.78701e-17 -0.846332 0.532656 -1.06416e-16 -0.912582 0.408894 -1.13937e-16 -0.968582 0.248695 -1.07193e-16 -0.9185 0.395422 -1.13937e-16 -0.968582 0.248695 1.18136e-16 0.984903 0.173105 1.18968e-16 0.995348 0.0963445 1.19028e-16 0.999991 0.00422309 1.09058e-16 0.932621 -0.360857 1.01561e-16 0.87515 -0.483852 1.1062e-16 0.944314 -0.329046 1.18487e-16 0.998277 -0.0586854 1.15159e-16 0.97721 -0.212275 1.16498e-16 0.98633 -0.16478 1.00309e-16 0.865406 -0.501072 7.59239e-17 0.671292 -0.741193 7.50279e-17 0.664055 -0.747684 8.9582e-17 0.780827 -0.624748 8.92073e-17 0.777845 -0.628456 6.0824e-17 0.548671 -0.836038 2.66237e-17 0.267027 -0.963689 3.99294e-17 0.377147 -0.926154 4.42593e-17 0.41284 -0.910803 5.8317e-17 0.528193 -0.849124 8.35154e-18 0.114822 -0.993386 2.0394e-17 0.215257 -0.976557 -1.01089e-17 -0.0400381 -0.999198 2.72295e-19 0.0471801 -0.998886 -1.98572e-17 -0.122254 -0.992499 -6.23786e-17 -0.484855 -0.874594 -7.46041e-17 -0.590626 -0.806946 -5.78414e-17 -0.445807 -0.895129 -3.94159e-17 -0.288173 -0.957578 -2.83185e-17 -0.193868 -0.981028 -4.58957e-17 -0.343449 -0.939171 -8.9222e-17 -0.718464 -0.695564 -7.72866e-17 -0.613957 -0.789339 -1.01275e-16 -0.825648 -0.564186 -9.03602e-17 -0.728501 -0.685044 -0.865482 -0.478576 0.148007 -0.865298 -0.480828 0.141644 -0.865492 -0.449386 0.221307 -0.865326 -0.497898 0.0575163 -0.865499 -0.495707 0.0720168 -0.865314 -0.44896 0.222859 -0.86554 -0.500826 -0.0037916 -0.86537 -0.403395 0.297334 -0.865526 -0.409003 0.289104 -0.865529 -0.494406 -0.0801382 -0.865392 -0.500438 -0.0256715 -0.865302 -0.462113 -0.194174 -0.865342 -0.488761 -0.110886 -0.865493 -0.475753 -0.156783 -0.865482 -0.445239 -0.229573 -0.865305 -0.421674 -0.270995 -0.865497 -0.404191 -0.295879 -0.865349 -0.369839 -0.338215 -0.865532 -0.296731 -0.403491 -0.865495 -0.229765 -0.445115 -0.865321 -0.235522 -0.442436 -0.865537 -0.35464 -0.353662 -0.865382 -0.308573 -0.394837 -0.865319 -0.0712282 -0.496135 -0.865534 -0.00518421 -0.500823 -0.865379 0.0123585 -0.500966 -0.865298 -0.155152 -0.476642 -0.865482 -0.156981 -0.475708 -0.865496 -0.0811592 -0.494298 -0.865535 0.0708416 -0.495813 -0.865496 0.147755 -0.478628 -0.865352 0.096989 -0.49169 -0.865482 0.221153 -0.44948 -0.865306 0.180977 -0.467432 -0.865301 0.259088 -0.4291 -0.865494 0.288357 -0.409598 -0.865531 0.347243 -0.360941 -0.86534 0.32804 -0.378916 -0.865538 0.397847 -0.30424 -0.865395 0.38599 -0.319535 -0.865328 0.435555 -0.24799 -0.865498 0.440685 -0.238139 -0.865482 0.472668 -0.165911 -0.865299 0.472064 -0.168565 -0.865493 0.492716 -0.090299 -0.865312 0.493982 -0.0849496 -0.86536 -0.348079 0.360545 -0.865543 -0.359939 0.348251 -0.865309 -0.282647 0.413945 -0.865501 -0.303278 0.398662 -0.8653 -0.207198 0.456427 -0.86534 -0.130326 0.483944 -0.86549 -0.165755 0.472707 -0.865482 -0.237898 0.440845 -0.865524 -0.089421 0.492821 -0.865415 -0.0490546 0.498649 -0.865521 0.281362 0.414377 -0.865494 0.312163 0.391758 -0.865549 0.34178 0.366074 -0.865546 -0.0127269 0.500667 -0.865384 0.0288757 0.500277 -0.865365 0.105715 0.489864 -0.865503 0.0628775 0.496942 -0.865489 0.212769 0.453495 -0.865381 0.179663 0.4678 -0.865426 0.249018 0.434772 -0.865483 0.138995 0.481269 -0.865492 0.365311 0.342742 -0.865476 0.410125 0.287661 -0.865505 0.393019 0.310544 -0.865482 0.446411 0.227285 -0.865488 0.421616 0.2705 1.20675e-07 -0.248695 -0.968582 1.20675e-07 -0.248695 -0.968582 1.20675e-07 -0.248695 -0.968582 1.20675e-07 -0.248695 -0.968582 1.11689e-16 0.921 0.389561 1.1528e-16 0.955421 0.295248 1.09505e-16 0.900633 0.434581 1.07018e-16 0.87773 0.479155 1.01276e-16 0.825657 0.564173 1.16197e-16 0.964531 0.263968 1.18471e-16 0.988792 0.149298 1.19006e-16 1 6.78173e-08 1.1866e-16 0.991113 0.133021 -1.01341e-16 -0.826239 -0.56332 -1.01341e-16 -0.826239 -0.56332 -9.08757e-17 -0.733052 -0.680173 -9.08757e-17 -0.733052 -0.680173 -7.83808e-17 -0.62349 -0.781832 -6.41351e-17 -0.5 -0.866025 -7.83808e-17 -0.62349 -0.781832 -6.41351e-17 -0.5 -0.866025 -1.09542e-16 -0.900969 -0.433884 -1.09542e-16 -0.900969 -0.433884 -1.15296e-16 -0.955573 -0.294755 -1.15296e-16 -0.955573 -0.294755 -1.18474e-16 -0.988831 -0.149042 -1.18474e-16 -0.988831 -0.149042 -1.19006e-16 -1 4.6357e-08 -1.19006e-16 -1 4.6357e-08 -1.42268e-17 -0.0747302 -0.997204 3.55992e-18 0.0747301 -0.997204 3.55992e-18 0.0747301 -0.997204 2.12671e-17 0.222521 -0.974928 2.12671e-17 0.222521 -0.974928 3.84993e-17 0.365341 -0.930874 3.84993e-17 0.365341 -0.930874 5.48714e-17 0.5 -0.866025 5.48714e-17 0.5 -0.866025 -1.42268e-17 -0.0747302 -0.997204 -3.16957e-17 -0.222521 -0.974928 -3.16957e-17 -0.222521 -0.974928 -4.84566e-17 -0.365341 -0.930874 -4.84566e-17 -0.365341 -0.930874 -6.41351e-17 -0.5 -0.866025 -6.41351e-17 -0.5 -0.866025 9.53149e-17 0.826239 -0.56332 1.04901e-16 0.900969 -0.433884 1.04901e-16 0.900969 -0.433884 1.12143e-16 0.955573 -0.294755 1.12143e-16 0.955573 -0.294755 1.1688e-16 0.988831 -0.149042 1.1688e-16 0.988831 -0.149042 1.19006e-16 1 -1.7216e-08 1.19006e-16 1 -1.7216e-08 9.53149e-17 0.826239 -0.56332 8.36001e-17 0.733052 -0.680173 8.36001e-17 0.733052 -0.680173 7.00178e-17 0.62349 -0.781831 7.00178e-17 0.62349 -0.781831 5.48714e-17 0.5 -0.866025 5.48714e-17 0.5 -0.866025 1.01341e-16 0.826239 0.56332 1.01341e-16 0.826239 0.56332 9.08757e-17 0.733052 0.680173 9.08757e-17 0.733052 0.680173 7.83808e-17 0.62349 0.781832 6.41351e-17 0.5 0.866025 7.83808e-17 0.62349 0.781832 6.41351e-17 0.5 0.866025 1.09542e-16 0.900969 0.433884 1.09542e-16 0.900969 0.433884 1.15296e-16 0.955573 0.294755 1.15296e-16 0.955573 0.294755 1.18474e-16 0.988831 0.149042 1.18474e-16 0.988831 0.149042 1.19006e-16 1 -4.6357e-08 1.19006e-16 1 -4.6357e-08 -3.55992e-18 -0.0747301 0.997204 -3.55992e-18 -0.0747301 0.997204 -2.12671e-17 -0.222521 0.974928 -2.12671e-17 -0.222521 0.974928 -3.84993e-17 -0.365341 0.930874 -5.48714e-17 -0.5 0.866025 -3.84993e-17 -0.365341 0.930874 -5.48714e-17 -0.5 0.866025 1.42268e-17 0.0747302 0.997204 1.42268e-17 0.0747302 0.997204 3.16957e-17 0.222521 0.974928 3.16957e-17 0.222521 0.974928 4.84566e-17 0.365341 0.930874 4.84566e-17 0.365341 0.930874 6.41351e-17 0.5 0.866025 6.41351e-17 0.5 0.866025 -1.04901e-16 -0.900969 0.433884 -1.04901e-16 -0.900969 0.433884 -1.12143e-16 -0.955573 0.294755 -1.12143e-16 -0.955573 0.294755 -1.1688e-16 -0.988831 0.149042 -1.19006e-16 -1 1.7216e-08 -1.1688e-16 -0.988831 0.149042 -1.19006e-16 -1 1.7216e-08 -9.53149e-17 -0.826239 0.56332 -9.53149e-17 -0.826239 0.56332 -8.36001e-17 -0.733052 0.680173 -8.36001e-17 -0.733052 0.680173 -7.00178e-17 -0.62349 0.781831 -7.00178e-17 -0.62349 0.781831 -5.48714e-17 -0.5 0.866025 -5.48714e-17 -0.5 0.866025 -7.01456e-17 -0.638728 0.769433 -8.32042e-17 -0.746272 0.665641 -8.32042e-17 -0.746272 0.665641 -9.44041e-17 -0.837145 0.54698 -9.44041e-17 -0.837145 0.54698 -1.03495e-16 -0.909318 0.416101 -1.03495e-16 -0.909318 0.416101 -1.10274e-16 -0.961179 0.275927 -1.10274e-16 -0.961179 0.275927 -7.01456e-17 -0.638728 0.769433 -5.55201e-17 -0.516916 0.856036 -5.55201e-17 -0.516916 0.856036 -3.96544e-17 -0.383557 0.923517 -3.96544e-17 -0.383557 0.923517 -2.29028e-17 -0.24163 0.970369 -2.29028e-17 -0.24163 0.970369 -1.15503e-16 -0.985712 -0.168438 -1.1208e-16 -0.949598 -0.31347 -1.1208e-16 -0.949598 -0.31347 -1.06154e-16 -0.892272 -0.451499 -1.06154e-16 -0.892272 -0.451499 -9.78555e-17 -0.815013 -0.579442 -9.78555e-17 -0.815013 -0.579442 -8.73715e-17 -0.719549 -0.694442 -8.73715e-17 -0.719549 -0.694442 -1.15503e-16 -0.985712 -0.168438 -1.16346e-16 -0.999807 -0.0196445 -1.16346e-16 -0.999807 -0.0196445 -1.1459e-16 -0.991568 0.129588 -1.1459e-16 -0.991568 0.129588 -1.10274e-16 -0.961179 0.275927 -1.10274e-16 -0.961179 0.275927 4.53577e-17 0.346984 0.937871 2.88761e-17 0.203326 0.979111 2.88761e-17 0.203326 0.979111 1.17494e-17 0.0551262 0.998479 1.17494e-17 0.0551262 0.998479 -5.63971e-18 -0.0943053 0.995543 -5.63971e-18 -0.0943053 0.995543 -2.29028e-17 -0.24163 0.970368 -2.29028e-17 -0.24163 0.970368 4.53577e-17 0.346984 0.937871 6.08261e-17 0.482891 0.875681 6.08261e-17 0.482891 0.875681 7.49358e-17 0.608011 0.793929 7.49358e-17 0.608011 0.793929 8.73715e-17 0.719549 0.694442 8.73715e-17 0.719549 0.694442 1.15503e-16 0.985712 0.168438 1.1208e-16 0.949598 0.31347 1.1208e-16 0.949598 0.31347 1.06154e-16 0.892272 0.451499 1.06154e-16 0.892272 0.451499 9.78555e-17 0.815013 0.579442 9.78555e-17 0.815013 0.579442 8.73715e-17 0.719549 0.694442 8.73715e-17 0.719549 0.694442 1.15503e-16 0.985712 0.168438 1.16346e-16 0.999807 0.0196445 1.16346e-16 0.999807 0.0196445 1.1459e-16 0.991568 -0.129588 1.1459e-16 0.991568 -0.129588 1.10274e-16 0.961179 -0.275927 1.10274e-16 0.961179 -0.275927 7.01456e-17 0.638728 -0.769433 8.32042e-17 0.746272 -0.665641 8.32042e-17 0.746272 -0.665641 9.44041e-17 0.837145 -0.54698 9.44041e-17 0.837145 -0.54698 1.03495e-16 0.909318 -0.416101 1.03495e-16 0.909318 -0.416101 1.10274e-16 0.961179 -0.275927 1.10274e-16 0.961179 -0.275927 7.01456e-17 0.638728 -0.769433 5.55201e-17 0.516916 -0.856036 5.55201e-17 0.516916 -0.856036 3.96544e-17 0.383557 -0.923517 3.96544e-17 0.383557 -0.923517 2.29028e-17 0.24163 -0.970369 2.29028e-17 0.24163 -0.970369 -4.53577e-17 -0.346984 -0.937871 -2.88761e-17 -0.203326 -0.979111 -2.88761e-17 -0.203326 -0.979111 -1.17494e-17 -0.0551262 -0.998479 -1.17494e-17 -0.0551262 -0.998479 5.63971e-18 0.0943053 -0.995543 5.63971e-18 0.0943053 -0.995543 2.29028e-17 0.24163 -0.970368 2.29028e-17 0.24163 -0.970368 -4.53577e-17 -0.346984 -0.937871 -6.08261e-17 -0.482891 -0.875681 -6.08261e-17 -0.482891 -0.875681 -7.49358e-17 -0.608011 -0.793929 -7.49358e-17 -0.608011 -0.793929 -8.73715e-17 -0.719549 -0.694442 -8.73715e-17 -0.719549 -0.694442 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 1 -3.61049e-15 -5.3484e-18 5.88991e-16 0.164595 -0.986361 -5.3484e-18 3.07066e-22 -1 6.04904e-16 0.169001 -0.985616 2.26402e-15 0.62822 -0.778036 2.21339e-15 0.614213 -0.789141 1.75615e-15 0.487695 -0.873014 1.19775e-15 0.33314 -0.942877 1.7137e-15 0.475947 -0.879474 1.16726e-15 0.324699 -0.945817 3.30424e-15 0.915773 -0.401695 3.07163e-15 0.851529 -0.524307 3.34814e-15 0.927889 -0.372856 2.6527e-15 0.735724 -0.677282 2.70676e-15 0.750672 -0.660675 3.01965e-15 0.837166 -0.546948 3.60701e-15 0.999099 -0.0424412 3.58192e-15 0.9919 0.127018 3.5986e-15 0.996584 0.0825792 3.52832e-15 0.977555 -0.210679 3.59771e-15 0.996584 -0.0825794 3.49869e-15 0.9694 -0.245485 2.906e-15 0.803997 0.594633 3.0255e-15 0.837166 0.546948 3.22631e-15 0.892926 0.450204 3.30854e-15 0.915773 0.401695 3.50132e-15 0.9694 0.245485 3.45379e-15 0.956167 0.292823 1.72311e-15 0.475947 0.879474 2.02621e-15 0.559975 0.82851 1.49204e-15 0.411901 0.911229 2.65994e-15 0.735724 0.677282 2.5021e-15 0.691939 0.721956 2.22183e-15 0.614213 0.78914 3.1152e-16 0.0848059 0.996397 -3.00861e-16 -0.0848059 0.996397 5.34809e-18 -8.74228e-08 1 9.14939e-16 0.251978 0.967733 5.99542e-16 0.164595 0.986361 1.17738e-15 0.324699 0.945817 -2.01735e-15 -0.559975 0.82851 -1.7137e-15 -0.475947 0.879474 -1.48229e-15 -0.411901 0.911228 -1.16726e-15 -0.324699 0.945817 -5.88992e-16 -0.164595 0.986361 -9.04588e-16 -0.251978 0.967733 -3.01965e-15 -0.837167 0.546948 -2.89964e-15 -0.803997 0.594633 -3.22149e-15 -0.892926 0.450204 -2.21339e-15 -0.614213 0.78914 -2.49438e-15 -0.691939 0.721956 -2.6527e-15 -0.735724 0.677282 -3.58056e-15 -0.9919 0.127018 -3.60746e-15 -0.999099 -0.0424415 -3.59771e-15 -0.996584 0.0825794 -3.45066e-15 -0.956167 0.292823 -3.49869e-15 -0.9694 0.245486 -3.30424e-15 -0.915773 0.401695 -3.5986e-15 -0.996584 -0.0825794 -3.53058e-15 -0.977555 -0.210679 -3.50132e-15 -0.9694 -0.245485 -3.30854e-15 -0.915773 -0.401695 -3.35213e-15 -0.927889 -0.372856 -3.07724e-15 -0.851529 -0.524307 -3.0255e-15 -0.837166 -0.546948 -2.71383e-15 -0.750672 -0.660675 -2.65994e-15 -0.735724 -0.677282 -2.22183e-15 -0.614213 -0.789141 -2.27234e-15 -0.62822 -0.778036 -1.76549e-15 -0.487695 -0.873014 -1.72311e-15 -0.475947 -0.879474 -1.20784e-15 -0.33314 -0.942877 -1.17738e-15 -0.324699 -0.945817 -5.99542e-16 -0.164595 -0.986361 -6.15447e-16 -0.169001 -0.985616 -5.34949e-18 -3.01992e-07 -1 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1 0 3.20475e-31 1.10274e-16 0.961179 -0.275927 1.10274e-16 0.961179 -0.275927 1.10274e-16 0.961179 -0.275927 1.10274e-16 0.961179 -0.275927 8.73715e-17 0.719549 0.694442 8.73715e-17 0.719549 0.694442 8.73715e-17 0.719549 0.694442 8.73715e-17 0.719549 0.694442 -2.29028e-17 -0.24163 0.970368 -2.29028e-17 -0.24163 0.970368 -2.29028e-17 -0.24163 0.970368 -2.29028e-17 -0.24163 0.970368 -1.10274e-16 -0.961179 0.275927 -1.10274e-16 -0.961179 0.275927 -1.10274e-16 -0.961179 0.275927 -1.10274e-16 -0.961179 0.275927 -8.73715e-17 -0.719549 -0.694442 -8.73715e-17 -0.719549 -0.694442 -8.73715e-17 -0.719549 -0.694442 -8.73715e-17 -0.719549 -0.694442 2.29028e-17 0.24163 -0.970368 2.29028e-17 0.24163 -0.970368 2.29028e-17 0.24163 -0.970368 2.29028e-17 0.24163 -0.970368 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 1.18686e-16 0.991445 0.130526 1.17518e-16 0.978148 0.207912 1.1909e-16 0.997564 0.0697565 1.13659e-16 0.939693 0.34202 1.16336e-16 0.965926 0.258819 1.11994e-16 0.92388 0.382683 1.07587e-16 0.882948 0.469472 1.05737e-16 0.866025 0.5 9.94219e-17 0.809017 0.587785 8.93214e-17 0.71934 0.694658 9.76701e-17 0.793353 0.608761 8.79322e-17 0.707107 0.707107 7.74823e-17 0.615661 0.788011 7.66897e-17 0.608761 0.793353 6.41351e-17 0.5 0.866026 6.41351e-17 0.5 0.866025 5.04831e-17 0.382683 0.92388 3.59673e-17 0.258819 0.965926 4.95395e-17 0.374606 0.927184 2.08361e-17 0.130526 0.991445 3.39798e-17 0.241922 0.970296 1.77587e-17 0.104528 0.994522 5.34841e-18 4.37114e-08 1 -1.02308e-17 -0.130526 0.991445 1.19188e-18 -0.0348995 0.999391 -2.5635e-17 -0.258819 0.965926 -1.53981e-17 -0.173648 0.984808 -3.16884e-17 -0.309017 0.951056 -4.06005e-17 -0.382683 0.92388 -5.48714e-17 -0.5 0.866025 -4.73619e-17 -0.438371 0.898794 -6.82034e-17 -0.608761 0.793353 -6.21135e-17 -0.559193 0.829038 -7.56562e-17 -0.669131 0.743145 -8.03684e-17 -0.707107 0.707107 -9.11583e-17 -0.793353 0.608761 -8.77263e-17 -0.766044 0.642788 -1.00388e-16 -0.866025 0.5 -9.8089e-17 -0.848048 0.529919 -1.06542e-16 -0.913545 0.406737 -1.07901e-16 -0.92388 0.382683 -1.13567e-16 -0.965926 0.258819 -1.12922e-16 -0.961262 0.275637 -1.1729e-16 -0.991445 0.130526 -1.17104e-16 -0.990268 0.139173 -1.19006e-16 -1 -1.37186e-11 -1.19006e-16 -1 -5.34827e-18 1.19006e-16 1 -8.74228e-08 1.18343e-16 0.997564 -0.0697564 1.1729e-16 0.991445 -0.130526 1.13567e-16 0.965926 -0.258819 1.15294e-16 0.978148 -0.207912 1.1e-16 0.939693 -0.34202 1.07901e-16 0.92388 -0.382683 1.02566e-16 0.882948 -0.469472 1.00388e-16 0.866025 -0.5 9.11582e-17 0.793353 -0.608762 9.31345e-17 0.809017 -0.587785 8.18908e-17 0.71934 -0.694658 8.03684e-17 0.707107 -0.707107 6.90531e-17 0.615662 -0.788011 6.82034e-17 0.608761 -0.793353 5.48714e-17 0.5 -0.866025 5.48714e-17 0.5 -0.866025 4.06005e-17 0.382684 -0.92388 3.96216e-17 0.374606 -0.927184 2.36007e-17 0.241922 -0.970296 2.5635e-17 0.258819 -0.965926 7.12044e-18 0.104528 -0.994522 1.02308e-17 0.130526 -0.991445 -5.3484e-18 -1.19249e-08 -1 -9.49844e-18 -0.0348998 -0.999391 -2.59324e-17 -0.173648 -0.984808 -2.08361e-17 -0.130526 -0.991445 -4.18617e-17 -0.309017 -0.951056 -3.59673e-17 -0.258819 -0.965926 -5.04831e-17 -0.382684 -0.923879 -5.69761e-17 -0.438371 -0.898794 -7.09816e-17 -0.559193 -0.829038 -6.41351e-17 -0.5 -0.866025 -8.36055e-17 -0.669131 -0.743145 -7.66897e-17 -0.608762 -0.793353 -8.79321e-17 -0.707107 -0.707107 -9.46021e-17 -0.766045 -0.642787 -1.03757e-16 -0.848048 -0.529919 -9.76701e-17 -0.793353 -0.608761 -1.10893e-16 -0.913546 -0.406736 -1.05737e-16 -0.866026 -0.5 -1.11994e-16 -0.92388 -0.382683 -1.15871e-16 -0.961262 -0.275638 -1.18593e-16 -0.990268 -0.139173 -1.16336e-16 -0.965926 -0.258819 -1.18686e-16 -0.991445 -0.130526 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 5.48714e-17 0.5 -0.866025 5.48714e-17 0.5 -0.866025 5.48714e-17 0.5 -0.866025 5.48714e-17 0.5 -0.866025 5.48714e-17 0.5 -0.866025 5.48714e-17 0.5 -0.866025 1.19006e-16 1 5.3484e-18 1.19006e-16 1 5.3484e-18 1.19006e-16 1 5.3484e-18 1.19006e-16 1 5.3484e-18 1.19006e-16 1 5.3484e-18 1.19006e-16 1 5.3484e-18 6.41351e-17 0.5 0.866025 6.41351e-17 0.5 0.866025 6.41351e-17 0.5 0.866025 6.41351e-17 0.5 0.866025 6.41351e-17 0.5 0.866025 6.41351e-17 0.5 0.866025 -5.48714e-17 -0.5 0.866025 -5.48714e-17 -0.5 0.866025 -5.48714e-17 -0.5 0.866025 -5.48714e-17 -0.5 0.866025 -5.48714e-17 -0.5 0.866025 -5.48714e-17 -0.5 0.866025 -1.19006e-16 -1 1.32201e-16 -1.19006e-16 -1 1.32201e-16 -1.19006e-16 -1 1.32201e-16 -1.19006e-16 -1 1.32201e-16 -1.19006e-16 -1 1.32201e-16 -1.19006e-16 -1 1.32201e-16 -6.41351e-17 -0.5 -0.866025 -6.41351e-17 -0.5 -0.866025 -6.41351e-17 -0.5 -0.866025 -6.41351e-17 -0.5 -0.866025 -6.41351e-17 -0.5 -0.866025 -6.41351e-17 -0.5 -0.866025 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 1 -1.16264e-16 -5.3484e-18 0.944497 0.327399 -0.027129 0.944497 0.325177 -0.0467533 0.944497 0.318468 -0.0806471 0.944497 -0.022419 0.327755 0.944497 0.0224191 0.327755 0.944497 2.87202e-08 0.328521 0.944497 0.315213 -0.0925549 0.944497 0.30085 -0.131965 0.944497 0.275026 -0.179684 0.944497 0.298833 -0.136472 0.944497 0.276369 -0.177612 0.944497 0.248279 -0.215135 0.944497 0.215135 -0.248279 0.944497 0.2417 -0.222501 0.944497 0.201782 -0.259249 0.944497 0.177612 -0.276369 0.944497 0.136472 -0.298833 0.944497 0.156359 -0.288925 0.944497 0.092555 -0.315213 0.944497 0.10667 -0.31072 0.944497 0.0540727 -0.32404 0.944497 0.0467534 -0.325177 0.944497 -5.74404e-08 -0.328521 0.944497 -5.74404e-08 -0.328521 0.944497 0.328521 -3.91757e-09 0.944497 0.325461 0.0447335 0.944497 0.327399 0.027129 0.944497 0.318468 0.0806471 0.944497 0.316338 0.0886338 0.944497 0.30085 0.131965 0.944497 0.301323 0.130883 0.944497 0.275026 0.179684 0.944497 0.280694 0.170694 0.944497 0.254837 0.207325 0.944497 0.2417 0.222501 0.944497 0.224233 0.240095 0.944497 0.201782 0.259249 0.944497 0.189451 0.268391 0.944497 0.151141 0.291689 0.944497 0.156359 0.288925 0.944497 0.10667 0.31072 0.944497 0.110015 0.309552 0.944497 0.0540728 0.32404 0.944497 0.0668395 0.321649 0.944497 -0.151141 0.291689 0.944497 -0.110015 0.309552 0.944497 -0.106671 0.31072 0.944497 -0.0540727 0.32404 0.944497 -0.0668395 0.321649 0.944497 -0.2417 0.222501 0.944497 -0.224233 0.240095 0.944497 -0.201782 0.259249 0.944497 -0.156359 0.288925 0.944497 -0.189451 0.268391 0.944497 -0.30085 0.131965 0.944497 -0.301323 0.130883 0.944497 -0.280694 0.170694 0.944497 -0.254837 0.207325 0.944497 -0.275026 0.179684 0.944497 -0.328521 1.43601e-08 0.944497 -0.327399 0.0271291 0.944497 -0.327399 -0.027129 0.944497 -0.325461 0.0447336 0.944497 -0.316338 0.0886338 0.944497 -0.318468 0.080647 0.944497 -0.298833 -0.136472 0.944497 -0.315213 -0.0925549 0.944497 -0.30085 -0.131965 0.944497 -0.318468 -0.0806471 0.944497 -0.325177 -0.0467533 0.944497 -0.276369 -0.177612 0.944497 -0.275026 -0.179684 0.944497 -0.248279 -0.215135 0.944497 -0.2417 -0.222501 0.944497 -0.215135 -0.248279 0.944497 -0.177612 -0.276369 0.944497 -0.201782 -0.259249 0.944497 -0.156359 -0.288925 0.944497 -0.136472 -0.298833 0.944497 -0.10667 -0.31072 0.944497 -0.0925549 -0.315213 0.944497 -0.0467534 -0.325177 0.944497 -0.0540727 -0.32404 -2.22303e-17 -0.142315 -0.989821 -5.3484e-18 -1.19249e-08 -1 -2.08361e-17 -0.130526 -0.991445 1.19006e-16 1 -8.74228e-08 1.18686e-16 0.991445 0.130526 1.19006e-16 1 -8.74228e-08 -3.59673e-17 -0.258819 -0.965926 -3.86597e-17 -0.281732 -0.959493 -5.04831e-17 -0.382684 -0.923879 -5.43022e-17 -0.415415 -0.909632 -6.88391e-17 -0.540641 -0.841254 -6.41351e-17 -0.5 -0.866025 -7.66897e-17 -0.608762 -0.793353 -8.19747e-17 -0.654861 -0.75575 -8.79321e-17 -0.707107 -0.707107 -9.76701e-17 -0.793353 -0.608761 -9.34415e-17 -0.755749 -0.654861 -1.03006e-16 -0.841254 -0.54064 -1.05737e-16 -0.866026 -0.5 -1.11994e-16 -0.92388 -0.382683 -1.10474e-16 -0.909632 -0.415415 -1.16336e-16 -0.965926 -0.258819 -1.15693e-16 -0.959493 -0.281733 -1.18556e-16 -0.989821 -0.142315 -1.18686e-16 -0.991445 -0.130526 -1.19006e-16 -1 1.74846e-07 -1.19006e-16 -1 -3.01992e-07 -5.3484e-18 -1.19249e-08 -1 1.16424e-17 0.142315 -0.989821 1.02308e-17 0.130526 -0.991445 2.83962e-17 0.281732 -0.959493 2.5635e-17 0.258819 -0.965926 4.06005e-17 0.382684 -0.92388 4.4572e-17 0.415415 -0.909632 5.98404e-17 0.540641 -0.841254 5.48714e-17 0.5 -0.866025 7.38906e-17 0.654861 -0.75575 6.82034e-17 0.608761 -0.793353 8.03684e-17 0.707107 -0.707107 8.64366e-17 0.75575 -0.654861 9.7223e-17 0.841254 -0.540641 9.11582e-17 0.793353 -0.608762 1.0603e-16 0.909632 -0.415415 1.00388e-16 0.866025 -0.5 1.07901e-16 0.92388 -0.382683 1.12679e-16 0.959493 -0.281733 1.17034e-16 0.989821 -0.142315 1.13567e-16 0.965926 -0.258819 1.1729e-16 0.991445 -0.130526 1.16036e-16 0.962917 0.269797 1.16336e-16 0.965926 0.258819 1.18626e-16 0.990686 0.136167 9.56899e-17 0.775711 0.631088 9.76701e-17 0.793353 0.608761 1.0446e-16 0.854419 0.519584 1.11285e-16 0.917211 0.398401 1.05737e-16 0.866025 0.5 1.11994e-16 0.92388 0.382683 7.29982e-17 0.57668 0.81697 5.94995e-17 0.460065 0.887885 6.41351e-17 0.5 0.866026 8.79322e-17 0.707107 0.707107 8.5137e-17 0.682553 0.730836 7.66897e-17 0.608761 0.793353 2.08361e-17 0.130526 0.991445 2.94491e-17 0.203456 0.979084 1.34572e-17 0.0682424 0.997669 3.59673e-17 0.258819 0.965926 5.04831e-17 0.382684 0.92388 4.48924e-17 0.33488 0.942261 -2.78535e-18 -0.0682424 0.997669 -1.02308e-17 -0.130526 0.991445 5.34841e-18 4.37114e-08 1 -5.00019e-17 -0.460065 0.887885 -5.48714e-17 -0.5 0.866025 -4.06005e-17 -0.382683 0.92388 -1.8976e-17 -0.203456 0.979084 -3.48132e-17 -0.33488 0.942261 -2.5635e-17 -0.258819 0.965926 -7.73194e-17 -0.682553 0.730836 -8.89393e-17 -0.775711 0.631088 -8.03684e-17 -0.707107 0.707107 -6.82034e-17 -0.608761 0.793353 -6.42592e-17 -0.57668 0.81697 -9.89025e-17 -0.854419 0.519584 -9.11583e-17 -0.793353 0.608761 -1.00388e-16 -0.866025 0.5 -1.07023e-16 -0.917211 0.398401 -1.1315e-16 -0.962917 0.269797 -1.07901e-16 -0.92388 0.382683 -1.1717e-16 -0.990686 0.136167 -1.13567e-16 -0.965926 0.258819 -1.1729e-16 -0.991445 0.130526 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -1 1.16264e-16 5.3484e-18 -5.3484e-18 1.19249e-08 -1 -5.3484e-18 1.19249e-08 -1 1.33342e-17 0.156435 -0.987688 -1.19006e-16 -1 -8.74228e-08 -1.16705e-16 -0.987688 0.156434 -1.19006e-16 -1 -8.74228e-08 1.33342e-17 0.156435 -0.987688 3.16884e-17 0.309017 -0.951056 4.92623e-17 0.45399 -0.891007 3.16884e-17 0.309017 -0.951056 4.92624e-17 0.453991 -0.891006 6.56233e-17 0.587785 -0.809017 6.56233e-17 0.587785 -0.809017 8.03684e-17 0.707107 -0.707107 9.31345e-17 0.809017 -0.587785 8.03684e-17 0.707107 -0.707107 9.31345e-17 0.809017 -0.587785 1.03607e-16 0.891007 -0.453991 1.03607e-16 0.891007 -0.453991 1.11529e-16 0.951057 -0.309017 1.16705e-16 0.987688 -0.156434 1.11529e-16 0.951057 -0.309017 1.16705e-16 0.987688 -0.156435 1.19006e-16 1 1.74846e-07 1.19006e-16 1 -3.01992e-07 -2.38993e-17 -0.156435 -0.987688 -4.18617e-17 -0.309017 -0.951056 -2.38993e-17 -0.156435 -0.987688 -4.18617e-17 -0.309017 -0.951056 -5.87932e-17 -0.45399 -0.891007 -5.87932e-17 -0.45399 -0.891007 -7.42772e-17 -0.587785 -0.809017 -8.79322e-17 -0.707107 -0.707107 -7.42772e-17 -0.587785 -0.809017 -8.79322e-17 -0.707107 -0.707107 -9.9422e-17 -0.809017 -0.587785 -9.94219e-17 -0.809017 -0.587785 -1.08464e-16 -0.891007 -0.453991 -1.14835e-16 -0.951056 -0.309017 -1.08464e-16 -0.891007 -0.453991 -1.14835e-16 -0.951057 -0.309017 -1.18378e-16 -0.987688 -0.156434 -1.18378e-16 -0.987688 -0.156434 -1.11529e-16 -0.951056 0.309017 -1.11529e-16 -0.951056 0.309017 -1.16705e-16 -0.987688 0.156434 -8.03684e-17 -0.707107 0.707107 -8.03684e-17 -0.707107 0.707107 -9.31345e-17 -0.809017 0.587785 -1.03607e-16 -0.891007 0.45399 -9.31345e-17 -0.809017 0.587785 -1.03607e-16 -0.891006 0.453991 -4.92623e-17 -0.45399 0.891007 -3.16884e-17 -0.309017 0.951056 -3.16884e-17 -0.309017 0.951057 -6.56233e-17 -0.587785 0.809017 -6.56233e-17 -0.587785 0.809017 -4.92623e-17 -0.45399 0.891007 2.38993e-17 0.156434 0.987688 5.3484e-18 -4.37114e-08 1 2.38993e-17 0.156434 0.987688 5.3484e-18 -4.37114e-08 1 -1.33342e-17 -0.156435 0.987688 -1.33342e-17 -0.156434 0.987688 7.42772e-17 0.587785 0.809017 7.42772e-17 0.587785 0.809017 5.87933e-17 0.453991 0.891007 4.18616e-17 0.309017 0.951057 5.87933e-17 0.453991 0.891007 4.18617e-17 0.309017 0.951056 9.94219e-17 0.809017 0.587785 9.94219e-17 0.809017 0.587785 8.79322e-17 0.707107 0.707107 8.79322e-17 0.707107 0.707107 1.08464e-16 0.891007 0.453991 1.08464e-16 0.891007 0.453991 1.14835e-16 0.951057 0.309017 1.14835e-16 0.951057 0.309017 1.18378e-16 0.987688 0.156434 1.18378e-16 0.987688 0.156434 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 -1 0 -3.20475e-31 1.17491e-16 0.992688 -0.120712 1.14242e-16 0.970752 -0.240084 1.17396e-16 0.992105 -0.125411 1.13931e-16 0.968535 -0.248875 1.19006e-16 1 1.55429e-09 1.09332e-16 0.93468 -0.35549 0.86534 0.264955 -0.425423 0.86555 0.324654 -0.381345 0.865502 0.264564 -0.425337 0.865395 0.333658 -0.373851 0.865302 0.187288 -0.464947 0.865474 0.198896 -0.459778 0.865328 0.390767 -0.313861 0.865512 0.375815 -0.331138 0.865485 0.419329 -0.274041 0.865467 0.129397 -0.483967 0.865305 0.104579 -0.490214 0.865299 0.438452 -0.242935 0.865481 0.454425 -0.210811 0.865312 0.473803 -0.16354 0.86549 0.47523 -0.15838 0.865481 0.0572762 -0.497657 0.865351 0.0207011 -0.500739 0.865381 -0.0624119 -0.497213 0.865516 -0.0157876 -0.500633 0.865352 -0.416214 -0.279162 0.865379 -0.36312 -0.345345 0.865409 -0.363762 -0.344593 0.865476 -0.0918491 -0.492458 0.86532 -0.147396 -0.479057 0.865421 -0.166893 -0.472432 0.865388 -0.238498 -0.440706 0.865298 -0.228064 -0.44637 0.865319 -0.300865 -0.400878 0.865382 -0.304651 -0.397872 -1.94892e-15 -0.674536 -0.738242 -1.90739e-15 -0.669339 -0.742957 -2.87077e-15 -0.784108 -0.620624 -9.17221e-16 -0.539415 -0.84204 -3.81195e-15 -0.882453 -0.4704 -4.56787e-15 -0.947707 -0.319143 -4.60423e-15 -0.950429 -0.310942 -2.9131e-15 -0.788852 -0.614583 1.57384e-16 -0.386223 -0.922406 -8.76635e-16 -0.533855 -0.845576 -5.22572e-15 -0.988426 -0.151704 -5.72792e-15 -0.999799 0.0200418 -5.74026e-15 -0.999684 0.0251408 -5.25435e-15 -0.989683 -0.143272 -3.77539e-15 -0.878943 -0.476926 -6.05998e-15 -0.981611 0.190891 -6.06448e-15 -0.980996 0.194028 -6.21461e-15 -0.932942 0.360027 -6.21326e-15 -0.934348 0.356363 -6.18237e-15 -0.859303 0.511467 -5.96832e-15 -0.758889 0.65122 -6.17887e-15 -0.856837 0.515588 -5.96177e-15 -0.756482 0.654015 -5.57714e-15 -0.635894 0.771776 -5.02086e-15 -0.494114 0.869397 -5.02482e-15 -0.495051 0.868864 -5.57815e-15 -0.636176 0.771544 -4.31549e-15 -0.337626 0.94128 1.22763e-15 -0.221416 -0.975179 1.94841e-16 -0.380662 -0.924714 1.26032e-15 -0.216184 -0.976353 2.24657e-15 -0.0524815 -0.998622 3.1882e-15 0.115755 -0.993278 2.27367e-15 -0.0478137 -0.998856 4.0559e-15 0.28404 -0.958812 3.21035e-15 0.119877 -0.992789 4.07293e-15 0.287503 -0.95778 4.81009e-15 0.445342 -0.895361 5.41661e-15 0.592435 -0.805618 4.82192e-15 0.448028 -0.894019 5.85504e-15 0.719537 -0.694454 5.42382e-15 0.594333 -0.804219 5.85872e-15 0.720748 -0.693197 6.12749e-15 0.82662 -0.562761 6.2235e-15 0.911135 -0.412109 6.12879e-15 0.827292 -0.561772 6.13329e-15 0.968582 -0.248695 6.22351e-15 0.911383 -0.411559 6.13329e-15 0.968582 -0.248695 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 0.999745 6.16679e-33 0.0225996 0.999745 6.15699e-33 -0.0225995 0.999745 6.15699e-33 -0.0225995 0.997702 6.13462e-33 -0.0677522 0.997702 6.13462e-33 -0.0677522 0.993622 6.09972e-33 -0.112766 0.993622 6.09972e-33 -0.112766 0.987511 6.05235e-33 -0.157551 0.987511 6.05235e-33 -0.15755 0.979383 5.99262e-33 -0.202013 0.979383 5.99262e-33 -0.202013 0.969254 5.92065e-33 -0.246062 0.969254 5.92065e-33 -0.246062 0.957145 5.83658e-33 -0.289609 0.957145 5.83658e-33 -0.289609 0.943081 5.74059e-33 -0.332564 0.943081 5.74059e-33 -0.332564 0.92709 5.63287e-33 -0.374839 0.92709 5.63287e-33 -0.374839 0.909205 5.51364e-33 -0.416349 0.909205 5.51364e-33 -0.416349 0.889462 5.38315e-33 -0.457009 0.889462 5.38315e-33 -0.457009 0.867903 5.24166e-33 -0.496734 0.867903 5.24166e-33 -0.496734 0.84457 5.08947e-33 -0.535445 0.84457 5.08947e-33 -0.535445 0.819512 4.92687e-33 -0.573062 0.819512 4.92687e-33 -0.573062 0.79278 4.75421e-33 -0.609508 0.79278 4.75421e-33 -0.609508 0.764428 4.57184e-33 -0.644709 0.764428 4.57184e-33 -0.644709 0.734514 4.38012e-33 -0.678593 0.734514 4.38012e-33 -0.678593 0.7031 4.17946e-33 -0.711091 0.7031 4.17946e-33 -0.711091 0.67025 3.97026e-33 -0.742136 0.67025 3.97026e-33 -0.742136 0.63603 3.75295e-33 -0.771664 0.63603 3.75295e-33 -0.771664 0.60051 3.52797e-33 -0.799617 0.600511 3.52798e-33 -0.799617 0.563764 3.29579e-33 -0.825936 0.563764 3.29579e-33 -0.825936 0.525867 3.05687e-33 -0.850567 0.525867 3.05687e-33 -0.850567 0.486895 2.81171e-33 -0.873461 0.486895 2.81171e-33 -0.873461 0.446928 2.5608e-33 -0.89457 0.446928 2.5608e-33 -0.89457 0.406048 2.30466e-33 -0.913852 0.406048 2.30466e-33 -0.913852 0.364339 2.04382e-33 -0.931266 0.364339 2.04382e-33 -0.931266 0.321885 1.77879e-33 -0.946779 0.321885 1.77879e-33 -0.946779 0.278774 1.51014e-33 -0.960357 0.278774 1.51014e-33 -0.960357 0.235093 1.2384e-33 -0.971973 0.235093 1.2384e-33 -0.971973 0.190932 9.64124e-34 -0.981603 0.190932 9.64121e-34 -0.981603 0.146381 6.8788e-34 -0.989228 0.146381 6.87883e-34 -0.989228 0.101531 4.10237e-34 -0.994832 0.101531 4.10237e-34 -0.994832 0.0564732 1.31749e-34 -0.998404 0.0564732 1.31749e-34 -0.998404 0.0113003 -1.47004e-34 -0.999936 0.0113003 -1.47004e-34 -0.999936 -0.0338957 -4.25458e-34 -0.999425 -0.0338952 -4.25455e-34 -0.999425 -0.0790224 -7.03042e-34 -0.996873 -0.0790224 -7.03042e-34 -0.996873 -0.123988 -9.79189e-34 -0.992284 -0.123988 -9.79189e-34 -0.992284 -0.1687 -1.25334e-33 -0.985667 -0.1687 -1.25334e-33 -0.985667 -0.213067 -1.52492e-33 -0.977038 -0.213067 -1.52492e-33 -0.977038 -0.256999 -1.7934e-33 -0.966412 -0.257 -1.7934e-33 -0.966411 -0.300406 -2.0582e-33 -0.953811 -0.300406 -2.0582e-33 -0.953811 -0.3432 -2.31881e-33 -0.939263 -0.3432 -2.31881e-33 -0.939263 -0.385292 -2.57467e-33 -0.922795 -0.385292 -2.57467e-33 -0.922795 -0.426597 -2.82528e-33 -0.904442 -0.426597 -2.82528e-33 -0.904442 -0.46703 -3.07011e-33 -0.884241 -0.467031 -3.07011e-33 -0.884241 -0.50651 -3.30868e-33 -0.862234 -0.50651 -3.30868e-33 -0.862234 -0.544955 -3.54048e-33 -0.838465 -0.544955 -3.54048e-33 -0.838465 -0.582286 -3.76505e-33 -0.812984 -0.582286 -3.76505e-33 -0.812984 -0.618428 -3.98193e-33 -0.785841 -0.618428 -3.98193e-33 -0.785841 -0.653307 -4.19067e-33 -0.757093 -0.653307 -4.19067e-33 -0.757093 -0.68685 -4.39085e-33 -0.726799 -0.68685 -4.39085e-33 -0.726799 -0.718991 -4.58206e-33 -0.69502 -0.718991 -4.58206e-33 -0.69502 -0.749663 -4.76391e-33 -0.66182 -0.749663 -4.76391e-33 -0.66182 -0.778803 -4.93603e-33 -0.627269 -0.778803 -4.93603e-33 -0.627269 -0.806352 -5.09807e-33 -0.591436 -0.806352 -5.09807e-33 -0.591436 -0.832254 -5.24969e-33 -0.554395 -0.832254 -5.24969e-33 -0.554395 -0.856455 -5.39058e-33 -0.516221 -0.856455 -5.39058e-33 -0.516222 -0.878907 -5.52046e-33 -0.476993 -0.878907 -5.52046e-33 -0.476993 -0.899563 -5.63906e-33 -0.43679 -0.899563 -5.63906e-33 -0.43679 -0.918382 -5.74615e-33 -0.395695 -0.918382 -5.74615e-33 -0.395695 -0.935324 -5.84149e-33 -0.353792 -0.935324 -5.84149e-33 -0.353792 -0.950356 -5.9249e-33 -0.311166 -0.950356 -5.9249e-33 -0.311166 -0.963446 -5.99621e-33 -0.267903 -0.963446 -5.99621e-33 -0.267904 -0.974567 -6.05527e-33 -0.224095 -0.974567 -6.05527e-33 -0.224095 -0.983698 -6.10195e-33 -0.179828 -0.983698 -6.10195e-33 -0.179828 -0.990819 -6.13617e-33 -0.135193 -0.990819 -6.13617e-33 -0.135193 -0.995916 -6.15786e-33 -0.0902827 -0.995916 -6.15786e-33 -0.0902827 -0.998979 -6.16696e-33 -0.0451872 -0.998978 -6.16696e-33 -0.0451876 -1 -6.16347e-33 1.74846e-07 -1 -6.16347e-33 -3.01992e-07 0.999745 6.16679e-33 0.0225994 0.997702 6.16398e-33 0.0677521 0.997702 6.16398e-33 0.0677521 0.993622 6.14858e-33 0.112767 0.993622 6.14858e-33 0.112767 0.987511 6.12062e-33 0.157551 0.987511 6.12062e-33 0.157551 0.979383 6.08016e-33 0.202013 0.979383 6.08016e-33 0.202013 0.969254 6.02728e-33 0.246062 0.969254 6.02728e-33 0.246062 0.957145 5.96208e-33 0.289609 0.957145 5.96208e-33 0.289609 0.943081 5.8847e-33 0.332564 0.943081 5.8847e-33 0.332564 0.92709 5.7953e-33 0.374839 0.92709 5.7953e-33 0.374839 0.909205 5.69406e-33 0.416349 0.909205 5.69406e-33 0.416349 0.889462 5.58119e-33 0.457009 0.889462 5.58119e-33 0.457009 0.867903 5.45691e-33 0.496734 0.867903 5.45691e-33 0.496734 0.84457 5.32149e-33 0.535445 0.84457 5.32149e-33 0.535445 0.819512 5.1752e-33 0.573062 0.819512 5.1752e-33 0.573062 0.79278 5.01833e-33 0.609508 0.79278 5.01833e-33 0.609508 0.764428 4.85121e-33 0.644709 0.764428 4.85121e-33 0.644709 0.734514 4.67418e-33 0.678593 0.734514 4.67418e-33 0.678593 0.7031 4.4876e-33 0.711091 0.7031 4.4876e-33 0.711091 0.670249 4.29186e-33 0.742136 0.670249 4.29186e-33 0.742136 0.63603 4.08734e-33 0.771665 0.63603 4.08734e-33 0.771664 0.600511 3.87448e-33 0.799617 0.600511 3.87448e-33 0.799617 0.563765 3.6537e-33 0.825936 0.563765 3.6537e-33 0.825936 0.525867 3.42545e-33 0.850567 0.525867 3.42545e-33 0.850567 0.486895 3.19021e-33 0.873461 0.486895 3.19021e-33 0.873461 0.446928 2.94845e-33 0.89457 0.446928 2.94845e-33 0.89457 0.406048 2.70067e-33 0.913852 0.406048 2.70067e-33 0.913852 0.364339 2.44736e-33 0.931266 0.364339 2.44737e-33 0.931266 0.321885 2.18906e-33 0.946779 0.321885 2.18906e-33 0.946779 0.278774 1.92629e-33 0.960357 0.278774 1.92629e-33 0.960357 0.235093 1.65958e-33 0.971973 0.235093 1.65958e-33 0.971973 0.190932 1.38949e-33 0.981603 0.190932 1.38949e-33 0.981603 0.146381 1.11655e-33 0.989228 0.146381 1.11655e-33 0.989228 0.101531 8.4133e-34 0.994832 0.101531 8.4133e-34 0.994832 0.0564733 5.64392e-34 0.998404 0.0564734 5.64393e-34 0.998404 0.0113004 2.86303e-34 0.999936 0.0113005 2.86303e-34 0.999936 -0.0338955 7.62883e-36 0.999425 -0.0338956 7.62809e-36 0.999425 -0.0790224 -2.71062e-34 0.996873 -0.0790224 -2.71062e-34 0.996873 -0.123988 -5.49199e-34 0.992284 -0.123988 -5.49199e-34 0.992284 -0.1687 -8.26214e-34 0.985667 -0.1687 -8.26213e-34 0.985667 -0.213067 -1.10154e-33 0.977038 -0.213067 -1.10154e-33 0.977038 -0.256999 -1.37462e-33 0.966412 -0.256999 -1.37462e-33 0.966412 -0.300406 -1.64489e-33 0.953811 -0.300406 -1.64488e-33 0.953811 -0.3432 -1.91179e-33 0.939262 -0.3432 -1.91179e-33 0.939262 -0.385292 -2.17479e-33 0.922795 -0.385292 -2.17479e-33 0.922795 -0.426597 -2.43335e-33 0.904442 -0.426597 -2.43335e-33 0.904442 -0.467031 -2.68694e-33 0.884241 -0.467031 -2.68694e-33 0.884241 -0.50651 -2.93504e-33 0.862234 -0.50651 -2.93504e-33 0.862234 -0.544955 -3.17714e-33 0.838465 -0.544955 -3.17714e-33 0.838465 -0.582286 -3.41275e-33 0.812984 -0.582286 -3.41275e-33 0.812984 -0.618428 -3.64139e-33 0.785841 -0.618428 -3.64139e-33 0.785841 -0.653307 -3.86259e-33 0.757093 -0.653307 -3.86259e-33 0.757093 -0.68685 -4.0759e-33 0.726799 -0.68685 -4.0759e-33 0.726799 -0.718991 -4.28089e-33 0.69502 -0.718991 -4.28089e-33 0.69502 -0.749663 -4.47712e-33 0.66182 -0.749663 -4.47712e-33 0.66182 -0.778803 -4.66421e-33 0.627269 -0.778803 -4.66421e-33 0.627269 -0.806352 -4.84178e-33 0.591436 -0.806352 -4.84178e-33 0.591436 -0.832254 -5.00945e-33 0.554395 -0.832254 -5.00945e-33 0.554395 -0.856455 -5.16688e-33 0.516222 -0.856455 -5.16688e-33 0.516222 -0.878907 -5.31376e-33 0.476993 -0.878907 -5.31376e-33 0.476993 -0.899563 -5.44979e-33 0.43679 -0.899563 -5.44979e-33 0.43679 -0.918382 -5.57468e-33 0.395695 -0.918382 -5.57468e-33 0.395695 -0.935324 -5.68818e-33 0.353792 -0.935324 -5.68818e-33 0.353792 -0.950356 -5.79006e-33 0.311166 -0.950356 -5.79006e-33 0.311166 -0.963446 -5.88012e-33 0.267904 -0.963446 -5.88012e-33 0.267904 -0.974567 -5.95816e-33 0.224095 -0.974567 -5.95816e-33 0.224095 -0.983698 -6.02403e-33 0.179827 -0.983698 -6.02403e-33 0.179827 -0.990819 -6.07759e-33 0.135193 -0.990819 -6.07759e-33 0.135193 -0.995916 -6.11873e-33 0.0902824 -0.995916 -6.11873e-33 0.0902824 -0.998979 -6.14738e-33 0.0451874 -0.998979 -6.14738e-33 0.0451874 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 1.2326e-32 -1 2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 -1.2326e-32 1 -2.16667e-34 0.999771 1.84796e-32 -0.0214185 0.999745 1.84788e-32 -0.0225995 0.999745 1.84886e-32 0.0225994 0.997702 1.84313e-32 -0.0677522 0.99778 1.8433e-32 -0.0665904 0.99375 1.83487e-32 -0.111627 0.993622 1.83461e-32 -0.112766 0.987688 1.82269e-32 -0.156434 0.987511 1.82234e-32 -0.15755 0.979383 1.80635e-32 -0.202013 0.979607 1.80679e-32 -0.200922 0.969523 1.78719e-32 -0.245 0.969254 1.78667e-32 -0.246062 0.957457 1.76394e-32 -0.288576 0.957145 1.76334e-32 -0.289609 0.943081 1.7364e-32 -0.332564 0.943433 1.73708e-32 -0.331563 0.927481 1.70667e-32 -0.373871 0.92709 1.70592e-32 -0.374839 0.909632 1.67277e-32 -0.415415 0.909205 1.67196e-32 -0.416349 0.889462 1.63457e-32 -0.457009 0.889924 1.63545e-32 -0.45611 0.868396 1.59478e-32 -0.495872 0.867903 1.59385e-32 -0.496734 0.845092 1.55086e-32 -0.534621 0.84457 1.54988e-32 -0.535445 0.819512 1.50273e-32 -0.573062 0.820061 1.50377e-32 -0.572276 0.793353 1.4536e-32 -0.608762 0.79278 1.45252e-32 -0.609508 0.765023 1.40046e-32 -0.644002 0.764428 1.39934e-32 -0.644709 0.734514 1.3433e-32 -0.678593 0.73513 1.34445e-32 -0.677927 0.703733 1.2857e-32 -0.710465 0.7031 1.28452e-32 -0.711091 0.670897 1.22432e-32 -0.74155 0.67025 1.22311e-32 -0.742136 0.63603 1.1592e-32 -0.771664 0.63669 1.16043e-32 -0.77112 0.601181 1.09418e-32 -0.799113 0.60051 1.09292e-32 -0.799617 0.564443 1.02568e-32 -0.825472 0.563764 1.02442e-32 -0.825936 0.525867 9.53817e-33 -0.850567 0.526551 9.55091e-33 -0.850143 0.487583 8.82547e-33 -0.873077 0.486895 8.81267e-33 -0.873461 0.447617 8.08199e-33 -0.894225 0.446928 8.06918e-33 -0.89457 0.406048 7.3092e-33 -0.913852 0.406737 7.32199e-33 -0.913545 0.365025 6.54702e-33 -0.930998 0.364339 6.53428e-33 -0.931266 0.322566 5.75866e-33 -0.946547 0.321885 5.74602e-33 -0.946779 0.278774 4.94602e-33 -0.960357 0.279448 4.95853e-33 -0.960161 0.235759 4.14825e-33 -0.971812 0.235093 4.13592e-33 -0.971973 0.191588 3.3295e-33 -0.981476 0.190932 3.31735e-33 -0.981603 0.146381 2.49203e-33 -0.989228 0.147025 2.50394e-33 -0.989133 0.102161 1.67327e-33 -0.994768 0.101531 1.66161e-33 -0.994832 0.0570888 8.39169e-34 -0.998369 0.0564732 8.2778e-34 -0.998404 0.0113003 -7.72817e-36 -0.999936 0.0118997 3.35427e-36 -0.999929 -0.0333138 -8.32467e-34 -0.999445 -0.0338957 -8.43221e-34 -0.999425 -0.0784591 -1.66659e-33 -0.996917 -0.0790224 -1.67699e-33 -0.996873 -0.123988 -2.50734e-33 -0.992284 -0.123444 -2.4973e-33 -0.992352 -0.168177 -3.3229e-33 -0.985757 -0.1687 -3.33256e-33 -0.985667 -0.212565 -4.14172e-33 -0.977147 -0.213067 -4.15097e-33 -0.977038 -0.257 -4.96091e-33 -0.966411 -0.256519 -4.95206e-33 -0.966539 -0.299949 -5.75228e-33 -0.953955 -0.300406 -5.7607e-33 -0.953811 -0.342766 -6.54074e-33 -0.939421 -0.3432 -6.54873e-33 -0.939263 -0.385292 -7.32339e-33 -0.922795 -0.384881 -7.31583e-33 -0.922966 -0.42621 -8.07596e-33 -0.904624 -0.426597 -8.08307e-33 -0.904442 -0.466667 -8.81958e-33 -0.884433 -0.467031 -8.82626e-33 -0.884241 -0.50651 -9.5514e-33 -0.862234 -0.506171 -9.54517e-33 -0.862433 -0.544639 -1.02512e-32 -0.83867 -0.544955 -1.0257e-32 -0.838465 -0.581994 -1.09363e-32 -0.813193 -0.582286 -1.09417e-32 -0.812984 -0.618428 -1.1604e-32 -0.785841 -0.618159 -1.15991e-32 -0.786053 -0.653307 -1.22427e-32 -0.757093 -0.65306 -1.22381e-32 -0.757306 -0.686626 -1.28522e-32 -0.727011 -0.68685 -1.28563e-32 -0.726799 -0.718789 -1.34399e-32 -0.695229 -0.718991 -1.34436e-32 -0.69502 -0.749663 -1.40035e-32 -0.66182 -0.749481 -1.40002e-32 -0.662026 -0.778642 -1.45318e-32 -0.627469 -0.778803 -1.45348e-32 -0.627269 -0.80621 -1.50338e-32 -0.591629 -0.806352 -1.50363e-32 -0.591436 -0.832254 -1.55072e-32 -0.554395 -0.83213 -1.55049e-32 -0.554581 -0.856349 -1.59444e-32 -0.516398 -0.856455 -1.59464e-32 -0.516222 -0.878817 -1.63513e-32 -0.477159 -0.878907 -1.6353e-32 -0.476993 -0.899563 -1.67262e-32 -0.43679 -0.899489 -1.67248e-32 -0.436944 -0.918321 -1.70641e-32 -0.395837 -0.918382 -1.70652e-32 -0.395695 -0.935276 -1.73685e-32 -0.35392 -0.935324 -1.73693e-32 -0.353792 -0.950356 -1.7638e-32 -0.311166 -0.950318 -1.76373e-32 -0.311279 -0.963418 -1.78702e-32 -0.268003 -0.963446 -1.78707e-32 -0.267904 -0.974548 -1.80664e-32 -0.224178 -0.974567 -1.80668e-32 -0.224095 -0.983698 -1.8226e-32 -0.179828 -0.983686 -1.82258e-32 -0.179895 -0.990812 -1.83479e-32 -0.135244 -0.990819 -1.8348e-32 -0.135193 -0.995913 -1.84324e-32 -0.0903164 -0.995916 -1.84325e-32 -0.0902827 -0.998979 -1.84793e-32 -0.0451872 -0.998978 -1.84793e-32 -0.0452043 -1 -1.84884e-32 1.74846e-07 -1 -1.84884e-32 -3.01992e-07 0.999717 1.84884e-32 0.0237976 0.997702 1.84606e-32 0.0677521 0.997619 1.84594e-32 0.0689652 0.993622 1.83949e-32 0.112767 0.993482 1.83926e-32 0.113992 0.987313 1.82883e-32 0.158785 0.987511 1.82917e-32 0.157551 0.979383 1.8151e-32 0.202013 0.979126 1.81466e-32 0.203253 0.969254 1.79733e-32 0.246062 0.968937 1.79677e-32 0.247307 0.956767 1.77522e-32 0.290854 0.957145 1.77589e-32 0.289609 0.943081 1.75081e-32 0.332564 0.942642 1.75003e-32 0.333807 0.92709 1.72217e-32 0.374839 0.926588 1.72127e-32 0.376077 0.908641 1.68898e-32 0.417579 0.909205 1.69e-32 0.416349 0.889462 1.65438e-32 0.457009 0.888835 1.65325e-32 0.458227 0.867903 1.61538e-32 0.496734 0.867213 1.61413e-32 0.497937 0.843817 1.57171e-32 0.53663 0.84457 1.57308e-32 0.535445 0.819512 1.52757e-32 0.573062 0.818697 1.52608e-32 0.574226 0.79278 1.47893e-32 0.609508 0.791902 1.47733e-32 0.610648 0.763489 1.42556e-32 0.645821 0.764428 1.42728e-32 0.644709 0.734514 1.37271e-32 0.678593 0.733514 1.37088e-32 0.679674 0.7031 1.31533e-32 0.711091 0.70204 1.31339e-32 0.712137 0.669131 1.25322e-32 0.743145 0.670249 1.25527e-32 0.742136 0.63603 1.19264e-32 0.771664 0.634853 1.19048e-32 0.772633 0.600511 1.12758e-32 0.799617 0.599278 1.12532e-32 0.800541 0.562477 1.05785e-32 0.826813 0.563765 1.06021e-32 0.825936 0.525867 9.90675e-33 0.850567 0.524526 9.88214e-33 0.851394 0.486895 9.19117e-33 0.873461 0.485503 9.16562e-33 0.874235 0.445488 8.43035e-33 0.895288 0.446928 8.45683e-33 0.89457 0.406048 7.7052e-33 0.913852 0.404561 7.67785e-33 0.914511 0.364339 6.93783e-33 0.931266 0.362808 6.90965e-33 0.931864 0.320312 6.12733e-33 0.947312 0.321885 6.15629e-33 0.946779 0.278774 5.36217e-33 0.960357 0.277162 5.33248e-33 0.960823 0.235093 4.5571e-33 0.971973 0.233445 4.52672e-33 0.97237 0.189251 3.71171e-33 0.981929 0.190932 3.74272e-33 0.981603 0.146381 2.92069e-33 0.989228 0.14467 2.88911e-33 0.98948 0.101531 2.0927e-33 0.994832 0.0997934 2.06061e-33 0.995008 0.0547125 1.22789e-33 0.998502 0.0564733 1.26042e-33 0.998404 0.0113005 4.25582e-34 0.999936 0.00951984 3.92664e-34 0.999955 -0.0338955 -4.10132e-34 0.999425 -0.0356923 -4.43367e-34 0.999363 -0.0808315 -1.27849e-33 0.996728 -0.0790224 -1.24501e-33 0.996873 -0.123988 -2.07734e-33 0.992284 -0.125805 -2.111e-33 0.992055 -0.1687 -2.90543e-33 0.985667 -0.170522 -2.9392e-33 0.985354 -0.21489 -3.76138e-33 0.976638 -0.213067 -3.72759e-33 0.977038 -0.256999 -4.54213e-33 0.966412 -0.258819 -4.57588e-33 0.965926 -0.300406 -5.34739e-33 0.953811 -0.302219 -5.38102e-33 0.953239 -0.345 -6.17515e-33 0.938603 -0.3432 -6.14172e-33 0.939262 -0.385292 -6.92351e-33 0.922795 -0.387077 -6.95667e-33 0.922047 -0.426597 -7.69115e-33 0.904442 -0.428362 -7.72396e-33 0.903607 -0.468771 -8.47546e-33 0.88332 -0.467031 -8.44308e-33 0.884241 -0.50651 -9.17777e-33 0.862234 -0.508222 -9.20963e-33 0.861226 -0.544955 -9.8937e-33 0.838465 -0.546634 -9.92497e-33 0.837372 -0.583928 -1.062e-32 0.811806 -0.582286 -1.05894e-32 0.812984 -0.618428 -1.12635e-32 0.785841 -0.620028 -1.12934e-32 0.78458 -0.653307 -1.19146e-32 0.757093 -0.654861 -1.19436e-32 0.75575 -0.688355 -1.25694e-32 0.725374 -0.68685 -1.25413e-32 0.726799 -0.718991 -1.31424e-32 0.69502 -0.720441 -1.31696e-32 0.693516 -0.749663 -1.37167e-32 0.66182 -0.751055 -1.37428e-32 0.66024 -0.780133 -1.42879e-32 0.625614 -0.778803 -1.42629e-32 0.627269 -0.806352 -1.478e-32 0.591436 -0.807616 -1.48038e-32 0.589709 -0.832254 -1.52669e-32 0.554395 -0.833448 -1.52894e-32 0.552598 -0.857576 -1.57438e-32 0.514358 -0.856455 -1.57227e-32 0.516222 -0.878907 -1.61463e-32 0.476993 -0.87995 -1.6166e-32 0.475066 -0.899563 -1.65369e-32 0.43679 -0.900526 -1.65551e-32 0.434803 -0.91926 -1.69104e-32 0.39365 -0.918382 -1.68937e-32 0.395695 -0.935324 -1.7216e-32 0.353792 -0.936115 -1.72311e-32 0.351693 -0.950356 -1.75032e-32 0.311166 -0.951057 -1.75166e-32 0.309017 -0.963963 -1.77645e-32 0.266037 -0.963446 -1.77546e-32 0.267904 -0.974567 -1.79697e-32 0.224095 -0.974928 -1.79767e-32 0.222521 -0.983698 -1.81481e-32 0.179827 -0.98393 -1.81526e-32 0.178557 -0.99095 -1.8292e-32 0.134233 -0.990819 -1.82894e-32 0.135193 -0.995916 -1.83934e-32 0.0902824 -0.995974 -1.83946e-32 0.0896393 -0.998979 -1.84598e-32 0.0451874 -0.998993 -1.84601e-32 0.0448648 -0.849718 0.156434 -0.503496 -0.83213 -1.74846e-07 -0.55458 -0.752404 0.156434 -0.639857 -0.941166 0.309017 0.136803 -0.977417 0.156434 0.142072 -0.950748 0.309017 -0.0242233 -0.899488 -1.74846e-07 -0.436945 -0.922586 0.156434 -0.352651 0.302157 0.707107 0.639297 0.157747 0.809017 0.566222 0.25117 0.809017 0.531418 -0.974928 -1.74846e-07 0.222521 -0.98393 -1.74846e-07 0.178557 -0.99095 -1.74846e-07 0.134233 -0.150245 0.587785 -0.794943 -0.28243 0.587785 -0.758117 -0.311053 0.453991 -0.834948 -0.963418 -1.74846e-07 -0.268003 -0.950318 -1.74846e-07 -0.31128 -0.939347 0.156434 0.305213 -0.963963 -1.74846e-07 0.266037 -0.119169 0.987688 -0.101343 -0.100328 0.987688 -0.120025 -8.37902e-09 1 -8.48498e-09 -0.205197 0.809017 -0.550804 -0.295332 0.809017 -0.508203 -0.355285 0.707107 -0.611369 -0.40649 0.587785 -0.699482 -0.246853 0.707107 -0.662619 -0.951056 -1.74846e-07 0.309017 -0.987368 0.156434 -0.0251558 -0.995974 -1.74846e-07 0.0896394 -0.998993 -1.74846e-07 0.0448649 -0.904509 0.309017 0.293892 -0.146123 0.987688 -0.0558544 -1.08735e-08 1 -4.89588e-09 -1.10875e-08 1 -4.38984e-09 -0.131319 0.707107 -0.694806 -1.19164e-08 1 4.49453e-10 -1.18831e-08 1 9.97845e-10 -0.154808 0.987688 0.022502 -0.153461 0.987688 -0.030356 -0.156384 0.987688 -0.00398429 -0.308917 0.951056 -0.00787062 -1.14989e-08 1 3.15869e-09 -0.148778 0.987688 0.0483409 -1.16322e-08 1 2.6257e-09 -1.17408e-08 1 2.08713e-09 -1.18245e-08 1 1.54413e-09 -1.13412e-08 1 3.68499e-09 -0.305804 0.951056 0.0444499 -1.18647e-08 1 -1.1968e-09 -1.1797e-08 1 -1.74202e-09 -1.19072e-08 1 -6.4904e-10 -0.303143 0.951056 -0.0599645 -0.288649 0.951056 -0.110334 -1.14444e-08 1 -3.35091e-09 -0.424067 0.891006 -0.162096 -0.390573 0.891006 -0.231432 -0.26585 0.951056 -0.157528 -0.235404 0.951056 -0.200191 -0.345842 0.891006 -0.29411 -0.505677 0.809017 -0.299636 -0.447765 0.809017 -0.380786 -0.60833 0.707107 -0.360463 -0.696005 0.587785 -0.412414 -0.538662 0.707107 -0.458087 -0.134582 0.987688 -0.0797459 -1.06365e-08 1 -5.39152e-09 -0.453497 0.707107 -0.542532 -0.376971 0.809017 -0.450982 -9.79211e-09 1 -6.80569e-09 -1.00952e-08 1 -6.34744e-09 -0.198185 0.951056 -0.237095 -0.109159 0.809017 -0.57756 -0.00998098 0.809017 -0.5877 -0.0120071 0.707107 -0.707005 -0.80621 -1.74846e-07 -0.59163 -0.778642 -1.74846e-07 -0.627469 -0.718788 -1.74846e-07 -0.695229 -0.686626 -1.74846e-07 -0.727011 -0.633445 0.156434 -0.75781 -0.107879 0.951056 -0.289575 -0.155265 0.951056 -0.267178 -0.228107 0.891006 -0.392523 0.0894843 0.809017 -0.580934 0.10765 0.707107 -0.698864 0.186375 0.809017 -0.557454 -2.13629e-09 1 -1.1732e-08 -0.0290519 0.987688 -0.153713 -1.59364e-09 1 -1.18179e-08 0.22421 0.707107 -0.670619 0.277905 0.809017 -0.517938 -0.013738 0.587785 -0.8089 0.123165 0.587785 -0.799587 0.421268 0.453991 -0.785128 0.497479 0.587785 -0.637984 0.382503 0.587785 -0.712881 0.33432 0.707107 -0.623081 0.434812 0.707107 -0.557618 -0.256519 -1.74846e-07 -0.966539 -0.212565 -1.74846e-07 -0.977147 -0.183427 0.156434 -0.970507 2.77166e-09 1 -1.15983e-08 0.0238156 0.987688 -0.154611 0.0496024 0.987688 -0.148362 -0.0167716 0.156434 -0.987546 -0.123444 -1.74846e-07 -0.992351 -0.078459 -1.74846e-07 -0.996917 0.19002 0.951056 -0.243688 0.214647 0.891006 -0.400043 0.279167 0.891006 -0.358013 0.522796 0.707107 -0.476114 0.495211 0.809017 -0.316635 0.434576 0.809017 -0.395771 0.0739622 0.987688 -0.137845 6.3051e-09 1 -1.01217e-08 5.8322e-09 1 -1.04014e-08 0.150365 0.156434 -0.976175 0.191588 -1.74846e-07 -0.981475 0.235759 -1.74846e-07 -0.971812 0.598143 0.587785 -0.544732 0.541599 0.809017 -0.228389 0.651545 0.707107 -0.274753 0.572407 0.809017 -0.133573 0.745447 0.587785 -0.314351 0.688607 0.707107 -0.160689 0.131797 0.987688 -0.0842699 1.04257e-08 1 -5.78858e-09 1.0148e-08 1 -6.26264e-09 0.313177 0.156434 -0.936722 0.365025 -1.74846e-07 -0.930998 0.406737 -1.74846e-07 -0.913545 0.78785 0.587785 -0.183848 0.586747 0.809017 -0.0349148 0.804093 0.587785 0.0891182 0.67953 0.707107 0.195546 0.702803 0.707107 0.0778924 0.91008 0.156434 -0.383775 0.832131 0.156434 -0.532059 0.889924 -1.74846e-07 -0.45611 0.564862 0.809017 0.162548 0.584208 0.809017 0.0647482 0.885584 0.453991 0.0981499 0.777466 0.587785 0.223729 0.529266 0.809017 0.255673 0.636708 0.707107 0.307575 0.658522 0.587785 0.469954 0.728473 0.587785 0.351903 0.8023 0.453991 0.387567 0.57557 0.707107 0.410755 0.72526 0.453991 0.517581 0.569628 0.587785 0.574485 0.155483 0.987688 0.0172323 0.150334 0.987688 0.043261 1.17205e-08 1 2.19829e-09 0.987688 -1.74846e-07 -0.156434 0.99375 -1.74846e-07 -0.111627 0.985944 0.156434 -0.0586693 0.451228 0.891006 0.0500099 0.296966 0.951056 0.0854568 0.307137 0.951056 0.0340402 0.337367 0.809017 0.481326 0.413859 0.809017 0.417388 0.497873 0.707107 0.502118 1.04082e-08 1 5.82005e-09 1.06667e-08 1 5.33154e-09 0.14086 0.987688 0.0680453 0.405853 0.707107 0.579036 0.345705 0.587785 0.731434 0.380741 0.453991 0.805561 0.21712 0.587785 0.779338 0.18977 0.707107 0.681166 0.0822878 0.587785 0.804821 0.239123 0.453991 0.85832 0.0897876 0.987688 0.128101 7.59174e-09 1 9.1961e-09 0.110145 0.987688 0.111085 0.803957 0.156434 0.573743 0.867213 -1.74846e-07 0.497937 0.843818 -1.74846e-07 0.53663 5.76637e-09 1 1.0438e-08 6.24382e-09 1 1.01596e-08 -0.16653 0.707107 0.687217 -0.0479943 0.707107 0.705476 -0.0549113 0.587785 0.807151 0.763489 -1.74846e-07 0.645821 0.791902 -1.74846e-07 0.610648 0.0159115 0.987688 0.155623 2.1379e-09 1 1.17317e-08 0.0419831 0.987688 0.150696 -0.0604763 0.453991 0.888952 -0.190531 0.587785 0.786261 -6.14148e-11 1 1.19247e-08 4.91181e-10 1 1.19148e-08 0.634853 -1.74846e-07 0.772633 0.599278 -1.74846e-07 0.800541 0.566896 0.156434 0.8088 -0.320669 0.587785 0.742752 -0.353167 0.453991 0.818026 -0.441582 0.587785 0.677874 0.422054 0.156434 0.892972 0.524526 -1.74846e-07 0.851394 0.485503 -1.74846e-07 0.874235 0.100461 0.156434 0.982566 0.00951983 -1.74846e-07 0.999955 -0.0670385 0.156434 0.985411 0.26507 0.156434 0.951455 0.362808 -1.74846e-07 0.931864 0.320312 -1.74846e-07 0.947312 -0.320828 0.809017 0.492505 -0.23298 0.809017 0.53964 -0.280275 0.707107 0.649189 -0.0727763 0.951056 0.300325 -0.122485 0.951056 0.283706 -0.0620057 0.987688 0.143621 -0.486334 0.453991 0.746573 -0.549792 0.587785 0.593496 -0.399447 0.809017 0.4312 -0.385957 0.707107 0.592484 -0.0209743 0.951056 0.308304 -0.0308142 0.891006 0.452944 0.189251 -1.74846e-07 0.981929 0.14467 -1.74846e-07 0.98948 -5.3864e-09 1 1.06391e-08 -4.88766e-09 1 1.08772e-08 -0.642185 0.587785 0.492044 -0.60551 0.453991 0.653644 0.0547125 -1.74846e-07 0.998502 -5.87358e-09 1 1.0378e-08 -0.0356923 -1.74846e-07 0.999363 -0.56129 0.707107 0.430062 -0.625897 0.707107 0.329018 -6.80905e-09 1 9.78977e-09 -0.0853859 0.987688 0.131076 -7.25535e-09 1 9.46376e-09 -0.707267 0.453991 0.54191 -0.716103 0.587785 0.376437 -0.170522 -1.74846e-07 0.985354 -0.232609 0.156434 0.959907 -0.125805 -1.74846e-07 0.992055 -0.520279 0.809017 0.273497 -0.466574 0.809017 0.357491 -0.539105 0.156434 0.827583 -0.620028 -1.74846e-07 0.78458 -0.671213 0.156434 0.72457 -0.936115 -1.74846e-07 0.351693 -0.387077 -1.74846e-07 0.922047 -0.391489 0.156434 0.906788 -0.345 -1.74846e-07 0.938603 -0.302219 -1.74846e-07 0.953239 -0.784011 0.156434 0.600712 -0.720441 -1.74846e-07 0.693516 -0.91926 -1.74846e-07 0.39365 -0.468771 -1.74846e-07 0.88332 -0.508222 -1.74846e-07 0.861226 -0.874255 0.156434 0.459573 -0.900526 -1.74846e-07 0.434803 -0.87995 -1.74846e-07 0.475066 -0.84183 0.309017 0.442528 -0.847398 0.453991 0.275336 -0.654861 -1.74846e-07 0.75575 -0.807616 -1.74846e-07 0.589709 -0.833448 -1.74846e-07 0.552598 -0.857576 -1.74846e-07 0.514358 -0.751055 -1.74846e-07 0.66024 -0.688355 -1.74846e-07 0.725374 -0.788677 0.453991 0.414587 -0.583928 -1.74846e-07 0.811806 -0.10631 0.987688 0.114761 -0.769421 0.587785 0.25 -0.672498 0.707107 0.218508 -0.210002 0.951056 0.226695 -0.168669 0.951056 0.258925 -0.2478 0.891006 0.380398 -0.245293 0.951056 0.187944 -0.124175 0.987688 0.0951435 -0.559017 0.809017 0.181636 -8.8756e-09 1 7.96408e-09 -0.431771 0.891006 0.140291 -0.401851 0.891006 0.211242 -9.8938e-09 1 6.65699e-09 -9.57472e-09 1 7.10827e-09 -1.01916e-08 1 6.19141e-09 -0.293893 0.951056 0.0954915 -0.273527 0.951056 0.143786 -0.138468 0.987688 0.0727892 -1.09514e-08 1 4.71903e-09 -1.0721e-08 1 5.22139e-09 -1.11583e-08 1 4.20653e-09 -0.480535 0.707107 0.518735 0.233445 -1.74846e-07 0.97237 -0.0106179 0.987688 0.156074 -0.0368417 0.987688 0.152034 -1.71366e-09 1 1.18011e-08 -1.16502e-09 1 1.18678e-08 -0.20984 0.453991 0.865944 -0.138429 0.809017 0.571252 1.04272e-09 1 1.18792e-08 -0.0398954 0.809017 0.58643 0.69543 0.156434 0.70136 0.669131 -1.74846e-07 0.743145 0.0829323 0.951056 0.297681 0.0314311 0.951056 0.307415 0.132048 0.951056 0.279383 0.193997 0.891006 0.410454 0.0597856 0.809017 0.584737 0.0719222 0.707107 0.703439 0.733514 -1.74846e-07 0.679674 4.77536e-09 1 1.0927e-08 0.0668469 0.987688 0.141433 4.26394e-09 1 1.11365e-08 0.0906272 0.453991 0.886386 6.70786e-09 1 9.85938e-09 0.926588 -1.74846e-07 0.376077 0.889356 0.156434 0.429621 0.942641 -1.74846e-07 0.333807 0.820995 0.453991 -0.346209 0.177364 0.951056 0.253048 0.217578 0.951056 0.219434 0.369539 0.891006 0.263721 0.251533 0.951056 0.179506 0.979126 -1.74846e-07 0.203253 0.981678 0.156434 0.1088 0.987313 -1.74846e-07 0.158785 0.968937 -1.74846e-07 0.247307 0.94917 0.156434 0.273139 0.127334 0.987688 0.090872 9.15688e-09 1 7.639e-09 9.501e-09 1 7.20651e-09 0.997619 -1.74846e-07 0.068965 0.999717 -1.74846e-07 0.0237977 0.511405 0.453991 0.729629 0.464346 0.587785 0.662489 1.01273e-08 1 6.29606e-09 0.627356 0.453991 0.632706 0.999771 -1.74846e-07 -0.0214183 1.11144e-08 1 4.32124e-09 0.478444 0.809017 0.341441 0.278252 0.951056 0.134415 0.943433 -1.74846e-07 -0.331562 0.957457 -1.74846e-07 -0.288576 0.961847 0.156434 -0.224451 1.18098e-08 1 1.65286e-09 0.868395 -1.74846e-07 -0.495872 0.909632 -1.74846e-07 -0.415415 1.19122e-08 1 -5.49265e-10 0.156158 0.987688 -0.0092923 1.19249e-08 1 4.83301e-16 1.19121e-08 1 5.52538e-10 0.793353 -1.74846e-07 -0.608761 0.820061 -1.74846e-07 -0.572276 0.856258 0.453991 0.246403 0.300932 0.951056 -0.0702237 0.284736 0.951056 -0.120071 0.418318 0.891006 -0.176402 0.152342 0.987688 -0.0355495 1.18111e-08 1 -1.64313e-09 0.308471 0.951056 -0.0183558 0.730243 0.156434 -0.665037 0.765024 -1.74846e-07 -0.644002 0.705858 0.707107 -0.0420025 0.670897 -1.74846e-07 -0.74155 0.703733 -1.74846e-07 -0.710464 1.131e-08 1 -3.77987e-09 1.11239e-08 1 -4.2968e-09 0.144143 0.987688 -0.060784 0.607347 0.156434 -0.778882 0.526551 -1.74846e-07 -0.850143 0.564443 -1.74846e-07 -0.825472 0.807588 0.587785 -0.0480561 0.889433 0.453991 -0.0529263 1.06813e-08 1 -5.30222e-09 0.447617 -1.74846e-07 -0.894225 0.466979 0.156434 -0.870321 0.867695 0.453991 -0.20248 0.22847 0.951056 -0.208069 0.115659 0.987688 -0.105332 0.681599 0.587785 -0.435811 0.279448 -1.74846e-07 -0.960161 0.260348 0.951056 -0.166465 8.05326e-09 1 -8.79475e-09 0.0961944 0.987688 -0.123363 0.59574 0.707107 -0.380912 0.750676 0.453991 -0.479978 0.146103 0.951056 -0.272297 0.0570889 -1.74846e-07 -0.998369 0.102161 -1.74846e-07 -0.994768 6.76461e-09 1 -9.82053e-09 0.658761 0.453991 -0.599938 0.36144 0.809017 -0.463522 3.82721e-09 1 -1.1294e-08 4.34336e-09 1 -1.11058e-08 0.547896 0.453991 -0.70264 -0.299949 -1.74846e-07 -0.953955 -0.00524732 0.951056 -0.308973 -0.00770907 0.891006 -0.453925 0.0470447 0.951056 -0.305415 -0.344804 0.156434 -0.925548 -0.42621 -1.74846e-07 -0.904624 -0.384881 -1.74846e-07 -0.922966 0.256524 0.587785 -0.76727 1.14709e-09 1 -1.18696e-08 5.99157e-10 1 -1.19098e-08 -0.00265636 0.987688 -0.156412 -0.466667 -1.74846e-07 -0.884433 -0.496263 0.156434 -0.853962 0.282521 0.453991 -0.845029 4.9949e-11 1 -1.19248e-08 -0.544639 -1.74846e-07 -0.838671 -0.581994 -1.74846e-07 -0.813193 0.0691156 0.891006 -0.448699 0.135647 0.453991 -0.880621 -3.20684e-09 1 -1.14856e-08 -0.0546117 0.987688 -0.146592 -0.0151299 0.453991 -0.890878 -0.0786004 0.987688 -0.135254 -4.75885e-09 1 -1.09342e-08 -5.25743e-09 1 -1.07034e-08 -0.165471 0.453991 -0.875507 -5.74486e-09 1 -1.04499e-08 -0.878817 -1.74846e-07 -0.477159 -7.12994e-09 1 -9.55859e-09 -6.6821e-09 1 -9.87685e-09 -0.918321 -1.74846e-07 -0.395837 -7.56265e-09 1 -9.22004e-09 -0.447685 0.453991 -0.77037 -0.571439 0.453991 -0.68363 -0.518856 0.587785 -0.620723 -0.983686 -1.74846e-07 -0.179895 -0.968914 0.156434 -0.19166 -0.990812 -1.74846e-07 -0.135244 -0.678753 0.453991 -0.577223 -0.616295 0.587785 -0.524108 -0.995913 -1.74846e-07 -0.0903165 -0.998978 -1.74846e-07 -0.0452044 -0.766541 0.453991 -0.45421 -0.793639 0.587785 -0.156989 -0.890718 0.453991 -0.0226934 -0.87407 0.453991 -0.172899 -1 -1.74846e-07 4.6894e-08 -0.780133 -1.74846e-07 0.625614 -0.546634 -1.74846e-07 0.837372 -0.754933 0.309017 0.578433 -0.21489 -1.74846e-07 0.976638 -0.36037 0.891006 0.276117 -1.04676e-08 1 5.71254e-09 -0.428362 -1.74846e-07 0.903607 -0.646319 0.309017 0.697697 -0.308523 0.891006 0.333048 -7.68605e-09 1 9.11742e-09 -8.49705e-09 1 8.36677e-09 -9.23508e-09 1 7.54428e-09 -0.258819 -1.74846e-07 0.965926 -0.519111 0.309017 0.796889 -3.85977e-09 1 1.12829e-08 -8.10025e-09 1 8.7515e-09 -0.0808315 -1.74846e-07 0.996728 -0.376969 0.309017 0.873157 -0.179948 0.891006 0.416805 -6.34813e-09 1 1.00948e-08 0.0997934 -1.74846e-07 0.995008 -0.223982 0.309017 0.924305 0.445488 -1.74846e-07 0.895288 -0.106919 0.891006 0.441221 -2.25863e-09 1 1.1709e-08 -3.33283e-09 1 1.14497e-08 -4.37842e-09 1 1.1092e-08 0.277162 -1.74846e-07 0.960823 -0.064552 0.309017 0.948863 -2.79874e-09 1 1.15918e-08 0.404561 -1.74846e-07 0.914511 0.0967351 0.309017 0.946124 0.0461769 0.891006 0.451636 -6.13878e-10 1 1.19091e-08 0.562477 -1.74846e-07 0.826813 0.255239 0.309017 0.916167 0.12184 0.891006 0.437336 3.74335e-09 1 1.13221e-08 2.67919e-09 1 1.162e-08 1.59202e-09 1 1.18181e-08 0.70204 -1.74846e-07 0.712137 0.406401 0.309017 0.859853 0.908641 -1.74846e-07 0.417579 3.21472e-09 1 1.14834e-08 0.818697 -1.74846e-07 0.574226 0.545871 0.309017 0.778803 0.260574 0.891006 0.371765 5.27653e-09 1 1.0694e-08 0.888835 -1.74846e-07 0.458227 0.669637 0.309017 0.675348 0.319654 0.891006 0.32238 8.7931e-09 1 8.05507e-09 8.00968e-09 1 8.83446e-09 7.15748e-09 1 9.53799e-09 0.956767 -1.74846e-07 0.290854 0.77414 0.309017 0.552464 8.41042e-09 1 8.45385e-09 0.993482 -1.74846e-07 0.113991 0.856371 0.309017 0.413687 0.969523 -1.74846e-07 -0.245 0.408792 0.891006 0.197475 9.82471e-09 1 6.75854e-09 0.99778 -1.74846e-07 -0.0665905 0.913967 0.309017 0.263009 0.436286 0.891006 0.125548 1.16061e-08 1 2.739e-09 1.13027e-08 1 3.80161e-09 1.09022e-08 1 4.83158e-09 0.979607 -1.74846e-07 -0.200923 0.945269 0.309017 0.104765 1.14667e-08 1 3.27382e-09 0.927481 -1.74846e-07 -0.373871 0.949377 0.309017 -0.0564933 0.453189 0.891006 -0.0269673 1.18737e-08 1 1.10389e-09 0.845092 -1.74846e-07 -0.534621 0.926174 0.309017 -0.216126 0.601181 -1.74846e-07 -0.799113 0.442113 0.891006 -0.103169 1.14721e-08 1 -3.25492e-09 1.17229e-08 1 -2.18541e-09 1.18743e-08 1 -1.09736e-09 0.73513 -1.74846e-07 -0.677926 0.876326 0.309017 -0.369542 9.52864e-09 1 -7.16992e-09 1.16098e-08 1 -2.72306e-09 0.63669 -1.74846e-07 -0.77112 0.801268 0.309017 -0.512326 0.382489 0.891006 -0.244561 1.09141e-08 1 -4.80461e-09 0.487583 -1.74846e-07 -0.873077 0.703159 0.309017 -0.640371 0.335656 0.891006 -0.305684 8.44981e-09 1 -8.41448e-09 9.18828e-09 1 -7.60121e-09 9.84878e-09 1 -6.72342e-09 0.322566 -1.74846e-07 -0.946547 0.584822 0.309017 -0.749995 -0.0333137 -1.74846e-07 -0.999445 4.85028e-09 1 -1.08939e-08 7.63963e-09 1 -9.15636e-09 8.82841e-09 1 -8.01635e-09 0.147025 -1.74846e-07 -0.989133 0.44966 0.309017 -0.838042 0.0979835 0.951056 -0.293071 7.20977e-09 1 -9.49852e-09 0.0118998 -1.74846e-07 -0.999929 0.301562 0.309017 -0.901981 0.143952 0.891006 -0.430564 5.34692e-09 1 -1.0659e-08 -0.168177 -1.74846e-07 -0.985757 0.144789 0.309017 -0.939971 -1.04761e-09 1 -1.18788e-08 2.2345e-09 1 -1.17137e-08 3.30294e-09 1 -1.14583e-08 -0.342765 -1.74846e-07 -0.939421 -0.0161496 0.309017 -0.950919 -0.65306 -1.74846e-07 -0.757306 -0.0573885 0.951056 -0.303641 1.69259e-09 1 -1.18041e-08 -0.506171 -1.74846e-07 -0.862433 -0.176624 0.309017 -0.934512 -0.084312 0.891006 -0.446093 -4.99365e-10 1 -1.19144e-08 -0.618159 -1.74846e-07 -0.786053 -0.332016 0.309017 -0.89122 -0.158489 0.891006 -0.425428 -3.73247e-09 1 -1.13257e-08 -2.6744e-09 1 -1.16211e-08 -0.749481 -1.74846e-07 -0.662026 -0.477858 0.309017 -0.82229 -4.25017e-09 1 -1.11418e-08 -0.856349 -1.74846e-07 -0.516397 -0.609952 0.309017 -0.729704 -0.291163 0.891006 -0.348327 -6.22008e-09 1 -1.01742e-08 -0.935276 -1.74846e-07 -0.35392 -0.724499 0.309017 -0.616125 -9.46824e-09 1 -7.2495e-09 -8.76095e-09 1 -8.09003e-09 -7.9793e-09 1 -8.86191e-09 -0.974548 -1.74846e-07 -0.224178 -0.818203 0.309017 -0.484822 -0.453843 0.891006 -0.0115631 -9.12428e-09 1 -7.67791e-09 -0.832277 0.453991 -0.318131 -0.888369 0.309017 -0.339571 -0.755692 0.587785 -0.288857 -0.660499 0.707107 -0.25247 -0.549042 0.809017 -0.209867 -1.03768e-08 1 -5.87571e-09 -0.932979 0.309017 -0.184552 -0.693666 0.707107 -0.137213 -0.576612 0.809017 -0.114059 -0.445361 0.891006 -0.0880965 -1.15866e-08 1 -2.82022e-09 -1.12779e-08 1 -3.87449e-09 -0.808755 0.587785 -0.0206051 -0.706877 0.707107 -0.0180099 -0.587594 0.809017 -0.0149705 -1.17042e-08 1 -2.28354e-09 -0.881741 0.453991 0.128165 -0.800604 0.587785 0.116371 -0.699753 0.707107 0.101712 -0.581672 0.809017 0.0845486 -0.449269 0.891006 0.0653033 -1.19245e-08 1 -9.98996e-11 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 0.942877 5.73921e-33 -0.33314 0.942877 5.73921e-33 -0.33314 0.985616 6.03819e-33 -0.169001 1 6.16347e-33 1.74846e-07 1 6.16346e-33 -3.01992e-07 0.985616 6.03819e-33 -0.169001 0.778036 4.65928e-33 -0.62822 0.660675 3.9094e-33 -0.750672 0.660675 3.9094e-33 -0.750672 0.778036 4.65928e-33 -0.62822 0.873014 5.27512e-33 -0.487695 0.873014 5.27512e-33 -0.487695 0.210679 1.08671e-33 -0.977555 0.210679 1.08671e-33 -0.977555 0.372856 2.09704e-33 -0.927889 0.372857 2.09705e-33 -0.927889 0.524307 3.04705e-33 -0.851529 0.524307 3.04705e-33 -0.851529 -0.292823 -2.01197e-33 -0.956167 -0.127018 -9.97781e-34 -0.9919 -0.292823 -2.01197e-33 -0.956167 0.0424415 4.51148e-35 -0.999099 0.042441 4.51119e-35 -0.999099 -0.127018 -9.97781e-34 -0.9919 -0.594633 -3.8392e-33 -0.803997 -0.721956 -4.59967e-33 -0.691939 -0.721956 -4.59967e-33 -0.691939 -0.450204 -2.96828e-33 -0.892926 -0.594633 -3.8392e-33 -0.803997 -0.450204 -2.96828e-33 -0.892926 -0.967733 -6.01918e-33 -0.251978 -0.967733 -6.01918e-33 -0.251978 -0.911228 -5.70557e-33 -0.411901 -0.911228 -5.70557e-33 -0.411901 -0.82851 -5.22782e-33 -0.559975 -0.82851 -5.22782e-33 -0.559975 -0.967733 -5.90999e-33 0.251978 -0.996397 -6.12289e-33 0.0848059 -0.967733 -5.90999e-33 0.251978 -0.996397 -6.15964e-33 -0.0848059 -0.996397 -6.15964e-33 -0.0848059 -0.996397 -6.12289e-33 0.0848059 -0.82851 -4.98516e-33 0.559975 -0.721956 -4.29983e-33 0.691939 -0.721956 -4.29983e-33 0.691939 -0.911228 -5.52708e-33 0.411901 -0.82851 -4.98516e-33 0.559975 -0.911229 -5.52708e-33 0.411901 -0.292823 -1.59763e-33 0.956167 -0.292823 -1.59763e-33 0.956167 -0.450204 -2.58135e-33 0.892926 -0.450204 -2.58135e-33 0.892926 -0.594633 -3.4908e-33 0.803997 -0.594633 -3.4908e-33 0.803997 0.210679 1.51032e-33 0.977555 0.0424412 4.78057e-34 0.999099 0.0424412 4.78057e-34 0.999099 -0.127018 -5.67957e-34 0.9919 -0.127018 -5.67957e-34 0.9919 0.372857 2.49913e-33 0.927889 0.210679 1.51032e-33 0.977555 0.372856 2.49913e-33 0.927889 0.524307 3.41605e-33 0.851529 0.660675 4.23469e-33 0.750672 0.524307 3.41605e-33 0.851529 0.778036 4.93151e-33 0.62822 0.660675 4.23469e-33 0.750672 0.778036 4.93151e-33 0.62822 0.873014 5.48646e-33 0.487695 0.942877 5.88357e-33 0.33314 0.873014 5.48646e-33 0.487695 0.985616 6.11143e-33 0.169001 0.942877 5.88357e-33 0.33314 0.985616 6.11143e-33 0.169001 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 6.16347e-33 -1 2.16667e-34 0.942877 5.73921e-33 -0.33314 0.942877 5.73921e-33 -0.33314 0.985616 6.03819e-33 -0.169001 1 6.16347e-33 1.74846e-07 1 6.16346e-33 -3.01992e-07 0.985616 6.03819e-33 -0.169001 0.778036 4.65928e-33 -0.62822 0.660675 3.9094e-33 -0.750672 0.660675 3.9094e-33 -0.750672 0.778036 4.65928e-33 -0.62822 0.873014 5.27512e-33 -0.487695 0.873014 5.27512e-33 -0.487695 0.210679 1.08671e-33 -0.977555 0.210679 1.08671e-33 -0.977555 0.372856 2.09704e-33 -0.927889 0.372857 2.09705e-33 -0.927889 0.524307 3.04705e-33 -0.851529 0.524307 3.04705e-33 -0.851529 -0.292823 -2.01197e-33 -0.956167 -0.127018 -9.97781e-34 -0.9919 -0.292823 -2.01197e-33 -0.956167 0.0424415 4.51148e-35 -0.999099 0.042441 4.51119e-35 -0.999099 -0.127018 -9.97781e-34 -0.9919 -0.594633 -3.8392e-33 -0.803997 -0.721956 -4.59967e-33 -0.691939 -0.721956 -4.59967e-33 -0.691939 -0.450204 -2.96828e-33 -0.892926 -0.594633 -3.8392e-33 -0.803997 -0.450204 -2.96828e-33 -0.892926 -0.967733 -6.01918e-33 -0.251978 -0.967733 -6.01918e-33 -0.251978 -0.911228 -5.70557e-33 -0.411901 -0.911228 -5.70557e-33 -0.411901 -0.82851 -5.22782e-33 -0.559975 -0.82851 -5.22782e-33 -0.559975 -0.967733 -5.90999e-33 0.251978 -0.996397 -6.12289e-33 0.0848059 -0.967733 -5.90999e-33 0.251978 -0.996397 -6.15964e-33 -0.0848059 -0.996397 -6.15964e-33 -0.0848059 -0.996397 -6.12289e-33 0.0848059 -0.82851 -4.98516e-33 0.559975 -0.721956 -4.29983e-33 0.691939 -0.721956 -4.29983e-33 0.691939 -0.911228 -5.52708e-33 0.411901 -0.82851 -4.98516e-33 0.559975 -0.911229 -5.52708e-33 0.411901 -0.292823 -1.59763e-33 0.956167 -0.292823 -1.59763e-33 0.956167 -0.450204 -2.58135e-33 0.892926 -0.450204 -2.58135e-33 0.892926 -0.594633 -3.4908e-33 0.803997 -0.594633 -3.4908e-33 0.803997 0.210679 1.51032e-33 0.977555 0.0424412 4.78057e-34 0.999099 0.0424412 4.78057e-34 0.999099 -0.127018 -5.67957e-34 0.9919 -0.127018 -5.67957e-34 0.9919 0.372857 2.49913e-33 0.927889 0.210679 1.51032e-33 0.977555 0.372856 2.49913e-33 0.927889 0.524307 3.41605e-33 0.851529 0.660675 4.23469e-33 0.750672 0.524307 3.41605e-33 0.851529 0.778036 4.93151e-33 0.62822 0.660675 4.23469e-33 0.750672 0.778036 4.93151e-33 0.62822 0.873014 5.48646e-33 0.487695 0.942877 5.88357e-33 0.33314 0.873014 5.48646e-33 0.487695 0.985616 6.11143e-33 0.169001 0.942877 5.88357e-33 0.33314 0.985616 6.11143e-33 0.169001 0.986361 6.04374e-33 -0.164595 1 6.16347e-33 -4.37114e-08 1 6.16347e-33 -4.37114e-08 0.789141 4.73076e-33 -0.614213 0.879474 5.31748e-33 -0.475947 0.879474 5.31748e-33 -0.475947 0.945817 5.75916e-33 -0.3247 0.945817 5.75916e-33 -0.3247 0.986361 6.04374e-33 -0.164595 0.546948 3.18971e-33 -0.837166 0.546948 3.18971e-33 -0.837166 0.401695 2.27742e-33 -0.915773 0.789141 4.73076e-33 -0.614213 0.677282 4.01499e-33 -0.735724 0.677282 4.01499e-33 -0.735724 0.0825793 2.93048e-34 -0.996584 -0.0825795 -7.24903e-34 -0.996584 0.0825793 2.93048e-34 -0.996584 0.245486 1.303e-33 -0.9694 0.245486 1.303e-33 -0.9694 0.401695 2.27742e-33 -0.915773 -0.546948 -3.55248e-33 -0.837166 -0.401695 -2.67425e-33 -0.915773 -0.401695 -2.67425e-33 -0.915773 -0.245486 -1.72308e-33 -0.9694 -0.0825795 -7.24903e-34 -0.996584 -0.245486 -1.72308e-33 -0.9694 -0.789141 -4.99692e-33 -0.614213 -0.677281 -4.33381e-33 -0.735724 -0.789141 -4.99692e-33 -0.614213 -0.546948 -3.55248e-33 -0.837166 -0.677281 -4.33381e-33 -0.735724 -0.879474 -5.52373e-33 -0.475947 -0.879474 -5.52373e-33 -0.475947 -0.945817 -5.89986e-33 -0.3247 -0.945817 -5.89986e-33 -0.3247 -0.986361 -6.11507e-33 -0.164595 -0.986361 -6.11507e-33 -0.164595 -1 -6.16347e-33 1.19249e-08 -1 -6.16347e-33 1.19249e-08 1 6.16347e-33 2.63678e-16 1 6.16347e-33 2.63678e-16 1 6.16347e-33 2.63678e-16 1 6.16347e-33 2.63678e-16 -1 -6.16347e-33 -2.63678e-16 -1 -6.16347e-33 -2.63678e-16 -1 -6.16347e-33 -2.63678e-16 -1 -6.16347e-33 -2.63678e-16 -0.986361 -6.04374e-33 0.164595 -1 -6.16347e-33 4.37114e-08 -1 -6.16347e-33 4.37114e-08 -0.789141 -4.73076e-33 0.614213 -0.879474 -5.31748e-33 0.475947 -0.879474 -5.31748e-33 0.475947 -0.945817 -5.75916e-33 0.3247 -0.945817 -5.75916e-33 0.3247 -0.986361 -6.04374e-33 0.164595 -0.546948 -3.18971e-33 0.837166 -0.546948 -3.18971e-33 0.837166 -0.401695 -2.27742e-33 0.915773 -0.789141 -4.73076e-33 0.614213 -0.677282 -4.01499e-33 0.735724 -0.677282 -4.01499e-33 0.735724 -0.0825793 -2.93048e-34 0.996584 0.0825795 7.24903e-34 0.996584 -0.0825793 -2.93048e-34 0.996584 -0.245486 -1.303e-33 0.9694 -0.245486 -1.303e-33 0.9694 -0.401695 -2.27742e-33 0.915773 0.546948 3.55248e-33 0.837166 0.401695 2.67425e-33 0.915773 0.401695 2.67425e-33 0.915773 0.245486 1.72308e-33 0.9694 0.0825795 7.24903e-34 0.996584 0.245486 1.72308e-33 0.9694 0.789141 4.99692e-33 0.614213 0.677281 4.33381e-33 0.735724 0.789141 4.99692e-33 0.614213 0.546948 3.55248e-33 0.837166 0.677281 4.33381e-33 0.735724 0.879474 5.52373e-33 0.475947 0.879474 5.52373e-33 0.475947 0.945817 5.89986e-33 0.3247 0.945817 5.89986e-33 0.3247 0.986361 6.11507e-33 0.164595 0.986361 6.11507e-33 0.164595 1 6.16347e-33 -1.19249e-08 1 6.16347e-33 -1.19249e-08 4.37114e-08 2.16668e-34 1 -0.0448649 -6.13033e-34 0.998993 4.37114e-08 2.16668e-34 1 0.99958 1.84744e-32 -0.0289691 0.999289 1.84671e-32 -0.0377013 0.998993 1.84601e-32 -0.0448647 -0.0896393 -1.4415e-33 0.995974 -0.0448648 -6.13031e-34 0.998993 -0.0896393 -1.4415e-33 0.995974 -0.134233 -2.26706e-33 0.99095 -0.134233 -2.26706e-33 0.99095 -0.178557 -3.08805e-33 0.98393 -0.222521 -3.90283e-33 0.974928 -0.178557 -3.08805e-33 0.98393 -0.222521 -3.90283e-33 0.974928 -0.266037 -4.70975e-33 0.963963 -0.266037 -4.70975e-33 0.963963 -0.309017 -5.50718e-33 0.951056 -0.351375 -6.29352e-33 0.936235 -0.309017 -5.50718e-33 0.951057 -0.351375 -6.29352e-33 0.936235 -0.393025 -7.06719e-33 0.919528 -0.393025 -7.06719e-33 0.919528 -0.433884 -7.82662e-33 0.900969 -0.473869 -8.5703e-33 0.880596 -0.433884 -7.82662e-33 0.900969 -0.473869 -8.57029e-33 0.880596 -0.512899 -9.29671e-33 0.858449 -0.512899 -9.29671e-33 0.858449 -0.550897 -1.00044e-32 0.834573 -0.587785 -1.06919e-32 0.809017 -0.550897 -1.00044e-32 0.834573 -0.587785 -1.06919e-32 0.809017 -0.62349 -1.1358e-32 0.781832 -0.62349 -1.1358e-32 0.781832 -0.657939 -1.20011e-32 0.753071 -0.691063 -1.26201e-32 0.722795 -0.657939 -1.20011e-32 0.753071 -0.691063 -1.26201e-32 0.722795 -0.722795 -1.32136e-32 0.691063 -0.722795 -1.32136e-32 0.691063 -0.753071 -1.37806e-32 0.657939 -0.781831 -1.43198e-32 0.62349 -0.753071 -1.37806e-32 0.657939 -0.781831 -1.43198e-32 0.62349 -0.809017 -1.48301e-32 0.587785 -0.809017 -1.48301e-32 0.587785 -0.834573 -1.53106e-32 0.550897 -0.858449 -1.57602e-32 0.512899 -0.834573 -1.53106e-32 0.550897 -0.858449 -1.57602e-32 0.512899 -0.880596 -1.61782e-32 0.473869 -0.880596 -1.61782e-32 0.473869 -0.900969 -1.65635e-32 0.433884 -0.919528 -1.69155e-32 0.393025 -0.900969 -1.65635e-32 0.433884 -0.919528 -1.69155e-32 0.393025 -0.936235 -1.72334e-32 0.351375 -0.936235 -1.72334e-32 0.351375 -0.951057 -1.75166e-32 0.309017 -0.963963 -1.77645e-32 0.266037 -0.951057 -1.75166e-32 0.309017 -0.963963 -1.77645e-32 0.266037 -0.974928 -1.79767e-32 0.222521 -0.974928 -1.79767e-32 0.222521 -0.98393 -1.81526e-32 0.178557 -0.99095 -1.8292e-32 0.134233 -0.98393 -1.81526e-32 0.178557 -0.99095 -1.8292e-32 0.134233 -0.995974 -1.83946e-32 0.0896393 -0.995974 -1.83946e-32 0.0896393 -0.998993 -1.84601e-32 0.0448648 -1 -1.84884e-32 -1.37156e-11 -0.998993 -1.84601e-32 0.0448648 -1 -1.84884e-32 -1.08587e-16 0.0448649 1.04593e-33 0.998993 0.0448648 1.04593e-33 0.998993 0.0896393 1.87309e-33 0.995974 0.134233 2.69647e-33 0.99095 0.0896394 1.87309e-33 0.995974 0.134233 2.69647e-33 0.99095 0.178557 3.51442e-33 0.98393 0.178557 3.51442e-33 0.98393 0.222521 4.3253e-33 0.974928 0.266037 5.12747e-33 0.963963 0.222521 4.3253e-33 0.974928 0.266037 5.12747e-33 0.963963 0.309017 5.91931e-33 0.951056 0.309017 5.9193e-33 0.951057 0.351375 6.69922e-33 0.936235 0.393025 7.46565e-33 0.919528 0.351375 6.69922e-33 0.936235 0.393025 7.46565e-33 0.919528 0.433884 8.21704e-33 0.900969 0.433884 8.21704e-33 0.900969 0.473869 8.95189e-33 0.880595 0.512899 9.6687e-33 0.858449 0.473869 8.95189e-33 0.880596 0.512899 9.6687e-33 0.858449 0.550897 1.03661e-32 0.834573 0.550897 1.0366e-32 0.834573 0.587785 1.10425e-32 0.809017 0.62349 1.16967e-32 0.781832 0.587785 1.10425e-32 0.809017 0.62349 1.16967e-32 0.781832 0.657939 1.23274e-32 0.753071 0.657939 1.23274e-32 0.753071 0.691063 1.29333e-32 0.722795 0.722795 1.35131e-32 0.691063 0.691063 1.29333e-32 0.722795 0.722795 1.35131e-32 0.691063 0.753071 1.40657e-32 0.657939 0.753071 1.40657e-32 0.657939 0.781832 1.45899e-32 0.62349 0.809017 1.50848e-32 0.587785 0.781832 1.45899e-32 0.62349 0.809017 1.50848e-32 0.587785 0.834573 1.55493e-32 0.550897 0.834573 1.55493e-32 0.550897 0.858449 1.59825e-32 0.512899 0.880596 1.63835e-32 0.473869 0.858449 1.59825e-32 0.512899 0.880596 1.63835e-32 0.473869 0.900969 1.67515e-32 0.433884 0.900969 1.67515e-32 0.433884 0.919528 1.70858e-32 0.393025 0.936235 1.73857e-32 0.351375 0.919528 1.70858e-32 0.393025 0.936235 1.73857e-32 0.351375 0.951056 1.76505e-32 0.309017 0.951056 1.76505e-32 0.309017 0.963963 1.78798e-32 0.266037 0.974928 1.80731e-32 0.222521 0.963963 1.78798e-32 0.266037 0.974928 1.80731e-32 0.222521 0.98393 1.823e-32 0.178557 0.98393 1.823e-32 0.178557 0.99095 1.83502e-32 0.134233 0.995974 1.84334e-32 0.0896393 0.99095 1.83502e-32 0.134233 0.9989 1.84783e-32 0.0468835 0.998993 1.84795e-32 0.044865 0.998605 1.84741e-32 0.0528084 0.995974 1.84334e-32 0.0896393 1 1.84884e-32 -8.74228e-08 0.999933 1.84897e-32 0.0115961 0.999999 1.84887e-32 0.00121752 0.999217 1.84825e-32 0.0395559 0.999958 1.84857e-32 -0.0092146 0.98393 1.81526e-32 -0.178557 0.99095 1.8292e-32 -0.134233 0.99095 1.8292e-32 -0.134233 0.998993 1.84601e-32 -0.0448647 0.998748 1.84544e-32 -0.0500283 0.999097 1.84625e-32 -0.0424759 0.963963 1.77645e-32 -0.266037 0.951057 1.75166e-32 -0.309017 0.963963 1.77645e-32 -0.266037 0.98393 1.81526e-32 -0.178557 0.974928 1.79767e-32 -0.222521 0.974928 1.79767e-32 -0.222521 0.919528 1.69155e-32 -0.393025 0.919528 1.69155e-32 -0.393025 0.900969 1.65635e-32 -0.433884 0.936235 1.72334e-32 -0.351375 0.951056 1.75166e-32 -0.309017 0.936235 1.72334e-32 -0.351375 0.834573 1.53106e-32 -0.550897 0.858449 1.57602e-32 -0.512899 0.858449 1.57602e-32 -0.512899 0.880596 1.61782e-32 -0.473869 0.880596 1.61782e-32 -0.473869 0.900969 1.65635e-32 -0.433884 0.781831 1.43198e-32 -0.62349 0.753072 1.37806e-32 -0.657939 0.781831 1.43198e-32 -0.62349 0.834573 1.53106e-32 -0.550897 0.809017 1.48301e-32 -0.587785 0.809017 1.48301e-32 -0.587785 0.691063 1.26201e-32 -0.722795 0.691063 1.26201e-32 -0.722795 0.657939 1.20011e-32 -0.753071 0.722795 1.32136e-32 -0.691063 0.753072 1.37806e-32 -0.657939 0.722795 1.32136e-32 -0.691063 0.550897 1.00044e-32 -0.834573 0.587785 1.06919e-32 -0.809017 0.587785 1.06919e-32 -0.809017 0.62349 1.1358e-32 -0.781832 0.62349 1.1358e-32 -0.781831 0.657939 1.20011e-32 -0.753072 0.473869 8.5703e-33 -0.880595 0.433884 7.82663e-33 -0.900969 0.473869 8.5703e-33 -0.880595 0.550897 1.00044e-32 -0.834573 0.512899 9.2967e-33 -0.858449 0.512899 9.2967e-33 -0.858449 0.351375 6.29352e-33 -0.936235 0.351375 6.29352e-33 -0.936235 0.309017 5.50718e-33 -0.951056 0.393025 7.06718e-33 -0.919528 0.433884 7.82663e-33 -0.900969 0.393025 7.06718e-33 -0.919528 0.178557 3.08805e-33 -0.98393 0.222521 3.90283e-33 -0.974928 0.222521 3.90283e-33 -0.974928 0.266037 4.70975e-33 -0.963963 0.266037 4.70975e-33 -0.963963 0.309017 5.50718e-33 -0.951056 0.0896393 1.4415e-33 -0.995974 0.0448648 6.13032e-34 -0.998993 0.0896393 1.4415e-33 -0.995974 0.178557 3.08805e-33 -0.98393 0.134233 2.26706e-33 -0.99095 0.134233 2.26706e-33 -0.99095 -0.0448649 -1.04593e-33 -0.998993 -0.0448649 -1.04593e-33 -0.998993 -0.0896394 -1.87309e-33 -0.995974 -1.19249e-08 -2.16667e-34 -1 0.0448648 6.13032e-34 -0.998993 -1.19249e-08 -2.16667e-34 -1 -0.222521 -4.3253e-33 -0.974928 -0.178557 -3.51443e-33 -0.98393 -0.178557 -3.51443e-33 -0.98393 -0.134233 -2.69647e-33 -0.99095 -0.134233 -2.69647e-33 -0.99095 -0.0896394 -1.87309e-33 -0.995974 -0.309017 -5.91931e-33 -0.951056 -0.351375 -6.69923e-33 -0.936235 -0.309017 -5.91931e-33 -0.951056 -0.222521 -4.3253e-33 -0.974928 -0.266037 -5.12746e-33 -0.963963 -0.266037 -5.12747e-33 -0.963963 -0.433884 -8.21705e-33 -0.900969 -0.433883 -8.21704e-33 -0.900969 -0.473869 -8.95189e-33 -0.880595 -0.393025 -7.46565e-33 -0.919528 -0.351375 -6.69923e-33 -0.936235 -0.393025 -7.46565e-33 -0.919528 -0.587785 -1.10425e-32 -0.809017 -0.550897 -1.0366e-32 -0.834573 -0.550897 -1.0366e-32 -0.834573 -0.512899 -9.66871e-33 -0.858449 -0.512899 -9.6687e-33 -0.858449 -0.473869 -8.95189e-33 -0.880595 -0.657939 -1.23274e-32 -0.753072 -0.691063 -1.29333e-32 -0.722795 -0.657939 -1.23274e-32 -0.753072 -0.587785 -1.10425e-32 -0.809017 -0.62349 -1.16968e-32 -0.781831 -0.62349 -1.16968e-32 -0.781831 -0.722795 -1.35131e-32 -0.691062 -0.753071 -1.40657e-32 -0.657939 -0.722795 -1.35131e-32 -0.691062 -0.691063 -1.29333e-32 -0.722795 -0.781831 -1.45899e-32 -0.62349 -0.753071 -1.40657e-32 -0.657939 -0.781831 -1.45899e-32 -0.62349 -0.809017 -1.50848e-32 -0.587785 -0.809017 -1.50848e-32 -0.587785 -0.834573 -1.55493e-32 -0.550897 -0.858449 -1.59825e-32 -0.512899 -0.834573 -1.55493e-32 -0.550897 -0.858449 -1.59825e-32 -0.512899 -0.880596 -1.63835e-32 -0.473869 -0.880596 -1.63835e-32 -0.473869 -0.900969 -1.67515e-32 -0.433884 -0.919528 -1.70858e-32 -0.393025 -0.900969 -1.67515e-32 -0.433884 -0.919528 -1.70858e-32 -0.393025 -0.936235 -1.73857e-32 -0.351375 -0.936235 -1.73857e-32 -0.351375 -0.951057 -1.76505e-32 -0.309017 -0.963963 -1.78798e-32 -0.266037 -0.951057 -1.76505e-32 -0.309017 -0.963963 -1.78798e-32 -0.266037 -0.974928 -1.80731e-32 -0.222521 -0.974928 -1.80731e-32 -0.222521 -0.98393 -1.823e-32 -0.178557 -0.99095 -1.83502e-32 -0.134233 -0.98393 -1.823e-32 -0.178557 -0.99095 -1.83502e-32 -0.134233 -0.995974 -1.84334e-32 -0.0896396 -0.995974 -1.84334e-32 -0.0896396 -0.998993 -1.84795e-32 -0.0448647 -0.998993 -1.84795e-32 -0.0448647 0.995974 1.83946e-32 -0.0896394 0.995974 1.83946e-32 -0.0896392 0.999419 1.84703e-32 -0.0340804 0.998403 1.84467e-32 -0.0564859 1 1.84884e-32 -8.74228e-08 0.999858 1.84822e-32 -0.0168254 0.999964 1.84859e-32 -0.00845932 0.999812 1.84808e-32 -0.0193871 0.999688 1.84773e-32 -0.0249902 0.998993 1.84795e-32 0.0448648 0.999625 1.84874e-32 0.0273789 0.999367 1.84844e-32 0.0355764 0.999766 1.84888e-32 0.0216459 0.999828 1.84893e-32 0.0185514 0.999956 1.84897e-32 0.00934793 0.999517 1.84862e-32 0.0310702 0.999079 1.84807e-32 0.0429035 0.998789 1.84767e-32 0.0491961 0.998077 1.84663e-32 0.0619869 0.998364 1.84706e-32 0.0571803 0.998304 1.84697e-32 0.0582222 0.998522 1.84729e-32 0.0543452 0.998186 1.84679e-32 0.0602021 0.998151 1.84674e-32 0.0607828 0.998089 1.84665e-32 0.0618001 1 1.84884e-32 -8.74228e-08 0.997685 1.84309e-32 -0.0680084 0.998581 1.84507e-32 -0.0532493 0.998243 1.84431e-32 -0.0592496 0.998097 1.84399e-32 -0.0616649 0.997961 1.84369e-32 -0.063825 0.997717 1.84316e-32 -0.0675267 0.99786 1.84347e-32 -0.0653893 0.997769 1.84327e-32 -0.0667658 0.998942 1.84589e-32 -0.0459946 - + @@ -166,169 +141,21 @@ - + -

0 1 2 1 3 4 3 1 0 5 4 6 3 6 4 7 8 5 5 6 7 8 9 10 9 8 7 11 10 12 9 12 10 13 14 11 11 12 13 14 15 16 15 14 13 17 16 18 15 18 16 19 20 17 17 18 19 20 21 22 21 20 19 23 22 24 21 24 22 25 26 23 23 24 25 26 27 28 27 26 25 29 28 30 27 30 28 31 32 29 29 30 31 32 33 34 33 32 31 35 34 36 33 36 34 37 38 35 35 36 37 38 39 40 39 38 37 41 40 42 39 42 40 43 44 41 41 42 43 44 45 46 45 44 43 47 46 48 45 48 46 49 50 47 47 48 49 50 51 52 51 50 49 53 52 54 51 54 52 55 56 53 53 54 55 56 57 58 57 56 55 59 58 60 57 60 58 61 62 59 59 60 61 62 63 64 63 62 61 65 64 66 63 66 64 67 68 65 65 66 67 68 69 70 69 68 67 71 70 72 69 72 70 73 74 71 71 72 73 74 75 76 75 74 73 77 76 78 75 78 76 79 80 77 77 78 79 80 81 82 81 80 79 83 82 84 81 84 82 85 86 83 83 84 85 86 87 88 87 86 85 89 88 90 87 90 88 91 92 89 89 90 91 92 93 94 93 92 91 95 94 96 93 96 94 97 98 95 95 96 97 98 99 100 99 98 97 101 100 102 99 102 100 103 104 101 101 102 103 104 105 106 105 104 103 107 106 108 105 108 106 109 110 107 107 108 109 111 110 109 111 112 110 0 2 113 114 113 115 2 115 113 116 117 114 114 115 116 117 118 119 118 117 116 120 119 121 118 121 119 122 123 120 120 121 122 123 124 125 124 123 122 126 125 127 124 127 125 128 129 126 126 127 128 129 130 131 130 129 128 132 131 133 130 133 131 134 135 132 132 133 134 135 136 137 136 135 134 138 137 139 136 139 137 140 141 138 138 139 140 141 142 143 142 141 140 144 143 145 142 145 143 146 147 144 144 145 146 147 148 149 148 147 146 150 149 151 148 151 149 152 153 150 150 151 152 153 154 155 154 153 152 156 155 157 154 157 155 158 159 156 156 157 158 159 160 161 160 159 158 162 161 163 160 163 161 164 165 162 162 163 164 165 166 167 166 165 164 168 167 169 166 169 167 170 171 168 168 169 170 171 172 173 172 171 170 174 173 175 172 175 173 176 177 174 174 175 176 177 178 179 178 177 176 180 179 181 178 181 179 182 183 180 180 181 182 183 184 185 184 183 182 186 185 187 184 187 185 188 189 186 186 187 188 189 190 191 190 189 188 192 191 193 190 193 191 194 195 192 192 193 194 195 196 197 196 195 194 198 197 199 196 199 197 200 201 198 198 199 200 201 202 203 202 201 200 204 203 205 202 205 203 206 207 204 204 205 206 207 208 209 208 207 206 210 209 211 208 211 209 212 213 210 210 211 212 213 214 215 214 213 212 216 215 217 214 217 215 218 219 216 216 217 218 219 220 221 220 219 218 220 112 221 221 112 111

+

382 384 383 385 387 386 388 390 389 391 393 392 394 396 395 397 399 398 400 402 401 403 405 404 406 408 407 409 411 410 412 414 413 415 417 416 418 420 419 421 423 422 424 426 425 427 429 428 430 432 431 433 435 434 436 438 437 439 441 440 440 434 439 442 443 441 440 441 443 444 442 445 442 444 443 445 447 446 446 444 445 448 449 447 446 447 449 450 448 451 448 450 449 451 453 452 452 450 451 454 455 453 452 453 455 383 454 456 454 383 455 435 433 437 434 435 439 429 438 436 436 437 433 432 427 428 427 438 429 430 431 421 432 428 431 422 423 424 430 421 422 426 416 425 423 426 424 415 419 417 416 417 425 411 420 418 418 419 415 414 409 410 409 420 411 410 413 414 412 403 404 412 413 403 405 408 406 404 405 406 398 399 407 408 398 407 400 401 397 397 401 399 391 402 393 393 402 400 396 392 395 396 391 392 394 385 386 394 395 385 387 388 389 386 387 389 384 382 390 388 384 390 383 456 382

-
-
- - - - -3.16265e-18 -0.05165 -0.019 0.00101727 -0.05164 -0.024182 0.00289604 -0.0515687 -0.019 -0.05165 3.16265e-18 -0.0378 -0.05165 3.16265e-18 -0.019 -0.0515687 0.00289604 -0.019 0.00200804 -0.0516109 -0.0244259 0.00295015 -0.0515656 -0.0248269 -9.48795e-18 -0.05165 -0.0241 0.00578297 -0.0513252 -0.019 0.00573528 -0.0513307 -0.0277244 0.00609781 -0.0512888 -0.0286782 0.00381202 -0.0515091 -0.0253715 0.0086517 -0.0509202 -0.0378 0.0114932 -0.050355 -0.0378 0.0086517 -0.0509202 -0.019 0.00630334 -0.0512641 -0.0296816 0.0114932 -0.050355 -0.019 0.0142986 -0.0496314 -0.0378 0.0170589 -0.0487516 -0.0378 0.0142986 -0.0496314 -0.019 0.0197656 -0.0477184 -0.0378 0.0170589 -0.0487516 -0.019 0.0197656 -0.0477184 -0.019 0.0224101 -0.046535 -0.0378 0.0249841 -0.0452053 -0.0378 0.0224101 -0.046535 -0.019 0.0274795 -0.0437333 -0.0378 0.0249841 -0.0452053 -0.019 0.0274795 -0.0437333 -0.019 0.0298884 -0.0421237 -0.0378 0.0322032 -0.0403816 -0.0378 0.0298884 -0.0421237 -0.019 0.0344168 -0.0385124 -0.0378 0.0322032 -0.0403816 -0.019 0.0344168 -0.0385124 -0.019 0.0365221 -0.0365221 -0.0378 0.0385124 -0.0344168 -0.0378 0.0365221 -0.0365221 -0.019 0.0403816 -0.0322032 -0.0378 0.0385124 -0.0344168 -0.019 0.0403816 -0.0322032 -0.019 0.0421237 -0.0298884 -0.0378 0.0437333 -0.0274795 -0.0378 0.0421237 -0.0298884 -0.019 0.0452053 -0.0249841 -0.0378 0.0437333 -0.0274795 -0.019 0.0452053 -0.0249841 -0.019 0.046535 -0.0224101 -0.0378 0.0477184 -0.0197656 -0.0378 0.046535 -0.0224101 -0.019 0.0487516 -0.0170589 -0.0378 0.0477184 -0.0197656 -0.019 0.0487516 -0.0170589 -0.019 0.0496314 -0.0142986 -0.0378 0.050355 -0.0114932 -0.0378 0.0496314 -0.0142986 -0.019 0.0509202 -0.0086517 -0.0378 0.050355 -0.0114932 -0.019 0.0509202 -0.0086517 -0.019 0.0513252 -0.00578297 -0.0378 0.0515687 -0.00289604 -0.0378 0.0513252 -0.00578297 -0.019 0.05165 -1.58133e-17 -0.0378 0.0515687 -0.00289604 -0.019 0.05165 -1.58133e-17 -0.019 -0.00295222 -0.0515655 -0.024828 -0.00201277 -0.0516108 -0.0244274 -0.00289604 -0.0515687 -0.019 -0.00522611 -0.0513849 -0.026843 -0.00457949 -0.0514466 -0.0260511 -0.00578297 -0.0513252 -0.019 -0.000510302 -0.0516475 -0.0367795 2.84734e-16 -0.05165 -0.0378 0.000513787 -0.0516473 -0.0367792 -0.00593607 -0.0513078 -0.0327051 -0.00578297 -0.0513252 -0.0378 -0.00549847 -0.0513565 -0.0336264 -0.00248979 -0.0515899 -0.0362915 -0.00339301 -0.0515384 -0.0358175 -0.00289604 -0.0515687 -0.0378 -0.0086517 -0.0509202 -0.0378 -0.0086517 -0.0509202 -0.019 -0.0114932 -0.050355 -0.019 -0.00622141 -0.051274 -0.0317214 -0.0142986 -0.0496314 -0.019 -0.0114932 -0.050355 -0.0378 -0.0170589 -0.0487516 -0.019 -0.0142986 -0.0496314 -0.0378 -0.0170589 -0.0487516 -0.0378 -0.0197656 -0.0477184 -0.019 -0.0224101 -0.046535 -0.019 -0.0197656 -0.0477184 -0.0378 -0.0249841 -0.0452053 -0.019 -0.0224101 -0.046535 -0.0378 -0.0249841 -0.0452053 -0.0378 -0.0274795 -0.0437333 -0.019 -0.0298884 -0.0421237 -0.019 -0.0274795 -0.0437333 -0.0378 -0.0322032 -0.0403816 -0.019 -0.0298884 -0.0421237 -0.0378 -0.0322032 -0.0403816 -0.0378 -0.0344168 -0.0385124 -0.019 -0.0365221 -0.0365221 -0.019 -0.0344168 -0.0385124 -0.0378 -0.0385124 -0.0344168 -0.019 -0.0365221 -0.0365221 -0.0378 -0.0385124 -0.0344168 -0.0378 -0.0403816 -0.0322032 -0.019 -0.0421237 -0.0298884 -0.019 -0.0403816 -0.0322032 -0.0378 -0.0437333 -0.0274795 -0.019 -0.0421237 -0.0298884 -0.0378 -0.0437333 -0.0274795 -0.0378 -0.0452053 -0.0249841 -0.019 -0.046535 -0.0224101 -0.019 -0.0452053 -0.0249841 -0.0378 -0.0477184 -0.0197656 -0.019 -0.046535 -0.0224101 -0.0378 -0.0477184 -0.0197656 -0.0378 -0.0487516 -0.0170589 -0.019 -0.0496314 -0.0142986 -0.019 -0.0487516 -0.0170589 -0.0378 -0.050355 -0.0114932 -0.019 -0.0496314 -0.0142986 -0.0378 -0.050355 -0.0114932 -0.0378 -0.0509202 -0.0086517 -0.019 -0.0513252 -0.00578297 -0.019 -0.0509202 -0.0086517 -0.0378 -0.0515687 -0.00289604 -0.019 -0.0513252 -0.00578297 -0.0378 -0.0515687 -0.00289604 -0.0378 -0.0513252 0.00578297 -0.0378 -0.0515687 0.00289604 -0.0378 -0.0513252 0.00578297 -0.019 -0.0496314 0.0142986 -0.0378 -0.050355 0.0114932 -0.0378 -0.0496314 0.0142986 -0.019 -0.0509202 0.0086517 -0.0378 -0.0509202 0.0086517 -0.019 -0.050355 0.0114932 -0.019 -0.0477184 0.0197656 -0.0378 -0.046535 0.0224101 -0.019 -0.046535 0.0224101 -0.0378 -0.0487516 0.0170589 -0.019 -0.0477184 0.0197656 -0.019 -0.0487516 0.0170589 -0.0378 -0.0421237 0.0298884 -0.019 -0.0421237 0.0298884 -0.0378 -0.0437333 0.0274795 -0.0378 -0.0437333 0.0274795 -0.019 -0.0452053 0.0249841 -0.0378 -0.0452053 0.0249841 -0.019 -0.0365221 0.0365221 -0.0378 -0.0385124 0.0344168 -0.0378 -0.0365221 0.0365221 -0.019 -0.0403816 0.0322032 -0.0378 -0.0403816 0.0322032 -0.019 -0.0385124 0.0344168 -0.019 -0.0322032 0.0403816 -0.0378 -0.0298884 0.0421237 -0.019 -0.0298884 0.0421237 -0.0378 -0.0344168 0.0385124 -0.019 -0.0322032 0.0403816 -0.019 -0.0344168 0.0385124 -0.0378 -0.0224101 0.046535 -0.019 -0.0224101 0.046535 -0.0378 -0.0249841 0.0452053 -0.0378 -0.0249841 0.0452053 -0.019 -0.0274795 0.0437333 -0.0378 -0.0274795 0.0437333 -0.019 -0.0142986 0.0496314 -0.0378 -0.0170589 0.0487516 -0.0378 -0.0142986 0.0496314 -0.019 -0.0197656 0.0477184 -0.0378 -0.0197656 0.0477184 -0.019 -0.0170589 0.0487516 -0.019 -0.0086517 0.0509202 -0.0378 -0.00578297 0.0513252 -0.019 -0.00578297 0.0513252 -0.0378 -0.0114932 0.050355 -0.019 -0.0086517 0.0509202 -0.019 -0.0114932 0.050355 -0.0378 0.00289604 0.0515687 -0.019 0.00289604 0.0515687 -0.0378 8.30595e-18 0.05165 -0.0378 -3.16265e-18 0.05165 -0.019 -0.00289604 0.0515687 -0.0378 -0.00289604 0.0515687 -0.019 0.0114932 0.050355 -0.0378 0.0086517 0.0509202 -0.0378 0.0114932 0.050355 -0.019 0.00578297 0.0513252 -0.0378 0.00578297 0.0513252 -0.019 0.0086517 0.0509202 -0.019 0.0170589 0.0487516 -0.0378 0.0197656 0.0477184 -0.019 0.0197656 0.0477184 -0.0378 0.0142986 0.0496314 -0.019 0.0170589 0.0487516 -0.019 0.0142986 0.0496314 -0.0378 0.0274795 0.0437333 -0.019 0.0274795 0.0437333 -0.0378 0.0249841 0.0452053 -0.0378 0.0249841 0.0452053 -0.019 0.0224101 0.046535 -0.0378 0.0224101 0.046535 -0.019 0.0344168 0.0385124 -0.0378 0.0322032 0.0403816 -0.0378 0.0344168 0.0385124 -0.019 0.0298884 0.0421237 -0.0378 0.0298884 0.0421237 -0.019 0.0322032 0.0403816 -0.019 0.0385124 0.0344168 -0.0378 0.0365221 0.0365221 -0.0378 0.0385124 0.0344168 -0.019 0.0365221 0.0365221 -0.019 0.0403816 0.0322032 -0.019 0.0403816 0.0322032 -0.0378 0.0421237 0.0298884 -0.019 0.0421237 0.0298884 -0.0378 0.0437333 0.0274795 -0.0378 0.0437333 0.0274795 -0.019 0.0452053 0.0249841 -0.019 0.0452053 0.0249841 -0.0378 0.046535 0.0224101 -0.019 0.046535 0.0224101 -0.0378 0.0477184 0.0197656 -0.0378 0.0477184 0.0197656 -0.019 0.0487516 0.0170589 -0.019 0.0487516 0.0170589 -0.0378 0.0496314 0.0142986 -0.019 0.0496314 0.0142986 -0.0378 0.050355 0.0114932 -0.0378 0.050355 0.0114932 -0.019 0.0509202 0.0086517 -0.019 0.0509202 0.0086517 -0.0378 0.0513252 0.00578297 -0.019 0.0513252 0.00578297 -0.0378 0.0515687 0.00289604 -0.0378 0.0515687 0.00289604 -0.019 -0.00151864 -0.0516275 -0.0366157 0.00339655 -0.0515382 -0.0358153 0.00249251 -0.0515897 -0.0362904 0.00289604 -0.0515687 -0.0378 0.00578297 -0.0513252 -0.0378 0.00549969 -0.0513564 -0.0336242 0.00491994 -0.0514151 -0.0344646 0.00457797 -0.0514467 -0.0260495 0.00522308 -0.0513853 -0.0268386 0.00593792 -0.0513075 -0.0327003 0.0062219 -0.051274 -0.0317191 0.00634499 -0.0512588 -0.0307023 0.00421276 -0.0514779 -0.0352013 0.00152244 -0.0516276 -0.0366148 -0.00101951 -0.0516398 -0.0241824 -0.00381612 -0.0515088 -0.0253746 -0.00421084 -0.0514781 -0.035203 -0.00573624 -0.0513306 -0.0277264 -0.00491703 -0.0514154 -0.0344681 -0.00609938 -0.0512886 -0.0286836 -0.00634476 -0.0512589 -0.0307079 -0.00630362 -0.051264 -0.0296839 0.0479188 0.00279095 -0.0358 0.048 0 -0.0358 0.048 0 -0.019 0.0467062 0.0110696 -0.0358 0.0472708 0.00833511 -0.0358 0.0472708 0.00833511 -0.019 0.0476754 0.00557246 -0.0358 0.0479188 0.00279095 -0.019 0.0476754 0.00557246 -0.019 0.0451052 0.016417 -0.019 0.0440744 0.0190118 -0.0358 0.0451052 0.016417 -0.0358 0.0467062 0.0110696 -0.019 0.0459835 0.0137666 -0.019 0.0459835 0.0137666 -0.0358 0.0415692 0.024 -0.0358 0.0415692 0.024 -0.019 0.0401034 0.0263764 -0.0358 0.0428944 0.0215424 -0.0358 0.0440744 0.0190118 -0.019 0.0428944 0.0215424 -0.019 0.0349139 0.0329396 -0.0358 0.0367701 0.0308538 -0.0358 0.0367701 0.0308538 -0.019 0.0385019 0.0286636 -0.019 0.0385019 0.0286636 -0.0358 0.0401034 0.0263764 -0.019 0.0308538 0.0367701 -0.019 0.0286636 0.0385019 -0.0358 0.0308538 0.0367701 -0.0358 0.0349139 0.0329396 -0.019 0.0329396 0.0349139 -0.019 0.0329396 0.0349139 -0.0358 0.024 0.0415692 -0.0358 0.024 0.0415692 -0.019 0.0215424 0.0428944 -0.0358 0.0263764 0.0401034 -0.0358 0.0286636 0.0385019 -0.019 0.0263764 0.0401034 -0.019 0.0137666 0.0459835 -0.0358 0.016417 0.0451052 -0.0358 0.016417 0.0451052 -0.019 0.0190118 0.0440744 -0.019 0.0190118 0.0440744 -0.0358 0.0215424 0.0428944 -0.019 0.00833511 0.0472708 -0.019 0.00557246 0.0476754 -0.0358 0.00833511 0.0472708 -0.0358 0.0137666 0.0459835 -0.019 0.0110696 0.0467062 -0.019 0.0110696 0.0467062 -0.0358 -8.81746e-18 0.048 -0.0358 2.93915e-18 0.048 -0.019 -0.00279095 0.0479188 -0.0358 0.00279095 0.0479188 -0.0358 0.00557246 0.0476754 -0.019 0.00279095 0.0479188 -0.019 -0.0110696 0.0467062 -0.0358 -0.00833511 0.0472708 -0.0358 -0.00833511 0.0472708 -0.019 -0.00557246 0.0476754 -0.019 -0.00557246 0.0476754 -0.0358 -0.00279095 0.0479188 -0.019 -0.016417 0.0451052 -0.019 -0.0190118 0.0440744 -0.0358 -0.016417 0.0451052 -0.0358 -0.0110696 0.0467062 -0.019 -0.0137666 0.0459835 -0.019 -0.0137666 0.0459835 -0.0358 -0.024 0.0415692 -0.0358 -0.024 0.0415692 -0.019 -0.0263764 0.0401034 -0.0358 -0.0215424 0.0428944 -0.0358 -0.0190118 0.0440744 -0.019 -0.0215424 0.0428944 -0.019 -0.0329396 0.0349139 -0.0358 -0.0308538 0.0367701 -0.0358 -0.0308538 0.0367701 -0.019 -0.0286636 0.0385019 -0.019 -0.0286636 0.0385019 -0.0358 -0.0263764 0.0401034 -0.019 -0.0367701 0.0308538 -0.019 -0.0385019 0.0286636 -0.0358 -0.0367701 0.0308538 -0.0358 -0.0329396 0.0349139 -0.019 -0.0349139 0.0329396 -0.019 -0.0349139 0.0329396 -0.0358 -0.0415692 0.024 -0.0358 -0.0415692 0.024 -0.019 -0.0428944 0.0215424 -0.0358 -0.0401034 0.0263764 -0.0358 -0.0385019 0.0286636 -0.019 -0.0401034 0.0263764 -0.019 -0.0459835 0.0137666 -0.0358 -0.0451052 0.016417 -0.0358 -0.0451052 0.016417 -0.019 -0.0440744 0.0190118 -0.019 -0.0440744 0.0190118 -0.0358 -0.0428944 0.0215424 -0.019 -0.0472708 0.00833511 -0.019 -0.0476754 0.00557246 -0.0358 -0.0472708 0.00833511 -0.0358 -0.0459835 0.0137666 -0.019 -0.0467062 0.0110696 -0.019 -0.0467062 0.0110696 -0.0358 -0.048 5.8783e-18 -0.0358 -0.048 1.97725e-16 -0.019 -0.0479188 -0.00279095 -0.0358 -0.0479188 0.00279095 -0.0358 -0.0476754 0.00557246 -0.019 -0.0479188 0.00279095 -0.019 -0.0467062 -0.0110696 -0.0358 -0.0472708 -0.00833511 -0.0358 -0.0472708 -0.00833511 -0.019 -0.0476754 -0.00557246 -0.019 -0.0476754 -0.00557246 -0.0358 -0.0479188 -0.00279095 -0.019 -0.0451052 -0.016417 -0.019 -0.0440744 -0.0190118 -0.0358 -0.0451052 -0.016417 -0.0358 -0.0467062 -0.0110696 -0.019 -0.0459835 -0.0137666 -0.019 -0.0459835 -0.0137666 -0.0358 -0.0415692 -0.024 -0.0358 -0.0415692 -0.024 -0.019 -0.0401034 -0.0263764 -0.0358 -0.0428944 -0.0215424 -0.0358 -0.0440744 -0.0190118 -0.019 -0.0428944 -0.0215424 -0.019 -0.0349139 -0.0329396 -0.0358 -0.0367701 -0.0308538 -0.0358 -0.0367701 -0.0308538 -0.019 -0.0385019 -0.0286636 -0.019 -0.0385019 -0.0286636 -0.0358 -0.0401034 -0.0263764 -0.019 -0.0308538 -0.0367701 -0.019 -0.0286636 -0.0385019 -0.0358 -0.0308538 -0.0367701 -0.0358 -0.0349139 -0.0329396 -0.019 -0.0329396 -0.0349139 -0.019 -0.0329396 -0.0349139 -0.0358 -0.024 -0.0415692 -0.0358 -0.024 -0.0415692 -0.019 -0.0215424 -0.0428944 -0.0358 -0.0263764 -0.0401034 -0.0358 -0.0286636 -0.0385019 -0.019 -0.0263764 -0.0401034 -0.019 -0.0137666 -0.0459835 -0.0358 -0.016417 -0.0451052 -0.0358 -0.016417 -0.0451052 -0.019 -0.0190118 -0.0440744 -0.019 -0.0190118 -0.0440744 -0.0358 -0.0215424 -0.0428944 -0.019 -0.00833511 -0.0472708 -0.019 -0.00557246 -0.0476754 -0.0358 -0.00833511 -0.0472708 -0.0358 -0.0137666 -0.0459835 -0.019 -0.0110696 -0.0467062 -0.019 -0.0110696 -0.0467062 -0.0358 -0.00279095 -0.0479188 -0.0358 -0.00557246 -0.0476754 -0.019 -0.00279095 -0.0479188 -0.019 -2.2198e-16 -0.048 -0.019 0.00279095 -0.0479188 -0.019 0.00279095 -0.0479188 -0.0358 2.93915e-18 -0.048 -0.0358 0.00557246 -0.0476754 -0.019 0.00557246 -0.0476754 -0.0358 0.00833511 -0.0472708 -0.0358 0.00833511 -0.0472708 -0.019 0.0110696 -0.0467062 -0.019 0.0110696 -0.0467062 -0.0358 0.0137666 -0.0459835 -0.019 0.0137666 -0.0459835 -0.0358 0.016417 -0.0451052 -0.0358 0.016417 -0.0451052 -0.019 0.0190118 -0.0440744 -0.019 0.0190118 -0.0440744 -0.0358 0.0215424 -0.0428944 -0.019 0.0215424 -0.0428944 -0.0358 0.024 -0.0415692 -0.0358 0.024 -0.0415692 -0.019 0.0263764 -0.0401034 -0.019 0.0263764 -0.0401034 -0.0358 0.0286636 -0.0385019 -0.019 0.0286636 -0.0385019 -0.0358 0.0308538 -0.0367701 -0.0358 0.0308538 -0.0367701 -0.019 0.0329396 -0.0349139 -0.019 0.0329396 -0.0349139 -0.0358 0.0349139 -0.0329396 -0.019 0.0349139 -0.0329396 -0.0358 0.0367701 -0.0308538 -0.0358 0.0367701 -0.0308538 -0.019 0.0385019 -0.0286636 -0.019 0.0385019 -0.0286636 -0.0358 0.0401034 -0.0263764 -0.019 0.0401034 -0.0263764 -0.0358 0.0415692 -0.024 -0.0358 0.0415692 -0.024 -0.019 0.0428944 -0.0215424 -0.019 0.0428944 -0.0215424 -0.0358 0.0440744 -0.0190118 -0.019 0.0440744 -0.0190118 -0.0358 0.0451052 -0.016417 -0.0358 0.0451052 -0.016417 -0.019 0.0459835 -0.0137666 -0.019 0.0459835 -0.0137666 -0.0358 0.0467062 -0.0110696 -0.019 0.0467062 -0.0110696 -0.0358 0.0472708 -0.00833511 -0.0358 0.0472708 -0.00833511 -0.019 0.0476754 -0.00557246 -0.019 0.0476754 -0.00557246 -0.0358 0.0479188 -0.00279095 -0.019 0.0479188 -0.00279095 -0.0358 -0.0274795 0.0437333 -0.0378 -0.0015 0.00259808 -0.0378 -0.0298884 0.0421237 -0.0378 0.0515687 -0.00289604 -0.0378 0.0513252 -0.00578297 -0.0378 0.00295442 -0.000520945 -0.0378 -0.00192836 0.00229813 -0.0378 -0.0322032 0.0403816 -0.0378 -0.0249841 0.0452053 -0.0378 -0.0344168 0.0385124 -0.0378 -0.0224101 0.046535 -0.0378 -0.00102606 0.00281908 -0.0378 -0.00229813 0.00192836 -0.0378 -0.0365221 0.0365221 -0.0378 -0.0197656 0.0477184 -0.0378 -0.0170589 0.0487516 -0.0378 -0.0385124 0.0344168 -0.0378 -0.0403816 0.0322032 -0.0378 -0.0142986 0.0496314 -0.0378 -0.0421237 0.0298884 -0.0378 -0.000520945 0.00295442 -0.0378 -0.0114932 0.050355 -0.0378 -0.00259808 0.0015 -0.0378 -0.0437333 0.0274795 -0.0378 -0.00578297 0.0513252 -0.0378 -0.0086517 0.0509202 -0.0378 -0.046535 0.0224101 -0.0378 -0.0452053 0.0249841 -0.0378 -0.00289604 0.0515687 -0.0378 1.83697e-19 0.003 -0.0378 8.30595e-18 0.05165 -0.0378 0.00289604 0.0515687 -0.0378 -0.00281908 0.00102606 -0.0378 0.000520945 0.00295442 -0.0378 0.00578297 0.0513252 -0.0378 -0.0477184 0.0197656 -0.0378 -0.0487516 0.0170589 -0.0378 0.0114932 0.050355 -0.0378 0.0086517 0.0509202 -0.0378 -0.0496314 0.0142986 -0.0378 0.0142986 0.0496314 -0.0378 -0.00295442 0.000520945 -0.0378 -0.050355 0.0114932 -0.0378 0.00102606 0.00281908 -0.0378 0.0170589 0.0487516 -0.0378 -0.0513252 0.00578297 -0.0378 -0.0509202 0.0086517 -0.0378 0.0197656 0.0477184 -0.0378 0.0224101 0.046535 -0.0378 -0.0515687 0.00289604 -0.0378 0.0015 0.00259808 -0.0378 0.0274795 0.0437333 -0.0378 0.0298884 0.0421237 -0.0378 -0.003 2.8473e-18 -0.0378 -0.0515687 -0.00289604 -0.0378 -0.05165 3.16265e-18 -0.0378 0.0344168 0.0385124 -0.0378 0.0365221 0.0365221 -0.0378 0.00192836 0.00229813 -0.0378 -0.0513252 -0.00578297 -0.0378 -0.00295442 -0.000520945 -0.0378 -0.0509202 -0.0086517 -0.0378 0.00229813 0.00192836 -0.0378 0.0403816 0.0322032 -0.0378 0.0421237 0.0298884 -0.0378 -0.00281908 -0.00102606 -0.0378 -0.0496314 -0.0142986 -0.0378 0.046535 0.0224101 -0.0378 0.00259808 0.0015 -0.0378 0.0452053 0.0249841 -0.0378 -0.0477184 -0.0197656 -0.0378 -0.046535 -0.0224101 -0.0378 0.00295442 0.000520945 -0.0378 0.00281908 0.00102606 -0.0378 0.0496314 0.0142986 -0.0378 -0.00259808 -0.0015 -0.0378 -0.0421237 -0.0298884 -0.0378 -0.0437333 -0.0274795 -0.0378 0.0513252 0.00578297 -0.0378 0.003 3.81218e-18 -0.0378 -0.0403816 -0.0322032 -0.0378 -0.00229813 -0.00192836 -0.0378 -0.0385124 -0.0344168 -0.0378 -0.0344168 -0.0385124 -0.0378 -0.0365221 -0.0365221 -0.0378 -0.00192836 -0.00229813 -0.0378 0.00281908 -0.00102606 -0.0378 0.050355 -0.0114932 -0.0378 -0.0015 -0.00259808 -0.0378 -0.0298884 -0.0421237 -0.0378 0.0477184 -0.0197656 -0.0378 0.046535 -0.0224101 -0.0378 -0.0224101 -0.046535 -0.0378 -0.0249841 -0.0452053 -0.0378 0.0437333 -0.0274795 -0.0378 0.0421237 -0.0298884 -0.0378 0.00259808 -0.0015 -0.0378 -0.0197656 -0.0477184 -0.0378 -0.00102606 -0.00281908 -0.0378 -0.0170589 -0.0487516 -0.0378 0.0385124 -0.0344168 -0.0378 0.0365221 -0.0365221 -0.0378 0.00229813 -0.00192836 -0.0378 -0.0086517 -0.0509202 -0.0378 -0.0114932 -0.050355 -0.0378 -0.000520945 -0.00295442 -0.0378 0.0322032 -0.0403816 -0.0378 0.0298884 -0.0421237 -0.0378 0.00192836 -0.00229813 -0.0378 -5.51091e-19 -0.003 -0.0378 2.84734e-16 -0.05165 -0.0378 -0.00289604 -0.0515687 -0.0378 0.0224101 -0.046535 -0.0378 0.0015 -0.00259808 -0.0378 0.0249841 -0.0452053 -0.0378 0.00578297 -0.0513252 -0.0378 0.000520945 -0.00295442 -0.0378 0.0086517 -0.0509202 -0.0378 0.00102606 -0.00281908 -0.0378 0.0170589 -0.0487516 -0.0378 0.0142986 -0.0496314 -0.0378 0.0197656 -0.0477184 -0.0378 0.0114932 -0.050355 -0.0378 0.0274795 -0.0437333 -0.0378 0.00289604 -0.0515687 -0.0378 0.0344168 -0.0385124 -0.0378 -0.00578297 -0.0513252 -0.0378 0.0403816 -0.0322032 -0.0378 -0.0142986 -0.0496314 -0.0378 0.0452053 -0.0249841 -0.0378 0.0496314 -0.0142986 -0.0378 0.0487516 -0.0170589 -0.0378 -0.0274795 -0.0437333 -0.0378 -0.0322032 -0.0403816 -0.0378 0.0509202 -0.0086517 -0.0378 0.05165 -1.58133e-17 -0.0378 0.0515687 0.00289604 -0.0378 0.0509202 0.0086517 -0.0378 0.050355 0.0114932 -0.0378 0.0487516 0.0170589 -0.0378 -0.0452053 -0.0249841 -0.0378 0.0437333 0.0274795 -0.0378 -0.0487516 -0.0170589 -0.0378 0.0385124 0.0344168 -0.0378 -0.050355 -0.0114932 -0.0378 0.0322032 0.0403816 -0.0378 0.0477184 0.0197656 -0.0378 0.0249841 0.0452053 -0.0378 -0.0263764 0.0401034 -0.019 -0.024 0.0415692 -0.019 -0.0274795 0.0437333 -0.019 0.0476754 0.00557246 -0.019 0.0509202 0.0086517 -0.019 0.0472708 0.00833511 -0.019 -0.0298884 0.0421237 -0.019 -0.0286636 0.0385019 -0.019 -0.0215424 0.0428944 -0.019 -0.0249841 0.0452053 -0.019 -0.0322032 0.0403816 -0.019 -0.0308538 0.0367701 -0.019 -0.0190118 0.0440744 -0.019 -0.0224101 0.046535 -0.019 -0.0344168 0.0385124 -0.019 -0.0329396 0.0349139 -0.019 -0.0197656 0.0477184 -0.019 -0.016417 0.0451052 -0.019 -0.0365221 0.0365221 -0.019 -0.0349139 0.0329396 -0.019 -0.0137666 0.0459835 -0.019 -0.0170589 0.0487516 -0.019 -0.0385124 0.0344168 -0.019 -0.0367701 0.0308538 -0.019 -0.0110696 0.0467062 -0.019 -0.0142986 0.0496314 -0.019 -0.0403816 0.0322032 -0.019 -0.0385019 0.0286636 -0.019 -0.0114932 0.050355 -0.019 -0.00833511 0.0472708 -0.019 -0.0421237 0.0298884 -0.019 -0.0401034 0.0263764 -0.019 -0.00557246 0.0476754 -0.019 -0.0086517 0.0509202 -0.019 -0.00279095 0.0479188 -0.019 -0.00578297 0.0513252 -0.019 2.93915e-18 0.048 -0.019 -0.00289604 0.0515687 -0.019 -0.0437333 0.0274795 -0.019 -0.0415692 0.024 -0.019 -3.16265e-18 0.05165 -0.019 0.00289604 0.0515687 -0.019 -0.0452053 0.0249841 -0.019 -0.0428944 0.0215424 -0.019 0.00578297 0.0513252 -0.019 0.00279095 0.0479188 -0.019 -0.046535 0.0224101 -0.019 -0.0440744 0.0190118 -0.019 0.00557246 0.0476754 -0.019 0.0086517 0.0509202 -0.019 -0.0477184 0.0197656 -0.019 -0.0451052 0.016417 -0.019 0.00833511 0.0472708 -0.019 0.0114932 0.050355 -0.019 -0.0487516 0.0170589 -0.019 -0.0459835 0.0137666 -0.019 0.0110696 0.0467062 -0.019 -0.0496314 0.0142986 -0.019 -0.0467062 0.0110696 -0.019 0.0197656 0.0477184 -0.019 0.016417 0.0451052 -0.019 0.0190118 0.0440744 -0.019 -0.050355 0.0114932 -0.019 -0.0509202 0.0086517 -0.019 -0.0472708 0.00833511 -0.019 0.0263764 0.0401034 -0.019 0.0274795 0.0437333 -0.019 0.024 0.0415692 -0.019 -0.048 1.97725e-16 -0.019 -0.0515687 0.00289604 -0.019 -0.05165 3.16265e-18 -0.019 0.0308538 0.0367701 -0.019 0.0329396 0.0349139 -0.019 0.0344168 0.0385124 -0.019 -0.0472708 -0.00833511 -0.019 -0.0476754 -0.00557246 -0.019 -0.0509202 -0.0086517 -0.019 0.0403816 0.0322032 -0.019 0.0367701 0.0308538 -0.019 0.0385019 0.0286636 -0.019 -0.0451052 -0.016417 -0.019 -0.0459835 -0.0137666 -0.019 -0.0487516 -0.0170589 -0.019 0.0428944 0.0215424 -0.019 0.0452053 0.0249841 -0.019 0.0415692 0.024 -0.019 -0.0452053 -0.0249841 -0.019 -0.0415692 -0.024 -0.019 -0.0428944 -0.0215424 -0.019 0.0451052 0.016417 -0.019 0.0459835 0.0137666 -0.019 0.0487516 0.0170589 -0.019 -0.0403816 -0.0322032 -0.019 -0.0367701 -0.0308538 -0.019 -0.0385019 -0.0286636 -0.019 0.050355 0.0114932 -0.019 -0.0329396 -0.0349139 -0.019 -0.0344168 -0.0385124 -0.019 -0.0308538 -0.0367701 -0.019 0.0479188 0.00279095 -0.019 0.0513252 0.00578297 -0.019 -0.024 -0.0415692 -0.019 -0.0263764 -0.0401034 -0.019 -0.0274795 -0.0437333 -0.019 0.048 0 -0.019 0.0515687 -0.00289604 -0.019 0.05165 -1.58133e-17 -0.019 -0.0190118 -0.0440744 -0.019 -0.0197656 -0.0477184 -0.019 -0.016417 -0.0451052 -0.019 0.0467062 -0.0110696 -0.019 0.0459835 -0.0137666 -0.019 0.0496314 -0.0142986 -0.019 -0.00833511 -0.0472708 -0.019 -0.0114932 -0.050355 -0.019 -0.0086517 -0.0509202 -0.019 0.0415692 -0.024 -0.019 0.0437333 -0.0274795 -0.019 0.0452053 -0.0249841 -0.019 -0.00289604 -0.0515687 -0.019 -3.16265e-18 -0.05165 -0.019 -2.2198e-16 -0.048 -0.019 0.0349139 -0.0329396 -0.019 0.0385124 -0.0344168 -0.019 0.0367701 -0.0308538 -0.019 0.0086517 -0.0509202 -0.019 0.00833511 -0.0472708 -0.019 0.00557246 -0.0476754 -0.019 0.0322032 -0.0403816 -0.019 0.0308538 -0.0367701 -0.019 0.0286636 -0.0385019 -0.019 0.016417 -0.0451052 -0.019 0.0137666 -0.0459835 -0.019 0.0170589 -0.0487516 -0.019 0.0298884 -0.0421237 -0.019 0.0263764 -0.0401034 -0.019 0.0249841 -0.0452053 -0.019 0.024 -0.0415692 -0.019 0.0215424 -0.0428944 -0.019 0.0274795 -0.0437333 -0.019 0.0190118 -0.0440744 -0.019 0.0197656 -0.0477184 -0.019 0.0224101 -0.046535 -0.019 0.0329396 -0.0349139 -0.019 0.0365221 -0.0365221 -0.019 0.0344168 -0.0385124 -0.019 0.0114932 -0.050355 -0.019 0.0110696 -0.0467062 -0.019 0.0142986 -0.0496314 -0.019 0.0421237 -0.0298884 -0.019 0.0401034 -0.0263764 -0.019 0.0385019 -0.0286636 -0.019 0.0403816 -0.0322032 -0.019 0.00289604 -0.0515687 -0.019 0.00279095 -0.0479188 -0.019 0.00578297 -0.0513252 -0.019 0.0451052 -0.016417 -0.019 0.0477184 -0.0197656 -0.019 0.0487516 -0.0170589 -0.019 0.0440744 -0.0190118 -0.019 0.0428944 -0.0215424 -0.019 0.046535 -0.0224101 -0.019 -0.00557246 -0.0476754 -0.019 -0.00578297 -0.0513252 -0.019 -0.00279095 -0.0479188 -0.019 0.0479188 -0.00279095 -0.019 0.0476754 -0.00557246 -0.019 0.0513252 -0.00578297 -0.019 0.0509202 -0.0086517 -0.019 0.0472708 -0.00833511 -0.019 0.050355 -0.0114932 -0.019 -0.0142986 -0.0496314 -0.019 -0.0110696 -0.0467062 -0.019 -0.0137666 -0.0459835 -0.019 0.0515687 0.00289604 -0.019 -0.0170589 -0.0487516 -0.019 -0.0215424 -0.0428944 -0.019 -0.0249841 -0.0452053 -0.019 -0.0224101 -0.046535 -0.019 -0.0286636 -0.0385019 -0.019 -0.0298884 -0.0421237 -0.019 -0.0322032 -0.0403816 -0.019 -0.0365221 -0.0365221 -0.019 -0.0349139 -0.0329396 -0.019 0.0467062 0.0110696 -0.019 0.0496314 0.0142986 -0.019 0.0477184 0.0197656 -0.019 0.0440744 0.0190118 -0.019 -0.0385124 -0.0344168 -0.019 -0.0401034 -0.0263764 -0.019 -0.0421237 -0.0298884 -0.019 0.046535 0.0224101 -0.019 0.0437333 0.0274795 -0.019 0.0401034 0.0263764 -0.019 -0.0437333 -0.0274795 -0.019 -0.0440744 -0.0190118 -0.019 -0.046535 -0.0224101 -0.019 0.0421237 0.0298884 -0.019 -0.0477184 -0.0197656 -0.019 0.0365221 0.0365221 -0.019 0.0349139 0.0329396 -0.019 0.0385124 0.0344168 -0.019 -0.050355 -0.0114932 -0.019 -0.0467062 -0.0110696 -0.019 -0.0496314 -0.0142986 -0.019 0.0286636 0.0385019 -0.019 0.0298884 0.0421237 -0.019 0.0322032 0.0403816 -0.019 -0.0515687 -0.00289604 -0.019 -0.0479188 -0.00279095 -0.019 -0.0513252 -0.00578297 -0.019 0.0215424 0.0428944 -0.019 0.0224101 0.046535 -0.019 0.0249841 0.0452053 -0.019 -0.0513252 0.00578297 -0.019 -0.0476754 0.00557246 -0.019 -0.0479188 0.00279095 -0.019 0.0142986 0.0496314 -0.019 0.0137666 0.0459835 -0.019 0.0170589 0.0487516 -0.019 -0.024 0.0415692 -0.0358 -0.0263764 0.0401034 -0.0358 -0.0015 0.00259808 -0.0358 -0.00192836 -0.00229813 -0.0358 -0.0286636 -0.0385019 -0.0358 -0.0015 -0.00259808 -0.0358 -0.0215424 0.0428944 -0.0358 -0.0190118 0.0440744 -0.0358 -0.00192836 0.00229813 -0.0358 -0.00102606 0.00281908 -0.0358 -0.0286636 0.0385019 -0.0358 -0.0308538 0.0367701 -0.0358 -0.0137666 0.0459835 -0.0358 -0.016417 0.0451052 -0.0358 -0.0349139 0.0329396 -0.0358 -0.0329396 0.0349139 -0.0358 -0.0110696 0.0467062 -0.0358 -0.000520945 0.00295442 -0.0358 -0.00229813 0.00192836 -0.0358 -0.00833511 0.0472708 -0.0358 -0.0367701 0.0308538 -0.0358 -0.0385019 0.0286636 -0.0358 -0.00279095 0.0479188 -0.0358 -0.00557246 0.0476754 -0.0358 -0.00259808 0.0015 -0.0358 -0.0401034 0.0263764 -0.0358 -8.81746e-18 0.048 -0.0358 -3.14697e-18 0.003 -0.0358 -0.0415692 0.024 -0.0358 -0.0428944 0.0215424 -0.0358 -0.0440744 0.0190118 -0.0358 -0.0451052 0.016417 -0.0358 -0.00281908 0.00102606 -0.0358 0.00279095 0.0479188 -0.0358 -0.0459835 0.0137666 -0.0358 0.000520945 0.00295442 -0.0358 0.00557246 0.0476754 -0.0358 -0.0467062 0.0110696 -0.0358 -0.00295442 0.000520945 -0.0358 0.0110696 0.0467062 -0.0358 0.00833511 0.0472708 -0.0358 -0.0472708 0.00833511 -0.0358 -0.0476754 0.00557246 -0.0358 0.0137666 0.0459835 -0.0358 -0.0479188 0.00279095 -0.0358 0.00102606 0.00281908 -0.0358 0.016417 0.0451052 -0.0358 -0.048 5.8783e-18 -0.0358 -0.0479188 -0.00279095 -0.0358 -0.003 2.8473e-18 -0.0358 0.0190118 0.0440744 -0.0358 0.0215424 0.0428944 -0.0358 -0.0472708 -0.00833511 -0.0358 -0.00295442 -0.000520945 -0.0358 -0.0476754 -0.00557246 -0.0358 0.0263764 0.0401034 -0.0358 0.0015 0.00259808 -0.0358 0.0286636 0.0385019 -0.0358 -0.0459835 -0.0137666 -0.0358 -0.00281908 -0.00102606 -0.0358 0.00192836 0.00229813 -0.0358 0.0349139 0.0329396 -0.0358 0.0329396 0.0349139 -0.0358 -0.0428944 -0.0215424 -0.0358 -0.0440744 -0.0190118 -0.0358 0.0385019 0.0286636 -0.0358 0.00229813 0.00192836 -0.0358 0.00259808 0.0015 -0.0358 -0.0401034 -0.0263764 -0.0358 -0.0385019 -0.0286636 -0.0358 -0.00259808 -0.0015 -0.0358 0.00281908 0.00102606 -0.0358 0.0428944 0.0215424 -0.0358 -0.0349139 -0.0329396 -0.0358 -0.00229813 -0.00192836 -0.0358 -0.0367701 -0.0308538 -0.0358 0.0459835 0.0137666 -0.0358 0.00295442 0.000520945 -0.0358 0.0467062 0.0110696 -0.0358 -0.0329396 -0.0349139 -0.0358 -0.0308538 -0.0367701 -0.0358 0.003 3.2147e-18 -0.0358 0.0479188 0.00279095 -0.0358 0.0476754 0.00557246 -0.0358 -0.0263764 -0.0401034 -0.0358 0.0476754 -0.00557246 -0.0358 0.0479188 -0.00279095 -0.0358 0.00295442 -0.000520945 -0.0358 -0.00102606 -0.00281908 -0.0358 -0.0215424 -0.0428944 -0.0358 0.0467062 -0.0110696 -0.0358 0.00281908 -0.00102606 -0.0358 0.0459835 -0.0137666 -0.0358 -0.0137666 -0.0459835 -0.0358 -0.000520945 -0.00295442 -0.0358 0.0440744 -0.0190118 -0.0358 0.00259808 -0.0015 -0.0358 0.0428944 -0.0215424 -0.0358 -0.00557246 -0.0476754 -0.0358 2.11344e-18 -0.003 -0.0358 0.0401034 -0.0263764 -0.0358 0.00229813 -0.00192836 -0.0358 0.0385019 -0.0286636 -0.0358 0.000520945 -0.00295442 -0.0358 0.00279095 -0.0479188 -0.0358 0.0349139 -0.0329396 -0.0358 0.00192836 -0.00229813 -0.0358 0.0329396 -0.0349139 -0.0358 0.0110696 -0.0467062 -0.0358 0.00102606 -0.00281908 -0.0358 0.0263764 -0.0401034 -0.0358 0.0015 -0.00259808 -0.0358 0.0137666 -0.0459835 -0.0358 0.016417 -0.0451052 -0.0358 0.0190118 -0.0440744 -0.0358 0.024 -0.0415692 -0.0358 0.0215424 -0.0428944 -0.0358 0.00557246 -0.0476754 -0.0358 0.00833511 -0.0472708 -0.0358 0.0308538 -0.0367701 -0.0358 0.0286636 -0.0385019 -0.0358 -0.00279095 -0.0479188 -0.0358 2.93915e-18 -0.048 -0.0358 0.0367701 -0.0308538 -0.0358 -0.0110696 -0.0467062 -0.0358 -0.00833511 -0.0472708 -0.0358 0.0415692 -0.024 -0.0358 -0.0190118 -0.0440744 -0.0358 -0.016417 -0.0451052 -0.0358 0.0451052 -0.016417 -0.0358 -0.024 -0.0415692 -0.0358 0.0472708 -0.00833511 -0.0358 0.048 0 -0.0358 0.0472708 0.00833511 -0.0358 0.0451052 0.016417 -0.0358 -0.0415692 -0.024 -0.0358 0.0415692 0.024 -0.0358 -0.0451052 -0.016417 -0.0358 0.0401034 0.0263764 -0.0358 0.0367701 0.0308538 -0.0358 -0.0467062 -0.0110696 -0.0358 0.0308538 0.0367701 -0.0358 0.0440744 0.0190118 -0.0358 0.024 0.0415692 -0.0358 0.00634989 -0.05065 -0.0304518 0.00634499 -0.0512588 -0.0307023 0.00630334 -0.0512641 -0.0296816 -0.000510302 -0.0516475 -0.0367795 0.000513787 -0.0516473 -0.0367792 7.77651e-19 -0.05065 -0.0368 0.00609781 -0.0512888 -0.0286782 0.00627199 -0.05065 -0.0294583 0.00573528 -0.0513307 -0.0277244 0.00603963 -0.05065 -0.0284893 0.0056585 -0.05065 -0.0275685 0.00522308 -0.0513853 -0.0268386 0.00457797 -0.0514467 -0.0260495 0.00513798 -0.05065 -0.0267186 0.00381202 -0.0515091 -0.0253715 0.00449089 -0.05065 -0.0259607 0.00373316 -0.05065 -0.0253133 0.00295015 -0.0515656 -0.0248269 0.00200804 -0.0516109 -0.0244259 0.00288346 -0.05065 -0.0247924 0.00101727 -0.05164 -0.024182 0.00196271 -0.05065 -0.0244109 0.000993594 -0.05065 -0.0241782 -9.48795e-18 -0.05165 -0.0241 0 -0.05065 -0.0241 0.00627141 -0.05065 -0.0314451 0.0062219 -0.051274 -0.0317191 0.00549969 -0.0513564 -0.0336242 0.00513614 -0.05065 -0.0341837 0.00491994 -0.0514151 -0.0344646 0.00593792 -0.0513075 -0.0327003 0.00565695 -0.05065 -0.0333344 0.00603851 -0.05065 -0.032414 0.00448892 -0.05065 -0.0349411 0.00421276 -0.0514779 -0.0352013 0.00373125 -0.05065 -0.035588 0.00339655 -0.0515382 -0.0358153 0.00249251 -0.0515897 -0.0362904 0.00288179 -0.05065 -0.0361083 0.00196146 -0.05065 -0.0364894 0.00152244 -0.0516276 -0.0366148 0.000993594 -0.05065 -0.0367218 -0.00248979 -0.0515899 -0.0362915 -0.00196271 -0.05065 -0.0364891 -0.00288346 -0.05065 -0.0361076 -0.00151864 -0.0516275 -0.0366157 -0.000993594 -0.05065 -0.0367218 -0.00513798 -0.05065 -0.0341814 -0.00491703 -0.0514154 -0.0344681 -0.00449089 -0.05065 -0.0349393 -0.00373316 -0.05065 -0.0355867 -0.00421084 -0.0514781 -0.035203 -0.00339301 -0.0515384 -0.0358175 -0.00603963 -0.05065 -0.0324107 -0.00622141 -0.051274 -0.0317214 -0.00593607 -0.0513078 -0.0327051 -0.0056585 -0.05065 -0.0333315 -0.00549847 -0.0513565 -0.0336264 -0.00634989 -0.05065 -0.0304482 -0.00627141 -0.05065 -0.0294549 -0.00630362 -0.051264 -0.0296839 -0.00627199 -0.05065 -0.0314417 -0.00634476 -0.0512589 -0.0307079 -0.00448892 -0.05065 -0.0259589 -0.00381612 -0.0515088 -0.0253746 -0.00457949 -0.0514466 -0.0260511 -0.00565695 -0.05065 -0.0275656 -0.00573624 -0.0513306 -0.0277264 -0.00603851 -0.05065 -0.028486 -0.00295222 -0.0515655 -0.024828 -0.00373125 -0.05065 -0.025312 -0.00288179 -0.05065 -0.0247917 -0.00201277 -0.0516108 -0.0244274 -0.00101951 -0.0516398 -0.0241824 -0.000993594 -0.05065 -0.0241782 -0.00196146 -0.05065 -0.0244106 -0.00522611 -0.0513849 -0.026843 -0.00513614 -0.05065 -0.0267163 -0.00609938 -0.0512886 -0.0286836 0 -0.05065 -0.0241 0.00565695 -0.05065 -0.0333344 0.00603851 -0.05065 -0.032414 0.00196271 -0.05065 -0.0244109 0.00634989 -0.05065 -0.0304518 0.00288346 -0.05065 -0.0247924 0.00373316 -0.05065 -0.0253133 0.00627199 -0.05065 -0.0294583 0.00627141 -0.05065 -0.0314451 0.0056585 -0.05065 -0.0275685 0.00513798 -0.05065 -0.0267186 0.00449089 -0.05065 -0.0259607 0.00603963 -0.05065 -0.0284893 0.000993594 -0.05065 -0.0241782 -0.000993594 -0.05065 -0.0241782 0.00513614 -0.05065 -0.0341837 -0.00196146 -0.05065 -0.0244106 -0.00288179 -0.05065 -0.0247917 0.00448892 -0.05065 -0.0349411 -0.00373125 -0.05065 -0.025312 0.00373125 -0.05065 -0.035588 0.00288179 -0.05065 -0.0361083 0.00196146 -0.05065 -0.0364894 -0.00448892 -0.05065 -0.0259589 -0.00513614 -0.05065 -0.0267163 0.000993594 -0.05065 -0.0367218 -0.00565695 -0.05065 -0.0275656 -0.00603851 -0.05065 -0.028486 7.77651e-19 -0.05065 -0.0368 -0.00196271 -0.05065 -0.0364891 -0.00634989 -0.05065 -0.0304482 -0.00288346 -0.05065 -0.0361076 -0.00627141 -0.05065 -0.0294549 -0.000993594 -0.05065 -0.0367218 -0.00449089 -0.05065 -0.0349393 -0.0056585 -0.05065 -0.0333315 -0.00513798 -0.05065 -0.0341814 -0.00603963 -0.05065 -0.0324107 -0.00373316 -0.05065 -0.0355867 -0.00627199 -0.05065 -0.0314417 2.11344e-18 -0.003 -0.0358 0.000520945 -0.00295442 -0.0378 -5.51091e-19 -0.003 -0.0378 -0.003 2.8473e-18 -0.0378 -0.00295442 0.000520945 -0.0358 -0.003 2.8473e-18 -0.0358 0.00102606 -0.00281908 -0.0378 0.000520945 -0.00295442 -0.0358 0.00102606 -0.00281908 -0.0358 0.0015 -0.00259808 -0.0378 0.0015 -0.00259808 -0.0358 0.00192836 -0.00229813 -0.0378 0.00229813 -0.00192836 -0.0378 0.00192836 -0.00229813 -0.0358 0.00229813 -0.00192836 -0.0358 0.00259808 -0.0015 -0.0378 0.00259808 -0.0015 -0.0358 0.00281908 -0.00102606 -0.0378 0.00295442 -0.000520945 -0.0378 0.00281908 -0.00102606 -0.0358 0.00295442 -0.000520945 -0.0358 0.003 3.81218e-18 -0.0378 0.003 3.2147e-18 -0.0358 -0.000520945 -0.00295442 -0.0358 -0.000520945 -0.00295442 -0.0378 -0.00102606 -0.00281908 -0.0358 -0.00102606 -0.00281908 -0.0378 -0.0015 -0.00259808 -0.0358 -0.00192836 -0.00229813 -0.0358 -0.0015 -0.00259808 -0.0378 -0.00192836 -0.00229813 -0.0378 -0.00229813 -0.00192836 -0.0358 -0.00229813 -0.00192836 -0.0378 -0.00259808 -0.0015 -0.0358 -0.00281908 -0.00102606 -0.0358 -0.00259808 -0.0015 -0.0378 -0.00281908 -0.00102606 -0.0378 -0.00295442 -0.000520945 -0.0358 -0.00295442 -0.000520945 -0.0378 -0.00281908 0.00102606 -0.0378 -0.00281908 0.00102606 -0.0358 -0.00295442 0.000520945 -0.0378 -0.00192836 0.00229813 -0.0378 -0.00192836 0.00229813 -0.0358 -0.00229813 0.00192836 -0.0378 -0.00259808 0.0015 -0.0378 -0.00229813 0.00192836 -0.0358 -0.00259808 0.0015 -0.0358 -0.00102606 0.00281908 -0.0378 -0.000520945 0.00295442 -0.0378 -0.000520945 0.00295442 -0.0358 -0.0015 0.00259808 -0.0358 -0.0015 0.00259808 -0.0378 -0.00102606 0.00281908 -0.0358 0.00102606 0.00281908 -0.0358 0.000520945 0.00295442 -0.0378 0.00102606 0.00281908 -0.0378 0.000520945 0.00295442 -0.0358 -3.14697e-18 0.003 -0.0358 1.83697e-19 0.003 -0.0378 0.00229813 0.00192836 -0.0378 0.00229813 0.00192836 -0.0358 0.00192836 0.00229813 -0.0378 0.0015 0.00259808 -0.0378 0.00192836 0.00229813 -0.0358 0.0015 0.00259808 -0.0358 0.00259808 0.0015 -0.0358 0.00259808 0.0015 -0.0378 0.00281908 0.00102606 -0.0378 0.00281908 0.00102606 -0.0358 0.00295442 0.000520945 -0.0378 0.00295442 0.000520945 -0.0358 - - - - - - - - - - 1.19249e-08 -1 0 0.019695 -0.999806 0 0.0560705 -0.998427 0 -1 -8.74228e-08 0 -1 -8.74228e-08 0 -0.998427 0.0560704 0 0.0388749 -0.999244 0 0.0571155 -0.998368 0 1.19249e-08 -1 0 0.111965 -0.993712 0 0.111033 -0.993817 0 0.118057 -0.993007 0 0.0738011 -0.997273 0 0.167506 -0.985871 0 0.222521 -0.974928 0 0.167506 -0.985871 0 0.122029 -0.992527 0 0.222521 -0.974928 0 0.276836 -0.960917 0 0.330279 -0.943883 0 0.276835 -0.960917 0 0.382684 -0.923879 0 0.330279 -0.943883 0 0.382684 -0.923879 0 0.433884 -0.900969 0 0.483719 -0.875224 0 0.433883 -0.900969 0 0.532032 -0.846724 0 0.483719 -0.875223 0 0.532032 -0.846724 0 0.578671 -0.815561 0 0.62349 -0.781831 0 0.578672 -0.815561 0 0.666346 -0.745642 0 0.62349 -0.781832 0 0.666346 -0.745642 0 0.707107 -0.707107 0 0.745642 -0.666346 0 0.707107 -0.707107 0 0.781831 -0.62349 0 0.745642 -0.666347 0 0.781831 -0.62349 0 0.815561 -0.578671 0 0.846724 -0.532032 0 0.815561 -0.578671 0 0.875223 -0.483719 0 0.846724 -0.532032 0 0.875223 -0.483719 0 0.900969 -0.433884 0 0.92388 -0.382683 0 0.900969 -0.433884 0 0.943883 -0.330279 0 0.92388 -0.382683 0 0.943883 -0.330279 0 0.960917 -0.276835 0 0.974928 -0.222521 0 0.960917 -0.276835 0 0.985871 -0.167506 0 0.974928 -0.222521 0 0.985871 -0.167506 0 0.993712 -0.111964 0 0.998427 -0.0560708 0 0.993712 -0.111965 0 1 1.74846e-07 0 0.998427 -0.0560703 0 1 1.74846e-07 0 -0.057153 -0.998365 0 -0.0389692 -0.99924 0 -0.0560705 -0.998427 0 -0.101182 -0.994868 0 -0.0886557 -0.996062 0 -0.111965 -0.993712 0 -0.00988037 -0.999951 0 1.19249e-08 -1 0 0.00994667 -0.999951 0 -0.114922 -0.993375 0 -0.111965 -0.993712 0 -0.106451 -0.994318 0 -0.0482038 -0.998838 0 -0.065687 -0.99784 0 -0.0560705 -0.998427 0 -0.167506 -0.985871 0 -0.167506 -0.985871 0 -0.222521 -0.974928 0 -0.120446 -0.99272 0 -0.276836 -0.960917 0 -0.222521 -0.974928 0 -0.330279 -0.943883 0 -0.276836 -0.960917 0 -0.330279 -0.943883 0 -0.382683 -0.92388 0 -0.433884 -0.900969 0 -0.382684 -0.92388 0 -0.483719 -0.875223 0 -0.433884 -0.900969 0 -0.483719 -0.875224 0 -0.532032 -0.846724 0 -0.578672 -0.815561 0 -0.532032 -0.846724 0 -0.62349 -0.781832 0 -0.578671 -0.815561 0 -0.62349 -0.781831 0 -0.666347 -0.745642 0 -0.707107 -0.707107 0 -0.666346 -0.745642 0 -0.745642 -0.666346 0 -0.707107 -0.707107 0 -0.745642 -0.666346 0 -0.781832 -0.62349 0 -0.815561 -0.578671 0 -0.781831 -0.62349 0 -0.846724 -0.532032 0 -0.815561 -0.578671 0 -0.846724 -0.532032 0 -0.875223 -0.483719 0 -0.900969 -0.433884 0 -0.875223 -0.483719 0 -0.923879 -0.382684 0 -0.900969 -0.433884 0 -0.92388 -0.382683 0 -0.943883 -0.330279 0 -0.960917 -0.276835 0 -0.943883 -0.330279 0 -0.974928 -0.222521 0 -0.960917 -0.276835 0 -0.974928 -0.222521 0 -0.985871 -0.167506 0 -0.993712 -0.111965 0 -0.985871 -0.167506 0 -0.998427 -0.0560703 0 -0.993712 -0.111964 0 -0.998427 -0.0560706 0 -0.993712 0.111964 0 -0.998427 0.0560704 0 -0.993712 0.111964 0 -0.960917 0.276836 0 -0.974928 0.222521 0 -0.960917 0.276836 0 -0.985871 0.167506 0 -0.985871 0.167506 0 -0.974928 0.222521 0 -0.92388 0.382683 0 -0.900969 0.433884 0 -0.900969 0.433884 0 -0.943883 0.330279 0 -0.92388 0.382683 0 -0.943883 0.330279 0 -0.815561 0.578671 0 -0.815561 0.578671 0 -0.846724 0.532032 0 -0.846724 0.532032 0 -0.875223 0.483719 0 -0.875223 0.483719 0 -0.707107 0.707107 0 -0.745642 0.666347 0 -0.707107 0.707107 0 -0.781832 0.62349 0 -0.781831 0.62349 0 -0.745642 0.666347 0 -0.62349 0.781832 0 -0.578671 0.815561 0 -0.578671 0.815561 0 -0.666347 0.745642 0 -0.62349 0.781832 0 -0.666347 0.745642 0 -0.433884 0.900969 0 -0.433884 0.900969 0 -0.483719 0.875223 0 -0.483719 0.875223 0 -0.532032 0.846724 0 -0.532032 0.846724 0 -0.276836 0.960917 0 -0.330279 0.943883 0 -0.276836 0.960917 0 -0.382683 0.92388 0 -0.382683 0.92388 0 -0.330279 0.943883 0 -0.167506 0.985871 0 -0.111964 0.993712 0 -0.111964 0.993712 0 -0.222521 0.974928 0 -0.167506 0.985871 0 -0.222521 0.974928 0 0.0560704 0.998427 0 0.0560704 0.998427 0 -4.37114e-08 1 0 7.54979e-08 1 0 -0.0560704 0.998427 0 -0.0560704 0.998427 0 0.222521 0.974928 0 0.167506 0.985871 0 0.222521 0.974928 0 0.111964 0.993712 0 0.111964 0.993712 0 0.167506 0.985871 0 0.330279 0.943883 0 0.382683 0.92388 0 0.382683 0.92388 0 0.276835 0.960917 0 0.330279 0.943883 0 0.276835 0.960917 0 0.532032 0.846724 0 0.532032 0.846724 0 0.483719 0.875223 0 0.483719 0.875223 0 0.433884 0.900969 0 0.433884 0.900969 0 0.666347 0.745642 0 0.62349 0.781832 0 0.666347 0.745642 0 0.578671 0.815561 0 0.578671 0.815561 0 0.62349 0.781832 0 0.745642 0.666347 0 0.707107 0.707107 0 0.745642 0.666347 0 0.707107 0.707107 0 0.781831 0.62349 0 0.781831 0.62349 0 0.815561 0.578671 0 0.815561 0.578671 0 0.846724 0.532032 0 0.846724 0.532032 0 0.875223 0.483719 0 0.875223 0.483719 0 0.900969 0.433884 0 0.900969 0.433884 0 0.92388 0.382683 0 0.92388 0.382683 0 0.943883 0.330279 0 0.943883 0.330279 0 0.960917 0.276836 0 0.960917 0.276836 0 0.974928 0.222521 0 0.974928 0.222521 0 0.985871 0.167506 0 0.985871 0.167506 0 0.993712 0.111964 0 0.993712 0.111964 0 0.998427 0.0560705 0 0.998427 0.0560705 0 -0.0293999 -0.999568 0 0.0657608 -0.997835 0 0.0482534 -0.998835 0 0.0560705 -0.998427 0 0.111965 -0.993712 0 0.10647 -0.994316 0 0.0952552 -0.995453 0 0.0886292 -0.996065 0 0.10112 -0.994874 0 0.114964 -0.99337 0 0.120451 -0.992719 0 0.122844 -0.992426 0 0.0815558 -0.996669 0 0.0294757 -0.999565 0 -0.0197369 -0.999805 0 -0.0738838 -0.997267 0 -0.0815234 -0.996671 0 -0.11105 -0.993815 0 -0.095193 -0.995459 0 -0.118087 -0.993003 0 -0.122836 -0.992427 0 -0.122036 -0.992526 0 -0.998308 -0.0581448 -0 -1 -2.77848e-23 -0 -1 4.59146e-13 0 -0.973045 -0.230616 -0 -0.984808 -0.173648 -0 -0.984808 -0.173648 -0 -0.993238 -0.116093 -0 -0.998308 -0.0581448 -0 -0.993238 -0.116093 -0 -0.939693 -0.34202 -0 -0.918216 -0.39608 -0 -0.939693 -0.34202 -0 -0.973045 -0.230616 -0 -0.95799 -0.286803 -0 -0.95799 -0.286803 -0 -0.866025 -0.5 -0 -0.866025 -0.5 -0 -0.835488 -0.549509 -0 -0.893633 -0.448799 -0 -0.918216 -0.39608 -0 -0.893633 -0.448799 -0 -0.727374 -0.686242 -0 -0.766044 -0.642788 -0 -0.766044 -0.642788 -0 -0.802123 -0.597159 -0 -0.802123 -0.597159 -0 -0.835488 -0.549509 -0 -0.642788 -0.766044 -0 -0.597159 -0.802123 -0 -0.642788 -0.766044 -0 -0.727374 -0.686242 -0 -0.686242 -0.727374 -0 -0.686242 -0.727374 -0 -0.5 -0.866025 -0 -0.5 -0.866025 -0 -0.448799 -0.893633 -0 -0.549509 -0.835488 -0 -0.597159 -0.802123 -0 -0.549509 -0.835488 -0 -0.286803 -0.95799 -0 -0.34202 -0.939693 -0 -0.34202 -0.939693 -0 -0.39608 -0.918216 -0 -0.39608 -0.918216 -0 -0.448799 -0.893633 -0 -0.173648 -0.984808 -0 -0.116093 -0.993238 -0 -0.173648 -0.984808 -0 -0.286803 -0.95799 -0 -0.230616 -0.973045 -0 -0.230616 -0.973045 -0 4.37114e-08 -1 0 -7.54979e-08 -1 -0 0.0581448 -0.998308 0 -0.0581449 -0.998308 -0 -0.116093 -0.993238 -0 -0.0581449 -0.998308 -0 0.230616 -0.973045 0 0.173648 -0.984808 0 0.173648 -0.984808 0 0.116093 -0.993238 0 0.116093 -0.993238 0 0.0581449 -0.998308 0 0.34202 -0.939693 0 0.39608 -0.918216 0 0.34202 -0.939693 0 0.230616 -0.973045 0 0.286803 -0.95799 0 0.286803 -0.95799 0 0.5 -0.866025 0 0.5 -0.866025 0 0.549509 -0.835488 0 0.448799 -0.893633 0 0.39608 -0.918216 0 0.448799 -0.893633 0 0.686242 -0.727374 0 0.642788 -0.766044 0 0.642788 -0.766044 0 0.597159 -0.802123 0 0.597159 -0.802123 0 0.549509 -0.835488 0 0.766044 -0.642788 0 0.802123 -0.597159 0 0.766044 -0.642788 0 0.686242 -0.727374 0 0.727374 -0.686242 0 0.727374 -0.686242 0 0.866025 -0.5 0 0.866025 -0.5 0 0.893633 -0.448799 0 0.835488 -0.549509 0 0.802123 -0.597159 0 0.835488 -0.549509 0 0.95799 -0.286803 0 0.939693 -0.34202 0 0.939693 -0.34202 0 0.918216 -0.39608 0 0.918216 -0.39608 0 0.893633 -0.448799 0 0.984808 -0.173648 0 0.993238 -0.116093 0 0.984808 -0.173648 0 0.95799 -0.286803 0 0.973045 -0.230616 0 0.973045 -0.230616 0 1 8.74228e-08 0 1 8.74228e-08 0 0.998308 0.058145 0 0.998308 -0.0581448 0 0.993238 -0.116093 0 0.998308 -0.0581448 0 0.973045 0.230616 0 0.984808 0.173648 0 0.984808 0.173648 0 0.993238 0.116093 0 0.993238 0.116093 0 0.998308 0.0581447 0 0.939693 0.34202 0 0.918216 0.39608 0 0.939693 0.34202 0 0.973045 0.230616 0 0.957989 0.286803 0 0.95799 0.286803 0 0.866025 0.5 0 0.866025 0.5 0 0.835488 0.549509 0 0.893633 0.448799 0 0.918216 0.39608 0 0.893633 0.448799 0 0.727374 0.686242 0 0.766044 0.642788 0 0.766044 0.642788 0 0.802123 0.597158 0 0.802123 0.597159 0 0.835488 0.549509 0 0.642788 0.766045 0 0.597159 0.802123 0 0.642788 0.766045 0 0.727374 0.686241 0 0.686242 0.727374 0 0.686242 0.727374 0 0.5 0.866025 0 0.5 0.866025 0 0.448799 0.893633 0 0.549509 0.835488 0 0.597159 0.802123 0 0.549509 0.835488 0 0.286803 0.95799 0 0.342021 0.939692 0 0.34202 0.939693 0 0.39608 0.918216 0 0.39608 0.918216 0 0.448799 0.893633 0 0.173648 0.984808 0 0.116093 0.993238 0 0.173648 0.984808 0 0.286803 0.95799 0 0.230616 0.973045 0 0.230616 0.973045 0 0.0581451 0.998308 0 0.116093 0.993238 0 0.0581446 0.998308 0 -1.19249e-08 1 0 -0.0581447 0.998308 0 -0.0581451 0.998308 0 -1.19249e-08 1 0 -0.116093 0.993238 0 -0.116093 0.993238 0 -0.173648 0.984808 0 -0.173648 0.984808 0 -0.230616 0.973045 0 -0.230616 0.973045 0 -0.286803 0.957989 0 -0.286803 0.957989 0 -0.34202 0.939693 0 -0.34202 0.939693 0 -0.39608 0.918216 0 -0.39608 0.918216 0 -0.448799 0.893633 0 -0.448799 0.893633 0 -0.5 0.866025 0 -0.5 0.866025 0 -0.549509 0.835488 0 -0.549509 0.835488 0 -0.597159 0.802123 0 -0.597159 0.802123 0 -0.642788 0.766044 0 -0.642788 0.766044 0 -0.686241 0.727374 0 -0.686242 0.727374 0 -0.727374 0.686242 0 -0.727374 0.686242 0 -0.766044 0.642788 0 -0.766045 0.642787 0 -0.802123 0.597158 0 -0.802123 0.597159 0 -0.835488 0.549509 0 -0.835488 0.549509 0 -0.866026 0.5 0 -0.866025 0.5 0 -0.893633 0.448799 0 -0.893633 0.448799 0 -0.918216 0.39608 0 -0.918216 0.39608 0 -0.939693 0.34202 0 -0.939693 0.34202 0 -0.95799 0.286803 0 -0.95799 0.286803 0 -0.973045 0.230616 0 -0.973045 0.230616 0 -0.984808 0.173648 0 -0.984808 0.173648 0 -0.993238 0.116093 0 -0.993238 0.116093 0 -0.998308 0.058145 0 -0.998308 0.058145 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -1 0 4.37114e-08 -0.99921 0 0.0397317 -0.992652 -0 -0.121007 0.0803624 0 0.996766 -0.0809112 0 0.996721 -1.50996e-07 0 1 -0.960285 -0 -0.27902 -0.987688 -0 -0.156434 -0.903194 -0 -0.429232 -0.951056 -0 -0.309017 -0.891007 -0 -0.453991 -0.822532 -0 -0.568719 -0.720941 -0 -0.692997 -0.809017 -0 -0.587785 -0.600317 -0 -0.799762 -0.707107 -0 -0.707107 -0.587785 -0 -0.809017 -0.46459 -0 -0.885526 -0.316227 -0 -0.948684 -0.453991 -0 -0.891007 -0.1602 -0 -0.987085 -0.309017 -0 -0.951057 -0.156434 -0 -0.987688 -3.33067e-15 -0 -1 8.22891e-12 0 -1 -0.987688 0 0.156435 -0.979826 0 0.199852 -0.866094 0 0.499882 -0.809017 0 0.587785 -0.774794 0 0.632213 -0.935105 0 0.354371 -0.891007 0 0.45399 -0.951057 0 0.309017 -0.707107 0 0.707107 -0.663427 0 0.748241 -0.587785 0 0.809017 -0.534889 0 0.844922 -0.392521 0 0.919743 -0.453991 0 0.891006 -0.309017 0 0.951056 -0.239755 0 0.970834 -0.156434 0 0.987688 0.392093 0 0.919926 0.309017 0 0.951057 0.453991 0 0.891006 0.239156 0 0.970981 0.156435 0 0.987688 0.809017 0 0.587785 0.774336 0 0.632775 0.707107 0 0.707107 0.587785 0 0.809017 0.663124 0 0.74851 0.534333 0 0.845274 0.951057 0 0.309017 0.97975 0 0.200226 0.934814 0 0.355138 0.891006 0 0.453991 0.865901 0 0.500216 1 0 -1.19249e-08 0.987688 0 -0.156435 0.992696 0 -0.12064 0.987688 0 0.156435 0.999175 0 0.0406206 0.707107 0 -0.707107 0.600964 0 -0.799276 0.72118 0 -0.692748 0.891006 0 -0.453991 0.903345 0 -0.428916 0.951056 0 -0.309017 0.464917 0 -0.885354 0.587785 0 -0.809017 0.453991 0 -0.891007 0.316972 0 -0.948435 0.160553 0 -0.987027 0.156434 0 -0.987688 0.309017 0 -0.951057 0.82301 0 -0.568027 0.809017 0 -0.587785 0.960533 0 -0.278167 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1.19249e-08 1 0 -0.173648 0.984808 0 -1.19249e-08 1 0 1 8.74228e-08 0 0.984808 -0.173648 0 1 8.74228e-08 0 -0.34202 0.939693 0 -0.173648 0.984808 0 -0.34202 0.939693 0 -0.5 0.866025 0 -0.5 0.866025 0 -0.642788 0.766044 0 -0.766044 0.642788 0 -0.642788 0.766044 0 -0.766044 0.642788 0 -0.866026 0.5 0 -0.866026 0.5 0 -0.939693 0.34202 0 -0.984808 0.173648 0 -0.939693 0.34202 0 -0.984808 0.173648 0 -1 -1.74846e-07 -0 -1 -1.74846e-07 -0 0.173648 0.984808 0 0.173648 0.984808 0 0.34202 0.939693 0 0.342021 0.939692 0 0.5 0.866025 0 0.642788 0.766045 0 0.5 0.866025 0 0.642788 0.766045 0 0.766044 0.642788 0 0.766044 0.642788 0 0.866026 0.5 0 0.939693 0.34202 0 0.866025 0.5 0 0.939693 0.34202 0 0.984808 0.173648 0 0.984808 0.173648 0 0.939693 -0.34202 0 0.939693 -0.34202 0 0.984808 -0.173648 0 0.642788 -0.766044 0 0.642788 -0.766044 0 0.766044 -0.642788 0 0.866025 -0.5 0 0.766044 -0.642788 0 0.866025 -0.5 0 0.34202 -0.939693 0 0.173648 -0.984808 0 0.173648 -0.984808 0 0.5 -0.866025 0 0.5 -0.866025 0 0.34202 -0.939693 0 -0.34202 -0.939693 -0 -0.173648 -0.984808 -0 -0.34202 -0.939693 -0 -0.173648 -0.984808 -0 -7.54979e-08 -1 -0 4.37114e-08 -1 0 -0.766044 -0.642788 -0 -0.766044 -0.642788 -0 -0.642788 -0.766044 -0 -0.5 -0.866025 -0 -0.642788 -0.766044 -0 -0.5 -0.866025 -0 -0.866025 -0.5 -0 -0.866025 -0.5 -0 -0.939693 -0.34202 -0 -0.939693 -0.34202 -0 -0.984808 -0.173648 -0 -0.984808 -0.173648 -0 - - - - - - - - - - - - - - -

0 1 2 3 4 5 6 7 2 0 8 1 9 10 11 12 2 7 13 14 15 11 16 9 17 14 18 14 17 15 19 20 18 17 18 20 19 21 22 22 20 19 23 21 24 21 23 22 25 26 24 23 24 26 25 27 28 28 26 25 29 27 30 27 29 28 31 32 30 29 30 32 31 33 34 34 32 31 35 33 36 33 35 34 37 38 36 35 36 38 37 39 40 40 38 37 41 39 42 39 41 40 43 44 42 41 42 44 43 45 46 46 44 43 47 45 48 45 47 46 49 50 48 47 48 50 49 51 52 52 50 49 53 51 54 51 53 52 55 56 54 53 54 56 55 57 58 58 56 55 59 57 60 57 59 58 61 62 60 59 60 62 61 63 64 64 62 61 63 65 64 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 76 75 84 85 86 83 81 83 86 85 87 88 88 86 85 89 87 90 87 89 88 91 92 90 89 90 92 91 93 94 94 92 91 95 93 96 93 95 94 97 98 96 95 96 98 97 99 100 100 98 97 101 99 102 99 101 100 103 104 102 101 102 104 103 105 106 106 104 103 107 105 108 105 107 106 109 110 108 107 108 110 109 111 112 112 110 109 113 111 114 111 113 112 115 116 114 113 114 116 115 117 118 118 116 115 119 117 120 117 119 118 121 122 120 119 120 122 121 123 124 124 122 121 125 123 126 123 125 124 127 128 126 125 126 128 127 129 130 130 128 127 131 129 4 129 131 130 132 133 134 131 4 3 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 215 214 217 218 213 213 215 217 218 219 220 219 218 217 221 220 222 219 222 220 223 224 221 221 222 223 224 225 226 225 224 223 227 226 228 225 228 226 229 230 227 227 228 229 230 231 232 231 230 229 233 232 234 231 234 232 235 236 233 233 234 235 236 237 238 237 236 235 239 238 240 237 240 238 65 63 239 239 240 65 207 209 216 207 216 214 208 210 212 208 212 209 211 202 201 210 202 211 204 203 205 201 203 204 196 206 197 206 205 197 200 199 195 199 196 195 189 191 198 189 198 200 190 192 194 190 194 191 193 184 183 192 184 193 186 185 187 183 185 186 178 188 179 188 187 179 182 181 177 181 178 177 171 173 180 171 180 182 172 174 176 172 176 173 175 166 165 174 166 175 168 167 169 165 167 168 160 170 161 170 169 161 164 163 159 163 160 159 153 155 162 153 162 164 154 156 158 154 158 155 157 148 147 156 148 157 150 149 151 147 149 150 142 152 143 152 151 143 146 145 141 145 142 141 135 137 144 135 144 146 136 138 140 136 140 137 139 132 134 138 132 139 5 133 3 134 133 5 241 80 73 242 243 244 2 1 6 245 246 247 12 248 2 249 9 248 2 248 9 250 246 245 250 245 251 9 249 10 15 16 252 16 15 9 245 252 251 245 13 252 15 252 13 247 253 245 242 244 253 245 253 244 73 244 254 244 243 254 73 254 74 8 0 255 73 72 241 66 68 256 80 241 78 76 80 257 80 79 257 69 71 258 77 76 259 76 257 259 258 71 260 81 261 82 84 261 76 262 260 71 76 261 81 71 82 262 82 261 262 71 70 68 68 70 256 0 68 255 68 67 255 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 427 428 425 429 430 426 427 426 430 431 429 432 429 431 430 432 433 434 434 431 432 435 436 433 434 433 436 437 435 438 435 437 436 438 439 440 440 437 438 441 442 439 440 439 442 443 441 444 441 443 442 444 445 446 446 443 444 447 448 445 446 445 448 449 447 450 447 449 448 450 451 452 452 449 450 453 454 451 452 451 454 455 453 456 453 455 454 456 457 458 458 455 456 459 460 457 458 457 460 461 459 462 459 461 460 462 463 464 464 461 462 465 466 463 464 463 466 467 465 468 465 467 466 468 469 470 470 467 468 471 472 469 470 469 472 473 471 474 471 473 472 474 475 476 476 473 474 477 478 475 476 475 478 264 477 265 477 264 478 422 424 428 428 424 425 416 423 417 417 423 422 420 418 421 420 416 418 419 410 412 419 421 410 411 414 413 412 411 413 406 405 415 414 406 415 407 409 404 404 409 405 398 408 399 399 408 407 402 400 403 402 398 400 401 392 394 401 403 392 393 396 395 394 393 395 388 387 397 396 388 397 389 391 386 386 391 387 380 390 381 381 390 389 384 382 385 384 380 382 383 374 376 383 385 374 375 378 377 376 375 377 370 369 379 378 370 379 371 373 368 368 373 369 362 372 363 363 372 371 366 364 367 366 362 364 365 356 358 365 367 356 357 360 359 358 357 359 352 351 361 360 352 361 353 355 350 350 355 351 344 354 345 345 354 353 348 346 349 348 344 346 347 338 340 347 349 338 339 342 341 340 339 341 334 333 343 342 334 343 335 337 332 332 337 333 326 336 327 327 336 335 330 328 331 330 326 328 329 320 322 329 331 320 321 324 323 322 321 323 316 315 325 324 316 325 317 319 314 314 319 315 308 318 309 309 318 317 312 310 313 312 308 310 311 302 304 311 313 302 303 306 305 304 303 305 298 297 307 306 298 307 299 301 296 296 301 297 290 300 291 291 300 299 294 292 295 294 290 292 293 284 286 293 295 284 285 288 287 286 285 287 280 279 289 288 280 289 281 283 278 278 283 279 272 282 273 273 282 281 276 274 277 276 272 274 275 266 268 275 277 266 267 269 271 268 267 271 263 265 270 269 263 270 479 480 481 482 483 484 485 486 481 487 480 479 486 485 488 489 490 480 491 492 485 493 494 490 495 491 496 490 494 497 498 496 491 499 490 500 501 502 498 503 499 504 505 506 501 503 507 499 508 507 509 508 509 510 511 505 501 512 508 513 514 511 515 516 512 517 518 515 511 516 519 512 511 520 521 522 519 523 524 525 520 522 526 527 520 528 524 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 539 546 547 548 549 544 550 551 552 553 554 555 556 557 558 551 559 560 561 558 482 484 562 563 564 565 484 566 564 567 568 569 570 565 571 572 567 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 592 591 597 598 599 597 597 591 600 601 595 597 601 597 599 592 587 586 602 593 592 588 595 603 595 594 603 587 581 580 604 585 587 588 605 584 590 605 588 581 575 574 606 579 581 607 577 584 607 584 583 575 565 570 608 573 575 567 577 571 577 576 571 609 565 566 610 569 565 611 568 567 572 611 567 564 568 612 566 484 613 614 482 558 612 562 564 564 563 560 558 557 615 557 551 616 561 560 563 555 560 559 553 617 551 552 618 553 560 555 554 619 550 554 619 554 556 544 554 550 547 541 543 548 547 620 545 544 621 621 544 549 537 536 541 541 622 542 539 623 540 539 545 623 531 537 529 624 535 537 538 533 532 538 532 539 529 522 527 528 532 534 547 546 552 552 546 625 523 526 522 607 578 577 605 582 584 603 589 588 601 596 595 600 598 597 586 602 592 580 604 587 574 606 581 570 608 575 609 610 565 483 613 484 615 614 558 617 616 551 625 618 552 543 620 547 536 622 541 531 624 537 527 626 529 530 529 626 519 522 512 517 512 513 510 513 508 507 508 499 500 504 499 490 497 500 490 489 493 489 480 487 480 485 481 488 485 492 495 492 491 498 491 501 501 506 502 514 505 511 511 521 518 521 520 525 520 532 528 627 628 629 630 631 632 627 633 634 635 636 628 634 637 638 635 639 640 638 641 642 643 639 644 642 645 646 647 648 644 646 649 650 647 651 652 650 653 654 655 651 656 654 657 658 659 660 656 659 661 662 663 664 661 658 665 666 667 663 668 666 669 670 671 668 672 670 673 674 675 676 671 674 677 678 676 679 680 678 681 682 679 683 680 682 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 632 631 722 723 724 725 726 727 630 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 757 762 763 764 765 766 762 764 767 758 768 767 769 765 770 771 749 770 756 772 773 774 753 759 774 775 776 777 778 751 779 778 748 780 781 782 754 781 783 784 785 786 787 788 789 742 790 791 790 746 792 793 794 795 796 797 798 799 800 741 740 799 727 726 801 800 736 802 803 728 804 734 803 805 806 807 729 631 630 727 743 777 744 808 806 725 809 723 810 717 811 812 716 813 814 815 810 720 721 816 817 814 818 710 819 820 712 816 714 821 715 822 823 824 706 820 822 707 825 826 699 827 827 705 828 701 829 830 830 831 708 692 832 833 698 834 832 835 836 695 836 837 702 838 839 688 840 838 694 841 842 690 841 696 843 844 683 845 845 687 846 689 691 685 801 726 731 731 733 801 812 811 722 722 811 632 718 717 812 813 716 718 818 814 813 711 710 818 819 712 711 824 820 819 704 706 824 828 705 704 826 827 828 700 699 826 834 698 700 833 832 834 693 692 833 840 694 693 839 838 840 686 688 839 846 687 686 844 845 846 680 683 844 676 675 679 671 672 675 668 663 672 664 663 667 662 661 664 660 659 662 655 656 660 652 651 655 648 647 652 643 644 648 640 639 643 636 635 640 629 628 636 633 627 629 637 634 633 641 638 637 645 642 641 649 646 645 653 650 649 657 654 653 665 658 657 669 666 665 673 670 669 677 674 673 681 678 677 684 682 681 689 685 684 690 842 691 841 843 842 696 695 843 835 695 697 837 836 835 703 702 837 829 701 703 831 830 829 709 708 831 825 707 709 823 822 825 713 715 823 821 714 713 817 816 821 719 721 817 815 720 719 809 810 815 724 723 809 808 725 724 807 806 808 730 729 807 804 728 730 805 803 804 735 734 805 802 736 735 798 800 802 741 799 798 742 789 740 790 791 789 746 748 791 780 748 747 782 781 780 752 754 782 773 753 752 775 774 773 760 759 775 768 758 760 769 767 768 763 765 769 766 764 763 761 762 766 755 757 761 772 756 755 771 770 772 750 749 771 779 751 750 776 778 779 744 777 776 745 787 743 784 786 788 788 787 745 738 783 785 783 786 784 737 739 797 738 785 739 796 795 793 737 797 796 794 732 792 795 794 793 731 792 732 847 848 849 850 851 852 853 849 854 855 849 848 856 854 849 855 857 858 859 860 856 861 855 862 863 856 864 865 855 861 864 866 863 867 868 865 864 869 870 871 865 872 873 869 874 871 872 875 871 876 877 878 879 877 873 874 880 879 878 881 874 882 883 884 885 879 882 886 887 885 888 889 890 886 882 889 891 885 890 892 893 894 895 896 897 892 898 899 900 901 902 903 904 900 905 906 907 908 909 910 906 911 912 913 914 915 916 917 914 918 919 920 921 922 923 924 925 850 926 927 928 929 930 851 931 852 932 933 934 935 852 936 937 938 939 935 940 941 942 943 944 945 946 941 947 948 949 950 946 951 952 953 954 950 955 956 957 953 958 956 959 960 955 959 956 958 956 961 962 958 963 958 961 963 950 951 964 964 965 950 966 953 967 957 967 953 968 946 945 946 968 969 970 948 952 952 948 953 940 971 941 972 941 971 973 943 947 947 943 948 935 936 974 974 975 935 976 938 942 942 938 943 977 852 931 936 852 977 937 978 934 934 938 937 851 850 927 979 928 933 934 933 928 920 850 921 920 926 850 930 980 924 924 928 930 917 916 921 921 916 922 918 923 981 923 918 924 910 917 906 982 917 910 914 919 983 911 906 984 914 985 912 912 986 913 906 905 984 987 905 900 908 907 913 907 909 988 987 900 899 900 896 901 907 904 903 895 901 896 894 896 891 892 903 898 919 918 989 915 917 982 897 893 892 940 935 975 945 941 972 951 946 969 955 950 965 961 956 960 957 958 962 954 953 966 949 948 970 944 943 973 939 938 976 932 934 978 929 928 979 925 924 980 989 918 981 985 914 983 908 913 986 904 907 988 898 903 990 902 990 903 890 882 892 887 883 882 880 874 883 869 864 874 864 870 866 859 856 863 860 854 856 849 853 847 855 848 857 862 855 858 861 867 865 865 868 872 876 871 875 871 877 879 879 881 884 884 888 885 885 891 896 991 992 993 994 995 996 993 997 998 998 991 993 999 1000 997 998 997 1000 1001 999 1002 999 1001 1000 1002 1003 1004 1004 1001 1002 1005 1006 1003 1004 1003 1006 1007 1005 1008 1005 1007 1006 1008 1009 1010 1010 1007 1008 1011 1012 1009 1010 1009 1012 1013 1011 1014 1011 1013 1012 1015 1013 1014 992 991 1016 1016 1017 992 1018 1019 1020 1021 1022 1018 1016 1023 1017 1022 1021 1023 1023 1021 1017 1019 1018 1022 1020 1024 1025 1024 1020 1019 1026 1027 1025 1025 1024 1026 1028 1027 1029 1026 1029 1027 1028 1030 1031 1030 1028 1029 1032 995 1031 1031 1030 1032 1032 996 995 1033 1034 1035 1036 1037 1034 1038 1039 1040 1041 1042 1043 1044 1045 1046 1038 1047 1048 1049 1050 1051 1045 1052 1053 1054 1055 1056 1057 1058 1059 1060 1055 1061 1054 1061 1055 1060 1062 1063 1014 1064 1065 1066 1063 1062 1064 1066 1065 1014 1065 1015 1062 1060 1061 1063 1066 1064 1067 1068 1056 1068 1054 1056 1058 1057 1067 1068 1067 1057 1069 1050 1059 1058 1069 1059 1053 1049 1051 1051 1050 1069 1044 1052 1045 1052 1049 1053 1047 1046 1048 1047 1044 1046 1042 1040 1039 1038 1048 1039 1041 1043 1035 1040 1042 1041 1033 1036 1034 1043 1033 1035 994 996 1037 1036 994 1037 1070 1071 1072 1073 1074 1075 1076 1075 1077 1073 1078 1074 1079 1080 1081 1082 1079 1081 1077 1082 1076 1076 1082 1081 1083 1078 1073 1075 1074 1077 1072 1078 1083 1084 1071 1070 1070 1072 1083 1085 1084 1086 1084 1085 1071 1087 1088 1086 1085 1086 1088 1087 1089 1090 1090 1088 1087 1089 1091 1090 1092 1091 1093 1089 1093 1091 1092 1093 1094 1095 1094 1096 1094 1095 1092 1097 1098 1096 1095 1096 1098 1099 1100 1101 1097 1102 1103 1104 1105 1106 1107 1108 1109 1104 1108 1107 1107 1105 1104 1109 1101 1100 1109 1108 1101 1102 1099 1103 1102 1100 1099 1103 1098 1097 1110 1111 1112 1113 1114 1115 1116 1111 1117 1110 1117 1111 1116 1118 1119 1118 1116 1117 1120 1121 1119 1119 1118 1120 1122 1121 1123 1120 1123 1121 1122 1124 1125 1124 1122 1123 1126 1127 1125 1125 1124 1126 1128 1127 1129 1126 1129 1127 1128 1130 1131 1130 1128 1129 1131 1130 1132 1133 1110 1112 1133 1134 1135 1134 1133 1112 1136 1137 1135 1135 1134 1136 1138 1137 1139 1136 1139 1137 1138 1140 1141 1140 1138 1139 1142 1143 1141 1141 1140 1142 1144 1143 1145 1142 1145 1143 1144 1146 1147 1146 1144 1145 1148 1115 1147 1147 1146 1148 1149 1150 1151 1148 1113 1115 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1170 1177 1170 1176 1171 1177 1178 1179 1179 1176 1177 1180 1181 1178 1179 1178 1181 1132 1180 1131 1180 1132 1181 1174 1173 1172 1172 1171 1174 1175 1164 1166 1173 1175 1166 1167 1169 1165 1164 1167 1165 1160 1159 1168 1168 1159 1169 1162 1158 1163 1163 1158 1160 1152 1161 1153 1152 1162 1161 1154 1156 1155 1154 1153 1156 1157 1150 1149 1155 1157 1149 1114 1113 1151 1150 1114 1151

+ + +

1946 1948 1947 1949 1947 1950 1948 1950 1947 1951 1952 1949 1949 1950 1951 1952 1954 1953 1954 1952 1951 1955 1953 1956 1954 1956 1953 1957 1958 1955 1955 1956 1957 1958 1960 1959 1960 1958 1957 1961 1959 1962 1960 1962 1959 1963 1964 1961 1961 1962 1963 1964 1966 1965 1966 1964 1963 1967 1965 1968 1966 1968 1965 1969 1970 1967 1967 1968 1969 1970 1972 1971 1972 1970 1969 1973 1971 1974 1972 1974 1971 1975 1976 1973 1973 1974 1975 1976 1978 1977 1978 1976 1975 1979 1977 1980 1978 1980 1977 1981 1982 1979 1979 1980 1981 1982 1984 1983 1984 1982 1981 1985 1983 1986 1984 1986 1983 1987 1988 1985 1985 1986 1987 1988 1990 1989 1990 1988 1987 1991 1989 1992 1990 1992 1989 1993 1994 1991 1991 1992 1993 1994 1996 1995 1996 1994 1993 1997 1995 1998 1996 1998 1995 1999 2000 1997 1997 1998 1999 2000 2002 2001 2002 2000 1999 2003 2001 2004 2002 2004 2001 2005 2006 2003 2003 2004 2005 2006 2008 2007 2008 2006 2005 2009 2007 2010 2008 2010 2007 2011 2012 2009 2009 2010 2011 2012 2014 2013 2014 2012 2011 2015 2013 2016 2014 2016 2013 2017 2018 2015 2015 2016 2017 2018 2020 2019 2020 2018 2017 2021 2019 2022 2020 2022 2019 2023 2024 2021 2021 2022 2023 2024 2026 2025 2026 2024 2023 2027 2025 2028 2026 2028 2025 2029 2030 2027 2027 2028 2029 2030 2032 2031 2032 2030 2029 2033 2031 2034 2032 2034 2031 2035 2036 2033 2033 2034 2035 2036 2038 2037 2038 2036 2035 2039 2037 2040 2038 2040 2037 2041 2042 2039 2039 2040 2041 2042 2044 2043 2044 2042 2041 2045 2043 2046 2044 2046 2043 2047 2048 2045 2045 2046 2047 2048 2050 2049 2050 2048 2047 2051 2049 2052 2050 2052 2049 2053 2054 2051 2051 2052 2053 2054 2056 2055 2056 2054 2053 2057 2055 2058 2056 2058 2055 2059 2060 2057 2057 2058 2059 2060 2062 2061 2062 2060 2059 2063 2061 2064 2062 2064 2061 2065 2066 2063 2063 2064 2065 2066 2068 2067 2068 2066 2065 2069 2067 2070 2068 2070 2067 2071 2072 2069 2069 2070 2071 2072 2074 2073 2074 2072 2071 2075 2073 2076 2074 2076 2073 2077 2078 2075 2075 2076 2077 2078 2080 2079 2080 2078 2077 2081 2079 2082 2080 2082 2079 2083 2084 2081 2081 2082 2083 2085 2084 2083 2085 2086 2084 1948 1946 2087 2088 2089 2087 2087 1946 2088 2089 2091 2090 2091 2089 2088 2092 2090 2093 2091 2093 2090 2094 2095 2092 2092 2093 2094 2095 2097 2096 2097 2095 2094 2098 2096 2099 2097 2099 2096 2100 2101 2098 2098 2099 2100 2101 2103 2102 2103 2101 2100 2104 2102 2105 2103 2105 2102 2106 2107 2104 2104 2105 2106 2107 2109 2108 2109 2107 2106 2110 2108 2111 2109 2111 2108 2112 2113 2110 2110 2111 2112 2113 2115 2114 2115 2113 2112 2116 2114 2117 2115 2117 2114 2118 2119 2116 2116 2117 2118 2119 2121 2120 2121 2119 2118 2122 2120 2123 2121 2123 2120 2124 2125 2122 2122 2123 2124 2125 2127 2126 2127 2125 2124 2128 2126 2129 2127 2129 2126 2130 2131 2128 2128 2129 2130 2131 2133 2132 2133 2131 2130 2134 2132 2135 2133 2135 2132 2136 2137 2134 2134 2135 2136 2137 2139 2138 2139 2137 2136 2140 2138 2141 2139 2141 2138 2142 2143 2140 2140 2141 2142 2143 2145 2144 2145 2143 2142 2146 2144 2147 2145 2147 2144 2148 2149 2146 2146 2147 2148 2149 2151 2150 2151 2149 2148 2152 2150 2153 2151 2153 2150 2154 2155 2152 2152 2153 2154 2155 2157 2156 2157 2155 2154 2158 2156 2159 2157 2159 2156 2160 2161 2158 2158 2159 2160 2161 2163 2162 2163 2161 2160 2164 2162 2165 2163 2165 2162 2166 2167 2164 2164 2165 2166 2167 2169 2168 2169 2167 2166 2170 2168 2171 2169 2171 2168 2172 2173 2170 2170 2171 2172 2173 2175 2174 2175 2173 2172 2176 2174 2177 2175 2177 2174 2178 2179 2176 2176 2177 2178 2179 2181 2180 2181 2179 2178 2182 2180 2183 2181 2183 2180 2184 2185 2182 2182 2183 2184 2185 2187 2186 2187 2185 2184 2188 2186 2189 2187 2189 2186 2190 2191 2188 2188 2189 2190 2191 2193 2192 2193 2191 2190 2194 2192 2195 2193 2195 2192 2196 2197 2194 2194 2195 2196 2197 2199 2198 2199 2197 2196 2200 2198 2201 2199 2201 2198 2202 2203 2200 2200 2201 2202 2203 2205 2204 2205 2203 2202 2206 2204 2207 2205 2207 2204 2208 2209 2206 2206 2207 2208 2209 2211 2210 2211 2209 2208 2212 2210 2213 2211 2213 2210 2214 2215 2212 2212 2213 2214 2215 2217 2216 2217 2215 2214 2218 2216 2219 2217 2219 2216 2220 2221 2218 2218 2219 2220 2221 2223 2222 2223 2221 2220 2223 2086 2222 2222 2086 2085

-
-
- - - - 3.14697e-18 -0.003 -0.0328 -3.21563e-18 -0.003 -0.0398 0.000520945 -0.00295442 -0.0398 -0.003 3.2147e-18 -0.0398 -0.003 3.2147e-18 -0.0328 -0.00295442 0.000520945 -0.0328 0.00102606 -0.00281908 -0.0398 0.000520945 -0.00295442 -0.0328 0.0015 -0.00259808 -0.0398 0.00102606 -0.00281908 -0.0328 0.0015 -0.00259808 -0.0328 0.00192836 -0.00229813 -0.0398 0.00229813 -0.00192836 -0.0398 0.00192836 -0.00229813 -0.0328 0.00259808 -0.0015 -0.0398 0.00229813 -0.00192836 -0.0328 0.00259808 -0.0015 -0.0328 0.00281908 -0.00102606 -0.0398 0.00295442 -0.000520945 -0.0398 0.00281908 -0.00102606 -0.0328 0.003 2.11252e-18 -0.0398 0.00295442 -0.000520945 -0.0328 0.003 2.11252e-18 -0.0328 -0.000520945 -0.00295442 -0.0328 -0.00102606 -0.00281908 -0.0328 -0.000520945 -0.00295442 -0.0398 -0.00102606 -0.00281908 -0.0398 -0.0015 -0.00259808 -0.0328 -0.00192836 -0.00229813 -0.0328 -0.0015 -0.00259808 -0.0398 -0.00229813 -0.00192836 -0.0328 -0.00192836 -0.00229813 -0.0398 -0.00229813 -0.00192836 -0.0398 -0.00259808 -0.0015 -0.0328 -0.00281908 -0.00102606 -0.0328 -0.00259808 -0.0015 -0.0398 -0.00295442 -0.000520945 -0.0328 -0.00281908 -0.00102606 -0.0398 -0.00295442 -0.000520945 -0.0398 -0.00281908 0.00102606 -0.0398 -0.00295442 0.000520945 -0.0398 -0.00281908 0.00102606 -0.0328 -0.00192836 0.00229813 -0.0398 -0.00229813 0.00192836 -0.0398 -0.00192836 0.00229813 -0.0328 -0.00259808 0.0015 -0.0398 -0.00259808 0.0015 -0.0328 -0.00229813 0.00192836 -0.0328 -0.00102606 0.00281908 -0.0398 -0.000520945 0.00295442 -0.0328 -0.000520945 0.00295442 -0.0398 -0.0015 0.00259808 -0.0328 -0.00102606 0.00281908 -0.0328 -0.0015 0.00259808 -0.0398 0.00102606 0.00281908 -0.0328 0.00102606 0.00281908 -0.0398 0.000520945 0.00295442 -0.0398 0.000520945 0.00295442 -0.0328 1.83697e-19 0.003 -0.0398 -1.83697e-19 0.003 -0.0328 0.00229813 0.00192836 -0.0398 0.00192836 0.00229813 -0.0398 0.00229813 0.00192836 -0.0328 0.0015 0.00259808 -0.0398 0.0015 0.00259808 -0.0328 0.00192836 0.00229813 -0.0328 0.00259808 0.0015 -0.0328 0.00259808 0.0015 -0.0398 0.00281908 0.00102606 -0.0328 0.00281908 0.00102606 -0.0398 0.00295442 0.000520945 -0.0398 0.00295442 0.000520945 -0.0328 -0.00229813 0.00192836 -0.0328 -0.0015 0.00259808 -0.0328 -0.00192836 0.00229813 -0.0328 0.00281908 0.00102606 -0.0328 -0.0015 -0.00259808 -0.0328 -0.00102606 -0.00281908 -0.0328 -0.00259808 0.0015 -0.0328 -0.00102606 0.00281908 -0.0328 -0.00281908 0.00102606 -0.0328 -0.000520945 0.00295442 -0.0328 -0.00295442 0.000520945 -0.0328 -0.003 3.2147e-18 -0.0328 -1.83697e-19 0.003 -0.0328 0.00102606 0.00281908 -0.0328 -0.00295442 -0.000520945 -0.0328 -0.00281908 -0.00102606 -0.0328 0.000520945 0.00295442 -0.0328 -0.00192836 -0.00229813 -0.0328 0.00229813 0.00192836 -0.0328 -0.00229813 -0.00192836 -0.0328 -0.00259808 -0.0015 -0.0328 0.00192836 0.00229813 -0.0328 0.0015 0.00259808 -0.0328 -0.000520945 -0.00295442 -0.0328 0.00295442 0.000520945 -0.0328 0.00259808 0.0015 -0.0328 0.00281908 -0.00102606 -0.0328 0.000520945 -0.00295442 -0.0328 0.00102606 -0.00281908 -0.0328 0.00295442 -0.000520945 -0.0328 0.003 2.11252e-18 -0.0328 3.14697e-18 -0.003 -0.0328 0.0015 -0.00259808 -0.0328 0.00229813 -0.00192836 -0.0328 0.00259808 -0.0015 -0.0328 0.00192836 -0.00229813 -0.0328 -0.00261224 0.0014752 -0.0428 -0.00232242 0.00189904 -0.0428 -0.00196458 0.00226725 -0.0428 -0.000999039 -0.00282874 -0.0428 -0.00147865 -0.00261027 -0.0428 0.00255324 0.00157498 -0.0428 -0.00154919 0.00256905 -0.0428 -0.00282553 0.00100815 -0.0428 -0.00295606 0.000511567 -0.0428 -0.00108842 0.00279559 -0.0428 -0.000595771 0.00294025 -0.0428 -0.003 2.56697e-18 -0.0428 -8.56682e-05 0.00299878 -0.0428 0.000927051 0.00285317 -0.0428 -0.00259191 -0.00151062 -0.0428 -0.00281627 -0.00103375 -0.0428 0.000426945 0.00296946 -0.0428 -0.00295371 -0.000524974 -0.0428 -0.00191262 -0.00231124 -0.0428 0.0022381 0.00199764 -0.0428 -0.00228757 -0.00194088 -0.0428 0.00141226 0.00264677 -0.0428 0.00185382 0.00235862 -0.0428 -0.000488591 -0.00295992 -0.0428 0.00293965 0.000598359 -0.0428 3.69413e-05 -0.00299974 -0.0428 0.00278952 0.0011037 -0.0428 0.00284093 -0.000963669 -0.0428 0.00154253 -0.00257299 -0.0428 0.00106842 -0.00280325 -0.0428 0.00296575 -0.000451535 -0.0428 0.00056134 -0.00294697 -0.0428 0.002999 7.45543e-05 -0.0428 0.00233475 -0.00188375 -0.0428 0.00196903 -0.00226331 -0.0428 0.00262841 -0.00144604 -0.0428 0.000342888 -0.00498809 -0.0398 -0.000339746 -0.00498837 -0.0398 0.000342888 -0.00498809 -0.0408 -0.005 3.1793e-18 -0.0398 -0.00495328 0.000681737 -0.0398 -0.00495461 0.000672011 -0.0408 0.00101838 -0.00489506 -0.0408 0.00101838 -0.00489506 -0.0398 0.00167458 -0.00471124 -0.0408 0.00167458 -0.00471124 -0.0398 0.00230126 -0.0044389 -0.0398 0.00230126 -0.0044389 -0.0408 0.00288467 -0.00408383 -0.0408 0.00288467 -0.00408383 -0.0398 0.00341382 -0.003653 -0.0408 0.00341382 -0.003653 -0.0398 0.00387891 -0.00315487 -0.0398 0.00387891 -0.00315487 -0.0408 0.00427238 -0.00259743 -0.0408 0.00427238 -0.00259743 -0.0398 0.00458654 -0.00199074 -0.0408 0.00458654 -0.00199074 -0.0398 0.00481492 -0.00134732 -0.0398 0.00481492 -0.00134732 -0.0408 0.00495328 -0.000681737 -0.0408 0.00495328 -0.000681737 -0.0398 0.005 1.34233e-18 -0.0408 0.005 1.34233e-18 -0.0398 -0.000339746 -0.00498837 -0.0408 -0.00101655 -0.00489556 -0.0398 -0.00101655 -0.00489556 -0.0408 -0.00167405 -0.00471138 -0.0408 -0.00167405 -0.00471138 -0.0398 -0.00229895 -0.00443998 -0.0398 -0.00229895 -0.00443998 -0.0408 -0.00288197 -0.00408572 -0.0398 -0.00288197 -0.00408572 -0.0408 -0.00341184 -0.00365498 -0.0408 -0.00341184 -0.00365498 -0.0398 -0.00387831 -0.00315573 -0.0398 -0.00387831 -0.00315573 -0.0408 -0.00427152 -0.00259866 -0.0398 -0.00427152 -0.00259866 -0.0408 -0.00458527 -0.00199346 -0.0408 -0.00458527 -0.00199346 -0.0398 -0.00481408 -0.00135046 -0.0398 -0.00481408 -0.00135046 -0.0408 -0.00495328 -0.000681737 -0.0398 -0.00495328 -0.000681737 -0.0408 -0.0045981 0.0019639 -0.0408 -0.00482013 0.0013286 -0.0408 -0.00481492 0.00134732 -0.0398 -0.005 3.1793e-18 -0.0408 -0.00345627 0.00361287 -0.0408 -0.00390944 0.00311699 -0.0408 -0.00387891 0.00315487 -0.0398 -0.00429254 0.00256399 -0.0408 -0.00458654 0.00199074 -0.0398 -0.00427238 0.00259743 -0.0398 -0.00237029 0.00440242 -0.0408 -0.00230126 0.0044389 -0.0398 -0.00175715 0.00468107 -0.0408 -0.00341382 0.003653 -0.0398 -0.00288467 0.00408383 -0.0398 -0.00294013 0.00404408 -0.0408 -0.000342888 0.00498809 -0.0398 0.00022286 0.00499495 -0.0408 -0.000449752 0.0049796 -0.0408 -0.00101838 0.00489506 -0.0398 -0.0011135 0.00487433 -0.0408 -0.00167458 0.00471124 -0.0398 0.00219217 0.00449381 -0.0408 0.00154508 0.00475528 -0.0408 0.00167405 0.00471138 -0.0398 0.000891938 0.00491978 -0.0408 0.000339746 0.00498837 -0.0398 0.00101655 0.00489556 -0.0398 0.00334471 0.00371645 -0.0408 0.00288197 0.00408572 -0.0398 0.00341184 0.00365498 -0.0398 0.00229895 0.00443998 -0.0398 0.0027951 0.00414566 -0.0408 0.00423958 0.00265054 -0.0408 0.00382937 0.00321483 -0.0408 0.00387831 0.00315573 -0.0398 0.00427152 0.00259866 -0.0398 0.0045673 0.00203454 -0.0408 0.00458527 0.00199346 -0.0398 0.0048061 0.00137884 -0.0408 0.00495129 0.000696215 -0.0408 0.00481408 0.00135046 -0.0398 0.00495328 0.000681737 -0.0398 -0.00288467 0.00408383 -0.0398 -0.0015 0.00259808 -0.0398 -0.00230126 0.0044389 -0.0398 0.00295442 -0.000520945 -0.0398 0.00281908 -0.00102606 -0.0398 0.00481492 -0.00134732 -0.0398 -0.00102606 0.00281908 -0.0398 -0.00101838 0.00489506 -0.0398 -0.00167458 0.00471124 -0.0398 -0.00341382 0.003653 -0.0398 -0.00192836 0.00229813 -0.0398 -0.000342888 0.00498809 -0.0398 1.83697e-19 0.003 -0.0398 0.000339746 0.00498837 -0.0398 -0.000520945 0.00295442 -0.0398 0.00101655 0.00489556 -0.0398 0.000520945 0.00295442 -0.0398 -0.00229813 0.00192836 -0.0398 -0.00387891 0.00315487 -0.0398 -0.00427238 0.00259743 -0.0398 -0.00458654 0.00199074 -0.0398 -0.00281908 0.00102606 -0.0398 -0.00259808 0.0015 -0.0398 -0.00481492 0.00134732 -0.0398 -0.00295442 0.000520945 -0.0398 0.00167405 0.00471138 -0.0398 0.00102606 0.00281908 -0.0398 -0.005 3.1793e-18 -0.0398 -0.00495328 -0.000681737 -0.0398 -0.003 3.2147e-18 -0.0398 0.00229895 0.00443998 -0.0398 0.0015 0.00259808 -0.0398 -0.00295442 -0.000520945 -0.0398 -0.00259808 -0.0015 -0.0398 -0.00427152 -0.00259866 -0.0398 -0.00229813 -0.00192836 -0.0398 -0.00281908 -0.00102606 -0.0398 -0.00458527 -0.00199346 -0.0398 0.00458654 -0.00199074 -0.0398 -0.00341184 -0.00365498 -0.0398 -0.00387831 -0.00315573 -0.0398 -0.000520945 -0.00295442 -0.0398 -0.00101655 -0.00489556 -0.0398 -0.000339746 -0.00498837 -0.0398 -0.00229895 -0.00443998 -0.0398 -0.00102606 -0.00281908 -0.0398 -0.0015 -0.00259808 -0.0398 0.00167458 -0.00471124 -0.0398 0.00230126 -0.0044389 -0.0398 0.00102606 -0.00281908 -0.0398 -3.21563e-18 -0.003 -0.0398 0.000342888 -0.00498809 -0.0398 0.000520945 -0.00295442 -0.0398 0.00101838 -0.00489506 -0.0398 0.00288467 -0.00408383 -0.0398 0.0015 -0.00259808 -0.0398 0.00341382 -0.003653 -0.0398 0.00192836 -0.00229813 -0.0398 -0.00167405 -0.00471138 -0.0398 0.00229813 -0.00192836 -0.0398 0.00259808 -0.0015 -0.0398 0.00427238 -0.00259743 -0.0398 0.00387891 -0.00315487 -0.0398 -0.00288197 -0.00408572 -0.0398 -0.00192836 -0.00229813 -0.0398 0.00495328 -0.000681737 -0.0398 0.003 2.11252e-18 -0.0398 0.00495328 0.000681737 -0.0398 0.005 1.34233e-18 -0.0398 0.00458527 0.00199346 -0.0398 0.00281908 0.00102606 -0.0398 0.00481408 0.00135046 -0.0398 0.00295442 0.000520945 -0.0398 -0.00481408 -0.00135046 -0.0398 0.00229813 0.00192836 -0.0398 0.00259808 0.0015 -0.0398 0.00427152 0.00259866 -0.0398 0.00288197 0.00408572 -0.0398 0.00192836 0.00229813 -0.0398 0.00341184 0.00365498 -0.0398 -0.00495328 0.000681737 -0.0398 0.00387831 0.00315573 -0.0398 0.00357133 -0.00279023 -0.0420856 0.00316636 -0.0035166 -0.0418 0.00303256 -0.003368 -0.0420856 -8.56682e-05 0.00299878 -0.0428 0.000465854 0.00331472 -0.0427696 0.000426945 0.00296946 -0.0428 -0.004686 0.000658574 -0.0418 -0.00448798 0.000630745 -0.0420856 -0.00452933 -0.000158168 -0.0420856 0.00462864 0.000983849 -0.0418 0.00443305 0.000942274 -0.0420856 0.00420208 0.00169775 -0.0420856 -0.00201196 -0.00378394 -0.0423321 -0.00132432 -0.00407582 -0.0423321 -0.00212769 -0.0040016 -0.0420856 -0.000595771 0.00294025 -0.0428 -0.000695942 0.00327415 -0.0427696 -0.000116819 0.00334526 -0.0427696 -0.000765955 0.00360354 -0.0426794 -0.00125392 0.00310356 -0.0427696 -0.00138007 0.00341578 -0.0426794 -0.00263846 -0.00337708 -0.0423321 -0.00279023 -0.00357133 -0.0420856 -0.0031848 -0.00286761 -0.0423321 -0.003368 -0.00303256 -0.0420856 -0.00267652 0.00297258 -0.0425321 -0.00286761 0.0031848 -0.0423321 -0.00227101 0.00363437 -0.0423321 -0.00211968 0.00339219 -0.0425321 -0.0024651 0.00273778 -0.0426794 -0.00357133 0.00279023 -0.0420856 -0.00316636 0.0035166 -0.0418 -0.00303256 0.003368 -0.0420856 -0.00431027 0.00140049 -0.0420856 -0.00417815 0.00222156 -0.0418 -0.0040016 0.00212769 -0.0420856 -0.0011135 0.00487433 -0.0408 -0.00103324 0.00486102 -0.0411473 -0.00186165 0.00460775 -0.0411473 -0.000449752 0.0049796 -0.0408 -0.000173437 0.00496659 -0.0411473 0.00150781 0.00464057 -0.041484 0.000679079 0.0048319 -0.041484 0.0015357 0.00472639 -0.0411473 -0.000983849 0.00462864 -0.0418 -0.000165146 0.00472917 -0.0418 -0.000942274 0.00443305 -0.0420856 -0.0025076 0.00401301 -0.0418 0.000691637 0.00492125 -0.0411473 0.000891938 0.00491978 -0.0408 -0.00378394 0.00201196 -0.0423321 -0.00337708 0.00263846 -0.0423321 0.00154508 0.00475528 -0.0408 -0.00290306 0.00226812 -0.0426794 -0.00315204 0.00246265 -0.0425321 0.00103437 0.00318347 -0.0427696 0.000927051 0.00285317 -0.0428 -0.00240164 0.00384343 -0.0420856 -0.00372891 0.00291334 -0.0418 -0.00407582 0.00132432 -0.0423321 -0.00450045 0.00146228 -0.0418 -0.00424387 0.000596437 -0.0423321 -0.00428296 -0.000149564 -0.0423321 -0.00419192 -0.000891021 -0.0423321 -0.00472917 -0.000165146 -0.0418 -0.00443305 -0.000942274 -0.0420856 -0.00397352 -0.0016054 -0.0423321 -0.0026335 0.00421447 -0.0411473 -0.00237029 0.00440242 -0.0408 -0.00438748 -0.00177266 -0.0418 -0.00420208 -0.00169775 -0.0420856 -0.00384343 -0.00240164 -0.0420856 -0.00462864 -0.000983849 -0.0418 -0.00401301 -0.0025076 -0.0418 -0.00363437 -0.00227101 -0.0423321 -0.00140049 -0.00431027 -0.0420856 -0.00222156 -0.00417815 -0.0418 -0.0035166 -0.00316636 -0.0418 0.000891021 -0.00419192 -0.0423321 0.000158168 -0.00452933 -0.0420856 0.000149564 -0.00428296 -0.0423321 -0.00486102 -0.00103324 -0.0411473 -0.00495328 -0.000681737 -0.0408 -0.00496659 -0.000173437 -0.0411473 0.00240164 -0.00384343 -0.0420856 0.00227101 -0.00363437 -0.0423321 0.00286761 -0.0031848 -0.0423321 0.00169775 -0.00420208 -0.0420856 0.00177266 -0.00438748 -0.0418 0.00431027 -0.00140049 -0.0420856 0.00417815 -0.00222156 -0.0418 0.0040016 -0.00212769 -0.0420856 0.00372891 -0.00291334 -0.0418 0.00230126 -0.0044389 -0.0408 0.00186165 -0.00460775 -0.0411473 0.0026335 -0.00421447 -0.0411473 0.00448798 -0.000630745 -0.0420856 0.00424387 -0.000596437 -0.0423321 0.00428296 0.000149564 -0.0423321 0.00391611 -0.0030596 -0.0411473 0.00438791 -0.00233309 -0.0411473 0.00427238 -0.00259743 -0.0408 0.00397352 0.0016054 -0.0423321 0.00363437 0.00227101 -0.0423321 0.00229073 0.00430824 -0.041484 0.00222156 0.00417815 -0.0418 0.00146228 0.00450045 -0.0418 0.00212769 0.0040016 -0.0420856 0.00140049 0.00431027 -0.0420856 0.00233309 0.00438791 -0.0411473 0.00201196 0.00378394 -0.0423321 0.00132432 0.00407582 -0.0423321 0.00496659 0.000173437 -0.0411473 0.00486102 0.00103324 -0.0411473 0.00495129 0.000696215 -0.0408 0.00113843 0.00350373 -0.0426794 0.00123607 0.00380423 -0.0425321 0.00187789 0.00353179 -0.0425321 0.00172955 0.00325281 -0.0426794 0.00157146 0.00295549 -0.0427696 0.00334471 0.00371645 -0.0408 0.00369314 0.00332532 -0.0411473 0.0030596 0.00391611 -0.0411473 0.0027951 0.00414566 -0.0408 0.00219217 0.00449381 -0.0408 0.00279023 0.00357133 -0.0420856 0.00291334 0.00372891 -0.0418 0.00263846 0.00337708 -0.0423321 0.0035166 0.00316636 -0.0418 0.003368 0.00303256 -0.0420856 0.0031848 0.00286761 -0.0423321 0.00384343 0.00240164 -0.0420856 0.00438748 0.00177266 -0.0418 0.00401301 0.0025076 -0.0418 0.00419192 0.000891021 -0.0423321 0.00452933 0.000158168 -0.0420856 0.00472917 0.000165146 -0.0418 0.00407582 -0.00132432 -0.0423321 0.004686 -0.000658574 -0.0418 0.00378394 -0.00201196 -0.0423321 0.00450045 -0.00146228 -0.0418 0.00337708 -0.00263846 -0.0423321 -0.000691637 -0.00492125 -0.0411473 -0.00101655 -0.00489556 -0.0408 -0.0015357 -0.00472639 -0.0411473 -0.00421447 -0.0026335 -0.0411473 -0.00369314 -0.00332532 -0.0411473 -0.00387831 -0.00315573 -0.0408 0.0025076 -0.00401301 -0.0418 0.0016054 -0.00397352 -0.0423321 0.000942274 -0.00443305 -0.0420856 0.000165146 -0.00472917 -0.0418 0.000983849 -0.00462864 -0.0418 -0.000630745 -0.00448798 -0.0420856 -0.000596437 -0.00424387 -0.0423321 -0.000658574 -0.004686 -0.0418 -0.00146228 -0.00450045 -0.0418 -0.00291334 -0.00372891 -0.0418 -0.00438791 0.00233309 -0.0411473 -0.00429254 0.00256399 -0.0408 -0.00391611 0.0030596 -0.0411473 0.00423958 0.00265054 -0.0408 0.0045673 0.00203454 -0.0408 0.00421447 0.0026335 -0.0411473 0.00495328 -0.000681737 -0.0408 0.00492125 -0.000691637 -0.0411473 0.005 1.34233e-18 -0.0408 0.00300405 0.00384501 -0.041484 0.00246265 0.00315204 -0.0425321 0.00226812 0.00290306 -0.0426794 0.00141226 0.00264677 -0.0428 0.0020608 0.00263771 -0.0427696 0.00382937 0.00321483 -0.0408 0.00362609 0.00326495 -0.041484 0.00297258 0.00267652 -0.0425321 0.00273778 0.0024651 -0.0426794 0.00185382 0.00235862 -0.0428 0.00248753 0.00223978 -0.0427696 0.00460775 0.00186165 -0.0411473 0.00413795 0.00258568 -0.041484 0.00339219 0.00211968 -0.0425321 0.00312424 0.00195224 -0.0426794 0.0022381 0.00199764 -0.0428 0.00283867 0.0017738 -0.0427696 0.0048061 0.00137884 -0.0408 0.00452409 0.00182785 -0.041484 0.00370874 0.00149843 -0.0425321 0.00341578 0.00138007 -0.0426794 0.00255324 0.00157498 -0.0428 0.00310356 0.00125392 -0.0427696 0.00387891 -0.00315487 -0.0408 0.00341382 -0.003653 -0.0408 0.00477276 0.00101448 -0.041484 0.00391259 0.000831647 -0.0425321 0.00360354 0.000765955 -0.0426794 0.00278952 0.0011037 -0.0428 0.00327415 0.000695942 -0.0427696 0.00487641 0.000170288 -0.041484 0.00399756 0.000139598 -0.0425321 0.0036818 0.000128571 -0.0426794 0.00293965 0.000598359 -0.0428 0.00334526 0.000116819 -0.0427696 0.00481492 -0.00134732 -0.0408 0.00472639 -0.0015357 -0.0411473 0.0048319 -0.000679079 -0.041484 0.00396107 -0.000556692 -0.0425321 0.00364819 -0.000512719 -0.0426794 0.002999 7.45543e-05 -0.0428 0.00331472 -0.000465854 -0.0427696 0.00458654 -0.00199074 -0.0408 0.00464057 -0.00150781 -0.041484 0.00380423 -0.00123607 -0.0425321 0.00350373 -0.00113843 -0.0426794 0.00296575 -0.000451535 -0.0428 0.00318347 -0.00103437 -0.0427696 0.00101838 -0.00489506 -0.0408 0.000342888 -0.00498809 -0.0408 0.00103324 -0.00486102 -0.0411473 0.00430824 -0.00229073 -0.041484 0.00353179 -0.00187789 -0.0425321 0.00325281 -0.00172955 -0.0426794 0.00284093 -0.000963669 -0.0428 0.00295549 -0.00157146 -0.0427696 0.00332532 -0.00369314 -0.0411473 0.00384501 -0.00300405 -0.041484 0.00315204 -0.00246265 -0.0425321 0.00290306 -0.00226812 -0.0426794 0.00262841 -0.00144604 -0.0428 0.00263771 -0.0020608 -0.0427696 0.00288467 -0.00408383 -0.0408 0.00326495 -0.00362609 -0.041484 0.00267652 -0.00297258 -0.0425321 0.0024651 -0.00273778 -0.0426794 0.00233475 -0.00188375 -0.0428 0.00223978 -0.00248753 -0.0427696 -0.00167405 -0.00471138 -0.0408 -0.00229895 -0.00443998 -0.0408 0.00258568 -0.00413795 -0.041484 0.00211968 -0.00339219 -0.0425321 0.00195224 -0.00312424 -0.0426794 0.00196903 -0.00226331 -0.0428 0.0017738 -0.00283867 -0.0427696 0.00167458 -0.00471124 -0.0408 0.00182785 -0.00452409 -0.041484 0.00149843 -0.00370874 -0.0425321 0.00138007 -0.00341578 -0.0426794 0.00154253 -0.00257299 -0.0428 0.00125392 -0.00310356 -0.0427696 0.000173437 -0.00496659 -0.0411473 0.00101448 -0.00477276 -0.041484 0.000831647 -0.00391259 -0.0425321 0.000765955 -0.00360354 -0.0426794 0.00106842 -0.00280325 -0.0428 0.000695942 -0.00327415 -0.0427696 -0.000339746 -0.00498837 -0.0408 0.000170288 -0.00487641 -0.041484 0.000139598 -0.00399756 -0.0425321 0.000128571 -0.0036818 -0.0426794 0.00056134 -0.00294697 -0.0428 0.000116819 -0.00334526 -0.0427696 -0.00427152 -0.00259866 -0.0408 -0.00458527 -0.00199346 -0.0408 -0.000679079 -0.0048319 -0.041484 -0.000556692 -0.00396107 -0.0425321 -0.000512719 -0.00364819 -0.0426794 3.69413e-05 -0.00299974 -0.0428 -0.000465854 -0.00331472 -0.0427696 -0.00233309 -0.00438791 -0.0411473 -0.00150781 -0.00464057 -0.041484 -0.00123607 -0.00380423 -0.0425321 -0.00113843 -0.00350373 -0.0426794 -0.000488591 -0.00295992 -0.0428 -0.00103437 -0.00318347 -0.0427696 -0.00288197 -0.00408572 -0.0408 -0.0030596 -0.00391611 -0.0411473 -0.00229073 -0.00430824 -0.041484 -0.00187789 -0.00353179 -0.0425321 -0.00172955 -0.00325281 -0.0426794 -0.000999039 -0.00282874 -0.0428 -0.00157146 -0.00295549 -0.0427696 -0.00341184 -0.00365498 -0.0408 -0.00300405 -0.00384501 -0.041484 -0.00246265 -0.00315204 -0.0425321 -0.00226812 -0.00290306 -0.0426794 -0.00147865 -0.00261027 -0.0428 -0.0020608 -0.00263771 -0.0427696 -0.005 3.1793e-18 -0.0408 -0.00495461 0.000672011 -0.0408 -0.00492125 0.000691637 -0.0411473 -0.00362609 -0.00326495 -0.041484 -0.00297258 -0.00267652 -0.0425321 -0.00273778 -0.0024651 -0.0426794 -0.00191262 -0.00231124 -0.0428 -0.00248753 -0.00223978 -0.0427696 -0.00460775 -0.00186165 -0.0411473 -0.00413795 -0.00258568 -0.041484 -0.00339219 -0.00211968 -0.0425321 -0.00312424 -0.00195224 -0.0426794 -0.00228757 -0.00194088 -0.0428 -0.00283867 -0.0017738 -0.0427696 -0.00481408 -0.00135046 -0.0408 -0.00452409 -0.00182785 -0.041484 -0.00370874 -0.00149843 -0.0425321 -0.00341578 -0.00138007 -0.0426794 -0.00259191 -0.00151062 -0.0428 -0.00310356 -0.00125392 -0.0427696 -0.00390944 0.00311699 -0.0408 -0.00345627 0.00361287 -0.0408 -0.00477276 -0.00101448 -0.041484 -0.00391259 -0.000831647 -0.0425321 -0.00360354 -0.000765955 -0.0426794 -0.00281627 -0.00103375 -0.0428 -0.00327415 -0.000695942 -0.0427696 -0.00487641 -0.000170288 -0.041484 -0.00399756 -0.000139598 -0.0425321 -0.0036818 -0.000128571 -0.0426794 -0.00295371 -0.000524974 -0.0428 -0.00334526 -0.000116819 -0.0427696 -0.00482013 0.0013286 -0.0408 -0.00472639 0.0015357 -0.0411473 -0.0048319 0.000679079 -0.041484 -0.00396107 0.000556692 -0.0425321 -0.00364819 0.000512719 -0.0426794 -0.003 2.56697e-18 -0.0428 -0.00331472 0.000465854 -0.0427696 -0.0045981 0.0019639 -0.0408 -0.00464057 0.00150781 -0.041484 -0.00380423 0.00123607 -0.0425321 -0.00350373 0.00113843 -0.0426794 -0.00295606 0.000511567 -0.0428 -0.00318347 0.00103437 -0.0427696 -0.00175715 0.00468107 -0.0408 -0.00430824 0.00229073 -0.041484 -0.00353179 0.00187789 -0.0425321 -0.00325281 0.00172955 -0.0426794 -0.00282553 0.00100815 -0.0428 -0.00295549 0.00157146 -0.0427696 -0.00332532 0.00369314 -0.0411473 -0.00384501 0.00300405 -0.041484 -0.00261224 0.0014752 -0.0428 -0.00263771 0.0020608 -0.0427696 -0.00294013 0.00404408 -0.0408 -0.00326495 0.00362609 -0.041484 -0.00232242 0.00189904 -0.0428 -0.00223978 0.00248753 -0.0427696 -0.000170288 0.00487641 -0.041484 -0.00258568 0.00413795 -0.041484 -0.00149843 0.00370874 -0.0425321 -0.00195224 0.00312424 -0.0426794 -0.00196458 0.00226725 -0.0428 -0.0017738 0.00283867 -0.0427696 -0.00177266 0.00438748 -0.0418 -0.00182785 0.00452409 -0.041484 -0.00169775 0.00420208 -0.0420856 -0.0016054 0.00397352 -0.0423321 -0.00154919 0.00256905 -0.0428 -0.00101448 0.00477276 -0.041484 -0.000891021 0.00419192 -0.0423321 -0.000831647 0.00391259 -0.0425321 -0.00108842 0.00279559 -0.0428 0.00022286 0.00499495 -0.0408 -0.000158168 0.00452933 -0.0420856 -0.000149564 0.00428296 -0.0423321 -0.000139598 0.00399756 -0.0425321 -0.000128571 0.0036818 -0.0426794 0.000512719 0.00364819 -0.0426794 0.000658574 0.004686 -0.0418 0.000630745 0.00448798 -0.0420856 0.000596437 0.00424387 -0.0423321 0.000556692 0.00396107 -0.0425321 - - - - - - - - - - 1.19249e-08 -1 0 1.19249e-08 -1 0 0.173648 -0.984808 0 -1 -8.74228e-08 0 -1 -8.74228e-08 0 -0.984808 0.173648 0 0.34202 -0.939693 0 0.173648 -0.984808 0 0.5 -0.866025 0 0.34202 -0.939693 0 0.5 -0.866025 0 0.642788 -0.766044 0 0.766044 -0.642788 0 0.642788 -0.766044 0 0.866026 -0.5 0 0.766044 -0.642788 0 0.866026 -0.5 0 0.939693 -0.34202 0 0.984808 -0.173648 0 0.939693 -0.34202 0 1 1.74846e-07 0 0.984808 -0.173648 0 1 1.74846e-07 0 -0.173648 -0.984808 0 -0.34202 -0.939693 0 -0.173648 -0.984808 0 -0.342021 -0.939692 0 -0.5 -0.866025 0 -0.642788 -0.766045 0 -0.5 -0.866025 0 -0.766044 -0.642788 0 -0.642788 -0.766045 0 -0.766044 -0.642788 0 -0.866026 -0.5 0 -0.939693 -0.34202 0 -0.866025 -0.5 0 -0.984808 -0.173648 0 -0.939693 -0.34202 0 -0.984808 -0.173648 0 -0.939693 0.34202 0 -0.984808 0.173648 0 -0.939693 0.34202 0 -0.642788 0.766044 0 -0.766044 0.642788 0 -0.642788 0.766044 0 -0.866025 0.5 0 -0.866025 0.5 0 -0.766044 0.642788 0 -0.34202 0.939693 0 -0.173648 0.984808 0 -0.173648 0.984808 0 -0.5 0.866025 0 -0.34202 0.939693 0 -0.5 0.866025 0 0.34202 0.939693 0 0.34202 0.939693 0 0.173648 0.984808 0 0.173648 0.984808 0 -4.37114e-08 1 0 7.54979e-08 1 0 0.766044 0.642788 0 0.642788 0.766044 0 0.766044 0.642788 0 0.5 0.866025 0 0.5 0.866025 0 0.642788 0.766044 0 0.866025 0.5 0 0.866025 0.5 0 0.939693 0.34202 0 0.939693 0.34202 0 0.984808 0.173648 0 0.984808 0.173648 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.0682424 -0.997669 0 -0.0682424 -0.997669 0 0.0682424 -0.997669 0 -1 -8.74228e-08 0 -0.990686 0.136167 0 -0.99095 0.134233 0 0.203456 -0.979084 0 0.203456 -0.979084 0 0.33488 -0.942261 0 0.33488 -0.942261 0 0.460065 -0.887885 0 0.460065 -0.887885 0 0.57668 -0.81697 0 0.57668 -0.81697 0 0.682553 -0.730836 0 0.682553 -0.730836 0 0.775711 -0.631088 0 0.775711 -0.631088 0 0.85442 -0.519584 0 0.85442 -0.519584 0 0.917211 -0.398401 0 0.917211 -0.398401 0 0.962917 -0.269797 0 0.962917 -0.269797 0 0.990686 -0.136166 0 0.990686 -0.136166 0 1 1.74846e-07 0 1 1.74846e-07 0 -0.0682424 -0.997669 0 -0.203456 -0.979084 0 -0.203456 -0.979084 0 -0.33488 -0.942261 0 -0.33488 -0.942261 0 -0.460065 -0.887885 0 -0.460065 -0.887885 0 -0.57668 -0.81697 0 -0.57668 -0.81697 0 -0.682553 -0.730836 0 -0.682553 -0.730836 0 -0.775711 -0.631088 0 -0.775711 -0.631088 0 -0.85442 -0.519584 0 -0.854419 -0.519584 0 -0.917211 -0.398401 0 -0.917211 -0.398401 0 -0.962917 -0.269797 0 -0.962917 -0.269797 0 -0.990686 -0.136167 0 -0.990686 -0.136167 0 -0.919528 0.393025 0 -0.963963 0.266037 0 -0.962917 0.269797 0 -1 -8.74228e-08 0 -0.691063 0.722795 0 -0.781832 0.62349 0 -0.775711 0.631088 0 -0.858449 0.512899 0 -0.917211 0.398401 0 -0.854419 0.519584 0 -0.473869 0.880595 0 -0.460065 0.887885 0 -0.351375 0.936235 0 -0.682553 0.730836 0 -0.57668 0.81697 0 -0.587785 0.809017 0 -0.0682423 0.997669 0 0.0448648 0.998993 0 -0.0896393 0.995974 0 -0.203456 0.979084 0 -0.222521 0.974928 0 -0.33488 0.942261 0 0.438371 0.898794 0 0.309017 0.951057 0 0.33488 0.942261 0 0.178557 0.98393 0 0.0682425 0.997669 0 0.203456 0.979084 0 0.669131 0.743145 0 0.57668 0.81697 0 0.682553 0.730836 0 0.460065 0.887885 0 0.559193 0.829038 0 0.848048 0.529919 0 0.766044 0.642788 0 0.775711 0.631088 0 0.854419 0.519584 0 0.913545 0.406737 0 0.917211 0.398401 0 0.961262 0.275637 0 0.990268 0.139173 0 0.962917 0.269797 0 0.990686 0.136167 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.603651 -0.471624 -0.642788 0.579484 -0.643582 -0.5 0.512584 -0.569282 -0.642788 -3.4053e-10 1.192e-08 -1 0.0241672 0.171958 -0.984808 1.69709e-09 1.18035e-08 -1 -0.857597 0.120527 -0.5 -0.758589 0.106613 -0.642788 -0.765578 -0.0267345 -0.642788 0.847101 0.180057 -0.5 0.749304 0.15927 -0.642788 0.710264 0.286965 -0.642788 -0.30177 -0.567548 -0.766044 -0.198632 -0.611327 -0.766044 -0.359636 -0.676377 -0.642788 -2.36817e-09 1.16874e-08 -1 -0.0361035 0.169854 -0.984808 -0.00606019 0.173542 -0.984808 -0.07111 0.334546 -0.939693 -0.0650498 0.161004 -0.984808 -0.128123 0.317116 -0.939693 -0.39574 -0.506523 -0.766044 -0.471624 -0.603651 -0.642788 -0.477684 -0.430109 -0.766044 -0.569282 -0.512584 -0.642788 -0.334565 0.371572 -0.866025 -0.430109 0.477684 -0.766044 -0.340626 0.545115 -0.766044 -0.26496 0.424024 -0.866025 -0.228856 0.25417 -0.939693 -0.603651 0.471624 -0.642788 -0.579484 0.643582 -0.5 -0.512583 0.569282 -0.642788 -0.728551 0.236721 -0.642788 -0.764655 0.406574 -0.5 -0.676377 0.359636 -0.642788 -0.222521 0.974928 1.74846e-07 -0.204753 0.963287 -0.173648 -0.368915 0.913098 -0.173648 -0.0896393 0.995974 1.74846e-07 -0.0343695 0.984208 -0.173648 0.290381 0.893701 -0.34202 0.13078 0.930547 -0.34202 0.304323 0.936608 -0.173648 -0.180057 0.847101 -0.5 -0.0302236 0.865498 -0.5 -0.15927 0.749304 -0.642788 -0.458923 0.734431 -0.5 0.137059 0.975224 -0.173648 0.178557 0.98393 1.74846e-07 -0.567548 0.30177 -0.766044 -0.506523 0.395739 -0.766044 0.309017 0.951056 1.74846e-07 -0.269516 0.210569 -0.939693 -0.394005 0.307831 -0.866025 0.0536602 0.165149 -0.984808 3.68499e-09 1.13412e-08 -1 -0.405942 0.649642 -0.642788 -0.682437 0.533178 -0.5 -0.611327 0.198632 -0.766044 -0.823639 0.267617 -0.5 -0.636532 0.0894588 -0.766044 -0.642396 -0.0224329 -0.766044 -0.628741 -0.133643 -0.766044 -0.865498 -0.0302238 -0.5 -0.749304 -0.159269 -0.642788 -0.595982 -0.240792 -0.766044 -0.521869 0.835164 -0.173648 -0.473869 0.880595 1.74846e-07 -0.802965 -0.324419 -0.5 -0.710264 -0.286965 -0.642788 -0.649642 -0.405942 -0.642788 -0.847101 -0.180057 -0.5 -0.734431 -0.458923 -0.5 -0.545115 -0.340626 -0.766044 -0.236721 -0.728552 -0.642788 -0.406574 -0.764655 -0.5 -0.643582 -0.579484 -0.5 0.133643 -0.628741 -0.766044 0.0267346 -0.765578 -0.642788 0.022433 -0.642396 -0.766045 -0.963287 -0.204753 -0.173648 -0.990686 -0.136167 1.74846e-07 -0.984208 -0.0343692 -0.173648 0.405942 -0.649642 -0.642788 0.340625 -0.545115 -0.766044 0.430109 -0.477684 -0.766044 0.286965 -0.710264 -0.642788 0.324419 -0.802965 -0.5 0.728551 -0.236721 -0.642788 0.764655 -0.406574 -0.5 0.676377 -0.359636 -0.642788 0.682437 -0.533178 -0.5 0.460065 -0.887885 1.74846e-07 0.368915 -0.913098 -0.173648 0.521869 -0.835164 -0.173648 0.758589 -0.106613 -0.642788 0.636532 -0.0894587 -0.766044 0.642396 0.022433 -0.766045 0.776039 -0.606308 -0.173648 0.869534 -0.462339 -0.173648 0.854419 -0.519584 1.74846e-07 0.595982 0.240792 -0.766044 0.545115 0.340625 -0.766044 0.441159 0.829699 -0.34202 0.406574 0.764655 -0.5 0.267617 0.823639 -0.5 0.359636 0.676377 -0.642788 0.236721 0.728551 -0.642788 0.462339 0.869534 -0.173648 0.30177 0.567548 -0.766044 0.198632 0.611327 -0.766044 0.984208 0.0343693 -0.173648 0.963287 0.204753 -0.173648 0.990268 0.139173 1.74846e-07 0.10569 0.32528 -0.939693 0.154508 0.475528 -0.866025 0.234736 0.441474 -0.866025 0.160569 0.301986 -0.939693 0.0815229 0.153322 -0.984808 0.669131 0.743145 1.74846e-07 0.731855 0.658965 -0.173648 0.606308 0.776039 -0.173648 0.559193 0.829038 1.74846e-07 0.438371 0.898794 1.74846e-07 0.471624 0.603651 -0.642788 0.533178 0.682437 -0.5 0.395739 0.506523 -0.766044 0.643582 0.579484 -0.5 0.569282 0.512584 -0.642788 0.477684 0.430109 -0.766044 0.649642 0.405942 -0.642788 0.802965 0.324419 -0.5 0.734431 0.458924 -0.5 0.628741 0.133643 -0.766044 0.765578 0.0267346 -0.642788 0.865498 0.0302239 -0.5 0.611327 -0.198632 -0.766044 0.857597 -0.120527 -0.5 0.567548 -0.30177 -0.766044 0.823639 -0.267617 -0.5 0.506523 -0.395739 -0.766044 -0.137059 -0.975224 -0.173648 -0.203456 -0.979084 1.74846e-07 -0.304322 -0.936608 -0.173648 -0.835164 -0.521869 -0.173648 -0.731855 -0.658965 -0.173648 -0.775711 -0.631088 1.74846e-07 0.458923 -0.734431 -0.5 0.240792 -0.595982 -0.766044 0.15927 -0.749304 -0.642788 0.0302237 -0.865498 -0.5 0.180057 -0.847101 -0.5 -0.106613 -0.758589 -0.642788 -0.0894588 -0.636532 -0.766044 -0.120527 -0.857597 -0.5 -0.267616 -0.823639 -0.5 -0.533178 -0.682437 -0.5 -0.869534 0.462339 -0.173648 -0.858449 0.512899 1.74846e-07 -0.776039 0.606308 -0.173648 0.848048 0.529919 1.74846e-07 0.913545 0.406737 1.74846e-07 0.835164 0.521869 -0.173648 0.990686 -0.136167 1.74846e-07 0.975224 -0.137059 -0.173648 1 -3.49691e-08 1.74846e-07 0.578533 0.740488 -0.34202 0.307831 0.394005 -0.866025 0.210569 0.269516 -0.939693 5.61309e-09 1.05212e-08 -1 0.106908 0.136837 -0.984808 0.766044 0.642788 1.74846e-07 0.698328 0.628777 -0.34202 0.371572 0.334565 -0.866025 0.25417 0.228856 -0.939693 7.3679e-09 9.3764e-09 -1 0.129046 0.116193 -0.984808 0.913098 0.368915 -0.173648 0.796904 0.497961 -0.34202 0.424024 0.26496 -0.866025 0.290049 0.181243 -0.939693 8.89526e-09 7.94211e-09 -1 0.147262 0.0920195 -0.984808 0.961262 0.275637 1.74846e-07 0.871268 0.352015 -0.34202 0.463592 0.187303 -0.866025 0.317115 0.128123 -0.939693 1.0148e-08 6.26264e-09 -1 0.161004 0.0650497 -0.984808 0.775711 -0.631088 1.74846e-07 0.682553 -0.730836 1.74846e-07 0.919158 0.195373 -0.34202 0.489074 0.103956 -0.866025 0.334546 0.07111 -0.939693 1.10875e-08 4.38984e-09 -1 0.169854 0.0361035 -0.984808 0.93912 0.0327948 -0.34202 0.499695 0.0174497 -0.866025 0.341812 0.0119363 -0.939693 1.16847e-08 2.38152e-09 -1 0.173542 0.00606023 -0.984808 0.962917 -0.269797 1.74846e-07 0.936608 -0.304322 -0.173648 0.930548 -0.13078 -0.34202 0.495134 -0.0695865 -0.866025 0.338692 -0.0476 -0.939693 1.19211e-08 2.99673e-10 -1 0.171958 -0.0241671 -0.984808 0.917211 -0.398401 1.74846e-07 0.893701 -0.290381 -0.34202 0.475528 -0.154508 -0.866025 0.32528 -0.10569 -0.939693 1.17896e-08 -1.79142e-09 -1 0.165149 -0.0536602 -0.984808 0.203456 -0.979084 1.74846e-07 0.0682424 -0.997669 1.74846e-07 0.204753 -0.963287 -0.173648 0.829699 -0.441159 -0.34202 0.441474 -0.234736 -0.866025 0.301986 -0.160569 -0.939693 1.1294e-08 -3.82722e-09 -1 0.153322 -0.0815229 -0.984808 0.658965 -0.731855 -0.173648 0.740488 -0.578532 -0.34202 0.394005 -0.307831 -0.866025 0.269515 -0.210569 -0.939693 1.04499e-08 -5.74486e-09 -1 0.136837 -0.106908 -0.984808 0.57668 -0.81697 1.74846e-07 0.628777 -0.698328 -0.34202 0.334565 -0.371572 -0.866025 0.228856 -0.25417 -0.939693 9.28307e-09 -7.48514e-09 -1 0.116193 -0.129046 -0.984808 -0.33488 -0.942261 1.74846e-07 -0.460065 -0.887885 1.74846e-07 0.497961 -0.796905 -0.34202 0.26496 -0.424024 -0.866025 0.181243 -0.290049 -0.939693 7.82971e-09 -8.99436e-09 -1 0.0920195 -0.147262 -0.984808 0.33488 -0.942261 1.74846e-07 0.352015 -0.871268 -0.34202 0.187303 -0.463592 -0.866025 0.128123 -0.317116 -0.939693 6.13463e-09 -1.02259e-08 -1 0.0650497 -0.161004 -0.984808 0.0343691 -0.984208 -0.173648 0.195373 -0.919158 -0.34202 0.103956 -0.489074 -0.866025 0.07111 -0.334546 -0.939693 4.25017e-09 -1.11418e-08 -1 0.0361035 -0.169854 -0.984808 -0.0682424 -0.997669 1.74846e-07 0.0327949 -0.93912 -0.34202 0.0174497 -0.499695 -0.866025 0.0119364 -0.341812 -0.939693 2.2345e-09 -1.17137e-08 -1 0.00606025 -0.173542 -0.984808 -0.854419 -0.519584 1.74846e-07 -0.917211 -0.398401 1.74846e-07 -0.13078 -0.930547 -0.34202 -0.0695865 -0.495134 -0.866025 -0.0476 -0.338692 -0.939693 1.49848e-10 -1.19239e-08 -1 -0.0241671 -0.171958 -0.984808 -0.462339 -0.869534 -0.173648 -0.290381 -0.893701 -0.34202 -0.154509 -0.475528 -0.866025 -0.10569 -0.32528 -0.939693 -1.93943e-09 -1.17661e-08 -1 -0.0536602 -0.165149 -0.984808 -0.57668 -0.81697 1.74846e-07 -0.606308 -0.776039 -0.173648 -0.441159 -0.829699 -0.34202 -0.234736 -0.441474 -0.866025 -0.160569 -0.301986 -0.939693 -3.96883e-09 -1.1245e-08 -1 -0.0815228 -0.153322 -0.984808 -0.682553 -0.730836 1.74846e-07 -0.578533 -0.740488 -0.34202 -0.307831 -0.394005 -0.866025 -0.210569 -0.269516 -0.939693 -5.87571e-09 -1.03768e-08 -1 -0.106908 -0.136837 -0.984808 -1 -1.16027e-07 1.74846e-07 -0.99095 0.134233 1.74846e-07 -0.975224 0.137059 -0.173648 -0.698328 -0.628777 -0.34202 -0.371572 -0.334565 -0.866025 -0.25417 -0.228856 -0.939693 -7.6012e-09 -9.18828e-09 -1 -0.129046 -0.116193 -0.984808 -0.913098 -0.368915 -0.173648 -0.796905 -0.497961 -0.34202 -0.424024 -0.26496 -0.866025 -0.29005 -0.181243 -0.939693 -9.09203e-09 -7.71607e-09 -1 -0.147262 -0.0920195 -0.984808 -0.962917 -0.269797 1.74846e-07 -0.871268 -0.352015 -0.34202 -0.463592 -0.187303 -0.866025 -0.317116 -0.128123 -0.939693 -1.03022e-08 -6.00565e-09 -1 -0.161004 -0.0650498 -0.984808 -0.781831 0.62349 1.74846e-07 -0.691063 0.722795 1.74846e-07 -0.919158 -0.195373 -0.34202 -0.489074 -0.103956 -0.866025 -0.334546 -0.0711101 -0.939693 -1.11943e-08 -4.10983e-09 -1 -0.169854 -0.0361035 -0.984808 -0.93912 -0.0327947 -0.34202 -0.499695 -0.0174497 -0.866025 -0.341812 -0.0119363 -0.939693 -1.17408e-08 -2.08713e-09 -1 -0.173542 -0.00606022 -0.984808 -0.963963 0.266037 1.74846e-07 -0.936608 0.304322 -0.173648 -0.930548 0.13078 -0.34202 -0.495134 0.0695866 -0.866025 -0.338692 0.0476 -0.939693 -1.19249e-08 4.30262e-15 -1 -0.171958 0.0241672 -0.984808 -0.919528 0.393025 1.74846e-07 -0.893701 0.290381 -0.34202 -0.475528 0.154508 -0.866025 -0.32528 0.10569 -0.939693 -1.17502e-08 2.03345e-09 -1 -0.165149 0.0536602 -0.984808 -0.351375 0.936235 1.74846e-07 -0.829699 0.441159 -0.34202 -0.441474 0.234736 -0.866025 -0.301986 0.160569 -0.939693 -1.12314e-08 4.00735e-09 -1 -0.153322 0.0815229 -0.984808 -0.658965 0.731855 -0.173648 -0.740488 0.578532 -0.34202 -1.03835e-08 5.86386e-09 -1 -0.136837 0.106908 -0.984808 -0.587785 0.809017 1.74846e-07 -0.628777 0.698328 -0.34202 -9.23155e-09 7.5486e-09 -1 -0.116193 0.129046 -0.984808 -0.032795 0.93912 -0.34202 -0.497961 0.796904 -0.34202 -0.187303 0.463592 -0.866025 -0.181243 0.290049 -0.939693 -7.80914e-09 9.01222e-09 -1 -0.0920195 0.147262 -0.984808 -0.324419 0.802965 -0.5 -0.352015 0.871268 -0.34202 -0.286965 0.710264 -0.642788 -0.240793 0.595982 -0.766044 -6.15798e-09 1.02119e-08 -1 -0.195373 0.919158 -0.34202 -0.133643 0.628741 -0.766044 -0.103956 0.489074 -0.866025 -4.32644e-09 1.11124e-08 -1 0.0448649 0.998993 1.74846e-07 -0.0267344 0.765578 -0.642788 -0.0224328 0.642396 -0.766044 -0.0174499 0.499695 -0.866025 -0.0119364 0.341812 -0.939693 0.0476001 0.338692 -0.939693 0.120528 0.857597 -0.5 0.106613 0.758589 -0.642788 0.0894586 0.636532 -0.766044 0.0695864 0.495134 -0.866025 - - - - - - - - - - - - - - -

0 1 2 3 4 5 6 7 2 0 2 7 6 8 9 9 7 6 10 8 11 8 10 9 12 13 11 10 11 13 12 14 15 15 13 12 16 14 17 14 16 15 18 19 17 16 17 19 18 20 21 21 19 18 20 22 21 23 1 0 23 24 25 25 1 23 26 24 27 24 26 25 28 29 27 26 27 29 28 30 31 31 29 28 32 30 33 30 32 31 34 35 33 32 33 35 34 36 37 37 35 34 38 36 4 36 38 37 39 40 41 38 4 3 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 60 60 62 66 67 68 69 68 67 66 70 69 71 68 71 69 22 20 70 70 71 22 65 61 63 61 65 62 64 55 54 63 55 64 57 56 58 54 56 57 49 59 50 59 58 50 53 52 48 52 49 48 42 44 51 42 51 53 43 45 47 43 47 44 46 39 41 45 39 46 5 40 3 41 40 5 72 73 74 75 76 77 73 78 79 78 73 72 80 81 79 79 78 80 82 81 80 82 83 84 84 81 82 85 86 87 84 83 88 89 90 91 92 93 94 77 95 96 97 76 75 98 99 100 101 102 103 104 105 106 100 104 106 105 104 107 99 98 101 100 106 98 103 102 95 99 101 103 96 75 77 102 96 95 89 76 97 90 93 91 97 90 89 93 92 91 94 85 87 94 87 92 83 86 88 88 86 85 108 109 110 111 112 113 108 114 115 114 108 110 116 115 117 114 117 115 118 116 117 119 118 120 118 119 116 121 122 123 124 125 120 112 126 127 128 129 130 131 132 133 113 134 111 135 136 137 138 139 140 141 142 143 143 136 135 136 143 142 138 137 139 138 135 137 132 140 133 133 140 139 111 134 131 131 134 132 113 112 127 128 130 126 126 130 127 128 122 129 123 124 121 122 121 129 120 125 119 123 125 124 144 145 146 147 148 149 150 151 144 144 146 150 151 152 153 152 151 150 154 153 155 152 155 153 156 157 154 154 155 156 157 158 159 158 157 156 160 159 161 158 161 159 162 163 160 160 161 162 163 164 165 164 163 162 166 165 167 164 167 165 168 169 166 166 167 168 170 169 168 170 171 169 146 145 172 172 173 174 173 172 145 175 174 176 173 176 174 177 178 175 175 176 177 178 179 180 179 178 177 181 180 182 179 182 180 183 184 181 181 182 183 184 185 186 185 184 183 187 186 188 185 188 186 189 190 187 187 188 189 190 191 192 191 190 189 191 147 192 193 194 195 192 147 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 222 225 226 227 228 223 228 227 229 230 226 226 228 229 230 231 232 231 230 229 233 232 234 231 234 232 235 170 233 233 234 235 171 170 235 221 225 222 221 223 227 215 217 224 215 224 225 216 218 220 216 220 217 219 210 209 218 210 219 212 211 213 209 211 212 204 214 205 214 213 205 208 207 203 207 204 203 197 199 206 197 206 208 198 200 202 198 202 199 201 193 195 200 193 201 148 194 149 195 194 148 147 149 196 236 237 238 239 240 241 242 243 244 236 245 246 247 248 249 243 250 247 251 249 252 253 254 255 256 257 258 257 259 260 261 251 262 263 264 265 266 262 267 265 264 268 269 270 271 272 273 269 241 240 274 275 271 276 277 278 279 280 281 282 283 284 285 286 287 288 288 289 285 290 291 284 290 292 293 279 287 286 294 278 281 292 295 293 274 296 297 295 298 297 299 300 275 282 300 299 301 302 239 270 269 273 303 302 304 305 306 307 307 308 303 309 273 272 310 311 312 268 309 272 313 267 314 313 314 315 316 263 265 315 310 317 264 309 268 248 247 250 276 271 270 300 271 275 280 282 299 294 281 280 277 281 278 286 277 279 289 288 287 283 285 289 291 285 284 293 291 290 298 295 292 296 295 297 240 296 274 301 239 241 304 302 301 308 302 303 306 308 307 312 311 305 305 311 306 317 310 312 314 310 315 266 267 313 261 262 266 252 262 251 248 252 249 243 242 250 238 242 244 246 237 236 237 242 238 253 246 245 253 255 258 253 245 254 256 259 257 255 256 258 259 316 260 265 260 316 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 330 340 341 339 342 343 344 345 343 346 347 348 349 350 351 352 353 354 355 356 355 357 358 359 360 361 362 363 364 365 350 349 361 366 367 368 348 369 367 370 361 322 321 335 371 372 343 373 374 323 365 375 350 376 348 353 353 368 377 378 351 325 379 351 377 380 325 379 326 380 381 382 326 383 384 383 381 356 385 386 387 388 389 390 383 388 389 342 391 384 392 388 389 392 341 393 394 332 340 395 342 396 397 398 399 400 401 402 403 404 405 402 406 407 408 409 410 318 409 411 412 413 414 415 416 417 418 419 420 421 329 422 423 424 423 425 426 359 422 424 361 427 359 425 428 429 430 431 432 433 434 435 426 425 429 436 373 433 435 434 428 374 373 437 435 436 433 359 427 422 438 439 440 441 427 442 442 427 361 424 423 426 442 361 370 443 425 444 445 428 443 443 446 447 421 448 449 448 445 447 450 329 449 447 451 449 328 452 420 453 328 454 453 416 452 415 407 455 414 453 456 455 409 457 407 414 458 459 457 318 320 404 459 460 461 462 463 464 465 320 466 402 396 467 468 467 403 405 469 397 468 405 470 468 398 471 472 471 397 473 474 393 471 331 472 393 475 340 332 476 477 478 438 440 441 479 480 481 427 441 440 482 483 484 485 422 440 486 436 435 423 485 444 423 444 425 436 487 437 429 428 434 443 428 425 488 437 489 445 486 435 486 487 436 374 437 488 373 436 437 427 440 422 490 439 438 481 439 490 422 485 423 439 491 485 492 487 486 444 491 446 444 446 443 487 493 489 428 445 435 447 445 443 494 489 495 448 492 486 492 493 487 488 489 494 437 487 489 440 439 485 479 481 490 480 496 481 485 491 444 497 491 481 498 493 492 446 497 451 451 447 446 493 499 495 445 448 486 449 448 447 500 495 501 421 498 492 498 499 493 494 495 500 489 493 495 439 481 491 502 496 480 502 431 496 491 497 446 503 497 496 504 499 498 503 450 451 451 450 449 499 505 501 448 421 492 329 421 449 506 501 507 420 504 498 504 505 499 500 501 506 495 499 501 481 496 497 432 431 502 417 508 509 497 503 451 510 503 431 511 505 504 450 510 327 450 327 329 505 512 507 421 420 498 328 420 329 513 507 514 452 511 504 511 512 505 506 507 513 501 505 507 496 431 503 484 430 432 483 430 484 503 510 450 430 515 510 516 512 511 327 515 454 454 328 327 512 517 514 420 452 504 453 452 328 518 514 519 416 516 511 516 517 512 513 514 518 507 512 514 430 510 431 520 483 482 520 521 483 510 515 327 522 515 483 523 517 516 454 522 456 456 453 454 517 524 519 452 416 511 414 416 453 525 519 526 415 523 516 523 524 517 518 519 525 514 517 519 430 483 515 527 521 520 527 418 521 515 522 454 528 522 521 529 524 523 528 458 456 456 458 414 524 530 526 416 415 516 407 415 414 531 526 532 455 529 523 529 530 524 525 526 531 519 524 526 483 521 522 419 418 527 533 534 535 522 528 456 536 528 418 537 530 529 458 536 408 458 408 407 530 538 532 415 455 523 409 455 407 539 532 540 457 537 529 537 538 530 531 532 539 526 530 532 521 418 528 508 417 419 509 541 417 528 536 458 542 536 417 543 538 537 408 542 410 410 409 408 538 544 540 455 457 529 318 457 409 545 540 546 459 543 537 543 544 538 539 540 545 532 538 540 417 536 418 547 541 509 547 413 541 536 542 408 548 542 541 549 544 543 548 319 410 410 319 318 544 550 546 457 459 537 320 459 318 551 546 552 404 549 543 549 550 544 545 546 551 540 544 546 417 541 542 411 413 547 553 554 462 542 548 410 555 548 413 556 550 549 319 555 466 319 466 320 550 557 552 459 404 543 402 404 320 558 552 559 403 556 549 556 557 550 551 552 558 546 550 552 541 413 548 560 412 411 535 412 560 548 555 319 412 561 555 562 557 556 466 561 406 466 406 402 557 563 559 404 403 549 405 403 402 564 559 565 467 562 556 562 563 557 558 559 564 552 557 559 413 412 555 533 535 560 534 566 535 555 561 466 567 561 535 568 563 562 406 567 470 470 405 406 563 569 565 403 467 556 468 467 405 570 565 571 396 568 562 568 569 563 564 565 570 559 563 565 412 535 561 572 566 534 572 460 566 561 567 406 573 567 566 574 569 568 573 469 470 470 469 468 569 575 571 467 396 562 397 396 468 576 571 577 398 574 568 574 575 569 570 571 576 565 569 571 535 566 567 461 460 572 578 579 463 567 573 470 580 573 460 581 575 574 469 580 473 469 473 397 575 582 577 396 398 568 471 398 397 583 577 584 472 581 574 581 582 575 576 577 583 571 575 577 566 460 573 553 462 461 554 585 462 573 580 469 462 586 580 587 582 581 473 586 474 474 471 473 582 588 584 398 472 574 393 472 471 589 584 590 331 587 581 587 588 582 583 584 589 577 582 584 462 580 460 591 585 554 591 592 585 580 586 473 593 586 585 594 588 587 474 593 394 474 394 393 588 595 590 472 331 581 332 331 393 596 590 597 330 594 587 594 595 588 589 590 596 584 588 590 462 585 586 598 592 591 598 464 592 586 593 474 599 593 592 600 595 594 394 599 475 394 475 332 595 601 597 331 330 587 340 330 332 602 597 603 339 600 594 600 601 595 596 597 602 590 595 597 585 592 593 465 464 598 604 605 606 593 599 394 464 607 599 608 601 600 475 607 395 475 395 340 601 609 603 330 339 594 342 339 340 610 603 611 341 608 600 608 609 601 602 603 610 597 601 603 592 464 599 578 463 465 579 612 463 599 607 475 613 607 463 614 609 608 395 613 391 391 342 395 609 615 611 339 341 600 389 341 342 616 611 617 392 614 608 614 615 609 610 611 616 603 609 611 464 463 607 618 612 579 618 399 612 607 613 395 619 613 612 620 615 614 619 387 391 391 387 389 615 621 617 341 392 608 388 392 389 622 617 623 384 620 614 620 621 615 616 617 622 611 615 617 463 612 613 400 399 618 624 625 478 613 619 391 626 619 399 627 621 620 387 626 390 387 390 388 621 628 623 392 384 614 383 384 388 629 623 630 381 627 620 627 628 621 622 623 629 617 621 623 612 399 619 604 401 400 606 401 604 619 626 387 401 631 626 632 628 627 390 631 382 382 383 390 628 633 630 384 381 620 326 381 383 634 630 635 380 632 627 632 633 628 629 630 634 623 628 630 401 626 399 636 606 605 636 637 606 626 631 390 638 631 606 639 633 632 382 638 324 382 324 326 633 640 635 381 380 627 325 380 326 641 635 642 379 639 632 639 640 633 634 635 641 630 633 635 401 606 631 643 637 636 643 476 637 631 638 382 644 638 637 645 640 639 324 644 378 324 378 325 640 646 642 380 379 632 351 379 325 647 642 648 377 645 639 645 646 640 641 642 647 635 640 642 606 637 638 477 476 643 356 649 354 638 644 324 476 650 644 651 646 645 378 650 352 378 352 351 646 652 648 379 377 639 353 377 351 653 648 654 368 651 645 651 652 646 647 648 653 642 646 648 637 476 644 624 478 477 625 655 478 644 650 378 650 478 656 372 652 651 352 656 376 376 353 352 652 371 654 377 368 645 348 368 353 657 654 658 369 372 651 372 371 652 653 654 657 648 652 654 476 478 650 659 655 625 659 385 655 650 656 352 655 660 656 350 344 369 349 376 660 376 349 348 371 347 658 368 369 651 369 348 350 661 658 662 344 343 372 343 347 371 657 658 661 654 371 658 478 655 656 386 385 659 360 663 366 656 660 376 664 660 385 344 350 375 664 365 349 665 666 346 347 666 662 369 344 372 344 375 345 667 662 668 345 346 343 346 666 347 661 662 667 658 347 662 655 385 660 649 356 386 365 669 375 660 664 349 670 664 356 375 671 345 670 669 365 345 672 346 671 375 669 666 338 668 672 345 671 673 668 337 665 346 672 665 338 666 667 668 673 662 666 668 356 664 385 357 355 354 669 362 671 664 670 365 355 674 670 671 364 672 674 362 669 672 675 665 362 364 671 676 338 665 364 675 672 677 337 334 665 675 676 676 336 338 673 337 677 668 338 337 356 355 670 678 358 357 679 675 364 670 674 669 358 663 674 680 676 675 663 363 362 681 336 676 363 679 364 682 334 336 679 680 675 683 335 682 681 676 680 682 336 681 677 334 333 337 336 334 355 358 674 366 678 367 360 684 363 674 663 362 360 363 663 684 685 679 684 679 363 685 686 680 685 680 679 686 687 681 686 681 680 687 683 682 687 682 681 322 335 683 333 335 321 334 682 335 678 366 358 663 358 366 684 359 424 361 360 366 685 424 426 359 684 360 686 426 429 424 685 684 687 429 434 426 686 685 683 434 433 429 687 686 322 433 373 434 683 687 373 323 322 433 322 683

+ + +

1413 1415 1414 1416 1418 1417 1419 1421 1420 1413 1414 1422 1423 1425 1424 1426 1428 1427 1429 1431 1430 1432 1434 1433 1435 1432 1436 1432 1425 1423 1437 1436 1432 1426 1438 1428 1416 1440 1439 1441 1417 1418 1442 1418 1423 1443 1444 1419 1445 1447 1446 1448 1450 1449 1451 1453 1452 1434 1454 1433 1455 1442 1423 1456 1458 1457 1459 1416 1460 1442 1461 1418 1462 1464 1463 1465 1466 1458 1447 1462 1467 1468 1469 1439 1470 1457 1471 1472 1466 1465 1418 1473 1441 1469 1416 1439 1423 1474 1455 1459 1440 1416 1456 1475 1458 1435 1425 1432 1464 1472 1476 1477 1479 1478 1480 1445 1481 1482 1484 1483 1485 1487 1486 1488 1490 1489 1454 1434 1491 1492 1494 1493 1434 1495 1491 1428 1438 1451 1496 1497 1444 1498 1426 1427 1499 1444 1443 1498 1427 1422 1421 1419 1500 1501 1503 1502 1504 1419 1503 1505 1501 1502 1414 1498 1422 1505 1507 1506 1415 1508 1414 1508 1415 1509 1431 1506 1507 1510 1501 1511 1508 1509 1512 1511 1501 1513 1512 1514 1508 1515 1508 1514 1516 1517 1513 1515 1514 1518 1513 1519 1516 1519 1513 1520 1521 1523 1522 1524 1526 1525 1527 1528 1520 1520 1528 1519 1529 1528 1527 1530 1531 1523 1531 1533 1532 1471 1524 1534 1535 1532 1533 1527 1536 1529 1537 1539 1538 1538 1536 1537 1535 1515 1540 1535 1540 1532 1541 1515 1518 1539 1542 1538 1542 1543 1538 1544 1541 1518 1545 1496 1444 1541 1544 1546 1547 1549 1548 1550 1552 1551 1471 1534 1470 1553 1555 1554 1554 1541 1546 1556 1558 1557 1559 1561 1560 1554 1563 1562 1564 1565 1556 1566 1568 1567 1554 1562 1569 1570 1572 1571 1573 1575 1574 1576 1578 1577 1579 1581 1580 1582 1578 1576 1494 1584 1583 1576 1577 1581 1585 1586 1581 1587 1589 1588 1590 1587 1588 1576 1592 1591 1593 1595 1594 1589 1596 1592 1597 1599 1598 1597 1601 1600 1602 1592 1603 1597 1598 1588 1600 1599 1597 1595 1604 1594 1605 1607 1606 1493 1608 1492 1609 1607 1605 1610 1611 1605 1609 1605 1612 1450 1495 1449 1592 1602 1591 1470 1469 1613 1449 1494 1614 1611 1610 1615 1615 1610 1616 1595 1593 1617 1618 1610 1569 1569 1619 1618 1571 1621 1620 1622 1623 1569 1619 1569 1623 1624 1564 1566 1568 1626 1625 1554 1555 1563 1453 1451 1438 1627 1629 1628 1568 1572 1626 1572 1570 1630 1631 1633 1632 1537 1536 1527 1511 1513 1517 1504 1503 1510 1497 1634 1493 1437 1432 1433 1474 1423 1424 1461 1473 1418 1416 1417 1460 1458 1471 1457 1458 1475 1465 1464 1466 1472 1464 1476 1463 1462 1463 1467 1447 1467 1446 1445 1446 1481 1481 1479 1480 1480 1479 1477 1487 1635 1478 1478 1479 1487 1635 1487 1485 1486 1575 1573 1486 1487 1575 1575 1482 1483 1483 1574 1575 1636 1484 1482 1482 1488 1637 1637 1636 1482 1488 1489 1638 1637 1488 1638 1490 1488 1629 1629 1640 1639 1490 1629 1639 1627 1628 1641 1640 1629 1627 1641 1628 1642 1453 1642 1452 1628 1452 1642 1643 1645 1644 1646 1648 1647 1649 1644 1650 1470 1534 1469 1583 1651 1494 1621 1594 1652 1449 1614 1653 1613 1469 1654 1652 1594 1604 1605 1606 1597 1589 1592 1588 1591 1655 1576 1580 1581 1586 1571 1620 1570 1572 1630 1626 1568 1625 1567 1566 1567 1624 1564 1624 1565 1556 1565 1558 1647 1558 1646 1647 1557 1558 1648 1644 1649 1648 1646 1644 1656 1645 1643 1645 1650 1644 1643 1551 1657 1657 1656 1643 1551 1659 1658 1657 1551 1658 1552 1550 1660 1659 1551 1552 1550 1632 1661 1660 1550 1661 1633 1631 1662 1550 1631 1632 1548 1662 1547 1631 1547 1662 1547 1543 1549 1542 1549 1543 1571 1663 1594 1654 1469 1468 1594 1621 1571 1525 1534 1524 1526 1521 1522 1522 1525 1526 1530 1523 1521 1531 1530 1533 1515 1541 1540 1546 1553 1554 1562 1622 1569 1618 1616 1610 1611 1612 1605 1606 1601 1597 1598 1590 1588 1596 1603 1592 1655 1582 1576 1577 1585 1581 1593 1579 1664 1579 1593 1581 1665 1617 1593 1593 1664 1665 1594 1663 1666 1559 1666 1561 1663 1561 1666 1560 1430 1559 1506 1431 1429 1429 1430 1560 1507 1505 1502 1503 1501 1510 1419 1504 1500 1420 1443 1419 1499 1545 1444 1497 1493 1444 1493 1634 1608 1584 1494 1492 1494 1651 1614 1449 1653 1448 1449 1495 1434 1667 1669 1668 1670 1672 1671 1673 1675 1674 1667 1677 1676 1678 1680 1679 1681 1683 1682 1684 1686 1685 1687 1689 1688 1690 1692 1691 1693 1680 1694 1691 1695 1689 1696 1697 1681 1698 1700 1699 1701 1702 1671 1703 1705 1704 1706 1707 1697 1708 1710 1709 1711 1713 1712 1714 1716 1715 1687 1718 1717 1719 1720 1704 1721 1723 1722 1724 1726 1725 1727 1728 1703 1729 1731 1730 1732 1734 1733 1730 1708 1735 1736 1737 1720 1723 1738 1698 1732 1740 1739 1741 1727 1702 1742 1670 1725 1737 1743 1679 1744 1724 1699 1722 1733 1745 1746 1690 1693 1740 1731 1747 1748 1750 1749 1710 1748 1751 1752 1754 1753 1752 1755 1750 1756 1754 1757 1717 1759 1758 1757 1715 1760 1761 1711 1758 1714 1707 1762 1763 1712 1764 1765 1766 1683 1767 1768 1763 1769 1765 1770 1674 1772 1771 1773 1774 1684 1774 1775 1772 1686 1777 1776 1676 1778 1770 1779 1777 1780 1669 1782 1781 1782 1784 1783 1780 1786 1785 1786 1788 1787 1789 1790 1784 1791 1788 1792 1789 1794 1793 1794 1796 1795 1797 1798 1792 1799 1796 1800 1801 1797 1802 1803 1802 1804 1800 1806 1805 1807 1808 1806 1809 1811 1810 1812 1804 1811 1810 1814 1813 1807 1816 1815 1817 1819 1818 1816 1817 1818 1820 1819 1821 1822 1814 1823 1824 1826 1825 1823 1825 1827 1828 1830 1829 1829 1820 1831 1832 1830 1833 1824 1835 1834 1835 1837 1836 1832 1839 1838 1840 1841 1837 1842 1838 1843 1844 1840 1845 1846 1847 1845 1842 1849 1848 1850 1852 1851 1850 1848 1853 1854 1856 1855 1857 1846 1856 1858 1860 1859 1861 1855 1862 1863 1865 1864 1866 1867 1860 1868 1870 1869 1871 1870 1872 1873 1875 1874 1876 1878 1877 1873 1880 1879 1881 1883 1882 1874 1885 1884 1884 1886 1876 1887 1889 1888 1890 1888 1891 1892 1894 1893 1893 1895 1880 1889 1897 1896 1898 1900 1899 1901 1903 1902 1904 1896 1905 1898 1906 1891 1907 1900 1902 1901 1909 1908 1909 1911 1910 1912 1914 1913 1915 1911 1916 1913 1882 1917 1918 1916 1914 1919 1921 1920 1904 1922 1892 1921 1924 1923 1919 1925 1881 1924 1927 1926 1927 1929 1928 1930 1931 1877 1932 1933 1929 1934 1932 1935 1931 1936 1869 1937 1867 1938 1935 1937 1939 1862 1864 1940 1941 1863 1871 1859 1851 1942 1943 1675 1944 1764 1767 1763 1945 1768 1943 1713 1764 1712 1761 1713 1711 1759 1761 1758 1718 1759 1717 1688 1718 1687 1695 1688 1689 1692 1695 1691 1746 1692 1690 1694 1746 1693 1678 1694 1680 1743 1678 1679 1736 1743 1737 1719 1736 1720 1705 1719 1704 1728 1705 1703 1741 1728 1727 1701 1741 1702 1672 1701 1671 1742 1672 1670 1726 1742 1725 1744 1726 1724 1700 1744 1699 1738 1700 1698 1721 1738 1723 1745 1721 1722 1734 1745 1733 1739 1734 1732 1747 1739 1740 1729 1747 1731 1735 1729 1730 1709 1735 1708 1751 1709 1710 1749 1751 1748 1755 1749 1750 1753 1755 1752 1756 1753 1754 1760 1756 1757 1716 1760 1715 1762 1716 1714 1706 1762 1707 1696 1706 1697 1682 1696 1681 1766 1682 1683 1769 1766 1765 1778 1769 1770 1677 1778 1676 1668 1677 1667 1781 1668 1669 1783 1781 1782 1790 1783 1784 1793 1790 1789 1795 1793 1794 1799 1795 1796 1805 1799 1800 1808 1805 1806 1815 1808 1807 1818 1815 1816 1819 1817 1821 1820 1821 1831 1829 1831 1828 1830 1828 1833 1832 1833 1839 1838 1839 1843 1842 1843 1849 1848 1849 1853 1850 1853 1852 1851 1852 1942 1859 1942 1858 1860 1858 1866 1867 1866 1938 1937 1938 1939 1935 1939 1934 1932 1934 1933 1929 1933 1928 1927 1928 1926 1924 1926 1923 1921 1923 1920 1919 1920 1925 1881 1925 1883 1882 1883 1917 1913 1917 1912 1914 1912 1918 1916 1918 1915 1911 1915 1910 1909 1910 1908 1901 1908 1903 1902 1903 1907 1900 1907 1899 1898 1899 1906 1891 1906 1890 1888 1890 1887 1889 1887 1897 1896 1897 1905 1904 1905 1922 1892 1922 1894 1893 1894 1895 1880 1895 1879 1873 1879 1875 1874 1875 1885 1884 1885 1886 1876 1886 1878 1877 1878 1930 1931 1930 1936 1869 1936 1868 1870 1868 1872 1871 1872 1941 1863 1941 1865 1864 1865 1940 1862 1940 1861 1855 1861 1854 1856 1854 1857 1846 1857 1847 1845 1847 1844 1840 1844 1841 1837 1841 1836 1835 1836 1834 1824 1834 1826 1825 1826 1827 1823 1827 1822 1814 1822 1813 1810 1813 1809 1811 1809 1812 1804 1812 1803 1802 1803 1801 1797 1801 1798 1792 1798 1791 1788 1791 1787 1786 1787 1785 1780 1785 1779 1777 1779 1776 1686 1776 1685 1684 1685 1773 1774 1773 1775 1772 1775 1771 1674 1771 1673 1675 1673 1944 1943 1944 1945 1763 1768 1945 2224 2226 2225 2225 2226 2227 2228 2229 2224 2225 2228 2224 2230 2231 2229 2228 2230 2229 2232 2233 2231 2230 2232 2231 2234 2235 2233 2232 2234 2233 2236 2237 2235 2234 2236 2235 2238 2239 2237 2236 2238 2237 2240 2241 2239 2238 2240 2239 2242 2243 2241 2240 2242 2241 2244 2245 2243 2242 2244 2243 2246 2247 2245 2244 2246 2245 2248 2249 2247 2246 2248 2247 2250 2251 2249 2248 2250 2249 2252 2253 2251 2250 2252 2251 2254 2255 2253 2252 2254 2253 2256 2257 2255 2254 2256 2255 2258 2259 2257 2256 2258 2257 2260 2261 2259 2258 2260 2259 2262 2263 2261 2260 2262 2261 2264 2265 2263 2262 2264 2263 2266 2267 2265 2264 2266 2265 2268 2269 2267 2266 2268 2267 2270 2271 2269 2268 2270 2269 2272 2273 2271 2270 2272 2271 2274 2275 2273 2272 2274 2273 2276 2277 2275 2274 2276 2275 2278 2279 2277 2276 2278 2277 2280 2281 2279 2278 2280 2279 2282 2283 2281 2280 2282 2281 2284 2285 2283 2282 2284 2283 2286 2287 2285 2284 2286 2285 2288 2289 2287 2286 2288 2287 2290 2291 2289 2288 2290 2289 2292 2293 2291 2290 2292 2291 2294 2295 2293 2292 2294 2293 2296 2297 2295 2294 2296 2295 2298 2299 2297 2296 2298 2297 2300 2301 2299 2298 2300 2299 2302 2303 2301 2300 2302 2301 2304 2305 2303 2302 2304 2303 2306 2307 2305 2304 2306 2305 2308 2309 2307 2306 2308 2307 2310 2311 2309 2308 2310 2309 2312 2313 2311 2310 2312 2311 2314 2315 2313 2312 2314 2313 2316 2317 2315 2314 2316 2315 2318 2319 2317 2316 2318 2317 2320 2321 2319 2318 2320 2319 2322 2323 2321 2320 2322 2321 2324 2325 2323 2322 2324 2323 2326 2327 2325 2324 2326 2325 2328 2329 2327 2326 2328 2327 2330 2331 2329 2328 2330 2329 2332 2333 2331 2330 2332 2331 2334 2335 2333 2332 2334 2333 2336 2337 2335 2334 2336 2335 2338 2339 2337 2336 2338 2337 2340 2341 2339 2338 2340 2339 2342 2343 2341 2340 2342 2341 2344 2345 2343 2342 2344 2343 2346 2347 2345 2344 2346 2345 2348 2349 2347 2346 2348 2347 2350 2351 2349 2348 2350 2349 2352 2353 2351 2350 2352 2351 2354 2355 2353 2352 2354 2353 2356 2357 2355 2354 2356 2355 2358 2359 2357 2356 2358 2357 2360 2361 2359 2358 2360 2359 2362 2363 2361 2360 2362 2361 2364 2365 2363 2362 2364 2363 2366 2367 2365 2364 2366 2365 2368 2369 2367 2366 2368 2367 2370 2371 2369 2368 2370 2369 2372 2373 2371 2370 2372 2371 2374 2375 2373 2372 2374 2373 2376 2377 2375 2374 2376 2375 2378 2379 2377 2376 2378 2377 2380 2381 2379 2378 2380 2379 2382 2383 2381 2380 2382 2381 2384 2385 2383 2382 2384 2383 2386 2387 2385 2384 2386 2385 2388 2389 2387 2386 2388 2387 2390 2391 2389 2388 2390 2389 2392 2393 2391 2390 2392 2391 2394 2395 2393 2392 2394 2393 2396 2397 2395 2394 2396 2395 2398 2399 2397 2396 2398 2397 2400 2401 2399 2398 2400 2399 2402 2403 2401 2400 2402 2401 2404 2405 2403 2402 2404 2403 2406 2407 2405 2404 2406 2405 2408 2409 2407 2406 2408 2407 2410 2411 2409 2408 2410 2409 2412 2413 2411 2410 2412 2411 2414 2415 2413 2412 2414 2413 2416 2417 2415 2414 2416 2415 2418 2419 2417 2416 2418 2417 2420 2421 2419 2418 2420 2419 2422 2423 2421 2420 2422 2421 2424 2425 2423 2422 2424 2423 2426 2427 2425 2424 2426 2425 2428 2429 2427 2426 2428 2427 2430 2431 2429 2428 2430 2429 2432 2433 2431 2430 2432 2431 2434 2435 2433 2432 2434 2433 2436 2437 2435 2434 2436 2435 2438 2439 2437 2436 2438 2437 2440 2441 2439 2438 2440 2439 2442 2443 2441 2440 2442 2441 2444 2445 2443 2442 2444 2443 2446 2447 2445 2444 2446 2445 2448 2449 2447 2446 2448 2447 2450 2451 2449 2448 2450 2449 2452 2453 2451 2450 2452 2451 2454 2455 2453 2452 2454 2453 2456 2457 2455 2454 2456 2455 2458 2459 2457 2456 2458 2457 2460 2461 2459 2458 2460 2459 2462 2463 2461 2460 2462 2461 2464 2465 2463 2462 2464 2463 2466 2467 2465 2464 2466 2465 2468 2469 2467 2466 2468 2467 2470 2471 2469 2468 2470 2469 2472 2473 2471 2470 2472 2471 2474 2475 2473 2472 2474 2473 2476 2477 2475 2474 2476 2475 2478 2479 2477 2476 2478 2477 2480 2481 2479 2478 2480 2479 2482 2483 2481 2480 2482 2481 2484 2485 2483 2482 2484 2483 2486 2487 2485 2484 2486 2485 2488 2489 2487 2486 2488 2487 2490 2491 2489 2488 2490 2489 2492 2493 2491 2490 2492 2491 2494 2495 2493 2492 2494 2493 2496 2497 2495 2494 2496 2495 2498 2499 2497 2496 2498 2497 2500 2501 2499 2498 2500 2499 2226 2501 2227 2500 2227 2501 2502 2504 2503 2505 2507 2506 2508 2510 2509 2502 2503 2511 2512 2514 2513 2515 2509 2510 2516 2518 2517 2519 2521 2520 2519 2513 2521 2512 2522 2514 2520 2524 2523 2525 2527 2526 2528 2507 2529 2530 2528 2531 2532 2523 2533 2534 2536 2535 2505 2538 2537 2539 2541 2540 2542 2543 2529 2525 2526 2544 2545 2546 2507 2507 2528 2506 2529 2507 2539 2513 2519 2547 2548 2506 2528 2549 2539 2507 2525 2550 2522 2551 2552 2533 2553 2524 2521 2529 2543 2528 2549 2507 2546 2538 2505 2506 2540 2529 2539 2539 2554 2541 2529 2556 2555 2556 2557 2555 2556 2529 2540 2530 2548 2528 2558 2543 2542 2506 2532 2552 2548 2532 2506 2532 2560 2559 2552 2532 2533 2520 2523 2559 2532 2559 2523 2521 2513 2514 2524 2520 2521 2525 2512 2561 2522 2512 2525 2544 2526 2535 2561 2527 2525 2562 2563 2535 2535 2563 2544 2564 2534 2535 2536 2562 2535 2534 2509 2565 2536 2534 2565 2510 2508 2566 2509 2515 2565 2567 2566 2568 2566 2567 2510 2569 2567 2503 2568 2503 2567 2502 2511 2570 2504 2569 2503 2570 2572 2571 2571 2502 2570 2571 2518 2516 2518 2571 2572 2573 2574 2518 2518 2574 2517 2575 2574 2576 2574 2573 2576 2577 2574 2575 2575 2578 2577 2579 2578 2580 2575 2580 2578 2580 2582 2581 2581 2579 2580 2583 2584 2581 2583 2581 2582 2584 2585 2581 2586 2584 2587 2586 2585 2584 2587 2589 2588 2584 2589 2587 2590 2591 2588 2587 2588 2591 2590 2593 2592 2592 2591 2590 2594 2595 2593 2593 2595 2592 2596 2594 2597 2594 2593 2597 2596 2599 2598 2598 2594 2596 2600 2599 2601 2599 2600 2598 2602 2604 2603 2601 2602 2600 2605 2607 2606 2603 2604 2608 2609 2611 2610 2608 2613 2612 2614 2616 2615 2611 2617 2610 2614 2619 2618 2620 2622 2621 2623 2619 2624 2625 2627 2626 2628 2629 2618 2623 2618 2619 2630 2628 2631 2628 2630 2629 2629 2633 2632 2632 2625 2629 2625 2614 2629 2629 2634 2633 2618 2629 2614 2614 2625 2626 2615 2619 2614 2635 2615 2616 2621 2619 2611 2615 2611 2619 2620 2611 2636 2620 2621 2611 2609 2612 2636 2636 2611 2609 2612 2607 2608 2607 2612 2609 2605 2603 2608 2607 2605 2608 2637 2600 2603 2602 2603 2600 2638 2640 2639 2641 2642 2639 2638 2639 2642 2641 2644 2643 2643 2642 2641 2645 2644 2646 2644 2645 2643 2647 2648 2646 2645 2646 2648 2647 2650 2649 2649 2648 2647 2651 2650 2652 2650 2651 2649 2653 2654 2652 2651 2652 2654 2653 2656 2655 2655 2654 2653 2657 2656 2658 2656 2657 2655 2659 2660 2658 2657 2658 2660 2659 2662 2661 2661 2660 2659 2663 2662 2664 2662 2663 2661 2665 2666 2664 2663 2664 2666 2665 2668 2667 2667 2666 2665 2669 2668 2670 2668 2669 2667 2671 2672 2670 2669 2670 2672 2671 2674 2673 2673 2672 2671 2675 2674 2676 2674 2675 2673 2677 2678 2676 2675 2676 2678 2677 2680 2679 2679 2678 2677 2681 2680 2682 2680 2681 2679 2683 2684 2682 2681 2682 2684 2683 2686 2685 2685 2684 2683 2687 2686 2688 2686 2687 2685 2689 2690 2688 2687 2688 2690 2689 2692 2691 2691 2690 2689 2693 2692 2694 2692 2693 2691 2695 2696 2694 2693 2694 2696 2695 2698 2697 2697 2696 2695 2699 2698 2700 2698 2699 2697 2701 2702 2700 2699 2700 2702 2701 2704 2703 2703 2702 2701 2705 2704 2706 2704 2705 2703 2707 2708 2706 2705 2706 2708 2707 2710 2709 2709 2708 2707 2711 2710 2712 2710 2711 2709 2713 2714 2712 2711 2712 2714 2713 2716 2715 2715 2714 2713 2717 2716 2718 2716 2717 2715 2719 2720 2718 2717 2718 2720 2719 2722 2721 2721 2720 2719 2723 2722 2724 2722 2723 2721 2725 2726 2724 2723 2724 2726 2725 2728 2727 2727 2726 2725 2729 2728 2730 2728 2729 2727 2731 2732 2730 2729 2730 2732 2731 2734 2733 2733 2732 2731 2735 2734 2736 2734 2735 2733 2737 2738 2736 2735 2736 2738 2739 2740 2738 2738 2737 2739 2740 2742 2741 2742 2740 2739 2743 2741 2744 2742 2744 2741 2745 2746 2743 2743 2744 2745 2746 2748 2747 2748 2746 2745 2749 2747 2750 2748 2750 2747 2751 2752 2749 2749 2750 2751 2752 2754 2753 2754 2752 2751 2755 2753 2756 2754 2756 2753 2757 2758 2755 2755 2756 2757 2758 2760 2759 2760 2758 2757 2761 2759 2762 2760 2762 2759 2763 2764 2761 2761 2762 2763 2764 2766 2765 2766 2764 2763 2767 2765 2768 2766 2768 2765 2769 2770 2767 2767 2768 2769 2770 2772 2771 2772 2770 2769 2773 2771 2774 2772 2774 2771 2775 2776 2773 2773 2774 2775 2777 2776 2775 2777 2778 2776 2640 2638 2779 2779 2781 2780 2780 2640 2779 2782 2781 2783 2781 2782 2780 2784 2785 2783 2782 2783 2785 2784 2787 2786 2786 2785 2784 2788 2787 2789 2787 2788 2786 2790 2791 2789 2788 2789 2791 2790 2793 2792 2792 2791 2790 2794 2793 2795 2793 2794 2792 2796 2797 2795 2794 2795 2797 2796 2799 2798 2798 2797 2796 2800 2799 2801 2799 2800 2798 2802 2803 2801 2800 2801 2803 2802 2805 2804 2804 2803 2802 2806 2805 2807 2805 2806 2804 2808 2809 2807 2806 2807 2809 2808 2811 2810 2810 2809 2808 2812 2811 2813 2811 2812 2810 2814 2815 2813 2812 2813 2815 2814 2817 2816 2816 2815 2814 2818 2817 2819 2817 2818 2816 2820 2821 2819 2818 2819 2821 2820 2823 2822 2822 2821 2820 2824 2823 2825 2823 2824 2822 2826 2827 2825 2824 2825 2827 2826 2829 2828 2828 2827 2826 2830 2829 2831 2829 2830 2828 2832 2833 2831 2830 2831 2833 2832 2835 2834 2834 2833 2832 2836 2835 2837 2835 2836 2834 2838 2839 2837 2836 2837 2839 2838 2841 2840 2840 2839 2838 2842 2841 2843 2841 2842 2840 2844 2845 2843 2842 2843 2845 2844 2847 2846 2846 2845 2844 2848 2847 2849 2847 2848 2846 2850 2851 2849 2848 2849 2851 2850 2853 2852 2852 2851 2850 2854 2853 2855 2853 2854 2852 2856 2857 2855 2854 2855 2857 2856 2859 2858 2858 2857 2856 2860 2859 2861 2859 2860 2858 2862 2863 2861 2860 2861 2863 2862 2865 2864 2864 2863 2862 2866 2865 2867 2865 2866 2864 2868 2869 2867 2866 2867 2869 2868 2871 2870 2870 2869 2868 2872 2871 2873 2871 2872 2870 2874 2875 2873 2872 2873 2875 2874 2877 2876 2876 2875 2874 2878 2877 2879 2877 2878 2876 2880 2881 2879 2878 2879 2881 2880 2883 2882 2882 2881 2880 2884 2883 2885 2883 2884 2882 2886 2887 2885 2884 2885 2887 2886 2889 2888 2888 2887 2886 2890 2889 2891 2889 2890 2888 2892 2893 2891 2890 2891 2893 2892 2895 2894 2894 2893 2892 2896 2895 2897 2895 2896 2894 2898 2899 2897 2896 2897 2899 2898 2901 2900 2900 2899 2898 2902 2901 2903 2901 2902 2900 2904 2905 2903 2902 2903 2905 2904 2907 2906 2906 2905 2904 2908 2907 2909 2907 2908 2906 2910 2911 2909 2908 2909 2911 2910 2913 2912 2912 2911 2910 2914 2913 2915 2913 2914 2912 2915 2778 2914 2914 2778 2777 2916 2918 2917 2919 2921 2920 2922 2923 2916 2924 2926 2925 2927 2920 2928 2928 2920 2929 2930 2932 2931 2933 2923 2934 2927 2936 2935 2935 2920 2927 2937 2939 2938 2940 2942 2941 2943 2942 2944 2945 2935 2936 2946 2948 2947 2949 2919 2935 2950 2952 2951 2931 2944 2953 2954 2956 2955 2957 2959 2958 2960 2962 2961 2962 2963 2956 2963 2964 2956 2960 2961 2965 2958 2956 2954 2956 2958 2966 2967 2968 2957 2967 2958 2969 2950 2971 2970 2957 2958 2967 2957 2972 2950 2973 2975 2974 2976 2977 2974 2978 2977 2979 2980 2982 2981 2983 2950 2984 2985 2986 2941 2987 2983 2988 2989 2976 2938 2983 2987 2937 2990 2944 2940 2976 2974 2975 2953 2990 2991 2992 2930 2953 2918 2994 2993 2918 2993 2917 2995 2997 2996 2998 3000 2999 3001 3003 3002 3004 3006 3005 3007 3003 3008 3009 3002 3010 3011 3013 3012 3014 3015 3013 3016 3018 3017 3019 3021 3020 3022 3024 3023 3025 3027 3026 3028 3030 3029 3031 3033 3032 3034 3036 3035 3012 3028 3037 3038 3040 3039 3041 3039 3042 3043 3045 3044 3046 3048 3047 3049 3041 3042 3040 3050 3042 3051 3053 3052 3054 3056 3055 3053 3058 3057 3051 3060 3059 3061 3052 3057 3060 3052 3062 3063 3065 3064 3064 3062 3066 3067 3063 3068 3069 3071 3070 3072 3074 3073 3075 3077 3076 3078 3080 3079 3081 3083 3082 3078 2926 3084 3080 3068 3063 3085 3087 3086 3088 3085 2924 3089 3090 3087 3091 3093 3092 3094 3096 3095 3091 3098 3097 3099 3101 3100 3102 3103 3094 3104 3106 3105 3107 3101 3108 3104 3110 3109 3111 3113 3112 3114 3116 3115 3117 3119 3118 3120 3122 3121 3123 3125 3124 3126 3128 3127 3129 3131 3130 3116 3133 3132 3134 3135 3126 3129 3137 3136 3116 3114 3135 3138 3120 3139 3131 3141 3140 3142 3143 3133 3120 3121 3144 3140 3145 3131 3122 3146 3121 3147 3148 3142 3149 3151 3150 3152 3142 3153 3154 3156 3155 3147 3158 3157 3159 3161 3160 2945 3162 2935 3163 3165 3164 3164 3165 3166 3167 3168 3161 3162 3169 2935 3159 3171 3170 3172 3169 3173 3173 3174 3172 3175 3176 2949 3172 2935 3169 3161 3177 3160 3167 3179 3178 3179 3172 3180 3168 3167 3181 3172 2949 2935 3161 3168 3182 2949 3172 3175 3175 3183 3176 3184 3159 3160 3150 3151 3185 3183 3186 3176 3187 3153 3148 3153 3187 3186 3188 3190 3189 3191 3188 3192 3157 3193 3148 3187 3148 3193 3153 3142 3148 3192 3185 3194 3157 3196 3195 3197 3192 3198 3192 3197 3199 3196 3200 3195 3201 2961 3200 3192 3199 3202 3202 3204 3203 3196 3201 3200 3203 2961 3202 3201 3202 2961 3205 2965 2961 3205 2961 3203 3186 3183 3153 3180 3172 3174 3206 3134 3158 3116 3206 3133 3138 3207 3123 3147 3133 3206 3208 3210 3209 3135 3206 3116 3208 3211 3210 3101 3099 3108 3135 3114 3128 3108 3114 3212 3099 3213 3127 3099 3128 3108 3104 3214 3110 3213 3100 3215 3216 3111 3217 3218 3104 3219 3220 3218 3221 3215 3223 3222 3216 3224 3102 3225 3227 3226 3227 3106 3226 3085 3088 3087 3089 3101 3228 3223 3100 3089 3113 3111 3216 3088 2925 3222 3087 3088 3223 3098 3091 3229 3230 3232 3231 3233 3041 3049 3234 3235 3091 3236 3237 3235 3238 3240 3239 3238 3242 3241 3243 3245 3244 3243 3244 3093 3246 3247 3239 3248 3249 3085 3250 3083 3081 3249 3084 2924 3249 3251 3068 3247 3252 3074 3253 3083 3070 3084 3068 3080 3238 3239 3242 3254 3079 3066 3066 3080 3063 3083 3255 3076 3061 3254 3062 3256 3258 3257 3051 3052 3060 3071 3069 3259 3260 3055 3056 3054 3261 3056 3262 3264 3263 3264 3265 3263 3055 3267 3266 3060 3064 3268 3269 3271 3270 3272 3273 3263 3263 3274 3269 3266 3276 3275 3277 3050 3058 3275 3279 3278 3280 3282 3281 3272 3282 3280 3283 3285 3284 3051 3287 3286 3044 3288 3043 3053 3286 3277 3048 3290 3289 3049 3286 3291 3277 3049 3042 3292 3293 3043 3039 3041 3294 3046 3295 3036 3043 3296 3292 3297 3293 3298 3029 3038 3299 3294 3041 3300 3301 3025 3026 3299 3039 3294 3034 3303 3302 3290 3048 3046 3304 3031 3032 3013 3015 3012 3294 3305 3037 3306 3030 3015 3299 3037 3028 3307 3308 3021 3012 3037 3309 3018 3016 3310 3015 3028 3012 3311 3313 3312 3306 3014 3008 3314 3316 3315 3007 3317 3010 3318 3320 3319 3321 3322 3315 3013 3323 3317 3324 3319 3320 3014 3317 3007 3325 3326 3322 3018 3310 3314 3327 3312 3313 3002 3007 3010 3328 3010 3317 3001 2992 2991 3005 3330 3329 2953 2930 2931 3010 3331 3009 3332 3334 3333 3002 3009 2992 3009 3335 2930 3336 3334 3332 2922 2916 3337 2943 2944 2931 3338 3339 2938 2923 2922 3340 2938 3341 3338 3342 2943 2931 2984 2950 2951 3343 3344 2943 3345 3347 3346 3348 3349 3344 3347 3350 3346 3350 3351 2946 3349 3348 3352 2923 2933 3346 2946 3346 3350 3353 3355 3354 2948 2946 3356 3357 3167 3178 3167 3357 3181 3167 3172 3179 3358 3159 3184 3359 3175 3167 3154 3155 3360 3183 3359 3152 3147 3142 3133 3152 3153 3183 3196 3361 3201 3201 3191 3202 3193 3157 3195 3147 3157 3148 3202 3191 3192 3158 3361 3196 3202 3199 3362 3361 3191 3201 3362 3204 3202 3175 3172 3167 3177 3161 3182 3170 3363 3164 3175 3359 3183 3161 3364 3359 3170 3164 3159 3143 3152 3364 3131 3145 3150 3142 3152 3143 3361 3365 3191 3366 3185 3151 3157 3158 3196 3158 3147 3206 3194 3185 3367 3361 3134 3365 3192 3194 3368 3365 3188 3191 3368 3198 3192 3359 3167 3161 3171 3159 3358 3166 3369 3155 3359 3364 3152 3370 3364 3159 3166 3155 3164 3132 3143 3370 3209 3371 3131 3133 3143 3132 3365 3190 3188 3188 3189 3185 3158 3134 3361 3134 3206 3135 3185 3189 3150 3126 3190 3365 3185 3366 3372 3367 3185 3372 3192 3188 3185 3159 3364 3161 3163 3164 3363 3373 3122 3156 3364 3370 3143 3374 3370 3164 3156 3122 3155 3132 3374 3115 3128 3114 3108 3115 3116 3132 3190 3375 3189 3189 3130 3150 3134 3126 3365 3128 3126 3135 3150 3130 3131 3127 3375 3190 3150 3145 3376 3375 3130 3189 3376 3149 3150 3370 3159 3164 3360 3155 3369 3377 3120 3144 3370 3374 3132 3378 3374 3155 3119 3117 3379 3212 3115 3378 3104 3109 3208 3212 3114 3115 3375 3380 3130 3381 3209 3210 3126 3127 3190 3127 3128 3099 3371 3209 3382 3375 3213 3380 3131 3371 3383 3380 3129 3130 3383 3141 3131 3374 3164 3155 3146 3122 3373 3384 3125 3123 3374 3378 3115 3122 3385 3378 3138 3123 3120 3107 3212 3385 3100 3101 3089 3108 3212 3107 3380 3137 3129 3129 3136 3209 3127 3213 3375 3213 3099 3100 3209 3136 3208 3215 3137 3380 3209 3381 3386 3382 3209 3386 3131 3129 3209 3378 3155 3122 3139 3120 3377 3124 3387 3117 3378 3385 3212 3388 3385 3120 3124 3117 3123 3107 3388 3228 3223 3089 3087 3101 3107 3228 3137 3389 3136 3136 3219 3208 3213 3215 3380 3223 3215 3100 3208 3219 3104 3222 3389 3137 3208 3109 3390 3389 3219 3136 3390 3211 3208 3120 3385 3122 3384 3123 3207 3391 3113 3118 3385 3388 3107 3392 3388 3123 3118 3113 3117 3090 3228 3392 3091 3097 3226 3090 3089 3228 3389 3393 3219 3394 3106 3227 3215 3222 3137 3222 3223 3088 3105 3106 3395 3389 2925 3393 3104 3105 3396 3393 3218 3219 3396 3214 3104 3388 3120 3123 3379 3117 3387 3397 3216 3217 3388 3392 3228 3398 3392 3117 3230 3231 3399 3090 3398 3086 2924 3085 3249 3086 3087 3090 3393 3221 3218 3218 3220 3106 3222 2925 3389 2925 3088 2924 3106 3220 3226 2926 3221 3393 3106 3394 3400 3395 3106 3400 3104 3218 3106 3392 3123 3117 3112 3113 3391 3401 3096 3094 3392 3398 3090 3113 3402 3398 3102 3094 3216 3248 3086 3402 3084 3249 3068 3085 3086 3248 3221 3403 3220 3220 3234 3226 2925 2926 3393 3084 2926 2924 3226 3234 3091 3078 3403 3221 3226 3097 3404 3403 3234 3220 3404 3225 3226 3398 3117 3113 3224 3216 3397 3095 3405 3231 3398 3402 3086 3216 3406 3402 3095 3231 3094 3251 3248 3406 3083 3250 3243 3249 3248 3251 3403 3407 3234 3408 3093 3244 2926 3078 3221 3078 3084 3080 3092 3093 3409 3403 3079 3407 3091 3092 3410 3407 3235 3234 3410 3229 3091 3216 3402 3113 3401 3094 3103 3411 3242 3232 3402 3406 3248 3412 3406 3094 3232 3242 3231 3251 3412 3067 3066 3063 3064 3067 3068 3251 3407 3236 3235 3235 3237 3093 3078 3079 3403 3079 3080 3066 3093 3237 3243 3254 3236 3407 3093 3408 3413 3409 3093 3413 3091 3235 3093 3406 3216 3094 3399 3231 3405 3414 3239 3240 3406 3412 3251 3415 3412 3231 3257 3258 3416 3067 3415 3065 3062 3064 3060 3065 3063 3067 3236 3417 3237 3237 3255 3243 3079 3254 3407 3062 3254 3066 3243 3255 3083 3061 3417 3236 3243 3250 3418 3417 3255 3237 3418 3245 3243 3412 3094 3231 3241 3242 3411 3419 3073 3074 3412 3415 3067 3242 3420 3415 3247 3074 3239 3268 3065 3420 3263 3265 3069 3064 3065 3268 3417 3421 3255 3071 3422 3070 3254 3061 3236 3061 3062 3052 3253 3070 3423 3417 3057 3421 3083 3253 3424 3255 3421 3076 3424 3082 3083 3415 3231 3242 3246 3239 3414 3072 3425 3258 3415 3420 3065 3239 3426 3420 3072 3258 3074 3268 3426 3059 3053 3051 3286 3060 3268 3059 3421 3075 3076 3076 3077 3070 3061 3057 3417 3057 3052 3053 3070 3077 3069 3058 3075 3421 3070 3422 3427 3423 3070 3427 3083 3076 3070 3239 3420 3242 3419 3074 3252 3428 3054 3256 3420 3426 3268 3429 3426 3074 3256 3054 3258 3059 3429 3287 3277 3286 3049 3287 3051 3059 3075 3430 3077 3077 3274 3069 3057 3058 3421 3277 3058 3053 3069 3274 3263 3050 3430 3075 3069 3265 3431 3430 3274 3077 3431 3259 3069 3426 3239 3074 3416 3258 3425 3432 3055 3260 3426 3429 3059 3433 3429 3258 3285 3283 3434 3287 3433 3291 3043 3288 3282 3291 3286 3287 3430 3435 3274 3436 3272 3280 3058 3050 3075 3050 3277 3042 3273 3272 3437 3430 3040 3435 3263 3273 3438 3435 3269 3274 3438 3262 3263 3429 3074 3258 3261 3054 3428 3439 3279 3275 3429 3433 3287 3054 3440 3433 3266 3275 3055 3440 3233 3291 3293 3441 3043 3049 3291 3233 3435 3271 3269 3269 3270 3272 3050 3040 3430 3040 3042 3039 3272 3270 3282 3038 3271 3435 3272 3436 3442 3437 3272 3442 3263 3269 3272 3433 3258 3054 3267 3055 3432 3278 3443 3283 3433 3440 3291 3055 3444 3440 3278 3283 3275 3233 3444 3300 3299 3294 3037 3041 3233 3300 3271 3445 3270 3270 3296 3282 3040 3038 3435 3299 3038 3039 3282 3296 3043 3029 3445 3271 3282 3288 3446 3445 3296 3270 3446 3281 3282 3055 3440 3054 3439 3275 3276 3447 3290 3284 3440 3444 3233 3448 3444 3275 3284 3290 3283 3300 3448 3305 3031 3304 3298 3305 3294 3300 3445 3449 3296 3450 3293 3297 3038 3029 3271 3029 3299 3028 3441 3293 3451 3445 3030 3449 3043 3441 3452 3449 3292 3296 3452 3045 3043 3444 3055 3275 3434 3283 3443 3453 3046 3047 3444 3448 3300 3454 3448 3283 3024 3022 3455 3309 3305 3454 3021 3456 3031 3309 3037 3305 3449 3027 3292 3292 3025 3293 3029 3030 3445 3030 3028 3015 3297 3298 3457 3306 3027 3449 3293 3458 3451 3292 3027 3025 3450 3458 3293 3448 3275 3283 3289 3290 3447 3459 3303 3034 3448 3454 3305 3290 3460 3454 3036 3034 3046 3011 3309 3460 3014 3013 3317 3011 3012 3309 3021 3031 3461 3025 3301 3298 3030 3306 3449 3014 3306 3015 3298 3301 3031 3008 3026 3027 3298 3304 3462 3457 3298 3462 3293 3025 3298 3454 3283 3290 3295 3046 3453 3302 3463 3022 3454 3460 3309 3046 3464 3460 3302 3022 3034 3011 3464 3323 3320 3318 3020 3013 3011 3323 3026 3465 3301 3301 3461 3031 3306 3008 3027 3008 3014 3007 3456 3021 3308 3026 3003 3465 3031 3456 3466 3465 3461 3301 3466 3033 3031 3046 3460 3290 3459 3034 3035 3467 3018 3023 3460 3464 3011 3468 3464 3034 3023 3018 3022 3328 3323 3468 3005 3469 3320 3328 3317 3323 3465 3327 3461 3461 3313 3021 3008 3003 3026 3003 3007 3002 3019 3020 3470 3465 3001 3327 3021 3019 3471 3461 3327 3313 3471 3307 3021 3464 3046 3034 3455 3022 3463 3472 3314 3310 3464 3468 3323 3473 3468 3022 2996 2997 3474 3328 3473 3331 2992 3009 2930 3328 3331 3010 3005 3320 3475 3313 3311 3020 3003 3001 3465 3001 3002 2992 3020 3311 3320 2991 3312 3327 3020 3318 3476 3470 3020 3476 3021 3313 3020 3468 3034 3022 3017 3018 3467 3477 3325 3322 3468 3473 3328 3018 3478 3473 3315 3322 3314 3331 3478 3335 3332 3333 3330 3009 3331 3335 3312 3479 3311 3311 3475 3320 3001 2991 3327 2991 2992 2953 3469 3005 3006 2990 3479 3312 3320 3469 3480 3479 3475 3311 3480 3324 3320 3473 3022 3018 3316 3314 3472 3326 3481 2997 3473 3478 3331 3314 3482 3478 3326 2997 3322 2932 3335 3482 2938 3339 3332 2930 3335 2932 3479 3483 3475 2998 3005 3475 2991 2990 3312 2990 2953 2944 3329 3330 3484 3479 2940 3483 3005 3329 3485 3475 3483 2998 3485 3004 3005 3314 3478 3018 3477 3322 3321 3486 2918 2995 3478 3482 3335 3487 3482 3322 2995 2918 2997 2932 3487 3342 3344 2942 2943 2932 3342 2931 3483 3000 2998 2998 2999 3330 2990 2940 3479 2940 2944 2942 3330 2999 3332 2941 3000 3483 3330 3333 3488 3484 3330 3488 3005 2998 3330 3482 3314 3322 3474 2997 3481 3489 2916 2917 3482 3487 2932 3490 3487 2997 3344 2985 2942 3343 3342 3490 2985 3344 3349 2943 3342 3343 3000 3491 2999 2999 2989 3332 2940 2941 3483 2985 2941 2942 3332 2989 2938 2986 3491 3000 3332 3339 3492 3491 2989 2999 3492 3336 3332 3487 3322 2997 2994 2918 3486 3493 2934 2923 3487 3490 3342 2918 3494 3490 3349 2982 2985 3348 3343 3494 2982 2979 2986 3348 3344 3343 3491 2977 2989 2987 3495 2937 2941 2986 3000 2986 2985 2982 2939 2937 3496 3491 2979 2977 2938 2939 3497 2989 2977 2976 3497 3341 2938 3490 2997 2918 3337 2916 3489 2933 3498 3346 3490 3494 3343 3494 2916 3499 2982 3349 2981 3499 3352 3348 2979 2982 2980 3352 2981 3349 2970 3500 2959 2976 2975 2937 2986 2979 3491 2980 2978 2979 2937 2975 2983 2978 2974 2977 2937 3495 3501 3496 2937 3501 2938 2976 2937 2916 3494 2918 3493 2923 3340 3352 3502 2981 3494 3499 3348 3499 2923 3503 2981 3504 2980 3503 3502 3352 2980 3505 2978 3502 3504 2981 2978 3506 2974 3505 2980 3504 2975 2971 2983 3505 3506 2978 2983 2971 2950 3506 2973 2974 2983 2984 3507 2973 2971 2975 3507 2988 2983 2923 3499 2916 3345 3346 3498 3502 3355 3504 3499 3503 3352 3346 3508 3503 3504 3353 3505 3508 3355 3502 3505 3509 3506 3355 3353 3504 3506 3510 2973 3353 3509 3505 2971 2973 3511 3506 3509 3510 2972 2957 3512 2973 3510 3511 2950 2972 3513 2971 3511 2970 3513 2952 2950 3503 2923 3346 3356 2946 3351 3514 3509 3353 3503 3508 3502 2946 2921 3508 3515 3510 3509 2921 3354 3355 3516 3511 3510 3354 3514 3353 3500 2970 3511 3514 3515 3509 2964 2955 2956 3515 3516 3510 2959 2957 2970 3516 3500 3511 2957 2968 3517 3512 2957 3517 2950 2970 2957 2946 3508 3346 2920 2947 2929 2919 3518 3354 3508 2921 3355 2919 3354 2921 3518 3519 3514 3518 3514 3354 3519 3520 3515 3519 3515 3514 3520 3521 3516 3520 3516 3515 3521 3522 3500 3521 3500 3516 3522 2966 2959 2959 3500 3522 2958 2954 3523 2966 2958 2959 3523 2969 2958 2947 2920 2946 2921 2946 2920 3518 2949 3176 2935 2919 2920 3519 3176 3186 2949 3518 2919 3520 3186 3187 3176 3519 3518 3521 3187 3193 3186 3520 3519 3522 3193 3195 3187 3521 3520 2966 3195 3200 3193 3522 3521 2956 3200 2961 3195 2966 3522 3200 2956 2966 2956 2961 2962 3524 3526 3525 3527 3529 3528 3527 3530 3529 3531 3528 3532 3529 3532 3528 3533 3534 3531 3531 3532 3533 3534 3536 3535 3536 3534 3533 3537 3539 3538 3536 3540 3535 3541 3543 3542 3544 3546 3545 3547 3549 3548 3550 3552 3551 3553 3555 3554 3556 3558 3557 3559 3560 3556 3560 3559 3552 3556 3557 3559 3553 3550 3551 3550 3560 3552 3555 3553 3551 3547 3554 3549 3549 3554 3555 3542 3543 3548 3548 3543 3547 3544 3545 3541 3542 3544 3541 3546 3526 3524 3545 3546 3524 3525 3539 3537 3525 3526 3539 3535 3540 3538 3540 3537 3538 3561 3563 3562 3564 3566 3565 3567 3569 3568 3570 3572 3571 3573 3575 3574 3576 3578 3577 3579 3581 3580 3582 3584 3583 3585 3587 3586 3588 3590 3589 3591 3593 3592 3594 3596 3595 3597 3599 3598 3600 3602 3601 3603 3605 3604 3606 3608 3607 3609 3611 3610 3612 3614 3613 3615 3617 3616 3618 3617 3619 3615 3621 3620 3621 3615 3616 3622 3623 3620 3620 3621 3622 3624 3623 3625 3622 3625 3623 3624 3627 3626 3627 3624 3625 3628 3629 3626 3626 3627 3628 3630 3629 3631 3628 3631 3629 3630 3633 3632 3633 3630 3631 3634 3565 3632 3632 3633 3634 3616 3617 3618 3634 3564 3565 3610 3618 3619 3609 3612 3611 3619 3609 3610 3614 3605 3613 3612 3613 3611 3607 3603 3604 3604 3605 3614 3597 3608 3606 3608 3603 3607 3598 3599 3602 3597 3606 3599 3600 3601 3592 3598 3602 3600 3591 3594 3593 3601 3591 3592 3596 3587 3595 3594 3595 3593 3589 3585 3586 3586 3587 3596 3579 3590 3588 3590 3585 3589 3580 3581 3584 3579 3588 3581 3582 3583 3574 3580 3584 3582 3573 3576 3575 3583 3573 3574 3578 3569 3577 3576 3577 3575 3570 3567 3568 3568 3569 3578 3562 3571 3572 3571 3567 3570 3563 3561 3566 3562 3572 3561 3566 3564 3563 3635 3637 3636 3638 3640 3639 3641 3642 3638 3641 3638 3639 3643 3644 3638 3643 3638 3642 3645 3646 3638 3645 3638 3644 3647 3646 3648 3646 3647 3638 3649 3651 3650 3652 3636 3653 3635 3636 3654 3655 3656 3636 3636 3656 3657 3657 3654 3636 3636 3658 3655 3650 3636 3649 3652 3658 3636 3659 3649 3660 3661 3662 3649 3663 3661 3649 3664 3660 3649 3664 3649 3662 3649 3659 3651 3665 3652 3653 3650 3653 3636 3665 3666 3648 3666 3665 3653 3647 3648 3667 3666 3667 3648 3668 3647 3669 3647 3667 3669 3670 3647 3671 3647 3668 3671 3672 3647 3673 3647 3670 3673 3647 3672 3674 3675 3677 3676 3678 3680 3679 3678 3681 3680 3682 3679 3683 3680 3683 3679 3684 3685 3682 3682 3683 3684 3685 3687 3686 3687 3685 3684 3688 3690 3689 3687 3691 3686 3692 3694 3693 3695 3697 3696 3698 3700 3699 3701 3703 3702 3704 3706 3705 3707 3709 3708 3710 3711 3707 3711 3710 3703 3707 3708 3710 3704 3701 3702 3701 3711 3703 3706 3704 3702 3698 3705 3700 3700 3705 3706 3693 3694 3699 3699 3694 3698 3695 3696 3692 3693 3695 3692 3697 3677 3675 3696 3697 3675 3676 3690 3688 3676 3677 3690 3686 3691 3689 3691 3688 3689 3712 3714 3713 3715 3717 3716 3718 3720 3719 3721 3723 3722 3724 3726 3725 3727 3729 3728 3730 3732 3731 3733 3735 3734 3736 3738 3737 3739 3741 3740 3742 3744 3743 3745 3747 3746 3748 3750 3749 3751 3753 3752 3754 3756 3755 3757 3759 3758 3760 3762 3761 3763 3765 3764 3766 3768 3767 3769 3768 3770 3766 3772 3771 3772 3766 3767 3773 3774 3771 3771 3772 3773 3775 3774 3776 3773 3776 3774 3775 3778 3777 3778 3775 3776 3779 3780 3777 3777 3778 3779 3781 3780 3782 3779 3782 3780 3781 3784 3783 3784 3781 3782 3785 3716 3783 3783 3784 3785 3769 3770 3761 3785 3715 3716 3768 3769 3767 3763 3762 3760 3760 3761 3770 3756 3764 3765 3764 3762 3763 3754 3755 3758 3756 3765 3755 3759 3757 3748 3754 3758 3759 3750 3753 3749 3757 3750 3748 3752 3743 3751 3753 3751 3749 3745 3744 3742 3742 3743 3752 3738 3746 3747 3746 3744 3745 3736 3737 3740 3738 3747 3737 3741 3739 3730 3736 3740 3741 3732 3735 3731 3739 3732 3730 3734 3725 3733 3735 3733 3731 3727 3726 3724 3724 3725 3734 3720 3728 3729 3728 3726 3727 3718 3719 3721 3720 3729 3719 3722 3723 3713 3718 3721 3722 3712 3717 3714 3723 3712 3713 3715 3714 3717 3786 3788 3787 3789 3791 3790 3792 3794 3793 3795 3797 3796 3798 3800 3799 3801 3803 3802 3804 3806 3805 3807 3809 3808 3810 3812 3811 3813 3815 3814 3816 3814 3817 3818 3813 3819 3813 3818 3815 3819 3821 3820 3820 3818 3819 3822 3823 3821 3820 3821 3823 3824 3822 3825 3822 3824 3823 3807 3816 3817 3814 3815 3817 3808 3809 3810 3816 3807 3808 3812 3802 3811 3809 3812 3810 3801 3805 3803 3802 3803 3811 3797 3806 3804 3804 3805 3801 3800 3795 3796 3795 3806 3797 3798 3799 3789 3800 3796 3799 3790 3791 3793 3798 3789 3790 3792 3786 3794 3791 3792 3793 3787 3794 3786 3826 3828 3827 3827 3829 3826 3830 3832 3831 3831 3833 3830 3834 3836 3835 3837 3839 3838 3840 3842 3841 3843 3845 3844 3846 3848 3847 3849 3851 3850 3852 3854 3853 3855 3857 3856 3858 3860 3859 3861 3863 3862 3864 3862 3865 3866 3861 3867 3861 3866 3863 3867 3869 3868 3868 3866 3867 3870 3871 3869 3868 3869 3871 3872 3870 3873 3870 3872 3871 3855 3864 3865 3862 3863 3865 3856 3857 3858 3864 3855 3856 3860 3850 3859 3857 3860 3858 3849 3853 3851 3850 3851 3859 3845 3854 3852 3852 3853 3849 3848 3843 3844 3843 3854 3845 3846 3847 3837 3848 3844 3847 3838 3839 3841 3846 3837 3838 3840 3834 3842 3839 3840 3841 3835 3842 3834 3874 3876 3875 3877 3879 3878 3880 3881 3875 3874 3875 3881 3880 3883 3882 3882 3881 3880 3884 3883 3885 3883 3884 3882 3886 3887 3885 3884 3885 3887 3886 3889 3888 3888 3887 3886 3890 3889 3891 3889 3890 3888 3892 3893 3891 3890 3891 3893 3892 3895 3894 3894 3893 3892 3896 3895 3897 3895 3896 3894 3898 3899 3897 3896 3897 3899 3898 3901 3900 3900 3899 3898 3902 3901 3903 3901 3902 3900 3904 3905 3903 3902 3903 3905 3904 3907 3906 3906 3905 3904 3908 3907 3909 3907 3908 3906 3910 3911 3909 3908 3909 3911 3910 3913 3912 3912 3911 3910 3914 3913 3915 3913 3914 3912 3916 3917 3915 3914 3915 3917 3916 3919 3918 3918 3917 3916 3920 3919 3921 3919 3920 3918 3922 3923 3921 3920 3921 3923 3922 3925 3924 3924 3923 3922 3926 3925 3927 3925 3926 3924 3928 3929 3927 3926 3927 3929 3928 3931 3930 3930 3929 3928 3932 3931 3933 3931 3932 3930 3934 3935 3933 3932 3933 3935 3934 3937 3936 3936 3935 3934 3938 3937 3939 3937 3938 3936 3940 3941 3939 3938 3939 3941 3940 3943 3942 3942 3941 3940 3944 3943 3945 3943 3944 3942 3946 3947 3945 3944 3945 3947 3948 3947 3946 3949 3876 3874 3950 3949 3951 3949 3950 3876 3952 3953 3951 3950 3951 3953 3952 3955 3954 3954 3953 3952 3956 3955 3957 3955 3956 3954 3958 3959 3957 3956 3957 3959 3958 3961 3960 3960 3959 3958 3962 3961 3963 3961 3962 3960 3964 3965 3963 3962 3963 3965 3964 3967 3966 3966 3965 3964 3968 3967 3969 3967 3968 3966 3970 3971 3969 3968 3969 3971 3970 3973 3972 3972 3971 3970 3974 3973 3975 3973 3974 3972 3976 3977 3975 3974 3975 3977 3976 3979 3978 3978 3977 3976 3980 3979 3981 3979 3980 3978 3982 3983 3981 3980 3981 3983 3982 3985 3984 3984 3983 3982 3986 3985 3987 3985 3986 3984 3988 3989 3987 3986 3987 3989 3988 3991 3990 3990 3989 3988 3992 3991 3993 3991 3992 3990 3994 3995 3993 3992 3993 3995 3994 3997 3996 3996 3995 3994 3998 3997 3999 3997 3998 3996 4000 4001 3999 3998 3999 4001 4000 4003 4002 4002 4001 4000 4004 4003 4005 4003 4004 4002 4006 4007 4005 4004 4005 4007 4006 4009 4008 4008 4007 4006 4010 4009 4011 4009 4010 4008 4012 4013 4011 4010 4011 4013 4014 4016 4015 4017 4013 4012 4018 4020 4019 4021 4014 4015 4018 4022 4020 4023 4025 4024 4026 4028 4027 4029 4031 4030 4032 4034 4033 4035 4037 4036 4038 4040 4039 4041 4043 4042 4044 4046 4045 4047 4049 4048 4050 4052 4051 4053 4055 4054 4056 4058 4057 4059 4061 4060 4062 4064 4063 4065 4067 4066 4068 4070 4069 4071 4073 4072 4074 4076 4075 4077 4079 4078 4080 4082 4081 4083 4085 4084 4086 4088 4087 4089 4091 4090 4092 4094 4093 4095 4097 4096 4098 4100 4099 4101 4103 4102 4104 4106 4105 4107 4109 4108 4110 4112 4111 4113 4115 4114 4116 4118 4117 4119 4121 4120 4122 4124 4123 4125 4127 4126 4127 4125 4128 4129 4130 4126 4125 4126 4130 4129 4132 4131 4131 4130 4129 4133 4132 4134 4132 4133 4131 4135 4136 4134 4133 4134 4136 4135 4138 4137 4137 4136 4135 4139 4138 4140 4138 4139 4137 4141 4142 4140 4139 4140 4142 4141 4144 4143 4143 4142 4141 4145 4144 4146 4144 4145 4143 4147 4148 4146 4145 4146 4148 4147 4150 4149 4149 4148 4147 4151 4150 4152 4150 4151 4149 4153 4154 4152 4151 4152 4154 4153 4156 4155 4155 4154 4153 4157 4156 4158 4156 4157 4155 3948 4159 4158 4157 4158 4159 3946 4159 3948 4128 4119 4120 4120 4127 4128 4123 4124 4121 4123 4121 4119 4122 4115 4113 4122 4113 4124 4114 4116 4117 4115 4116 4114 4109 4118 4108 4117 4118 4109 4110 4107 4112 4107 4108 4112 4101 4102 4111 4102 4110 4111 4105 4106 4103 4105 4103 4101 4104 4097 4095 4104 4095 4106 4096 4098 4099 4097 4098 4096 4091 4100 4090 4099 4100 4091 4092 4089 4094 4089 4090 4094 4083 4084 4093 4084 4092 4093 4087 4088 4085 4087 4085 4083 4086 4079 4077 4086 4077 4088 4078 4080 4081 4079 4080 4078 4073 4082 4072 4081 4082 4073 4074 4071 4076 4071 4072 4076 4065 4066 4075 4066 4074 4075 4069 4070 4067 4069 4067 4065 4068 4061 4059 4068 4059 4070 4060 4062 4063 4061 4062 4060 4055 4064 4054 4063 4064 4055 4056 4053 4058 4053 4054 4058 4047 4048 4057 4048 4056 4057 4051 4052 4049 4051 4049 4047 4050 4043 4041 4050 4041 4052 4042 4044 4045 4043 4044 4042 4037 4046 4036 4045 4046 4037 4038 4035 4040 4035 4036 4040 4029 4030 4039 4030 4038 4039 4033 4034 4031 4033 4031 4029 4032 4025 4023 4032 4023 4034 4024 4161 4160 4025 4161 4024 4026 4162 4028 4163 4026 4027 4164 4166 4165 3877 4167 3879 4164 4165 4168 4022 4018 4167 3879 4167 4018 4169 4171 4170 4019 4172 4018 4173 4174 4164 4175 4015 4172 4018 4172 4015 4176 4169 4177 4015 4175 4021 4012 4178 4017 4016 4179 4015 4180 4181 4169 4012 4015 4182 4179 4182 4015 4169 4017 4183 4012 4184 4178 4012 4182 4184 4017 4178 4183 4169 4183 4180 4169 4181 4177 4169 4176 4171 4170 4173 4169 4169 4173 4164 4164 4174 4185 4164 4185 4166 4164 4168 4026 4026 4168 4162 4160 4161 4186 4187 3879 4188 4161 4026 4189 4163 4189 4026 4190 3879 4160 4191 4161 4192 4161 4189 4192 4161 4191 4186 4160 4193 4190 4160 4186 4193 3879 4190 4188 3878 3879 4194 3879 4187 4194

-
-
- - - - 0.00258582 -0.07735 -0.0328086 0.00279256 -0.07735 -0.0325598 -0.00210837 -0.07735 -0.0276564 0.00235863 -0.07735 -0.0278642 0.00210992 -0.07735 -0.0276575 0.00184326 -0.07735 -0.0274748 -0.00155904 -0.07735 -0.0273165 0.00326338 -0.07735 -0.0317149 -0.00126402 -0.07735 -0.0271862 0.00313262 -0.07735 -0.0320109 0.0035 -0.07735 -0.03045 -0.000321925 -0.07735 -0.0269649 0.0034849 -0.07735 -0.030774 0.00344031 -0.07735 -0.0310934 -0.000643256 -0.07735 -0.0270096 -0.000956869 -0.07735 -0.0270834 0.000643725 -0.07735 -0.0270097 0.00344044 -0.07735 -0.0298071 0.00336663 -0.07735 -0.0294934 0.0003243 -0.07735 -0.0269651 -1.66951e-15 -0.07735 -0.02695 0.0034851 -0.07735 -0.0301282 0.00313351 -0.07735 -0.028891 0.00279366 -0.07735 -0.0283417 0.00126493 -0.07735 -0.0271867 0.00326378 -0.07735 -0.029186 0.00297605 -0.07735 -0.028608 0.00156103 -0.07735 -0.0273175 0.00258701 -0.07735 -0.0280926 0.000958919 -0.07735 -0.027084 0.00336605 -0.07735 -0.0314088 -0.00184217 -0.07735 -0.027474 0.00297528 -0.07735 -0.0322931 -0.00235744 -0.07735 -0.027863 -0.00258582 -0.07735 -0.0280914 0.00210837 -0.07735 -0.0332436 0.00235744 -0.07735 -0.033037 -0.00279256 -0.07735 -0.0283402 -0.00297528 -0.07735 -0.0286069 0.00155904 -0.07735 -0.0335835 0.00184217 -0.07735 -0.033426 -0.00313262 -0.07735 -0.0288891 -0.00326338 -0.07735 -0.0291851 0.00126403 -0.07735 -0.0337138 -0.00336605 -0.07735 -0.0294912 0.00095687 -0.07735 -0.0338166 -0.00344031 -0.07735 -0.0298066 0.000643257 -0.07735 -0.0338904 0.0003243 -0.07735 -0.0339349 -0.0034849 -0.07735 -0.0301259 0 -0.07735 -0.03395 -0.0035 -0.07735 -0.03045 -0.00344044 -0.07735 -0.0310929 -0.00336663 -0.07735 -0.0314066 -0.000643725 -0.07735 -0.0338903 -0.0034851 -0.07735 -0.0307718 -0.00313351 -0.07735 -0.032009 -0.00326378 -0.07735 -0.031714 -0.00126493 -0.07735 -0.0337133 -0.00095892 -0.07735 -0.033816 -0.00279366 -0.07735 -0.0325583 -0.00297605 -0.07735 -0.032292 -0.00184326 -0.07735 -0.0334252 -0.00235862 -0.07735 -0.0330358 -0.00258701 -0.07735 -0.0328074 -0.00156103 -0.07735 -0.0335825 -0.00210992 -0.07735 -0.0332425 -0.0003243 -0.07735 -0.0339349 0.0417658 -0.0680884 -0.0328074 0.0442298 -0.0720872 -0.0276575 0.0416574 -0.0679125 -0.0325583 0.0418863 -0.0682839 -0.027863 0.0421566 -0.0687225 -0.027474 0.0420169 -0.0684959 -0.0276564 0.0439418 -0.0716199 -0.0273175 0.0437865 -0.0713678 -0.0271867 0.0414108 -0.0675122 -0.031714 0.0414792 -0.0676231 -0.032009 0.0412869 -0.0673111 -0.03045 0.0412947 -0.0673238 -0.0307718 0.0432931 -0.070567 -0.0269651 0.0413181 -0.0673618 -0.0310929 0.043626 -0.0711073 -0.027084 0.0434606 -0.0708389 -0.0270097 0.0427855 -0.0697432 -0.0270096 0.0413572 -0.0674252 -0.0294912 0.0413182 -0.067362 -0.0298066 0.0429541 -0.0700168 -0.0269649 0.0412948 -0.067324 -0.0301259 0.0431229 -0.0702909 -0.02695 0.041658 -0.0679134 -0.0283402 0.0414796 -0.0676239 -0.0288891 0.0424599 -0.0692147 -0.0271862 0.041411 -0.0675126 -0.0291851 0.0415622 -0.0677579 -0.0286069 0.0423051 -0.0689636 -0.0273165 0.0417665 -0.0680894 -0.0280914 0.042621 -0.0694762 -0.0270834 0.0413569 -0.0674247 -0.0314066 0.0415618 -0.0677572 -0.032292 0.0440899 -0.0718602 -0.0274748 0.04448 -0.0724934 -0.0280926 0.0443602 -0.0722989 -0.0278642 0.0418856 -0.0682829 -0.0330358 0.0420161 -0.0684946 -0.0332425 0.0445885 -0.0726693 -0.0283417 0.0446841 -0.0728246 -0.028608 0.0423041 -0.0689619 -0.0335825 0.042156 -0.0687216 -0.0334252 0.0447667 -0.0729586 -0.028891 0.0424594 -0.069214 -0.0337133 0.0448351 -0.0730695 -0.029186 0.044889 -0.0731571 -0.0294934 0.0426199 -0.0694745 -0.033816 0.0449277 -0.0732199 -0.0298071 0.0427853 -0.0697428 -0.0338903 0.0429528 -0.0700148 -0.0339349 0.0449512 -0.073258 -0.0301282 0.0431229 -0.0702909 -0.03395 0.044959 -0.0732706 -0.03045 0.0449277 -0.0732198 -0.0310934 0.0434604 -0.0708385 -0.0338904 0.0448887 -0.0731566 -0.0314088 0.0449511 -0.0732578 -0.030774 0.0447663 -0.0729579 -0.0320109 0.0448349 -0.0730692 -0.0317149 0.0436249 -0.0711055 -0.0338166 0.043786 -0.071367 -0.0337138 0.0445879 -0.0726684 -0.0325598 0.0446837 -0.0728239 -0.0322931 0.0440893 -0.0718592 -0.033426 0.0443596 -0.0722979 -0.033037 0.0444794 -0.0724923 -0.0328086 0.0439408 -0.0716182 -0.0335835 0.044229 -0.0720859 -0.0332436 0.0432931 -0.070567 -0.0339349 0.0120286 -0.0841704 -0.033796 0.0105937 -0.0836534 -0.033796 0.0102595 -0.0838031 -0.0338871 0.00647321 -0.0827671 -0.0339356 0.00791211 -0.0835323 -0.0339356 0.00808034 -0.0833561 -0.03395 0.0131511 -0.0847911 -0.0338871 0.0113975 -0.0844943 -0.0339356 0.0128541 -0.084963 -0.0339356 0.0118264 -0.0848846 -0.03395 0.0157659 -0.0856746 -0.0339356 0.0157418 -0.0859062 -0.03395 0.0172121 -0.0859275 -0.0339356 0.0147518 -0.0856964 -0.03395 0.0143117 -0.0853547 -0.0339356 0.013768 -0.0854568 -0.03395 0.0187432 -0.086363 -0.03395 0.0197509 -0.0864606 -0.03395 0.0200622 -0.086253 -0.0339356 0.0186457 -0.0861187 -0.0339356 0.0207604 -0.0865328 -0.03395 0.021457 -0.0863357 -0.0339356 0.0217716 -0.0865799 -0.03395 0.0228256 -0.0863717 -0.0339356 0.0227835 -0.0866032 -0.03395 0.0241633 -0.0863661 -0.0339356 0.0237957 -0.0866035 -0.03395 0.0248078 -0.0865814 -0.03395 0.0258189 -0.0865385 -0.03395 0.0254656 -0.0863239 -0.0339356 0.0267279 -0.0862502 -0.0339356 0.0268292 -0.086475 -0.03395 0.0279456 -0.0861501 -0.0339356 0.0261799 -0.0854953 -0.0336529 0.0259289 -0.0857864 -0.033796 0.0274209 -0.085404 -0.0336529 0.0278379 -0.0863926 -0.03395 0.0291137 -0.0860277 -0.0339356 0.03356 -0.0844867 -0.033796 0.0326428 -0.0848177 -0.033796 0.0324682 -0.0851397 -0.0338871 0.0288447 -0.0862894 -0.03395 0.0298492 -0.0861647 -0.03395 0.0302285 -0.0858765 -0.0339356 0.0308477 -0.0860014 -0.03395 0.0312915 -0.085685 -0.0339356 0.0323047 -0.0854415 -0.0339356 0.0318387 -0.0857966 -0.03395 0.0343018 -0.0844275 -0.0338871 0.0352321 -0.0835939 -0.033796 0.0344213 -0.0840814 -0.033796 0.0293187 -0.0857524 -0.0338871 0.0281568 -0.0858797 -0.0338871 0.035147 -0.0839501 -0.0338871 0.0341897 -0.0847518 -0.0339356 0.0328135 -0.0855264 -0.03395 0.0332699 -0.0851341 -0.0339356 0.0337653 -0.0851852 -0.03395 0.0334103 -0.084821 -0.0338871 0.0346843 -0.0847594 -0.03395 0.0355538 -0.0842457 -0.03395 0.0350673 -0.0842839 -0.0339356 0.0359063 -0.0837192 -0.0339356 0.0363719 -0.0836459 -0.03395 0.0367111 -0.0830461 -0.0339356 0.039941 -0.0766009 -0.0336529 0.0400852 -0.076957 -0.033796 0.0405584 -0.0750337 -0.0336529 0.0374858 -0.0822525 -0.0339356 0.0371237 -0.0829709 -0.03395 0.0378138 -0.0822285 -0.03395 0.0384417 -0.0814336 -0.03395 0.0382342 -0.0813256 -0.0339356 0.0395559 -0.0786941 -0.0338871 0.0396646 -0.0790196 -0.0339356 0.0402226 -0.0772965 -0.0338871 0.0390157 -0.0805998 -0.03395 0.0389596 -0.0802523 -0.0339356 0.0395378 -0.0797309 -0.03395 0.0400196 -0.0788413 -0.03395 0.0403514 -0.0776146 -0.0339356 0.0408721 -0.077005 -0.03395 0.041022 -0.0760245 -0.0339356 0.0404617 -0.0779302 -0.03395 0.0412547 -0.0760676 -0.03395 0.0416116 -0.0751197 -0.03395 0.0416784 -0.074237 -0.0339356 0.0419486 -0.0741649 -0.03395 0.0423225 -0.0722398 -0.0339356 0.0422652 -0.0732031 -0.03395 0.0429528 -0.0700148 -0.0339349 0.0425655 -0.0722372 -0.03395 0.042851 -0.0712664 -0.03395 0.0431229 -0.0702909 -0.03395 0.00994636 -0.0839433 -0.0339356 0.00992704 -0.0841852 -0.03395 0.0108706 -0.084551 -0.03395 0.00899612 -0.0837869 -0.03395 0.00850515 -0.0833051 -0.0339356 0.00882559 -0.0831824 -0.0338871 0.00718003 -0.0828928 -0.03395 0.00740532 -0.0824703 -0.0338871 0.00916758 -0.0830514 -0.033796 0.00775429 -0.0823593 -0.033796 0.00707834 -0.0825744 -0.0339356 0.00629724 -0.0823972 -0.03395 0.0117028 -0.0843376 -0.0338871 0.00543333 -0.0818699 -0.03395 0.0127927 -0.0851863 -0.03395 0.00428579 -0.0808148 -0.0339356 0.00567039 -0.0817461 -0.0339356 0.00600295 -0.0816617 -0.0338871 0.00458898 -0.0813109 -0.03395 0.00126403 -0.07735 -0.0337138 0.00231272 -0.0785776 -0.033796 0.00269618 -0.0785535 -0.0336529 0.00376618 -0.0807217 -0.03395 0.0146002 -0.0851689 -0.0338871 0.00160481 -0.0786221 -0.0339356 0.00194725 -0.0786006 -0.0338871 0.0003243 -0.07735 -0.0339349 0.00296504 -0.0801024 -0.03395 0.00292908 -0.0797753 -0.0339356 0.00218765 -0.0794541 -0.03395 0.0160457 -0.0854759 -0.0338871 0.00348034 -0.0785043 -0.0331746 0.00210837 -0.07735 -0.0332436 0.00184217 -0.07735 -0.033426 0.016738 -0.0860865 -0.03395 0.00095687 -0.07735 -0.0338166 0.000643257 -0.07735 -0.0338904 0.0163443 -0.0852639 -0.033796 0.0177388 -0.0862385 -0.03395 0.000704987 -0.0780769 -0.03395 0.0014342 -0.0787783 -0.03395 0 -0.07735 -0.03395 0.0174833 -0.0857172 -0.0338871 0.019189 -0.085662 -0.033796 0.0177728 -0.0854927 -0.033796 0.0194832 -0.0854146 -0.0336529 0.0180765 -0.0852572 -0.0336529 0.0217035 -0.0860966 -0.0338871 0.0203167 -0.0860225 -0.0338871 0.0189085 -0.0858978 -0.0338871 0.0205884 -0.0857766 -0.033796 0.0219665 -0.0858414 -0.033796 0.0222425 -0.0855736 -0.0336529 0.0208734 -0.0855185 -0.0336529 0.0203711 -0.0846683 -0.0328254 0.018993 -0.0845466 -0.0328254 0.0186977 -0.0847756 -0.0331746 0.019785 -0.085161 -0.0334486 0.0211656 -0.0852538 -0.0334486 0.0225255 -0.0852991 -0.0334486 0.017603 -0.0843702 -0.0328254 0.0172984 -0.0845865 -0.0331746 0.0228069 -0.0850261 -0.0331746 0.0214562 -0.0849907 -0.0331746 0.020085 -0.0849088 -0.0331746 0.0217333 -0.0847398 -0.0328254 0.0233166 -0.0845316 -0.0323998 0.0219826 -0.084514 -0.0323998 0.0230752 -0.0847657 -0.0328254 0.0206285 -0.0844519 -0.0323998 0.0183502 -0.0838397 -0.0301462 0.0183502 -0.0838397 -0.0307538 0.0197173 -0.083985 -0.0301462 0.0310073 -0.0834858 -0.0307538 0.0320339 -0.0832699 -0.0307538 0.0320339 -0.0832699 -0.0301462 0.0221884 -0.0843276 -0.0319031 0.0208411 -0.0842733 -0.0319031 0.0235159 -0.0843382 -0.0319031 0.019478 -0.0841705 -0.0289969 0.0182655 -0.0838998 -0.0295522 0.0196352 -0.0840487 -0.0295522 0.0196352 -0.0840487 -0.0313478 0.0210729 -0.0840784 -0.0307538 0.0197173 -0.083985 -0.0307538 0.0186977 -0.0847756 -0.0277254 0.020085 -0.0849088 -0.0277254 0.019785 -0.085161 -0.0274514 0.0208411 -0.0842733 -0.0289969 0.0206285 -0.0844519 -0.0285002 0.0158915 -0.0843367 -0.0277254 0.0155622 -0.0845489 -0.0274514 0.0144807 -0.0840217 -0.0277254 0.016979 -0.0848133 -0.0274514 0.0172984 -0.0845865 -0.0277254 0.015231 -0.0847623 -0.0272471 0.0141417 -0.0842179 -0.0274514 0.019189 -0.085662 -0.027104 0.0189085 -0.0858978 -0.0270129 0.0177728 -0.0854927 -0.027104 0.0169611 -0.0861221 -0.02695 0.0181593 -0.0865275 -0.0269644 0.0167101 -0.0863168 -0.0269644 0.0134681 -0.0846077 -0.027104 0.014908 -0.0849705 -0.027104 0.0146002 -0.0851689 -0.0270129 0.0131511 -0.0847911 -0.0270129 0.0120286 -0.0841704 -0.027104 0.0125793 -0.0851221 -0.02695 0.0113975 -0.0844943 -0.0269644 0.0128541 -0.084963 -0.0269644 0.011115 -0.0846392 -0.02695 0.0123045 -0.0852811 -0.0269644 0.0108325 -0.0847842 -0.0269644 0.0117028 -0.0843376 -0.0270129 0.0152245 -0.0874687 -0.0277254 0.0155341 -0.0872286 -0.0274514 0.01672 -0.0877374 -0.0277254 0.0137779 -0.0856987 -0.0269644 0.0149682 -0.0862409 -0.0270129 0.0134895 -0.0858846 -0.0270129 0.0102014 -0.085108 -0.027104 0.00871944 -0.0844929 -0.027104 0.00905365 -0.0843432 -0.0270129 0.00936681 -0.0842029 -0.0269644 0.00965659 -0.0840731 -0.02695 0.00950904 -0.0854633 -0.0274514 0.00800919 -0.084811 -0.0274514 0.00836877 -0.08465 -0.0272471 0.0105272 -0.0849408 -0.0270129 0.00985958 -0.0852835 -0.0272471 0.015964 -0.0883729 -0.0289969 0.017465 -0.088605 -0.0289969 0.0173175 -0.0887385 -0.0295522 0.00652291 -0.0840643 -0.0274514 0.00689085 -0.0839234 -0.0272471 0.0129105 -0.0877019 -0.0289969 0.0127484 -0.087817 -0.0295522 0.0113683 -0.0872515 -0.0289969 0.00615706 -0.0842044 -0.0277254 0.00765167 -0.0849712 -0.0277254 0.00731075 -0.0851239 -0.0280746 0.00580821 -0.0843381 -0.0280746 0.00700404 -0.0852612 -0.0285002 0.00549436 -0.0844583 -0.0285002 0.00208411 -0.0826565 -0.0295522 0.00198342 -0.0826821 -0.0301462 0.000651008 -0.0815045 -0.0295522 0.00400615 -0.0835524 -0.0285002 0.0043264 -0.0834505 -0.0280746 0.0126637 -0.0878771 -0.0307538 0.0142048 -0.0882593 -0.0307538 0.014287 -0.0881956 -0.0313478 0.00374169 -0.0836366 -0.0289969 0.00523518 -0.0845575 -0.0289969 0.0138007 -0.0844152 -0.0272471 0.00355227 -0.0836969 -0.0295522 0.00227676 -0.0826076 -0.0289969 0.0164339 -0.0879778 -0.0328254 0.0149292 -0.0876976 -0.0328254 0.0146635 -0.0879036 -0.0323998 0.00345327 -0.0837284 -0.0301462 0.0152245 -0.0874687 -0.0331746 0.0137155 -0.0871303 -0.0331746 0.0134109 -0.0873466 -0.0328254 0.00345327 -0.0837284 -0.0307538 0.0125275 -0.0865046 -0.0334486 0.0121982 -0.0867168 -0.0331746 0.014035 -0.0869035 -0.0334486 0.0162055 -0.0841343 -0.0280746 0.017603 -0.0843702 -0.0280746 0.00198342 -0.0826821 -0.0307538 0.000548959 -0.0815239 -0.0301462 0.000651008 -0.0815045 -0.0313478 0.00208411 -0.0826565 -0.0313478 0.00227676 -0.0826076 -0.0319031 0.011017 -0.0860262 -0.0334486 0.00950904 -0.0854633 -0.0334486 0.0091605 -0.0856422 -0.0331746 0.00615706 -0.0842044 -0.0331746 0.00800919 -0.084811 -0.0334486 0.00652291 -0.0840643 -0.0334486 0.000548959 -0.0815239 -0.0307538 0.00111888 -0.0814157 -0.0323998 0.00287146 -0.0824566 -0.0328254 0.001449 -0.0813531 -0.0328254 0.00254574 -0.0825393 -0.0323998 0.000846266 -0.0814674 -0.0319031 0.0105272 -0.0849408 -0.0338871 0.00871944 -0.0844929 -0.033796 0.0102014 -0.085108 -0.033796 0.00759167 -0.083655 -0.0338871 0.00579727 -0.0829822 -0.033796 0.00724968 -0.083786 -0.033796 0.000263158 -0.0787064 -0.033796 0.00195876 -0.0798976 -0.0338871 0.000628625 -0.0786834 -0.0338871 -0.000904463 -0.0787797 -0.0331746 -0.000513503 -0.0787552 -0.0334486 -0.00210992 -0.07735 -0.0332425 0.00472236 -0.0819868 -0.0338871 0.00505493 -0.0819024 -0.0339356 0.00332494 -0.0809971 -0.0338871 -0.000120297 -0.0787305 -0.0336529 -0.00126493 -0.07735 -0.0337133 0.000971067 -0.0786619 -0.0339356 0.003662 -0.0809332 -0.0339356 0.00229915 -0.0798547 -0.0339356 -0.0003243 -0.07735 -0.0339349 0.0181034 -0.0840149 -0.0289969 0.0192586 -0.0843406 -0.0285002 -0.00156103 -0.07735 -0.0335825 0.0178771 -0.0841756 -0.0285002 0.016488 -0.0839523 -0.0285002 0.0210729 -0.0840784 -0.0301462 0.0224129 -0.0841243 -0.0301462 0.0209933 -0.0841453 -0.0313478 0.0224129 -0.0841243 -0.0307538 0.0223359 -0.0841941 -0.0313478 0.0236587 -0.0841996 -0.0313478 0.0237333 -0.0841272 -0.0307538 0.0250299 -0.0840916 -0.0307538 0.0237333 -0.0841272 -0.0301462 0.0250299 -0.0840916 -0.0301462 0.0260948 -0.0842457 -0.0289969 0.0249577 -0.0841663 -0.0295522 0.0262287 -0.0840987 -0.0295522 0.0279189 -0.084796 -0.0277254 0.0269371 -0.0846168 -0.0280746 0.0281556 -0.084507 -0.0280746 0.0271566 -0.0843622 -0.0285002 0.0259078 -0.084451 -0.0285002 0.0283686 -0.084247 -0.0285002 0.0288615 -0.0849779 -0.0274514 0.0291028 -0.0846692 -0.0277254 0.0276706 -0.0850992 -0.0274514 0.0286189 -0.0852884 -0.0272471 0.0347551 -0.0855915 -0.027104 0.0337508 -0.0860225 -0.027104 0.0338704 -0.0856764 -0.0270129 0.0295375 -0.0854587 -0.027104 0.0297671 -0.0851505 -0.0272471 0.0266931 -0.0848999 -0.0277254 0.0293187 -0.0857524 -0.0270129 0.0283823 -0.0855911 -0.027104 0.0311233 -0.0859546 -0.02695 0.0312915 -0.085685 -0.0269644 0.0321533 -0.0857207 -0.02695 0.0309551 -0.0862241 -0.0269644 0.032002 -0.0859999 -0.0269644 0.030424 -0.0855943 -0.0270129 0.0302285 -0.0858765 -0.0269644 0.0318384 -0.0863016 -0.0270129 0.0307733 -0.0865153 -0.0270129 0.0432931 -0.070567 -0.0339349 0.042809 -0.0730887 -0.0338871 0.0434604 -0.0708385 -0.0338904 0.0336253 -0.0863857 -0.0272471 0.0325631 -0.0867116 -0.0272471 0.0327202 -0.086361 -0.027104 0.0316638 -0.0866237 -0.027104 0.0345743 -0.0863485 -0.0274514 0.0355791 -0.0862119 -0.0277254 0.0344833 -0.0867295 -0.0277254 0.0334967 -0.086758 -0.0274514 0.032402 -0.0870712 -0.0274514 0.0333688 -0.0871283 -0.0277254 0.0426349 -0.0794711 -0.0301462 0.0434443 -0.0776081 -0.0307538 0.0426349 -0.0794711 -0.0307538 0.0318381 -0.0883296 -0.0289969 0.0307678 -0.0882766 -0.0285002 0.0319516 -0.0880763 -0.0285002 0.0377679 -0.0860462 -0.0307538 0.0388664 -0.085077 -0.0307538 0.0388491 -0.0849745 -0.0313478 0.0329816 -0.0882492 -0.0295522 0.0317568 -0.088511 -0.0295522 0.0354506 -0.0871906 -0.0289969 0.0366199 -0.0865465 -0.0289969 0.0366147 -0.0867452 -0.0295522 0.0398255 -0.0836453 -0.0319031 0.0398747 -0.0838379 -0.0313478 0.0377602 -0.0859426 -0.0295522 0.0377679 -0.0860462 -0.0301462 0.0388664 -0.085077 -0.0301462 0.036612 -0.086849 -0.0301462 0.03877 -0.0845048 -0.0323998 0.0387141 -0.0841734 -0.0328254 0.0377249 -0.0854676 -0.0323998 0.0412951 -0.0799454 -0.0331746 0.0414352 -0.0802917 -0.0328254 0.042088 -0.0783026 -0.0331746 0.0405795 -0.0817589 -0.0328254 0.040686 -0.0820777 -0.0323998 0.0404612 -0.0814046 -0.0331746 0.0424808 -0.0757688 -0.0336529 0.0417549 -0.0775907 -0.0336529 0.0419219 -0.0779476 -0.0334486 0.041148 -0.0795822 -0.0334486 0.0431822 -0.0737399 -0.0336529 0.0429911 -0.0734065 -0.033796 0.0423025 -0.0754284 -0.033796 0.0426383 -0.0727909 -0.0339356 0.00326946 -0.0797324 -0.0338871 0.00308938 -0.0785288 -0.0334486 0.00462285 -0.0807509 -0.0338871 0.00673027 -0.081477 -0.0336529 0.00498257 -0.0806826 -0.033796 0.00635788 -0.0815716 -0.033796 0.0095264 -0.082914 -0.0336529 0.00812043 -0.0822427 -0.0336529 0.0109444 -0.0834963 -0.0336529 0.0123705 -0.083995 -0.0336529 0.0134681 -0.0846077 -0.033796 0.0138007 -0.0844152 -0.0336529 0.014908 -0.0849705 -0.033796 0.0230643 -0.0861248 -0.0338871 0.0256897 -0.0860639 -0.0338871 0.0269453 -0.0859847 -0.0338871 0.0271774 -0.0857014 -0.033796 0.0243945 -0.0861123 -0.0338871 0.030424 -0.0855943 -0.0338871 0.0314733 -0.0853938 -0.0338871 0.0378598 -0.079104 -0.0328254 0.0373187 -0.0800058 -0.0328254 0.0373464 -0.0803784 -0.0331746 0.035951 -0.083379 -0.0338871 0.0408061 -0.0725717 -0.0331746 0.0402253 -0.0743218 -0.0331746 0.0403914 -0.0746768 -0.0334486 0.03672 -0.0827031 -0.0338871 0.0374603 -0.0819103 -0.0338871 0.0381772 -0.0809872 -0.0338871 0.0388748 -0.0799198 -0.0338871 0.0381163 -0.0806261 -0.033796 0.0374332 -0.0815451 -0.033796 0.0408766 -0.0757136 -0.0338871 0.0415191 -0.073933 -0.0338871 0.0407213 -0.0753819 -0.033796 0.0421519 -0.0719421 -0.0338871 0.0427853 -0.0697428 -0.0338903 0.00418853 -0.0784598 -0.0323998 0.00279256 -0.07735 -0.0325598 0.00258582 -0.07735 -0.0328086 0.00363273 -0.0796866 -0.033796 0.00711213 -0.0813801 -0.0334486 0.00536 -0.080611 -0.0336529 0.011304 -0.0833353 -0.0334486 0.00989435 -0.082773 -0.0334486 0.0141417 -0.0842179 -0.0334486 0.015231 -0.0847623 -0.0336529 0.0166577 -0.0850414 -0.0336529 0.023319 -0.0858613 -0.033796 0.0246413 -0.0858414 -0.033796 0.0349253 -0.0826225 -0.0328254 0.0348033 -0.0829756 -0.0331746 0.0355905 -0.0820925 -0.0328254 0.0283823 -0.0855911 -0.033796 0.0295375 -0.0854587 -0.033796 0.0306326 -0.0852931 -0.033796 0.0354128 -0.0828369 -0.0334486 0.0361509 -0.081856 -0.0331746 0.0355038 -0.0824558 -0.0331746 0.0316674 -0.0850829 -0.033796 0.03676 -0.0811673 -0.0331746 0.0360999 -0.0822444 -0.0334486 0.0367498 -0.081559 -0.0334486 0.037987 -0.0798587 -0.0334486 0.0379219 -0.0794724 -0.0331746 0.0373755 -0.080769 -0.0334486 0.0359986 -0.0830159 -0.033796 0.0337171 -0.0841361 -0.0336529 0.0367295 -0.082337 -0.033796 0.0387842 -0.079565 -0.033796 0.0374047 -0.0811619 -0.0336529 0.0380525 -0.0802472 -0.0336529 0.0394399 -0.0783468 -0.033796 0.0413492 -0.0736085 -0.033796 0.0426199 -0.0694745 -0.033816 0.0419698 -0.0716243 -0.033796 0.00155904 -0.07735 -0.0335835 0.00401388 -0.0796385 -0.0336529 0.00235744 -0.07735 -0.033037 0.00385314 -0.0784808 -0.0328254 0.00749181 -0.0812837 -0.0331746 0.00574703 -0.0805376 -0.0334486 0.00886919 -0.0820043 -0.0331746 0.00849588 -0.0821232 -0.0334486 0.0102602 -0.0826329 -0.0331746 0.0116615 -0.0831751 -0.0331746 0.012721 -0.0838151 -0.0334486 0.0144807 -0.0840217 -0.0331746 0.0155622 -0.0845489 -0.0334486 0.0158915 -0.0843367 -0.0331746 0.016979 -0.0848133 -0.0334486 0.0235863 -0.0855849 -0.0336529 0.0249002 -0.0855572 -0.0336529 0.0286189 -0.0852884 -0.0336529 0.0297671 -0.0851505 -0.0336529 0.0308515 -0.0849771 -0.0336529 0.0276706 -0.0850992 -0.0334486 0.0264372 -0.0851967 -0.0334486 0.031871 -0.0847568 -0.0336529 0.032826 -0.0844798 -0.0336529 0.0345468 -0.0837182 -0.0336529 0.0353213 -0.0832201 -0.0336529 0.0360487 -0.082635 -0.0336529 0.0338782 -0.0837765 -0.0334486 0.0367395 -0.0819529 -0.0336529 0.0386892 -0.0791927 -0.0336529 0.0393182 -0.0779823 -0.0336529 0.0411708 -0.073268 -0.0336529 0.0417787 -0.0712908 -0.0336529 0.0415828 -0.0709489 -0.0334486 0.0424594 -0.069214 -0.0337133 0.0044655 -0.0784424 -0.0319031 0.00313262 -0.07735 -0.0320109 0.00297528 -0.07735 -0.0322931 0.00440473 -0.0795892 -0.0334486 0.00922516 -0.081891 -0.0328254 0.010609 -0.0824993 -0.0328254 0.0120024 -0.0830224 -0.0328254 0.0134019 -0.0834657 -0.0328254 0.018388 -0.0850157 -0.0334486 0.0251657 -0.0852657 -0.0334486 0.0288615 -0.0849779 -0.0334486 0.0300025 -0.0848345 -0.0334486 0.031076 -0.084653 -0.0334486 0.0238603 -0.0853014 -0.0334486 0.0266931 -0.0848999 -0.0331746 0.0279189 -0.084796 -0.0331746 0.0320797 -0.0844224 -0.0334486 0.0330138 -0.0841333 -0.0334486 0.0346754 -0.0833458 -0.0334486 0.0340384 -0.083419 -0.0331746 0.0385917 -0.0788109 -0.0334486 0.0391933 -0.0776086 -0.0334486 0.0397931 -0.0762356 -0.0334486 0.0409879 -0.0729188 -0.0334486 0.0423041 -0.0689619 -0.0335825 0.00326338 -0.07735 -0.0317149 0.00466388 -0.0784299 -0.0313478 0.00336605 -0.07735 -0.0314088 0.00479333 -0.0795403 -0.0331746 0.00613184 -0.0804645 -0.0331746 0.00817957 -0.0811091 -0.0323998 0.00649878 -0.0803949 -0.0328254 0.00785386 -0.0811918 -0.0328254 0.0095454 -0.0817891 -0.0323998 0.0109229 -0.0823791 -0.0323998 0.0130695 -0.0836363 -0.0331746 0.0137009 -0.0833123 -0.0323998 0.0123091 -0.082885 -0.0323998 0.0148041 -0.0838346 -0.0328254 0.0150949 -0.0836662 -0.0323998 0.0162055 -0.0841343 -0.0328254 0.016488 -0.0839523 -0.0323998 0.0241328 -0.0850196 -0.0331746 0.0254296 -0.0849759 -0.0331746 0.0291028 -0.0846692 -0.0331746 0.0302366 -0.0845203 -0.0331746 0.0312992 -0.0843308 -0.0331746 0.0269371 -0.0846168 -0.0328254 0.0281556 -0.084507 -0.0328254 0.0322873 -0.0840898 -0.0331746 0.0332005 -0.0837888 -0.0331746 0.0383194 -0.0777436 -0.0323998 0.0382507 -0.0774747 -0.0319031 0.037804 -0.0787726 -0.0323998 0.0341912 -0.0830781 -0.0328254 0.0396784 -0.0731533 -0.0307538 0.039201 -0.0747731 -0.0313478 0.0397225 -0.0732474 -0.0313478 0.0392756 -0.0749574 -0.0319031 0.0398067 -0.0734275 -0.0319031 0.0384949 -0.0784313 -0.0331746 0.0396461 -0.0758725 -0.0331746 0.0400669 -0.0739834 -0.0328254 0.0395059 -0.0755262 -0.0328254 0.0390692 -0.077237 -0.0331746 0.041388 -0.0706089 -0.0331746 0.0420161 -0.0684946 -0.0332425 0.042156 -0.0687216 -0.0334252 0.00516389 -0.0794935 -0.0328254 0.00844855 -0.0810408 -0.0319031 0.0068289 -0.0803323 -0.0323998 0.0111821 -0.0822798 -0.0319031 0.00980987 -0.0817049 -0.0319031 0.0168884 -0.0836943 -0.0295522 0.0243926 -0.0847508 -0.0328254 0.0192586 -0.0843406 -0.0323998 0.0178771 -0.0841756 -0.0323998 0.0256813 -0.0846996 -0.0328254 0.0293328 -0.0843748 -0.0328254 0.0304598 -0.0842207 -0.0328254 0.031512 -0.0840235 -0.0328254 0.0283686 -0.084247 -0.0323998 0.0271566 -0.0843622 -0.0323998 0.0324852 -0.0837727 -0.0328254 0.0333786 -0.0834603 -0.0328254 0.0402073 -0.0714287 -0.0301462 0.0396784 -0.0731533 -0.0301462 0.0361995 -0.0814856 -0.0328254 0.0343286 -0.0827714 -0.0323998 0.0367697 -0.0807939 -0.0328254 0.0384025 -0.0780693 -0.0328254 0.0372938 -0.0796707 -0.0323998 0.0389509 -0.0768827 -0.0328254 0.0412022 -0.0702848 -0.0328254 0.0410351 -0.0699931 -0.0323998 0.0406327 -0.0722407 -0.0328254 0.0399244 -0.0736789 -0.0323998 0.0418856 -0.0682829 -0.0330358 0.00476756 -0.0784234 -0.0307538 0.0034849 -0.07735 -0.030774 0.00344031 -0.07735 -0.0310934 0.00549727 -0.0794515 -0.0323998 0.00864121 -0.0809919 -0.0313478 0.00710152 -0.0802806 -0.0319031 0.0113677 -0.0822087 -0.0313478 0.00999928 -0.0816446 -0.0313478 0.0127438 -0.0826903 -0.0313478 0.0125624 -0.0827716 -0.0319031 0.0141247 -0.0830948 -0.0313478 0.0153352 -0.0835272 -0.0319031 0.0155072 -0.0834276 -0.0313478 0.0139478 -0.0831856 -0.0319031 0.0246264 -0.084509 -0.0323998 0.019478 -0.0841705 -0.0319031 0.0181034 -0.0840149 -0.0319031 0.0259078 -0.084451 -0.0323998 0.0295397 -0.08411 -0.0323998 0.0306606 -0.0839512 -0.0323998 0.0317034 -0.0837471 -0.0323998 0.0285445 -0.0840322 -0.0319031 0.0273379 -0.0841519 -0.0319031 0.0326633 -0.0834875 -0.0323998 0.0335388 -0.0831648 -0.0323998 0.035035 -0.0823048 -0.0323998 0.0356686 -0.0817656 -0.0323998 0.0362433 -0.0811525 -0.0323998 0.0344421 -0.0825181 -0.0319031 0.0367785 -0.080458 -0.0323998 0.0372732 -0.0793939 -0.0319031 0.0377578 -0.0784989 -0.0319031 0.0388444 -0.0765639 -0.0323998 0.0393798 -0.0752147 -0.0323998 0.0404767 -0.0719429 -0.0323998 0.0416574 -0.0679125 -0.0325583 0.0417658 -0.0680884 -0.0328074 0.00344044 -0.07735 -0.0298071 0.0034851 -0.07735 -0.0301282 0.00476756 -0.0784234 -0.0301462 0.00577257 -0.0794168 -0.0319031 0.0035 -0.07735 -0.03045 0.00874189 -0.0809664 -0.0307538 0.00729678 -0.0802435 -0.0313478 0.0167213 -0.0838019 -0.0319031 0.0248194 -0.0843094 -0.0319031 0.0182655 -0.0838998 -0.0313478 0.0260948 -0.0842457 -0.0319031 0.0297106 -0.0838913 -0.0319031 0.0308264 -0.0837286 -0.0319031 0.0318615 -0.0835188 -0.0319031 0.0336711 -0.0829207 -0.0319031 0.0328103 -0.0832519 -0.0319031 0.0351256 -0.0820425 -0.0319031 0.0372585 -0.0791957 -0.0313478 0.0372508 -0.0790921 -0.0307538 0.0367909 -0.0799818 -0.0313478 0.0357331 -0.0814956 -0.0319031 0.0362794 -0.0808773 -0.0319031 0.0345234 -0.0823367 -0.0313478 0.0367857 -0.0801805 -0.0319031 0.0386935 -0.0761121 -0.0313478 0.0387565 -0.0763006 -0.0319031 0.0377248 -0.0783029 -0.0313478 0.0403478 -0.0716969 -0.0319031 0.0408971 -0.0697523 -0.0319031 0.0414792 -0.0676231 -0.032009 0.0415618 -0.0677572 -0.032292 0.00336663 -0.07735 -0.0294934 0.0044655 -0.0784424 -0.0289969 0.00326378 -0.07735 -0.029186 0.00596975 -0.0793919 -0.0313478 0.00466388 -0.0784299 -0.0295522 0.00739883 -0.0802241 -0.0301462 0.00874189 -0.0809664 -0.0301462 0.00864121 -0.0809919 -0.0295522 0.0114647 -0.0821716 -0.0301462 0.0100983 -0.0816131 -0.0301462 0.0100983 -0.0816131 -0.0307538 0.0114647 -0.0821716 -0.0307538 0.0128386 -0.0826479 -0.0301462 0.0120024 -0.0830224 -0.0280746 0.0123091 -0.082885 -0.0285002 0.0134019 -0.0834657 -0.0280746 0.0168884 -0.0836943 -0.0313478 0.0249577 -0.0841663 -0.0313478 0.0262287 -0.0840987 -0.0313478 0.0274677 -0.0840012 -0.0313478 0.0286705 -0.0838784 -0.0313478 0.029833 -0.0837347 -0.0313478 0.0309452 -0.0835691 -0.0313478 0.0319748 -0.0833553 -0.0313478 0.0337659 -0.0827459 -0.0313478 0.0329156 -0.0830832 -0.0313478 0.0351905 -0.0818546 -0.0313478 0.0357792 -0.0813023 -0.0313478 0.0363052 -0.0806802 -0.0313478 0.0345658 -0.0822419 -0.0307538 0.0382016 -0.0772821 -0.0313478 0.0377075 -0.0782005 -0.0307538 0.039162 -0.0746768 -0.0307538 0.0402556 -0.0715208 -0.0313478 0.0407982 -0.0695798 -0.0313478 0.0413569 -0.0674247 -0.0314066 0.0414108 -0.0675122 -0.031714 0.00418853 -0.0784598 -0.0285002 0.00297605 -0.07735 -0.028608 0.00313351 -0.07735 -0.028891 0.00607281 -0.079379 -0.0307538 0.00739883 -0.0802241 -0.0307538 0.0128386 -0.0826479 -0.0307538 0.0142171 -0.0830474 -0.0307538 0.0155971 -0.0833756 -0.0307538 0.0169758 -0.083638 -0.0307538 0.0274677 -0.0840012 -0.0295522 0.0273379 -0.0841519 -0.0289969 0.0287363 -0.083798 -0.0301462 0.0286705 -0.0838784 -0.0295522 0.0275356 -0.0839225 -0.0301462 0.0262987 -0.0840219 -0.0307538 0.0275356 -0.0839225 -0.0307538 0.0287363 -0.083798 -0.0307538 0.029897 -0.0836528 -0.0307538 0.0338154 -0.0826546 -0.0307538 0.0329707 -0.082995 -0.0307538 0.0352244 -0.0817565 -0.0307538 0.0358033 -0.0812012 -0.0307538 0.0363188 -0.0805772 -0.0307538 0.0345658 -0.0822419 -0.0301462 0.0367936 -0.0798779 -0.0307538 0.0397225 -0.0732474 -0.0295522 0.039201 -0.0747731 -0.0295522 0.039162 -0.0746768 -0.0301462 0.0381759 -0.0771814 -0.0307538 0.0377075 -0.0782005 -0.0301462 0.0372508 -0.0790921 -0.0301462 0.0386606 -0.0760135 -0.0307538 0.0402073 -0.0714287 -0.0307538 0.0412947 -0.0673238 -0.0307718 0.0407466 -0.0694896 -0.0307538 0.0413181 -0.0673618 -0.0310929 0.00279366 -0.07735 -0.0283417 0.00385314 -0.0784808 -0.0280746 0.00258701 -0.07735 -0.0280926 0.00607281 -0.079379 -0.0301462 0.00710152 -0.0802806 -0.0289969 0.00844855 -0.0810408 -0.0289969 0.00817957 -0.0811091 -0.0285002 0.0095454 -0.0817891 -0.0285002 0.00980987 -0.0817049 -0.0289969 0.0109229 -0.0823791 -0.0285002 0.0142171 -0.0830474 -0.0301462 0.0155971 -0.0833756 -0.0301462 0.0169758 -0.083638 -0.0301462 0.0262987 -0.0840219 -0.0301462 0.029897 -0.0836528 -0.0301462 0.0310073 -0.0834858 -0.0301462 0.0338154 -0.0826546 -0.0301462 0.0329707 -0.082995 -0.0301462 0.0352244 -0.0817565 -0.0301462 0.0358033 -0.0812012 -0.0301462 0.0363188 -0.0805772 -0.0301462 0.0345234 -0.0823367 -0.0295522 0.0367936 -0.0798779 -0.0301462 0.0381759 -0.0771814 -0.0301462 0.0372585 -0.0791957 -0.0295522 0.0377248 -0.0783029 -0.0295522 0.0386606 -0.0760135 -0.0301462 0.0407982 -0.0695798 -0.0295522 0.0407466 -0.0694896 -0.0301462 0.0413182 -0.067362 -0.0298066 0.0412869 -0.0673111 -0.03045 0.00596975 -0.0793919 -0.0295522 0.00729678 -0.0802435 -0.0295522 0.0113677 -0.0822087 -0.0295522 0.00999928 -0.0816446 -0.0295522 0.0127438 -0.0826903 -0.0295522 0.0141247 -0.0830948 -0.0295522 0.0155072 -0.0834276 -0.0295522 0.0209933 -0.0841453 -0.0295522 0.0223359 -0.0841941 -0.0295522 0.0236587 -0.0841996 -0.0295522 0.0318615 -0.0835188 -0.0289969 0.0317034 -0.0837471 -0.0285002 0.0308264 -0.0837286 -0.0289969 0.029833 -0.0837347 -0.0295522 0.0309452 -0.0835691 -0.0295522 0.0319748 -0.0833553 -0.0295522 0.0285445 -0.0840322 -0.0289969 0.0329156 -0.0830832 -0.0295522 0.0337659 -0.0827459 -0.0295522 0.0351905 -0.0818546 -0.0295522 0.0357792 -0.0813023 -0.0295522 0.0363052 -0.0806802 -0.0295522 0.0344421 -0.0825181 -0.0289969 0.0367909 -0.0799818 -0.0295522 0.0382016 -0.0772821 -0.0295522 0.0377578 -0.0784989 -0.0289969 0.0372732 -0.0793939 -0.0289969 0.0386935 -0.0761121 -0.0295522 0.0408971 -0.0697523 -0.0289969 0.0402556 -0.0715208 -0.0295522 0.0398067 -0.0734275 -0.0289969 0.0412948 -0.067324 -0.0301259 0.00184326 -0.07735 -0.0274748 0.00210992 -0.07735 -0.0276575 0.00308938 -0.0785288 -0.0274514 0.00577257 -0.0794168 -0.0289969 0.0111821 -0.0822798 -0.0289969 0.0125624 -0.0827716 -0.0289969 0.0139478 -0.0831856 -0.0289969 0.0153352 -0.0835272 -0.0289969 0.0167213 -0.0838019 -0.0289969 0.0150949 -0.0836662 -0.0285002 0.0221884 -0.0843276 -0.0289969 0.0235159 -0.0843382 -0.0289969 0.0248194 -0.0843094 -0.0289969 0.0306606 -0.0839512 -0.0285002 0.0304598 -0.0842207 -0.0280746 0.0295397 -0.08411 -0.0285002 0.0297106 -0.0838913 -0.0289969 0.0328103 -0.0832519 -0.0289969 0.0336711 -0.0829207 -0.0289969 0.0351256 -0.0820425 -0.0289969 0.0357331 -0.0814956 -0.0289969 0.0362794 -0.0808773 -0.0289969 0.0367857 -0.0801805 -0.0289969 0.0382507 -0.0774747 -0.0289969 0.0372938 -0.0796707 -0.0285002 0.037804 -0.0787726 -0.0285002 0.0399244 -0.0736789 -0.0285002 0.0404767 -0.0719429 -0.0285002 0.0387565 -0.0763006 -0.0289969 0.0392756 -0.0749574 -0.0289969 0.0403478 -0.0716969 -0.0289969 0.041411 -0.0675126 -0.0291851 0.0413572 -0.0674252 -0.0294912 0.000643725 -0.07735 -0.0270097 0.00160481 -0.0786221 -0.0269644 0.0003243 -0.07735 -0.0269651 0.00549727 -0.0794515 -0.0285002 0.00231272 -0.0785776 -0.027104 0.00126493 -0.07735 -0.0271867 0.00269618 -0.0785535 -0.0272471 0.0068289 -0.0803323 -0.0285002 0.00428579 -0.0808148 -0.0269644 0.00567039 -0.0817461 -0.0269644 0.00536266 -0.0818242 -0.02695 0.0137009 -0.0833123 -0.0285002 0.0230752 -0.0847657 -0.0280746 0.0219826 -0.084514 -0.0285002 0.0233166 -0.0845316 -0.0285002 0.0246264 -0.084509 -0.0285002 0.0326633 -0.0834875 -0.0285002 0.0333786 -0.0834603 -0.0280746 0.0324852 -0.0837727 -0.0280746 0.0335388 -0.0831648 -0.0285002 0.0343286 -0.0827714 -0.0285002 0.035035 -0.0823048 -0.0285002 0.0356686 -0.0817656 -0.0285002 0.0362433 -0.0811525 -0.0285002 0.0367785 -0.080458 -0.0285002 0.0383194 -0.0777436 -0.0285002 0.0378598 -0.079104 -0.0280746 0.0373187 -0.0800058 -0.0280746 0.0388444 -0.0765639 -0.0285002 0.0393798 -0.0752147 -0.0285002 0.0400669 -0.0739834 -0.0280746 0.0410351 -0.0699931 -0.0285002 0.0415622 -0.0677579 -0.0286069 0.0414796 -0.0676239 -0.0288891 0.00235863 -0.07735 -0.0278642 0.00348034 -0.0785043 -0.0277254 0.00516389 -0.0794935 -0.0280746 0.00785386 -0.0811918 -0.0280746 0.00649878 -0.0803949 -0.0280746 0.010609 -0.0824993 -0.0280746 0.00922516 -0.081891 -0.0280746 0.0095264 -0.082914 -0.0272471 0.0105937 -0.0836534 -0.027104 0.00916758 -0.0830514 -0.027104 0.0148041 -0.0838346 -0.0280746 0.0130695 -0.0836363 -0.0277254 0.018993 -0.0845466 -0.0280746 0.0203711 -0.0846683 -0.0280746 0.0217333 -0.0847398 -0.0280746 0.0243926 -0.0847508 -0.0280746 0.0256813 -0.0846996 -0.0280746 0.0259289 -0.0857864 -0.027104 0.0269453 -0.0859847 -0.0270129 0.0256897 -0.0860639 -0.0270129 0.031076 -0.084653 -0.0274514 0.0302366 -0.0845203 -0.0277254 0.0312992 -0.0843308 -0.0277254 0.0293328 -0.0843748 -0.0280746 0.0337171 -0.0841361 -0.0272471 0.0338782 -0.0837765 -0.0274514 0.0345468 -0.0837182 -0.0272471 0.031512 -0.0840235 -0.0280746 0.0349253 -0.0826225 -0.0280746 0.0355038 -0.0824558 -0.0277254 0.0348033 -0.0829756 -0.0277254 0.0341912 -0.0830781 -0.0280746 0.0355905 -0.0820925 -0.0280746 0.0361995 -0.0814856 -0.0280746 0.0367697 -0.0807939 -0.0280746 0.0384025 -0.0780693 -0.0280746 0.0379219 -0.0794724 -0.0277254 0.0373464 -0.0803784 -0.0277254 0.0389509 -0.0768827 -0.0280746 0.0395059 -0.0755262 -0.0280746 0.0406327 -0.0722407 -0.0280746 0.0402253 -0.0743218 -0.0277254 0.0412022 -0.0702848 -0.0280746 0.041658 -0.0679134 -0.0283402 0.0417665 -0.0680894 -0.0280914 0.00479333 -0.0795403 -0.0277254 0.00749181 -0.0812837 -0.0277254 0.00613184 -0.0804645 -0.0277254 0.0102602 -0.0826329 -0.0277254 0.00886919 -0.0820043 -0.0277254 0.0116615 -0.0831751 -0.0277254 0.0214562 -0.0849907 -0.0277254 0.0228069 -0.0850261 -0.0277254 0.0241328 -0.0850196 -0.0277254 0.0254296 -0.0849759 -0.0277254 0.0264372 -0.0851967 -0.0274514 0.0322873 -0.0840898 -0.0277254 0.0332005 -0.0837888 -0.0277254 0.0340384 -0.083419 -0.0277254 0.0361509 -0.081856 -0.0277254 0.03676 -0.0811673 -0.0277254 0.0384949 -0.0784313 -0.0277254 0.037987 -0.0798587 -0.0274514 0.0373755 -0.080769 -0.0274514 0.0396461 -0.0758725 -0.0277254 0.0408061 -0.0725717 -0.0277254 0.0403914 -0.0746768 -0.0274514 0.0390692 -0.077237 -0.0277254 0.041388 -0.0706089 -0.0277254 0.0418863 -0.0682839 -0.027863 0.00156103 -0.07735 -0.0273175 0.00440473 -0.0795892 -0.0274514 0.00711213 -0.0813801 -0.0274514 0.00574703 -0.0805376 -0.0274514 0.00989435 -0.082773 -0.0274514 0.00849588 -0.0821232 -0.0274514 0.011304 -0.0833353 -0.0274514 0.012721 -0.0838151 -0.0274514 0.0109444 -0.0834963 -0.0272471 0.0123705 -0.083995 -0.0272471 0.018388 -0.0850157 -0.0274514 0.0222425 -0.0855736 -0.0272471 0.0211656 -0.0852538 -0.0274514 0.0225255 -0.0852991 -0.0274514 0.0238603 -0.0853014 -0.0274514 0.0251657 -0.0852657 -0.0274514 0.0267279 -0.0862502 -0.0269644 0.0254656 -0.0863239 -0.0269644 0.0300025 -0.0848345 -0.0274514 0.03356 -0.0844867 -0.027104 0.0326428 -0.0848177 -0.027104 0.032826 -0.0844798 -0.0272471 0.0274209 -0.085404 -0.0272471 0.0261799 -0.0854953 -0.0272471 0.0320797 -0.0844224 -0.0274514 0.0330138 -0.0841333 -0.0274514 0.0346754 -0.0833458 -0.0274514 0.0354128 -0.0828369 -0.0274514 0.0360999 -0.0822444 -0.0274514 0.0367498 -0.081559 -0.0274514 0.0385917 -0.0788109 -0.0274514 0.0397931 -0.0762356 -0.0274514 0.0391933 -0.0776086 -0.0274514 0.0409879 -0.0729188 -0.0274514 0.0405584 -0.0750337 -0.0272471 0.0415828 -0.0709489 -0.0274514 0.0420169 -0.0684959 -0.0276564 0.0421566 -0.0687225 -0.027474 -0.00210837 -0.07735 -0.0276564 -0.00184217 -0.07735 -0.027474 -0.000904463 -0.0787797 -0.0277254 0.00401388 -0.0796385 -0.0272471 0.00673027 -0.081477 -0.0272471 0.00536 -0.080611 -0.0272471 0.00812043 -0.0822427 -0.0272471 0.0166577 -0.0850414 -0.0272471 0.0180765 -0.0852572 -0.0272471 0.0194832 -0.0854146 -0.0272471 0.0208734 -0.0855185 -0.0272471 0.0235863 -0.0855849 -0.0272471 0.0249002 -0.0855572 -0.0272471 0.0308515 -0.0849771 -0.0272471 0.0271774 -0.0857014 -0.027104 0.031871 -0.0847568 -0.0272471 0.03672 -0.0827031 -0.0270129 0.0359986 -0.0830159 -0.027104 0.0367295 -0.082337 -0.027104 0.0353213 -0.0832201 -0.0272471 0.0360487 -0.082635 -0.0272471 0.0367395 -0.0819529 -0.0272471 0.0374047 -0.0811619 -0.0272471 0.0380525 -0.0802472 -0.0272471 0.0386892 -0.0791927 -0.0272471 0.039941 -0.0766009 -0.0272471 0.0393182 -0.0779823 -0.0272471 0.0411708 -0.073268 -0.0272471 0.0417787 -0.0712908 -0.0272471 0.0423051 -0.0689636 -0.0273165 0.000958919 -0.07735 -0.027084 0.00194725 -0.0786006 -0.0270129 0.00363273 -0.0796866 -0.027104 0.00635788 -0.0815716 -0.027104 0.00498257 -0.0806826 -0.027104 0.00775429 -0.0823593 -0.027104 0.00707834 -0.0825744 -0.0269644 0.00820863 -0.0834187 -0.02695 0.00677578 -0.0826708 -0.02695 0.00850515 -0.0833051 -0.0269644 0.0102595 -0.0838031 -0.0270129 0.00994636 -0.0839433 -0.0269644 0.0163443 -0.0852639 -0.027104 0.0205884 -0.0857766 -0.027104 0.0219665 -0.0858414 -0.027104 0.023319 -0.0858613 -0.027104 0.0246413 -0.0858414 -0.027104 0.0306326 -0.0852931 -0.027104 0.0341897 -0.0847518 -0.0269644 0.0332699 -0.0851341 -0.0269644 0.0334103 -0.084821 -0.0270129 0.0316674 -0.0850829 -0.027104 0.0398658 -0.079622 -0.0269644 0.0407185 -0.0785213 -0.0270129 0.0399745 -0.0799474 -0.0270129 0.0344213 -0.0840814 -0.027104 0.0352321 -0.0835939 -0.027104 0.0374332 -0.0815451 -0.027104 0.0381163 -0.0806261 -0.027104 0.0387842 -0.079565 -0.027104 0.0400852 -0.076957 -0.027104 0.0394399 -0.0783468 -0.027104 0.0407213 -0.0753819 -0.027104 0.0413492 -0.0736085 -0.027104 0.0419698 -0.0716243 -0.027104 0.0424599 -0.0692147 -0.0271862 0.00326946 -0.0797324 -0.0270129 0.00600295 -0.0816617 -0.0270129 0.00462285 -0.0807509 -0.0270129 0.00882559 -0.0831824 -0.0270129 0.00740532 -0.0824703 -0.0270129 0.00724968 -0.083786 -0.027104 0.0160457 -0.0854759 -0.0270129 0.0174833 -0.0857172 -0.0270129 0.021457 -0.0863357 -0.0269644 0.0203167 -0.0860225 -0.0270129 0.0217035 -0.0860966 -0.0270129 0.0230643 -0.0861248 -0.0270129 0.0243945 -0.0861123 -0.0270129 0.0281568 -0.0858797 -0.0270129 0.0252582 -0.0865645 -0.02695 0.0265266 -0.0864959 -0.02695 0.0263254 -0.0867416 -0.0269644 0.0340861 -0.0850519 -0.02695 0.0331401 -0.0854239 -0.02695 0.0314733 -0.0853938 -0.0270129 0.0324682 -0.0851397 -0.0270129 0.0343018 -0.0844275 -0.0270129 0.035147 -0.0839501 -0.0270129 0.035951 -0.083379 -0.0270129 0.0381772 -0.0809872 -0.0270129 0.0388748 -0.0799198 -0.0270129 0.0389596 -0.0802523 -0.0269644 0.0374603 -0.0819103 -0.0270129 0.0402226 -0.0772965 -0.0270129 0.0395559 -0.0786941 -0.0270129 0.0408766 -0.0757136 -0.0270129 0.0415191 -0.073933 -0.0270129 0.0421519 -0.0719421 -0.0270129 0.042621 -0.0694762 -0.0270834 0.0427855 -0.0697432 -0.0270096 0.00128794 -0.078642 -0.02695 -1.66951e-15 -0.07735 -0.02695 0.00292908 -0.0797753 -0.0269644 0.00791211 -0.0835323 -0.0269644 0.0143117 -0.0853547 -0.0269644 0.0157659 -0.0856746 -0.0269644 0.0172121 -0.0859275 -0.0269644 0.0186457 -0.0861187 -0.0269644 0.0200622 -0.086253 -0.0269644 0.0228256 -0.0863717 -0.0269644 0.0241633 -0.0863661 -0.0269644 0.0239494 -0.0866009 -0.02695 0.0279456 -0.0861501 -0.0269644 0.0291137 -0.0860277 -0.0269644 0.0323047 -0.0854415 -0.0269644 0.0410002 -0.079217 -0.0272471 0.040856 -0.0788608 -0.027104 0.0417549 -0.0775907 -0.0272471 0.0350673 -0.0842839 -0.0269644 0.0359063 -0.0837192 -0.0269644 0.0367111 -0.0830461 -0.0269644 0.0374858 -0.0822525 -0.0269644 0.0382342 -0.0813256 -0.0269644 0.038287 -0.0816387 -0.02695 0.0375093 -0.0825691 -0.02695 0.0403514 -0.0776146 -0.0269644 0.0396646 -0.0790196 -0.0269644 0.041022 -0.0760245 -0.0269644 0.0416784 -0.074237 -0.0269644 0.0423225 -0.0722398 -0.0269644 0.0429541 -0.0700168 -0.0269649 0.000971067 -0.0786619 -0.0269644 -0.000321925 -0.07735 -0.0269649 0.00261411 -0.079815 -0.02695 0.000263158 -0.0787064 -0.027104 -0.000120297 -0.0787305 -0.0272471 -0.00126402 -0.07735 -0.0271862 0.00397389 -0.080874 -0.02695 0.00472236 -0.0819868 -0.0270129 0.003662 -0.0809332 -0.0269644 0.00505493 -0.0819024 -0.0269644 0.00614623 -0.0828712 -0.0270129 0.00647321 -0.0827671 -0.0269644 0.00759167 -0.083655 -0.0270129 0.0140448 -0.0855267 -0.02695 0.015507 -0.0858584 -0.02695 0.0184025 -0.0863231 -0.02695 0.0198267 -0.0864663 -0.02695 0.021229 -0.0865569 -0.02695 0.0226048 -0.0866001 -0.02695 0.02775 -0.0864003 -0.02695 0.028924 -0.0862823 -0.02695 0.0300477 -0.0861377 -0.02695 0.0298668 -0.0863989 -0.0269644 0.0348401 -0.0852353 -0.0270129 0.0339824 -0.085352 -0.0269644 0.03287 -0.0860268 -0.0270129 0.0349936 -0.0845927 -0.02695 0.035865 -0.0840339 -0.02695 0.0330103 -0.0857136 -0.0269644 0.0367028 -0.0833635 -0.02695 0.0390381 -0.08056 -0.02695 0.0383397 -0.0819518 -0.0269644 0.0375329 -0.0828858 -0.0269644 0.0397652 -0.0793208 -0.02695 0.0404706 -0.0779089 -0.02695 0.0411567 -0.0763122 -0.02695 0.0418258 -0.0745184 -0.02695 0.0424804 -0.0725154 -0.02695 0.0431229 -0.0702909 -0.02695 0.000628625 -0.0786834 -0.0270129 -0.000643256 -0.07735 -0.0270096 0.00229915 -0.0798547 -0.0269644 0.00579727 -0.0829822 -0.027104 0.015248 -0.0860422 -0.0269644 0.0193367 -0.08691 -0.0270129 0.0195912 -0.0866796 -0.0269644 0.0207545 -0.0870173 -0.0270129 0.0210009 -0.0867782 -0.0269644 0.0223839 -0.0868286 -0.0269644 0.0237354 -0.0868358 -0.0269644 0.0250508 -0.0868051 -0.0269644 0.0275545 -0.0866505 -0.0269644 0.0287343 -0.086537 -0.0269644 0.0366456 -0.0855596 -0.0277254 0.0356301 -0.0858235 -0.0274514 0.0366558 -0.085168 -0.0274514 0.0349198 -0.0849015 -0.0269644 0.0358237 -0.0843487 -0.0269644 0.0366945 -0.0836809 -0.0269644 0.0391167 -0.0808677 -0.0269644 0.0375583 -0.083228 -0.0270129 0.0383968 -0.0822902 -0.0270129 0.0405897 -0.0782033 -0.0269644 0.0412913 -0.0765999 -0.0269644 0.0414367 -0.0769107 -0.0270129 0.0426383 -0.0727909 -0.0269644 0.0432931 -0.070567 -0.0269651 0.0419732 -0.0747998 -0.0269644 -0.000956869 -0.07735 -0.0270834 0.00195876 -0.0798976 -0.0270129 -0.000513503 -0.0787552 -0.0274514 0.00332494 -0.0809971 -0.0270129 0.00399505 -0.0821714 -0.0272471 0.00296522 -0.0810654 -0.027104 0.00436744 -0.0820769 -0.027104 0.00543113 -0.0830988 -0.0272471 0.0120075 -0.085453 -0.0270129 0.0199325 -0.0878148 -0.0274514 0.0184878 -0.0876788 -0.0274514 0.01878 -0.0874141 -0.0272471 0.0164388 -0.0865271 -0.0270129 0.0178965 -0.0867484 -0.0270129 0.0232575 -0.0873605 -0.027104 0.0218905 -0.0873389 -0.027104 0.0221452 -0.0870754 -0.0270129 0.0235042 -0.0870896 -0.0270129 0.0248267 -0.0870651 -0.0270129 0.0261079 -0.0870071 -0.0270129 0.0273433 -0.0869209 -0.0270129 0.0285293 -0.0868122 -0.0270129 0.0296713 -0.0866811 -0.0270129 0.0376999 -0.0851325 -0.0280746 0.0376722 -0.0847599 -0.0277254 0.0387141 -0.0841734 -0.0280746 0.035779 -0.0846889 -0.0270129 0.0428456 -0.0764651 -0.0277254 0.042088 -0.0783026 -0.0277254 0.0419219 -0.0779476 -0.0274514 0.0366856 -0.0840239 -0.0270129 0.0392015 -0.0812002 -0.0270129 0.0384576 -0.0826513 -0.027104 0.0375855 -0.0835932 -0.027104 0.0421325 -0.0751038 -0.0270129 0.041592 -0.0772425 -0.027104 0.042809 -0.0730887 -0.0270129 0.0434606 -0.0708389 -0.0270097 -0.00161265 -0.0788242 -0.0285002 -0.00279256 -0.07735 -0.0283402 -0.00258582 -0.07735 -0.0280914 0.00159549 -0.0799434 -0.027104 0.00361318 -0.0822683 -0.0274514 0.00258779 -0.081137 -0.0272471 0.0116905 -0.0856364 -0.027104 0.0131817 -0.086083 -0.027104 0.0146696 -0.0864529 -0.027104 0.0161493 -0.0867515 -0.027104 0.0176161 -0.0869841 -0.027104 0.019065 -0.087156 -0.027104 0.0204914 -0.0872725 -0.027104 0.0245875 -0.0873426 -0.027104 0.0258759 -0.0872905 -0.027104 0.0280809 -0.0874141 -0.0272471 0.0268812 -0.0875123 -0.0272471 0.0271178 -0.0872095 -0.027104 0.0283105 -0.0871059 -0.027104 0.0294627 -0.0869823 -0.027104 0.0305792 -0.0868262 -0.027104 0.038587 -0.0834187 -0.0274514 0.0386521 -0.083805 -0.0277254 0.0376432 -0.0843693 -0.0274514 0.0357314 -0.085052 -0.027104 0.0366761 -0.08439 -0.027104 0.0392921 -0.081555 -0.027104 0.037614 -0.0839764 -0.0272471 0.0385215 -0.0830302 -0.0272471 0.0400905 -0.0802948 -0.027104 0.0423025 -0.0754284 -0.027104 0.043626 -0.0711073 -0.027084 0.0429911 -0.0734065 -0.027104 -0.00155904 -0.07735 -0.0273165 0.00121434 -0.0799914 -0.0272471 -0.00235744 -0.07735 -0.027863 -0.00127726 -0.0788032 -0.0280746 0.0032335 -0.0823647 -0.0277254 0.00220076 -0.0812104 -0.0274514 0.00468237 -0.0833372 -0.0277254 0.00505567 -0.0832183 -0.0274514 0.011358 -0.0858289 -0.0272471 0.0128587 -0.0862911 -0.0272471 0.0143563 -0.0866754 -0.0272471 0.0158456 -0.0869871 -0.0272471 0.0173218 -0.0872315 -0.0272471 0.0202155 -0.0875403 -0.0272471 0.0216232 -0.0876153 -0.0272471 0.0229986 -0.0876447 -0.0272471 0.0243365 -0.0876337 -0.0272471 0.0256323 -0.0875878 -0.0272471 0.0292438 -0.0872983 -0.0272471 0.0303756 -0.0871523 -0.0272471 0.0314807 -0.0869616 -0.0272471 0.0346658 -0.0859653 -0.0272471 0.0356814 -0.0854329 -0.0272471 0.0366661 -0.0847741 -0.0272471 0.0393871 -0.0819273 -0.0272471 0.0402123 -0.0806593 -0.0272471 0.0424808 -0.0757688 -0.0272471 0.0431822 -0.0737399 -0.0272471 0.0433781 -0.0740818 -0.0274514 0.0437865 -0.0713678 -0.0271867 -0.00188962 -0.0788416 -0.0289969 -0.00313262 -0.07735 -0.0288891 -0.00297528 -0.07735 -0.0286069 0.000823501 -0.0800407 -0.0274514 0.011017 -0.0860262 -0.0274514 0.0125275 -0.0865046 -0.0274514 0.014035 -0.0869035 -0.0274514 0.01702 -0.0874851 -0.0274514 0.0224691 -0.0882259 -0.0277254 0.0210767 -0.0881807 -0.0277254 0.0213492 -0.0878988 -0.0274514 0.0227331 -0.0879361 -0.0274514 0.0240792 -0.0879323 -0.0274514 0.0253826 -0.0878927 -0.0274514 0.0266386 -0.0878227 -0.0274514 0.0278455 -0.0877301 -0.0274514 0.0290193 -0.0876224 -0.0274514 0.0301669 -0.0874868 -0.0274514 0.0312928 -0.087308 -0.0274514 0.0343966 -0.0870929 -0.0280746 0.0355305 -0.0865823 -0.0280746 0.0322418 -0.0874287 -0.0277254 0.0394845 -0.0823091 -0.0274514 0.0403371 -0.081033 -0.0274514 0.041148 -0.0795822 -0.0274514 0.0426637 -0.076118 -0.0274514 0.0439418 -0.0716199 -0.0273175 -0.00326338 -0.07735 -0.0291851 -0.002088 -0.0788541 -0.0295522 -0.00336605 -0.07735 -0.0294912 0.000434892 -0.0800897 -0.0277254 0.00181595 -0.0812835 -0.0277254 0.00254574 -0.0825393 -0.0285002 0.001449 -0.0813531 -0.0280746 0.00287146 -0.0824566 -0.0280746 0.0091605 -0.0856422 -0.0277254 0.0106779 -0.0862224 -0.0277254 0.0121982 -0.0867168 -0.0277254 0.0137155 -0.0871303 -0.0277254 0.0205831 -0.0886912 -0.0285002 0.0191414 -0.0885823 -0.0285002 0.0193828 -0.0883481 -0.0280746 0.0181972 -0.0879419 -0.0277254 0.0196511 -0.0880878 -0.0277254 0.0238233 -0.0882291 -0.0277254 0.0261673 -0.0884258 -0.0280746 0.0248976 -0.0884848 -0.0280746 0.0251344 -0.0881958 -0.0277254 0.0263973 -0.0881314 -0.0277254 0.0276114 -0.0880443 -0.0277254 0.0287962 -0.0879446 -0.0277254 0.0299593 -0.0878193 -0.0277254 0.0311061 -0.0876525 -0.0277254 0.0397569 -0.0833763 -0.0285002 0.0398255 -0.0836453 -0.0289969 0.03877 -0.0845048 -0.0285002 0.032089 -0.0877696 -0.0280746 0.0417401 -0.0810447 -0.0295522 0.0425908 -0.079377 -0.0295522 0.0416655 -0.0808605 -0.0289969 0.0425066 -0.0791969 -0.0289969 0.0395814 -0.0826887 -0.0277254 0.0412951 -0.0799454 -0.0277254 0.0422464 -0.078641 -0.0280746 0.0414352 -0.0802917 -0.0280746 0.0404612 -0.0814046 -0.0277254 0.0435729 -0.0744218 -0.0277254 0.0442298 -0.0720872 -0.0276575 0.0440899 -0.0718602 -0.0274748 6.43331e-05 -0.0801364 -0.0280746 0.00111888 -0.0814157 -0.0285002 0.00882815 -0.0858127 -0.0280746 0.0103546 -0.0864096 -0.0280746 0.0118841 -0.0869192 -0.0280746 0.0134109 -0.0873466 -0.0280746 0.0149292 -0.0876976 -0.0280746 0.0164339 -0.0879778 -0.0280746 0.0179201 -0.0881928 -0.0280746 0.0208169 -0.0884494 -0.0280746 0.0222174 -0.0885022 -0.0280746 0.0235793 -0.0885122 -0.0280746 0.0273882 -0.0883439 -0.0280746 0.0285834 -0.0882519 -0.0280746 0.0297614 -0.0881364 -0.0280746 0.030928 -0.087981 -0.0280746 0.0343185 -0.0874198 -0.0285002 0.0331371 -0.087799 -0.0285002 0.0332468 -0.0874814 -0.0280746 0.0366359 -0.0859331 -0.0280746 0.0396738 -0.0830507 -0.0280746 0.0377249 -0.0854676 -0.0285002 0.0405795 -0.0817589 -0.0280746 0.0437587 -0.074746 -0.0280746 0.0439258 -0.0750376 -0.0285002 0.0430189 -0.0767962 -0.0280746 0.0423889 -0.0789455 -0.0285002 0.0443602 -0.0722989 -0.0278642 -0.00219168 -0.0788606 -0.0301462 -0.0034849 -0.07735 -0.0301259 -0.00344031 -0.07735 -0.0298066 -0.000269041 -0.0801784 -0.0285002 0.000846266 -0.0814674 -0.0289969 0.00852915 -0.0859662 -0.0285002 0.0100637 -0.0865779 -0.0285002 0.0116016 -0.0871012 -0.0285002 0.0131368 -0.0875412 -0.0285002 0.0146635 -0.0879036 -0.0285002 0.0161765 -0.0881942 -0.0285002 0.0176708 -0.0884186 -0.0285002 0.0219909 -0.0887508 -0.0285002 0.0231785 -0.0889771 -0.0289969 0.0218039 -0.0889561 -0.0289969 0.0233598 -0.0887668 -0.0285002 0.0246846 -0.0887449 -0.0285002 0.0259604 -0.0886906 -0.0285002 0.0271874 -0.0886135 -0.0285002 0.0283919 -0.0885283 -0.0285002 0.0295833 -0.0884216 -0.0285002 0.0417791 -0.081141 -0.0307538 0.0425908 -0.079377 -0.0313478 0.0417401 -0.0810447 -0.0313478 0.0354868 -0.0869154 -0.0285002 0.0366271 -0.086269 -0.0285002 0.0377454 -0.0857444 -0.0289969 0.0388161 -0.0847785 -0.0289969 0.040686 -0.0820777 -0.0285002 0.0415614 -0.0806032 -0.0285002 0.0431749 -0.077094 -0.0285002 0.0445885 -0.0726693 -0.0283417 0.04448 -0.0724934 -0.0280926 -0.00344044 -0.07735 -0.0310929 -0.0034851 -0.07735 -0.0307718 -0.00219168 -0.0788606 -0.0307538 -0.000544346 -0.0802131 -0.0289969 -0.0035 -0.07735 -0.03045 0.00675075 -0.0853747 -0.0289969 0.00828223 -0.0860929 -0.0289969 0.00982348 -0.0867169 -0.0289969 0.0144441 -0.0880737 -0.0289969 0.0189421 -0.0887757 -0.0289969 0.0203901 -0.0888909 -0.0289969 0.0243828 -0.0891134 -0.0295522 0.0245088 -0.0889596 -0.0289969 0.0257895 -0.0889093 -0.0289969 0.0270216 -0.0888361 -0.0289969 0.0282338 -0.0887566 -0.0289969 0.0294363 -0.0886572 -0.0289969 0.0306355 -0.0885206 -0.0289969 0.0330465 -0.0880613 -0.0289969 0.0342541 -0.0876897 -0.0289969 0.0408369 -0.0825295 -0.0295522 0.0407739 -0.082341 -0.0289969 0.0388491 -0.0849745 -0.0295522 0.0433038 -0.0773399 -0.0289969 0.0440638 -0.0752785 -0.0289969 0.0447667 -0.0729586 -0.028891 0.0446841 -0.0728246 -0.028608 -0.00336663 -0.07735 -0.0314066 -0.00188962 -0.0788416 -0.0319031 -0.00326378 -0.07735 -0.031714 -0.000741529 -0.080238 -0.0295522 -0.002088 -0.0788541 -0.0313478 0.00504955 -0.0846286 -0.0295522 0.00656934 -0.0854559 -0.0295522 0.00810538 -0.0861836 -0.0295522 0.00965143 -0.0868165 -0.0295522 0.0112012 -0.0873592 -0.0295522 0.0187247 -0.0889867 -0.0307538 0.0187993 -0.0889143 -0.0313478 0.0172405 -0.0888083 -0.0307538 0.014287 -0.0881956 -0.0295522 0.0158117 -0.0885008 -0.0295522 0.0201796 -0.0891086 -0.0301462 0.0216 -0.08918 -0.0301462 0.0216 -0.08918 -0.0307538 0.0187993 -0.0889143 -0.0295522 0.0202518 -0.0890339 -0.0295522 0.02167 -0.0891031 -0.0295522 0.0230487 -0.0891277 -0.0295522 0.0256671 -0.089066 -0.0295522 0.0269028 -0.0889955 -0.0295522 0.0281206 -0.0889201 -0.0295522 0.0293309 -0.0888259 -0.0295522 0.0305408 -0.0886954 -0.0295522 0.0341838 -0.0879841 -0.0301462 0.0342079 -0.0878831 -0.0295522 0.0354248 -0.0873876 -0.0295522 0.0398747 -0.0838379 -0.0295522 0.0417791 -0.081141 -0.0301462 0.043396 -0.077516 -0.0295522 0.0441627 -0.075451 -0.0295522 0.044889 -0.0731571 -0.0294934 0.0448351 -0.0730695 -0.029186 -0.00161265 -0.0788242 -0.0323998 -0.00297605 -0.07735 -0.032292 -0.00313351 -0.07735 -0.032009 -0.000844584 -0.080251 -0.0301462 0.00495253 -0.0846658 -0.0301462 0.00647453 -0.0854984 -0.0301462 0.00801295 -0.0862311 -0.0301462 0.00956151 -0.0868685 -0.0301462 0.0111139 -0.0874155 -0.0301462 0.0126637 -0.0878771 -0.0301462 0.0142048 -0.0882593 -0.0301462 0.0157322 -0.0885677 -0.0301462 0.0172405 -0.0888083 -0.0301462 0.0187247 -0.0889867 -0.0301462 0.0229808 -0.0892065 -0.0301462 0.0243169 -0.0891938 -0.0301462 0.0256031 -0.0891478 -0.0301462 0.0268407 -0.0890788 -0.0301462 0.0280614 -0.0890055 -0.0301462 0.0292759 -0.0889141 -0.0301462 0.0304913 -0.0887868 -0.0301462 0.0317144 -0.0886058 -0.0301462 0.0329477 -0.0883474 -0.0301462 0.0377602 -0.0859426 -0.0313478 0.036612 -0.086849 -0.0307538 0.0354113 -0.0874906 -0.0301462 0.0399004 -0.0839385 -0.0301462 0.0408698 -0.082628 -0.0301462 0.0434443 -0.0776081 -0.0301462 0.0449512 -0.073258 -0.0301282 0.0442143 -0.0755411 -0.0301462 0.0449277 -0.0732199 -0.0298071 -0.00279366 -0.07735 -0.0325583 -0.00127726 -0.0788032 -0.0328254 -0.00258701 -0.07735 -0.0328074 -0.000844584 -0.080251 -0.0307538 0.00495253 -0.0846658 -0.0307538 0.00647453 -0.0854984 -0.0307538 0.00801295 -0.0862311 -0.0307538 0.00956151 -0.0868685 -0.0307538 0.0111139 -0.0874155 -0.0307538 0.0157322 -0.0885677 -0.0307538 0.0201796 -0.0891086 -0.0307538 0.0229808 -0.0892065 -0.0307538 0.0256031 -0.0891478 -0.0307538 0.0256671 -0.089066 -0.0313478 0.0243169 -0.0891938 -0.0307538 0.0268407 -0.0890788 -0.0307538 0.0280614 -0.0890055 -0.0307538 0.0292759 -0.0889141 -0.0307538 0.0304913 -0.0887868 -0.0307538 0.0317144 -0.0886058 -0.0307538 0.0329477 -0.0883474 -0.0307538 0.0341838 -0.0879841 -0.0307538 0.0354113 -0.0874906 -0.0307538 0.0377454 -0.0857444 -0.0319031 0.0399004 -0.0839385 -0.0307538 0.0408698 -0.082628 -0.0307538 0.0441627 -0.075451 -0.0313478 0.0442143 -0.0755411 -0.0307538 0.0449277 -0.0732198 -0.0310934 0.044959 -0.0732706 -0.03045 -0.000741529 -0.080238 -0.0313478 0.00355227 -0.0836969 -0.0313478 0.00504955 -0.0846286 -0.0313478 0.00656934 -0.0854559 -0.0313478 0.00810538 -0.0861836 -0.0313478 0.00965143 -0.0868165 -0.0313478 0.0112012 -0.0873592 -0.0313478 0.0127484 -0.087817 -0.0313478 0.0208169 -0.0884494 -0.0328254 0.0193828 -0.0883481 -0.0328254 0.0191414 -0.0885823 -0.0323998 0.0158117 -0.0885008 -0.0313478 0.0173175 -0.0887385 -0.0313478 0.02167 -0.0891031 -0.0313478 0.0218039 -0.0889561 -0.0319031 0.0202518 -0.0890339 -0.0313478 0.0230487 -0.0891277 -0.0313478 0.0243828 -0.0891134 -0.0313478 0.0269028 -0.0889955 -0.0313478 0.0281206 -0.0889201 -0.0313478 0.0293309 -0.0888259 -0.0313478 0.0305408 -0.0886954 -0.0313478 0.0317568 -0.088511 -0.0313478 0.0329816 -0.0882492 -0.0313478 0.0354248 -0.0873876 -0.0313478 0.0354506 -0.0871906 -0.0319031 0.0342079 -0.0878831 -0.0313478 0.0366147 -0.0867452 -0.0313478 0.0397569 -0.0833763 -0.0323998 0.0388161 -0.0847785 -0.0319031 0.0408369 -0.0825295 -0.0313478 0.0440638 -0.0752785 -0.0319031 0.043396 -0.077516 -0.0313478 0.0425066 -0.0791969 -0.0319031 0.0449511 -0.0732578 -0.030774 -0.00184326 -0.07735 -0.0334252 -0.000544346 -0.0802131 -0.0319031 0.00374169 -0.0836366 -0.0319031 0.00523518 -0.0845575 -0.0319031 0.00675075 -0.0853747 -0.0319031 0.00828223 -0.0860929 -0.0319031 0.00982348 -0.0867169 -0.0319031 0.0113683 -0.0872515 -0.0319031 0.0129105 -0.0877019 -0.0319031 0.0144441 -0.0880737 -0.0319031 0.015964 -0.0883729 -0.0319031 0.017465 -0.088605 -0.0319031 0.0189421 -0.0887757 -0.0319031 0.0203901 -0.0888909 -0.0319031 0.0245088 -0.0889596 -0.0319031 0.0246846 -0.0887449 -0.0323998 0.0231785 -0.0889771 -0.0319031 0.0257895 -0.0889093 -0.0319031 0.0270216 -0.0888361 -0.0319031 0.0282338 -0.0887566 -0.0319031 0.0294363 -0.0886572 -0.0319031 0.0306355 -0.0885206 -0.0319031 0.0318381 -0.0883296 -0.0319031 0.0330465 -0.0880613 -0.0319031 0.0342541 -0.0876897 -0.0319031 0.0366199 -0.0865465 -0.0319031 0.0423889 -0.0789455 -0.0323998 0.0431749 -0.077094 -0.0323998 0.0407739 -0.082341 -0.0319031 0.0416655 -0.0808605 -0.0319031 0.0433038 -0.0773399 -0.0319031 0.0448349 -0.0730692 -0.0317149 0.0448887 -0.0731566 -0.0314088 -0.000269041 -0.0801784 -0.0323998 0.00400615 -0.0835524 -0.0323998 0.00549436 -0.0844583 -0.0323998 0.00700404 -0.0852612 -0.0323998 0.00852915 -0.0859662 -0.0323998 0.0100637 -0.0865779 -0.0323998 0.0116016 -0.0871012 -0.0323998 0.0131368 -0.0875412 -0.0323998 0.0161765 -0.0881942 -0.0323998 0.0176708 -0.0884186 -0.0323998 0.0205831 -0.0886912 -0.0323998 0.0219909 -0.0887508 -0.0323998 0.0233598 -0.0887668 -0.0323998 0.0259604 -0.0886906 -0.0323998 0.0273882 -0.0883439 -0.0328254 0.0261673 -0.0884258 -0.0328254 0.0271874 -0.0886135 -0.0323998 0.0283919 -0.0885283 -0.0323998 0.0295833 -0.0884216 -0.0323998 0.0307678 -0.0882766 -0.0323998 0.0319516 -0.0880763 -0.0323998 0.0331371 -0.087799 -0.0323998 0.0343185 -0.0874198 -0.0323998 0.0354868 -0.0869154 -0.0323998 0.0366271 -0.086269 -0.0323998 0.0421325 -0.0751038 -0.0338871 0.0414367 -0.0769107 -0.0338871 0.041592 -0.0772425 -0.033796 0.0415614 -0.0806032 -0.0323998 0.0422464 -0.078641 -0.0328254 0.0439258 -0.0750376 -0.0323998 0.0446837 -0.0728239 -0.0322931 0.0447663 -0.0729579 -0.0320109 -0.00235862 -0.07735 -0.0330358 6.43331e-05 -0.0801364 -0.0328254 0.0043264 -0.0834505 -0.0328254 0.00580821 -0.0843381 -0.0328254 0.00731075 -0.0851239 -0.0328254 0.00882815 -0.0858127 -0.0328254 0.0103546 -0.0864096 -0.0328254 0.0118841 -0.0869192 -0.0328254 0.0196511 -0.0880878 -0.0331746 0.0213492 -0.0878988 -0.0334486 0.0199325 -0.0878148 -0.0334486 0.0179201 -0.0881928 -0.0328254 0.0238233 -0.0882291 -0.0331746 0.0224691 -0.0882259 -0.0331746 0.0222174 -0.0885022 -0.0328254 0.0235793 -0.0885122 -0.0328254 0.0248976 -0.0884848 -0.0328254 0.0285834 -0.0882519 -0.0328254 0.0297614 -0.0881364 -0.0328254 0.030928 -0.087981 -0.0328254 0.032089 -0.0877696 -0.0328254 0.0332468 -0.0874814 -0.0328254 0.0343966 -0.0870929 -0.0328254 0.0366456 -0.0855596 -0.0331746 0.0355791 -0.0862119 -0.0331746 0.0355305 -0.0865823 -0.0328254 0.0366359 -0.0859331 -0.0328254 0.0376999 -0.0851325 -0.0328254 0.0396738 -0.0830507 -0.0328254 0.0430189 -0.0767962 -0.0328254 0.0437587 -0.074746 -0.0328254 0.0445879 -0.0726684 -0.0325598 0.0444794 -0.0724923 -0.0328086 0.0032335 -0.0823647 -0.0331746 0.00181595 -0.0812835 -0.0331746 0.000434892 -0.0800897 -0.0331746 0.00468237 -0.0833372 -0.0331746 0.00765167 -0.0849712 -0.0331746 0.0106779 -0.0862224 -0.0331746 0.01878 -0.0874141 -0.0336529 0.0184878 -0.0876788 -0.0334486 0.0202155 -0.0875403 -0.0336529 0.01672 -0.0877374 -0.0331746 0.0181972 -0.0879419 -0.0331746 0.0210767 -0.0881807 -0.0331746 0.0251344 -0.0881958 -0.0331746 0.0266386 -0.0878227 -0.0334486 0.0253826 -0.0878927 -0.0334486 0.0263973 -0.0881314 -0.0331746 0.0276114 -0.0880443 -0.0331746 0.0287962 -0.0879446 -0.0331746 0.0299593 -0.0878193 -0.0331746 0.0311061 -0.0876525 -0.0331746 0.0322418 -0.0874287 -0.0331746 0.0333688 -0.0871283 -0.0331746 0.0344833 -0.0867295 -0.0331746 0.0376722 -0.0847599 -0.0331746 0.0407185 -0.0785213 -0.0338871 0.0400905 -0.0802948 -0.033796 0.040856 -0.0788608 -0.033796 0.0386521 -0.083805 -0.0331746 0.0395814 -0.0826887 -0.0331746 0.0428456 -0.0764651 -0.0331746 0.0435729 -0.0744218 -0.0331746 0.0443596 -0.0722979 -0.033037 0.00220076 -0.0812104 -0.0334486 0.00361318 -0.0822683 -0.0334486 0.000823501 -0.0800407 -0.0334486 0.00505567 -0.0832183 -0.0334486 0.0131817 -0.086083 -0.033796 0.0134895 -0.0858846 -0.0338871 0.0116905 -0.0856364 -0.033796 0.0161493 -0.0867515 -0.033796 0.0164388 -0.0865271 -0.0338871 0.0146696 -0.0864529 -0.033796 0.0176161 -0.0869841 -0.033796 0.019065 -0.087156 -0.033796 0.0193367 -0.08691 -0.0338871 0.0155341 -0.0872286 -0.0334486 0.01702 -0.0874851 -0.0334486 0.0227331 -0.0879361 -0.0334486 0.0243365 -0.0876337 -0.0336529 0.0229986 -0.0876447 -0.0336529 0.0240792 -0.0879323 -0.0334486 0.0278455 -0.0877301 -0.0334486 0.0290193 -0.0876224 -0.0334486 0.0301669 -0.0874868 -0.0334486 0.0312928 -0.087308 -0.0334486 0.032402 -0.0870712 -0.0334486 0.0334967 -0.086758 -0.0334486 0.0346658 -0.0859653 -0.0336529 0.0336253 -0.0863857 -0.0336529 0.0345743 -0.0863485 -0.0334486 0.0356301 -0.0858235 -0.0334486 0.0366558 -0.085168 -0.0334486 0.0376432 -0.0843693 -0.0334486 0.038587 -0.0834187 -0.0334486 0.0394845 -0.0823091 -0.0334486 0.0403371 -0.081033 -0.0334486 0.0426637 -0.076118 -0.0334486 0.0433781 -0.0740818 -0.0334486 0.044229 -0.0720859 -0.0332436 0.0440893 -0.0718592 -0.033426 0.00399505 -0.0821714 -0.0336529 0.00258779 -0.081137 -0.0336529 0.00121434 -0.0799914 -0.0336529 0.00543113 -0.0830988 -0.0336529 0.00689085 -0.0839234 -0.0336529 0.00836877 -0.08465 -0.0336529 0.00985958 -0.0852835 -0.0336529 0.011358 -0.0858289 -0.0336529 0.0128587 -0.0862911 -0.0336529 0.0143563 -0.0866754 -0.0336529 0.0158456 -0.0869871 -0.0336529 0.0173218 -0.0872315 -0.0336529 0.0232575 -0.0873605 -0.033796 0.0235042 -0.0870896 -0.0338871 0.0218905 -0.0873389 -0.033796 0.0216232 -0.0876153 -0.0336529 0.0256323 -0.0875878 -0.0336529 0.0271178 -0.0872095 -0.033796 0.0258759 -0.0872905 -0.033796 0.0268812 -0.0875123 -0.0336529 0.0280809 -0.0874141 -0.0336529 0.0292438 -0.0872983 -0.0336529 0.0303756 -0.0871523 -0.0336529 0.0314807 -0.0869616 -0.0336529 0.0325631 -0.0867116 -0.0336529 0.0356814 -0.0854329 -0.0336529 0.0366661 -0.0847741 -0.0336529 0.037614 -0.0839764 -0.0336529 0.0385215 -0.0830302 -0.0336529 0.0392921 -0.081555 -0.033796 0.0384576 -0.0826513 -0.033796 0.0393871 -0.0819273 -0.0336529 0.0402123 -0.0806593 -0.0336529 0.0410002 -0.079217 -0.0336529 0.0439408 -0.0716182 -0.0335835 -0.00095892 -0.07735 -0.033816 0.00436744 -0.0820769 -0.033796 0.00296522 -0.0810654 -0.033796 0.00159549 -0.0799434 -0.033796 0.0204914 -0.0872725 -0.033796 0.0245875 -0.0873426 -0.033796 0.0283105 -0.0871059 -0.033796 0.0294627 -0.0869823 -0.033796 0.0296713 -0.0866811 -0.0338871 0.0305792 -0.0868262 -0.033796 0.0316638 -0.0866237 -0.033796 0.0327202 -0.086361 -0.033796 0.0337508 -0.0860225 -0.033796 0.0347551 -0.0855915 -0.033796 0.0357314 -0.085052 -0.033796 0.0366761 -0.08439 -0.033796 0.0375855 -0.0835932 -0.033796 0.0405897 -0.0782033 -0.0339356 0.0398658 -0.079622 -0.0339356 0.043786 -0.071367 -0.0337138 -0.000643725 -0.07735 -0.0338903 0.00614623 -0.0828712 -0.0338871 0.0108325 -0.0847842 -0.0339356 0.00905365 -0.0843432 -0.0338871 0.0137779 -0.0856987 -0.0339356 0.0120075 -0.085453 -0.0338871 0.0167101 -0.0863168 -0.0339356 0.0149682 -0.0862409 -0.0338871 0.0195912 -0.0866796 -0.0339356 0.0181593 -0.0865275 -0.0339356 0.0178965 -0.0867484 -0.0338871 0.0221452 -0.0870754 -0.0338871 0.0223839 -0.0868286 -0.0339356 0.0207545 -0.0870173 -0.0338871 0.0248267 -0.0870651 -0.0338871 0.0273433 -0.0869209 -0.0338871 0.0275545 -0.0866505 -0.0339356 0.0261079 -0.0870071 -0.0338871 0.0285293 -0.0868122 -0.0338871 0.0307733 -0.0865153 -0.0338871 0.0318384 -0.0863016 -0.0338871 0.03287 -0.0860268 -0.0338871 0.0338704 -0.0856764 -0.0338871 0.0348401 -0.0852353 -0.0338871 0.035779 -0.0846889 -0.0338871 0.0366856 -0.0840239 -0.0338871 0.0383968 -0.0822902 -0.0338871 0.0383397 -0.0819518 -0.0339356 0.0375583 -0.083228 -0.0338871 0.0392015 -0.0812002 -0.0338871 0.0399745 -0.0799474 -0.0338871 0.0419732 -0.0747998 -0.0339356 0.0436249 -0.0711055 -0.0338166 0.00936681 -0.0842029 -0.0339356 0.0123045 -0.0852811 -0.0339356 0.015248 -0.0860422 -0.0339356 0.0210009 -0.0867782 -0.0339356 0.0237354 -0.0868358 -0.0339356 0.0250508 -0.0868051 -0.0339356 0.0263254 -0.0867416 -0.0339356 0.0287343 -0.086537 -0.0339356 0.0298668 -0.0863989 -0.0339356 0.0309551 -0.0862241 -0.0339356 0.032002 -0.0859999 -0.0339356 0.0330103 -0.0857136 -0.0339356 0.0339824 -0.085352 -0.0339356 0.0349198 -0.0849015 -0.0339356 0.0358237 -0.0843487 -0.0339356 0.0366945 -0.0836809 -0.0339356 0.0375329 -0.0828858 -0.0339356 0.0391167 -0.0808677 -0.0339356 0.0412913 -0.0765999 -0.0339356 - - - - - - - - - - 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.851358 0.524585 0 0.124305 0.375257 -0.918548 0.143826 0.368475 -0.918445 0.0960805 0.239777 -0.966062 -0.0608608 -0.106856 -0.99241 -0.0545972 -0.110217 -0.992407 1.38786e-13 2.82048e-13 -1 0.0709951 0.248093 -0.966131 0.0411892 0.117716 -0.992193 0.0352235 0.119592 -0.992198 6.89276e-14 2.08676e-13 -1 0.0240569 0.122238 -0.992209 3.50569e-13 -4.83059e-13 -1 0.0189004 0.123096 -0.992215 1.04315e-13 -1.43411e-13 -1 0.0295033 0.121079 -0.992204 5.60267e-15 2.15343e-14 -1 8.38892e-13 -9.70594e-13 -1 8.78562e-13 -9.64855e-13 -1 0.00949938 0.124084 -0.992226 0.0140464 0.123697 -0.992221 8.38478e-13 -8.72215e-13 -1 0.00525828 0.124295 -0.992231 7.04723e-13 -7.05115e-13 -1 0.00131816 0.124366 -0.992236 4.62105e-13 -4.40359e-13 -1 -0.00232806 0.124325 -0.992239 9.4135e-14 -8.35747e-14 -1 -4.22375e-13 3.73665e-13 -1 -1.1121e-12 9.4229e-13 -1 -0.00568805 0.124198 -0.992241 -0.00876874 0.124003 -0.992243 -2.01284e-12 1.63448e-12 -1 -0.0115749 0.123757 -0.992245 -0.0320801 0.522928 -0.851773 -0.0218519 0.391452 -0.919939 -0.0445673 0.521639 -0.852001 -3.16871e-12 2.47569e-12 -1 -0.0145945 0.123574 -0.992228 -0.155644 0.376826 -0.913114 -0.1205 0.384714 -0.915137 -0.0737619 0.250965 -0.965182 -2.31843e-12 1.739e-12 -1 -1.77629e-13 1.27396e-13 -1 -0.0191613 0.123166 -0.992201 1.18027e-12 -7.54356e-13 -1 -0.0254192 0.122352 -0.992161 -0.0334431 0.120906 -0.9921 1.47374e-12 -8.33291e-13 -1 -0.118533 0.237051 -0.964239 -0.231133 0.342524 -0.910634 -0.19337 0.362808 -0.91158 -0.0316555 0.25519 -0.966372 -0.0249839 0.2553 -0.966539 -0.142469 0.224526 -0.963997 -0.0538295 0.114209 -0.991997 3.5174e-13 -1.66711e-13 -1 -0.043095 0.118339 -0.992038 -7.54576e-15 1.37319e-14 -1 -0.095156 0.245821 -0.964633 -7.76129e-15 8.45509e-15 -1 -3.87825e-15 2.71497e-15 -1 -0.0650526 0.108439 -0.991972 -0.0759686 0.101125 -0.991969 -3.52089e-15 4.30736e-15 -1 -0.085855 0.0926356 -0.991992 -0.488058 0.205581 -0.848255 -0.36305 0.157101 -0.91843 -0.493786 0.182408 -0.850237 -0.0942764 0.0836133 -0.992029 -6.68238e-15 5.91275e-15 -1 -3.33153e-15 3.71372e-15 -1 -6.72548e-15 4.93902e-15 -1 -0.101109 0.0746116 -0.992074 -0.230676 0.118673 -0.965767 -0.110515 0.0583783 -0.992158 -0.236119 0.104735 -0.966063 -2.09268e-15 1.56535e-15 -1 -0.106435 0.0661114 -0.992119 -8.55074e-15 3.72561e-15 -1 -1.11454e-14 4.61754e-15 -1 -0.113582 0.0515242 -0.992192 -4.99374e-15 2.2297e-15 -1 -0.11586 0.045553 -0.99222 -5.69713e-15 2.07757e-15 -1 -7.2358e-15 3.29726e-15 -1 -7.36842e-15 3.09244e-15 -1 -0.117569 0.0404226 -0.992242 -7.89665e-15 2.68838e-15 -1 -0.118874 0.0360454 -0.992255 -7.94557e-15 2.54206e-15 -1 -0.121336 0.0327071 -0.992073 -7.98667e-15 2.41247e-15 -1 -1.06033e-14 3.11728e-15 -1 -8.0507e-15 2.19307e-15 -1 0.0473523 0.115401 -0.99219 1.54362e-13 3.78548e-13 -1 1.15714e-13 3.12419e-13 -1 1.70875e-13 3.80596e-13 -1 0.0536568 0.112617 -0.992189 0.109154 0.234187 -0.966044 4.46864e-14 8.35966e-14 -1 0.122416 0.227608 -0.966027 0.163865 0.360197 -0.918372 0.184226 0.350397 -0.918304 0.0600431 0.109357 -0.992187 -1.26513e-13 -2.16008e-13 -1 0.0833217 0.244392 -0.96609 -3.15139e-13 -4.9467e-13 -1 2.95139e-14 1.01976e-13 -1 0.0727811 0.101381 -0.992182 0.0664492 0.105621 -0.992184 0.135743 0.220014 -0.966006 -5.00282e-13 -7.26275e-13 -1 0.340063 0.338272 -0.877456 0.263926 0.294751 -0.918403 0.349467 0.39802 -0.848206 -6.49665e-13 -8.72039e-13 -1 0.0592009 0.250985 -0.966179 0.0848261 0.0914618 -0.992189 0.174085 0.190888 -0.966052 0.0914896 0.0869734 -0.992001 -7.47123e-13 -9.31043e-13 -1 0.0789364 0.0966455 -0.992184 -7.54823e-13 -8.73889e-13 -1 0.0479863 0.253208 -0.966221 0.489213 0.580816 -0.650633 0.511096 0.530457 -0.676311 0.463518 0.474573 -0.748286 5.64637e-13 -7.24417e-13 -1 0.264857 0.259571 -0.928695 0.181088 0.174797 -0.967808 0.0704599 0.38792 -0.918996 7.29349e-13 -8.9666e-13 -1 -4.04382e-13 -4.07439e-13 -1 -6.51153e-13 -7.0109e-13 -1 6.09037e-15 5.70358e-15 -1 0.0373822 0.254823 -0.966265 0.0392271 0.3916 -0.919299 0.0543498 0.390149 -0.919146 0.0486257 0.524074 -0.850283 0.0686666 0.522395 -0.849935 0.00940064 0.256889 -0.966395 0.0180886 0.256579 -0.966354 0.0274141 0.255917 -0.96631 0.0250971 0.392409 -0.919448 0.0119485 0.392699 -0.919589 0.0125355 0.525101 -0.850947 0.029922 0.524923 -0.850624 0.0586422 0.839157 -0.540719 0.089636 0.837121 -0.539624 0.0863413 0.750541 -0.655159 0.0550036 0.6463 -0.761098 0.0322113 0.64713 -0.761699 0.011042 0.647162 -0.762273 0.122783 0.833616 -0.538524 0.116404 0.747254 -0.654264 0.00768171 0.753192 -0.657756 0.0320076 0.753278 -0.656923 0.0582141 0.752467 -0.656052 0.0297786 0.839989 -0.541786 -0.00224109 0.90632 -0.422586 0.0263212 0.906438 -0.421517 0.00299604 0.839852 -0.542808 0.0571083 0.905539 -0.420401 0.124781 0.990439 0.0588219 0.124781 0.990439 -0.0588219 0.0866077 0.99449 0.0590683 -0.17323 0.983072 -0.0596735 -0.240995 0.968824 -0.0574614 -0.240995 0.968824 0.0574614 0.0225872 0.953683 -0.299964 0.0546597 0.952691 -0.298984 -0.00716601 0.953628 -0.300903 0.0891135 0.950404 0.297978 0.125376 0.976171 0.177117 0.0876137 0.980157 0.177811 0.0876137 0.980157 -0.177811 0.0509454 0.996939 -0.0593125 0.0866077 0.99449 -0.0590683 0.0863413 0.750541 0.655159 0.0582141 0.752467 0.656052 0.0550036 0.6463 0.761098 0.0546597 0.952691 0.298984 0.0571083 0.905539 0.420401 0.148332 0.742374 0.65336 0.133257 0.63701 0.75925 0.182062 0.735673 0.65241 0.105553 0.641452 0.759867 0.116404 0.747254 0.654264 0.112708 0.515831 0.849244 0.162499 0.630971 0.758597 0.0392271 0.3916 0.919299 0.0274142 0.255917 0.96631 0.0543498 0.390149 0.919146 -6.04984e-13 7.75274e-13 1 -0.0153093 -0.122218 0.992385 -0.0201665 -0.121489 0.992388 0.105485 0.38064 0.918687 0.0875196 0.384783 0.918849 0.0592009 0.250985 0.966179 0.0709951 0.248093 0.966131 0.124305 0.375257 0.918548 -5.51183e-14 -1.82398e-13 1 0.0411892 0.117716 0.992193 0.0352235 0.119592 0.992198 -1.52866e-13 -4.29159e-13 1 -0.0364173 -0.117566 0.992397 -0.04232 -0.115554 0.992399 0.0833217 0.244392 0.96609 -0.143896 -0.714773 0.684393 -0.11907 -0.613334 0.780797 -0.11421 -0.720646 0.683832 -0.0307359 -0.119199 0.992395 -0.0534258 -0.246065 0.96778 -0.0645573 -0.243253 0.967812 -0.136546 -0.355503 0.924647 -0.155346 -0.347476 0.924731 -0.1007 -0.230325 0.96789 -0.048398 -0.113114 0.992403 -2.40881e-13 -5.74702e-13 1 -0.232935 -0.577678 0.782323 -0.263704 -0.563872 0.782629 -0.210381 -0.460052 0.862608 -0.0882834 -0.235469 0.967864 -0.18539 -0.471012 0.862426 -0.162832 -0.929807 0.330067 -0.125915 -0.935743 0.329439 -0.133636 -0.970774 0.199346 -0.29491 -0.547786 0.782917 -0.235761 -0.447239 0.862782 -0.243005 -0.911694 0.331304 -0.255598 -0.945738 0.200622 -0.286058 -0.898883 0.331934 -0.349722 -0.63655 0.687385 -0.313309 -0.655655 0.686989 -0.357436 -0.733257 0.578424 -0.398309 -0.7115 0.578893 -0.394614 -0.795563 0.459738 -0.439117 -0.771606 0.460218 -0.589966 -0.781553 0.202768 -0.602807 -0.794989 0.0679375 -0.636378 -0.744268 0.202702 -0.483681 -0.744231 0.460622 -0.43928 -0.68663 0.579286 -0.262049 -0.962714 -0.0671752 -0.218386 -0.973558 -0.0670258 -0.212793 -0.956367 -0.200201 -0.518176 -0.787233 0.334301 -0.470894 -0.816539 0.33395 0.136606 0.510637 0.848875 -0.541765 -0.815731 0.202668 -0.564652 -0.754529 0.334446 -0.133115 -0.807529 -0.57461 -0.166629 -0.800796 -0.575291 -0.186262 -0.870013 -0.45649 -0.553744 -0.829914 0.0679017 -0.143896 -0.714773 -0.684393 -0.175177 -0.707215 -0.684952 -0.201919 -0.792143 -0.575967 -0.553744 -0.829914 -0.0679017 -0.173688 -0.59911 -0.781601 -0.207978 -0.697705 -0.685531 -0.145722 -0.607047 -0.78119 0.158004 0.828389 0.537408 0.122783 0.833616 0.538524 -0.602807 -0.794989 -0.0679375 -0.649999 -0.756895 0.0679141 -0.636378 -0.744268 -0.202702 -0.589966 -0.781553 -0.202768 -0.564652 -0.754529 -0.334445 -0.202859 -0.589351 -0.781993 -0.232935 -0.577678 -0.782323 -0.277359 -0.672091 -0.68656 -0.349722 -0.63655 -0.687385 -0.263704 -0.563871 -0.78263 -0.29491 -0.547785 -0.782917 -0.649999 -0.756895 -0.0679141 -0.570021 -0.68034 -0.460667 -0.479716 -0.658882 -0.579437 -0.518955 -0.62855 -0.579319 -0.527567 -0.713689 -0.460784 -0.609491 -0.718841 -0.334346 -0.0882834 -0.235469 -0.967864 -0.155346 -0.347476 -0.924731 -0.136546 -0.355502 -0.924648 -0.113345 -0.224251 -0.967918 -0.193729 -0.327199 -0.924883 -0.174465 -0.338051 -0.924815 -0.267397 -0.270711 -0.924778 -0.163513 -0.190793 -0.967916 -0.175109 -0.180268 -0.967905 -0.523618 -0.503558 -0.687207 -0.44488 -0.435115 -0.782788 -0.535841 -0.45718 -0.709832 -0.138842 -0.209316 -0.967941 -0.067124 -0.103045 -0.992409 -0.151371 -0.2005 -0.967929 -0.358463 -0.356714 -0.862705 -0.34397 -0.304319 -0.888299 -0.0850056 -0.0889181 -0.992405 -0.073296 -0.0987771 -0.992407 -0.0792833 -0.0940547 -0.992405 -0.0915096 -0.0844414 -0.992218 0.125986 0.946541 0.296965 0.0901767 0.903378 0.419256 -0.415196 -0.362648 -0.834325 0.125558 0.89968 0.418104 0.16316 0.894174 0.416932 0.0509454 0.996939 0.0593125 0.0177503 0.998067 0.0595504 0.0523329 0.982548 -0.178498 0.0177503 0.998067 -0.0595504 0.0194923 0.983625 -0.179168 -0.0109733 0.98364 -0.179811 -0.0130447 0.998126 -0.0597787 -0.0415191 0.997335 -0.059995 -0.0130447 0.998126 0.0597787 -0.0415191 0.997335 0.059995 -0.0600216 0.951218 0.302624 -0.0391425 0.982811 0.18042 -0.0650977 0.981328 0.18099 -0.0719856 0.747321 0.660553 -0.0655336 0.835546 0.545498 -0.0846612 0.833321 0.546267 -0.0753102 0.90186 0.425414 -0.0529814 0.903858 0.424539 -0.0957011 0.89954 0.426227 -0.0721357 0.640491 0.764571 -0.0877708 0.745114 0.661137 -0.0583674 0.642362 0.764175 -0.0559133 0.520189 0.852219 0.161647 -0.331847 0.92938 0.130121 -0.346597 0.928945 0.0912875 -0.228652 0.969219 -0.0508536 0.389748 0.919516 -0.0714959 0.520627 0.850786 -0.0545946 0.749337 0.659934 -0.0316555 0.25519 0.966372 -0.039945 0.389587 0.920123 -1.38001e-12 8.57838e-13 1 -0.0254192 0.122352 0.992161 -1.28828e-12 6.93724e-13 1 0.0222725 -0.120421 0.992473 0.0292416 -0.11867 0.992503 -0.0419939 0.254861 0.966065 -0.0191613 0.123166 0.992201 0.0559167 -0.24205 0.968651 0.042573 -0.245875 0.968366 0.120571 -0.0331866 -0.99215 0.241422 -0.075952 -0.967443 0.238144 -0.0662223 -0.96897 0.162812 -0.462513 0.871535 0.126557 -0.47669 0.869914 0.102106 -0.357897 0.928162 0.0788463 -0.366324 0.927141 0.239806 -0.551683 0.798836 0.333995 -0.620753 0.709305 0.268001 -0.651985 0.709289 0.188876 -0.573146 0.797389 0.14513 -0.589315 0.794761 0.208436 -0.675451 0.707333 0.902599 -0.425251 0.0669023 0.92591 -0.371905 -0.0661536 0.902599 -0.425251 -0.0669023 0.171613 -0.920407 0.351283 0.125085 -0.871531 0.474118 0.170083 -0.860537 0.480155 0.615726 -0.78465 -0.0721468 0.70071 -0.709891 -0.0711304 0.689008 -0.693124 -0.21177 0.23891 -0.946549 0.216717 0.171802 -0.961556 0.21423 0.404277 -0.842101 0.356966 0.496683 -0.79186 0.355336 0.511846 -0.831224 0.21698 0.732426 -0.588266 -0.342775 0.758914 -0.616928 -0.208446 0.605962 -0.765989 0.21464 0.615726 -0.78465 0.0721468 0.70071 -0.709891 0.0711304 0.519334 -0.85145 0.0729752 0.630316 -0.613313 -0.475971 0.583258 -0.55381 -0.594226 0.556698 -0.677401 -0.480849 0.643316 -0.337372 -0.687259 0.719215 -0.384439 -0.578737 0.6664 -0.296874 -0.683942 0.684527 -0.437028 -0.583463 0.742102 -0.48283 -0.46493 0.612882 -0.382894 -0.691207 0.478157 -0.177228 -0.860207 0.466764 -0.200464 -0.861363 0.572751 -0.250603 -0.780483 0.553472 -0.28433 -0.782831 0.486755 -0.157323 -0.859255 0.366108 -0.116721 -0.923223 0.360018 -0.131322 -0.923657 0.117889 -0.03662 -0.992351 0.161783 0.201591 -0.966016 0.425793 0.495038 -0.757389 0.148938 0.211334 -0.966 0.269485 0.456698 -0.847823 0.225066 0.325881 -0.91823 0.204723 0.339002 -0.918241 0.214623 0.484376 -0.848126 0.241932 0.471629 -0.847959 0.187788 0.495082 -0.84831 0.161701 0.50379 -0.848557 0.105485 0.38064 -0.918687 0.136606 0.510637 -0.848875 0.0875196 0.384783 -0.918848 0.00133806 0.256919 -0.966432 -0.0129774 0.256371 -0.966491 -0.0192633 0.255885 -0.966515 -0.0313282 0.390587 -0.920033 -0.00611551 0.25673 -0.966464 -0.0419939 0.254861 -0.966065 -0.0559536 0.25362 -0.965684 -0.754973 0.422823 -0.501235 -0.733876 0.473722 -0.48684 -0.651561 0.447085 -0.612849 -0.165056 0.208576 -0.963978 -0.716999 0.224827 -0.659822 -0.712023 0.250584 -0.65592 -0.610257 0.220112 -0.76101 -0.184813 0.190215 -0.96419 -0.200982 0.17098 -0.964558 -0.213727 0.152089 -0.964982 -0.223376 0.134507 -0.965407 -0.334157 0.228297 -0.91445 -0.316998 0.257366 -0.912839 -0.240146 0.0926443 -0.966306 -0.243161 0.0822816 -0.96649 -0.368198 0.139116 -0.919281 -0.245479 0.0734444 -0.966616 -0.240811 0.0642236 -0.968445 0.573063 0.707601 -0.413399 0.60559 0.651364 -0.457149 0.581028 0.618164 -0.529415 0.244903 0.311075 -0.918289 0.326211 0.56656 -0.756701 0.296906 0.439382 -0.847815 0.225357 0.6126 -0.757585 0.258419 0.599841 -0.757239 0.162499 0.630971 -0.758597 0.112708 0.515831 -0.849244 0.090044 0.519704 -0.849588 -0.000240722 0.392578 -0.919719 -0.011498 0.392137 -0.919835 -0.507378 0.719035 -0.474928 -0.438291 0.666187 -0.603404 -0.590137 0.659278 -0.46593 -0.039945 0.389587 -0.920123 -0.0508536 0.389749 -0.919516 -0.0681542 0.389878 -0.918341 -0.423917 0.547682 -0.721345 -0.575387 0.560205 -0.595903 -0.513665 0.616945 -0.596261 -0.0912155 0.388483 -0.91693 -0.621 0.501831 -0.6021 -0.478824 0.500742 -0.7211 -0.520991 0.450263 -0.725143 -0.571419 0.355321 -0.739748 -0.672688 0.397142 -0.624315 -0.550508 0.401071 -0.732177 -0.265562 0.316753 -0.910573 -0.222295 0.50287 -0.835288 -0.294466 0.28748 -0.911397 -0.346706 0.201661 -0.916039 -0.436258 0.336301 -0.834614 -0.45606 0.297841 -0.83863 -0.356093 0.177894 -0.917361 -0.372058 0.123724 -0.919927 -0.353065 0.0931716 -0.930948 -0.375057 0.110588 -0.920382 0.406781 0.41063 -0.816034 0.323712 0.419748 -0.847952 0.549848 0.578037 -0.602943 0.538127 0.652086 -0.534044 0.37219 0.66292 -0.649624 0.360253 0.545546 -0.756702 0.332427 0.683419 -0.649947 0.292122 0.584569 -0.756931 0.293221 0.700707 -0.650408 0.254827 0.71509 -0.65093 0.193283 0.622919 -0.758033 0.182062 0.735673 -0.65241 0.133257 0.63701 -0.75925 0.148332 0.742374 -0.65336 0.105553 0.641452 -0.759867 -0.00356708 0.524751 -0.851248 -0.0184254 0.523993 -0.851523 -0.0559133 0.520189 -0.852219 -0.0714959 0.520627 -0.850786 -0.0967325 0.521208 -0.84793 -0.0583673 0.642362 -0.764175 -0.0432048 0.644056 -0.763758 -0.12998 0.519503 -0.844525 -0.171988 0.514213 -0.840241 -0.275332 0.482671 -0.831397 -0.327161 0.453614 -0.828975 -0.372707 0.417274 -0.828838 -0.291108 0.614269 -0.733437 -0.409264 0.376883 -0.83094 -0.47001 0.26314 -0.842525 -0.480377 0.232389 -0.845715 -0.498113 0.162563 -0.851737 -0.501526 0.145584 -0.852805 -0.61859 0.176646 -0.765599 -0.456971 0.119332 -0.881441 0.596012 0.747679 -0.292822 0.639191 0.700159 -0.318139 0.624663 0.678468 -0.386623 0.393635 0.521614 -0.756948 0.362111 0.764584 -0.533185 0.318486 0.783368 -0.533762 0.275833 0.798946 -0.534418 0.234618 0.811465 -0.535237 0.0794488 0.64448 -0.760482 -0.0266142 0.645491 -0.763304 -0.0721357 0.640491 -0.76457 -0.0925886 0.640933 -0.761993 -0.126306 0.641379 -0.756756 -0.00854926 0.646567 -0.762809 -0.0545946 0.749337 -0.659934 -0.0719856 0.747321 -0.660553 -0.170227 0.638561 -0.750509 -0.225372 0.630598 -0.742666 -0.359105 0.586481 -0.726005 -0.357184 0.703213 -0.614745 -0.585668 0.314633 -0.746993 -0.596285 0.278671 -0.752852 -0.604228 0.247306 -0.757462 -0.614879 0.196743 -0.763686 -0.549997 0.14216 -0.822979 0.649984 0.717046 -0.251724 0.609472 0.773415 -0.17428 0.657724 0.729673 -0.187019 0.451293 0.61142 -0.65 0.412055 0.638889 -0.64964 0.429916 0.803338 -0.412093 0.45116 0.715923 -0.53283 0.406484 0.742224 -0.532799 0.382042 0.82698 -0.41249 0.335107 0.846789 -0.413101 0.217656 0.726675 -0.65159 0.245085 0.87635 -0.414661 0.289284 0.863184 -0.413798 0.195237 0.821173 -0.536243 0.202933 0.886567 -0.415713 0.158004 0.828389 -0.537408 0.16316 0.894174 -0.416931 -0.0148191 0.752401 -0.658539 -0.0355573 0.751069 -0.659265 -0.0877708 0.745114 -0.661137 -0.112999 0.745059 -0.657357 -0.155178 0.744292 -0.649576 -0.0655336 0.835546 -0.545498 -0.0846612 0.833321 -0.546267 -0.209503 0.739021 -0.640278 -0.277161 0.726652 -0.628617 -0.831411 0.392663 -0.393157 -0.874949 0.398563 -0.274976 -0.816892 0.434972 -0.378798 -0.41607 0.766526 -0.489207 -0.950059 0.30639 -0.0592736 -0.926445 0.333624 -0.17434 -0.935806 0.304046 -0.178389 -0.897764 0.328973 -0.292911 -0.906376 0.298641 -0.298826 -0.686811 0.353299 -0.635194 -0.70566 0.280354 -0.650727 -0.795676 0.273319 -0.540552 -0.788748 0.304238 -0.53415 -0.697496 0.314434 -0.643918 -0.72106 0.202501 -0.662621 -0.70251 0.178084 -0.689032 -0.6319 0.161714 -0.757991 0.495309 0.685775 -0.533275 0.444473 0.846978 -0.291673 0.478316 0.775473 -0.412134 0.344909 0.891879 -0.292558 0.394137 0.871425 -0.292017 0.165517 0.970301 0.176409 -0.02177 0.838951 -0.543771 0.0901767 0.903378 -0.419256 0.125558 0.89968 -0.418104 -0.0445901 0.837466 -0.544668 -0.102018 0.830898 -0.546992 -0.131639 0.829792 -0.542325 -0.181687 0.826614 -0.532634 -0.0957011 0.89954 -0.426227 -0.0753102 0.90186 -0.425414 -0.245427 0.817483 -0.521044 -0.324053 0.799004 -0.50654 -0.958135 0.279884 0.0603528 -0.950059 0.30639 0.0592736 -0.655922 0.594209 -0.465492 -0.464725 0.806231 -0.366089 -0.703123 0.530663 -0.473302 -0.769116 0.378683 -0.51484 -0.795733 0.484358 -0.363602 -0.780108 0.339212 -0.525706 -0.805759 0.222634 -0.548805 -0.871644 0.237261 -0.428886 -0.801202 0.2463 -0.545355 -0.860202 0.288903 -0.420224 -0.762536 0.191573 -0.617931 0.615592 0.785941 -0.0578137 0.665858 0.743532 -0.0615871 0.66289 0.738397 -0.123878 0.526332 0.743462 -0.4126 0.452494 0.874728 -0.173494 0.495544 0.818131 -0.291714 0.349968 0.920441 -0.174098 0.400614 0.899626 -0.173727 0.300626 0.937638 -0.174524 0.296906 0.908787 -0.293176 0.253151 0.951459 -0.175046 0.206647 0.932927 -0.294862 0.207997 0.962224 -0.175678 0.250671 0.922369 -0.293937 -0.0286498 0.905398 -0.423596 0.0891135 0.950404 -0.297978 0.125986 0.946541 -0.296965 -0.0529814 0.903858 -0.424539 -0.114203 0.897015 -0.426992 -0.147594 0.894461 -0.422086 -0.204432 0.888027 -0.411845 -0.104523 0.946883 -0.304116 -0.0832816 0.949218 -0.303397 -0.276065 0.874131 -0.399605 -0.36355 0.848597 -0.384336 -0.563077 0.748149 -0.351023 -0.650168 0.678695 -0.341548 -0.717692 0.607102 -0.341094 -0.501622 0.827828 -0.251149 -0.765159 0.540838 -0.349322 -0.83847 0.484748 -0.248972 -0.859816 0.438062 -0.262331 -0.843056 0.354321 -0.404615 -0.852473 0.31985 -0.413505 -0.866462 0.261529 -0.42526 -0.854512 0.211277 -0.474522 -0.812894 0.202525 -0.546064 0.662887 0.738392 0.12393 0.665851 0.74352 0.0618124 0.615592 0.785941 0.0578137 0.546383 0.784939 -0.292124 0.66682 0.745219 -1.66428e-15 0.455951 0.888143 -0.0575346 0.505272 0.845334 -0.173524 0.165179 0.940819 -0.295932 -0.0346755 0.952743 -0.301792 0.125376 0.976171 -0.177117 -0.0600216 0.951218 -0.302624 -0.123796 0.944339 -0.304793 -0.160157 0.94025 -0.300467 -0.222353 0.930397 -0.291411 -0.39408 0.879387 -0.267167 -0.300046 0.911721 -0.280602 -0.604303 0.760399 -0.237932 -0.864788 0.480957 -0.144301 -0.877219 0.477767 -0.0471749 -0.834787 0.533567 -0.135783 -0.693435 0.682943 -0.229645 -0.761189 0.606658 -0.229253 -0.526246 0.837743 -0.145782 -0.808192 0.539367 -0.236452 -0.915321 0.365561 -0.168972 -0.887436 0.362202 -0.285075 -0.886343 0.436876 -0.153415 -0.913421 0.271469 -0.303259 -0.919256 0.24709 -0.306456 -0.915653 0.22353 -0.334087 -0.888502 0.218188 -0.403682 0.6577 0.729634 0.187253 0.596012 0.747679 0.292822 0.649968 0.71702 0.251839 0.55794 0.811477 -0.173804 0.609472 0.773415 0.17428 0.509556 0.858511 0.0575456 0.455951 0.888143 0.0575345 0.452494 0.874728 0.173494 0.352014 0.934211 0.057749 0.403332 0.913238 0.057617 0.403332 0.913238 -0.057617 0.352014 0.934211 -0.057749 0.302041 0.951535 0.0579006 0.275833 0.798946 0.534418 0.289284 0.863184 0.413798 0.234618 0.811465 0.535237 0.165517 0.970301 -0.176409 -0.0391425 0.982811 -0.18042 -0.0650977 0.981328 -0.18099 -0.0889177 0.979359 -0.181521 -0.110671 0.977048 -0.182015 -0.130409 0.974523 -0.18248 -0.168816 0.969163 -0.179514 -0.234701 0.956496 -0.173297 -0.414781 0.896326 -0.156702 -0.316476 0.933983 -0.165885 -0.631267 0.763408 -0.136785 -0.721102 0.680301 -0.13116 -0.788441 0.601022 -0.130896 -0.538537 0.841251 -0.0476987 -0.902073 0.400002 -0.162059 -0.898903 0.435239 -0.0504048 -0.94027 0.335481 -0.0578348 -0.94351 0.277263 -0.181426 -0.949883 0.252995 -0.183618 -0.952678 0.230515 -0.198161 -0.936867 0.227578 -0.265497 0.573063 0.707601 0.413399 0.624617 0.6784 0.386816 0.639143 0.700086 0.318396 0.563121 0.824362 -0.057645 0.509556 0.858511 -0.0575456 0.302041 0.951535 -0.0579007 0.253985 0.965462 -0.0580861 0.208305 0.976324 -0.0583105 0.165358 0.984493 -0.0585702 -0.0889177 0.979359 0.181521 -0.0832816 0.949218 0.303397 -0.113827 0.991653 0.0605628 -0.110671 0.977048 0.182015 -0.0918363 0.993941 0.0603868 -0.0677565 0.995884 -0.0601978 -0.0918363 0.993941 -0.0603869 -0.113827 0.991653 -0.0605628 -0.133781 0.989148 -0.0607282 -0.425221 0.903619 -0.0515679 -0.324818 0.944186 -0.0548267 -0.644549 0.763266 -0.0445147 -0.734526 0.677246 -0.0425272 -0.801477 0.596518 -0.0424339 -0.538537 0.841251 0.0476987 -0.847384 0.529141 -0.0441613 -0.935806 0.304046 0.178389 -0.926445 0.333624 0.17434 -0.94027 0.335481 0.0578348 -0.914992 0.399912 -0.053472 -0.898903 0.435239 0.0504048 -0.877219 0.477767 0.0471748 -0.928687 0.366624 -0.0559274 -0.958135 0.279884 -0.0603528 -0.970095 0.233663 -0.0657091 -0.964813 0.255733 -0.0611323 -0.96366 0.232511 -0.131518 0.605506 0.651248 0.457426 0.538127 0.652086 0.534044 0.580917 0.618017 0.529708 0.563121 0.824362 0.057645 0.495544 0.818131 0.291714 0.444473 0.846977 0.291673 0.429916 0.803338 0.412093 0.382042 0.82698 0.41249 0.394137 0.871425 0.292017 0.335107 0.846789 0.413101 0.253985 0.965462 0.0580861 0.208305 0.976324 0.0583105 0.165358 0.984493 0.0585702 -0.0677565 0.995884 0.0601978 -0.133781 0.989148 0.0607282 -0.17323 0.983072 0.0596735 -0.425221 0.903619 0.0515679 -0.324818 0.944186 0.0548267 -0.644549 0.763266 0.0445147 -0.734526 0.677246 0.0425272 -0.801477 0.596518 0.0424339 -0.526246 0.837743 0.145782 -0.847384 0.529141 0.0441613 -0.914992 0.399912 0.053472 -0.864788 0.480957 0.144301 -0.886343 0.436876 0.153415 -0.928687 0.366624 0.0559274 -0.949883 0.252995 0.183617 -0.964813 0.255733 0.0611322 -0.963668 0.232513 0.131462 -0.972227 0.234042 -6.48928e-16 0.55794 0.811477 0.173804 0.505272 0.845334 0.173524 0.349968 0.920441 0.174098 0.400614 0.899626 0.173727 0.300626 0.937638 0.174524 0.253151 0.951459 0.175046 0.207997 0.962224 0.175678 0.0523329 0.982548 0.178498 0.0194923 0.983625 0.179168 -0.0109733 0.98364 0.179811 -0.222353 0.930397 0.291411 -0.204432 0.888027 0.411845 -0.160157 0.94025 0.300467 -0.130409 0.974523 0.18248 -0.168816 0.969163 0.179514 -0.234701 0.956496 0.173297 -0.104523 0.946883 0.304116 -0.316476 0.933983 0.165885 -0.414781 0.896326 0.156702 -0.631267 0.763408 0.136785 -0.721102 0.680301 0.13116 -0.788441 0.601022 0.130895 -0.501622 0.827828 0.251149 -0.834787 0.533567 0.135783 -0.902073 0.400002 0.162059 -0.859816 0.438062 0.262331 -0.83847 0.484748 0.248972 -0.915321 0.365561 0.168972 -0.919256 0.24709 0.306455 -0.94351 0.277263 0.181426 -0.906376 0.298641 0.298826 -0.97011 0.233666 0.06547 0.46332 0.474345 0.748553 0.510851 0.530163 0.676727 0.425793 0.495038 0.757389 0.546383 0.784939 0.292124 0.344909 0.891879 0.292557 0.296906 0.908787 0.293176 0.250671 0.922369 0.293937 0.206647 0.932927 0.294862 0.165179 0.940819 0.295932 0.202933 0.886567 0.415713 0.0225872 0.953683 0.299964 -0.007166 0.953628 0.300903 -0.0346755 0.952743 0.301792 -0.147594 0.89446 0.422086 -0.131639 0.829792 0.542325 -0.114203 0.897015 0.426992 -0.123796 0.944339 0.304793 -0.300046 0.911721 0.280602 -0.39408 0.879387 0.267167 -0.604303 0.760399 0.237932 -0.693435 0.682943 0.229645 -0.76119 0.606658 0.229253 -0.808192 0.539367 0.236452 -0.874949 0.398563 0.274976 -0.795733 0.484358 0.363602 -0.816892 0.434972 0.378798 -0.860202 0.288903 0.420224 -0.866462 0.261529 0.42526 -0.887436 0.362202 0.285075 -0.897764 0.328973 0.292912 -0.913421 0.271469 0.303259 -0.936899 0.227584 0.265377 -0.952727 0.230524 0.197916 0.180897 0.174606 0.967879 0.084826 0.0914618 0.992189 0.0914895 0.0869734 0.992001 0.526332 0.743462 0.4126 0.263926 0.294751 0.918403 0.33984 0.338035 0.877634 0.349467 0.39802 0.848206 0.478316 0.775473 0.412134 0.0727811 0.101381 0.992182 0.0664491 0.10562 0.992184 4.02006e-13 6.27837e-13 1 0.245085 0.87635 0.41466 0.00299604 0.839852 0.542808 0.0263212 0.906438 0.421517 -0.00224109 0.90632 0.422586 -0.0286498 0.905398 0.423596 -0.276065 0.874131 0.399605 -0.324053 0.799004 0.50654 -0.245427 0.817483 0.521044 -0.36355 0.848597 0.384336 -0.464725 0.806231 0.366089 -0.563077 0.748149 0.351023 -0.650168 0.678695 0.341548 -0.717692 0.607102 0.341094 -0.765159 0.540838 0.349322 -0.831411 0.392663 0.393157 -0.754973 0.422823 0.501235 -0.733876 0.473722 0.48684 -0.843056 0.354321 0.404615 -0.852473 0.31985 0.413505 -0.795676 0.273319 0.540552 -0.871645 0.237261 0.428886 -0.888586 0.218205 0.403486 -0.915744 0.223548 0.333824 0.549713 0.577868 0.603228 0.489213 0.580816 0.650633 0.495309 0.685775 0.533275 0.406484 0.742224 0.532799 0.45116 0.715923 0.53283 0.318486 0.783368 0.533762 0.362111 0.764584 0.533185 0.214623 0.484376 0.848126 0.143826 0.368475 0.918444 0.163865 0.360197 0.918372 0.195237 0.821173 0.536243 0.217656 0.726675 0.65159 0.089636 0.837121 0.539624 0.0586422 0.839157 0.540719 0.0297786 0.839989 0.541786 -0.02177 0.838951 0.543771 -0.0445901 0.837465 0.544668 -0.0218519 0.391452 0.919939 -0.0192633 0.255885 0.966515 -0.0129774 0.256372 0.966491 -0.126306 0.641379 0.756756 -0.112999 0.745059 0.657357 -0.155178 0.744292 0.649576 -0.102018 0.830898 0.546992 -0.222295 0.50287 0.835288 -0.291108 0.614269 0.733437 -0.275332 0.482671 0.831397 -0.181687 0.826614 0.532634 -0.507378 0.719035 0.474928 -0.513665 0.616945 0.596261 -0.438291 0.666187 0.603404 -0.41607 0.766526 0.489207 -0.590137 0.659278 0.46593 -0.655922 0.594209 0.465492 -0.703123 0.530663 0.473302 -0.769116 0.378683 0.51484 -0.672688 0.397142 0.624315 -0.651561 0.447085 0.612849 -0.780108 0.339212 0.525706 -0.788748 0.304238 0.53415 -0.801202 0.2463 0.545355 -0.712023 0.250584 0.65592 -0.805759 0.222634 0.548805 -0.854658 0.211307 0.474246 -0.813078 0.202565 0.545776 0.451293 0.61142 0.65 0.37219 0.66292 0.649624 0.412055 0.638889 0.64964 0.293221 0.700707 0.650408 0.332427 0.683419 0.649947 0.254827 0.71509 0.65093 0.0320076 0.753278 0.656923 0.00768171 0.753192 0.657756 -0.0148191 0.752401 0.658539 -0.0355573 0.751069 0.659265 -0.0432048 0.644056 0.763758 -0.209503 0.739021 0.640278 -0.277161 0.726652 0.628617 -0.357184 0.703213 0.614745 -0.575387 0.560205 0.595903 -0.621 0.501831 0.6021 -0.686811 0.353299 0.635194 -0.571419 0.355321 0.739748 -0.550508 0.401071 0.732177 -0.70566 0.280354 0.650727 -0.716999 0.224827 0.659822 -0.610257 0.220112 0.76101 -0.697496 0.314434 0.643918 -0.72106 0.202501 0.662621 -0.762749 0.19162 0.617654 0.40633 0.410131 0.81651 0.393635 0.521614 0.756948 0.326211 0.56656 0.756701 0.360253 0.545546 0.756702 0.258419 0.599841 0.757239 0.292122 0.584569 0.756931 0.225357 0.6126 0.757585 0.193283 0.622919 0.758033 0.187788 0.495082 0.84831 0.161701 0.50379 0.848557 0.0794488 0.64448 0.760482 0.0125355 0.525101 0.850947 0.0322113 0.64713 0.761699 0.011042 0.647162 0.762272 -0.00854926 0.646567 0.762809 -0.0266142 0.645491 0.763304 -0.00876875 0.124004 0.992243 -0.00568805 0.124198 0.992241 -0.0925886 0.640933 0.761993 -0.155643 0.376825 0.913114 -0.1205 0.384714 0.915137 -0.171988 0.514213 0.840241 -0.0445673 0.521639 0.852001 -0.0320801 0.522928 0.851773 -0.170227 0.638561 0.750509 -0.225372 0.630598 0.742666 -0.359105 0.586481 0.726005 -0.423917 0.547682 0.721345 -0.478824 0.500742 0.7211 -0.520991 0.450263 0.725143 -0.585668 0.314633 0.746993 -0.604228 0.247306 0.757462 -0.596285 0.278671 0.752852 -0.614879 0.196743 0.763686 -0.493786 0.182408 0.850237 -0.61859 0.176646 0.765599 -0.702882 0.178169 0.688631 -0.632189 0.161783 0.757735 -0.536144 -0.45741 0.709455 -0.479425 -0.41368 0.773964 -0.523618 -0.503558 0.687207 0.323712 0.419748 0.847952 0.269485 0.456698 0.847824 0.296906 0.439382 0.847815 0.241932 0.471629 0.847959 0.090044 0.519704 0.849588 0.0686666 0.522395 0.849935 0.0486257 0.524074 0.850283 0.029922 0.524923 0.850624 -0.00356708 0.524751 0.851248 -0.0184254 0.523993 0.851523 -0.0967325 0.521208 0.84793 -0.0313282 0.390587 0.920033 -0.12998 0.519503 0.844525 -0.184813 0.190215 0.96419 -0.265562 0.316753 0.910573 -0.294466 0.28748 0.911397 -0.327161 0.453614 0.828975 -0.372707 0.417274 0.828838 -0.409264 0.376883 0.83094 -0.436258 0.336301 0.834614 -0.45606 0.297841 0.83863 -0.47001 0.26314 0.842525 -0.488058 0.205581 0.848255 -0.480377 0.23239 0.845715 -0.498113 0.162563 0.851737 -0.501526 0.145585 0.852805 -0.550636 0.142315 0.822525 0.264029 0.258719 0.929168 0.174085 0.190888 0.966052 0.244903 0.311075 0.918289 0.204723 0.339002 0.918241 0.225066 0.325881 0.918231 0.184226 0.350397 0.918304 0.060043 0.109357 0.992187 -2.20545e-13 -4.54374e-13 1 4.48066e-14 8.01051e-14 1 0.0536568 0.112616 0.992189 0.0960806 0.239777 0.966062 0.0473523 0.115401 0.99219 0.0704599 0.38792 0.918996 0.0250971 0.392409 0.919448 0.0119485 0.392699 0.919589 -0.00024072 0.392578 0.919719 -0.011498 0.392137 0.919835 -0.0681542 0.389878 0.918341 -0.0538295 0.114209 0.991997 -0.043095 0.118339 0.992038 -0.095156 0.245821 0.964633 -0.0912155 0.388483 0.91693 0.107418 -0.0594394 0.992436 0.226379 -0.109062 0.967914 0.217831 -0.123446 0.968148 -0.19337 0.362808 0.91158 -0.231133 0.342524 0.910634 -0.316998 0.257366 0.912839 -0.334157 0.228298 0.91445 -0.346705 0.201661 0.916039 -0.36305 0.157101 0.91843 -0.356093 0.177894 0.917361 -0.368198 0.139116 0.919281 -0.372058 0.123724 0.919927 -0.375057 0.110588 0.920382 -0.457279 0.119409 0.881271 0.161783 0.201591 0.966016 0.135742 0.220014 0.966006 0.148938 0.211334 0.966 0.109154 0.234187 0.966044 0.122416 0.227608 0.966027 -0.174465 -0.338051 0.924815 0.0479863 0.253208 0.966221 0.0373822 0.254823 0.966265 0.00525828 0.124295 0.992231 0.0180886 0.256579 0.966354 0.00940064 0.256889 0.966395 0.00133806 0.256919 0.966432 -0.00611551 0.25673 0.966464 -0.0249839 0.2553 0.966539 7.06372e-13 -6.06207e-13 1 1.71862e-12 -1.40369e-12 1 0.00768125 -0.123127 0.992361 2.84979e-17 -2.15782e-15 1 2.60312e-15 -5.61559e-15 1 -0.0559536 0.25362 0.965684 -0.073762 0.250965 0.965182 -0.118533 0.237051 0.964239 -0.142469 0.224526 0.963997 -0.165056 0.208576 0.963978 -0.213727 0.152089 0.964982 -0.223376 0.134507 0.965407 -0.106435 0.0661114 0.992119 -0.200982 0.17098 0.964558 -0.236119 0.104735 0.966063 -0.230676 0.118673 0.965767 -0.240146 0.0926444 0.966306 -0.243161 0.0822817 0.96649 -0.245479 0.0734445 0.966616 -0.35419 0.0934583 0.930492 -0.241067 0.0642904 0.968377 5.09132e-13 5.41635e-13 1 -4.06024e-15 -3.80238e-15 1 0.0789365 0.0966456 0.992184 -0.0545972 -0.110217 0.992407 0.0295033 0.121079 0.992204 0.0240569 0.122238 0.992209 0.0189004 0.123096 0.992215 0.0140464 0.123697 0.992221 0.00949939 0.124084 0.992226 0.00131816 0.124366 0.992236 -0.00232806 0.124325 0.992239 -2.5378e-14 2.17455e-14 1 -0.0115749 0.123757 0.992245 -0.0145945 0.123574 0.992228 -0.0334431 0.120906 0.9921 0.451758 -0.22716 0.862736 0.341366 -0.167987 0.924797 0.466764 -0.200464 0.861363 -0.0650526 0.108439 0.991972 -0.0759686 0.101125 0.991969 -0.085855 0.0926356 0.991992 -0.0942764 0.0836133 0.992029 -0.101109 0.0746117 0.992074 6.02803e-15 -3.10168e-15 1 1.89725e-15 -2.91262e-15 1 -0.113582 0.0515242 0.992192 -0.110515 0.0583783 0.992158 -0.11586 0.045553 0.99222 -0.117569 0.0404226 0.992242 -0.118874 0.0360454 0.992255 -0.117391 0.0316549 0.992581 -0.0850056 -0.0889181 0.992405 -0.0885433 -0.0817433 0.992712 6.9732e-13 8.40681e-13 1 -0.267397 -0.270711 0.924778 -0.358463 -0.356714 0.862705 -0.344204 -0.304514 0.888141 6.4111e-13 8.80156e-13 1 -0.138842 -0.209316 0.967941 -0.073296 -0.0987771 0.992407 -0.067124 -0.103045 0.992409 -0.126105 -0.217233 0.96794 -0.0608606 -0.106856 0.99241 -0.113346 -0.224251 0.967918 -2.73516e-15 -1.26206e-14 1 -2.95236e-13 4.10567e-13 1 -8.08504e-13 9.57113e-13 1 -8.7814e-13 9.69729e-13 1 -7.88593e-13 8.14269e-13 1 -5.13261e-13 4.97624e-13 1 3.05596e-12 -2.38409e-12 1 2.12705e-12 -1.58203e-12 1 -1.59916e-13 1.09525e-13 1 0.0169137 -0.121635 0.992431 0.112419 -0.218411 0.96936 0.0473978 -0.112043 0.992572 0.0721628 -0.236431 0.968965 2.06658e-15 -3.62423e-15 1 4.5173e-15 -3.66468e-15 1 0.037675 -0.115961 0.992539 3.6955e-15 -4.15792e-15 1 3.63058e-15 -2.21618e-15 1 0.0960616 -0.0755023 0.992508 0.0882311 -0.0841098 0.992543 3.60109e-15 -3.07792e-15 1 3.97948e-15 -1.67404e-15 1 6.24038e-15 -2.68187e-15 1 5.2508e-15 -1.83158e-15 1 -1.5611e-07 4.7916e-08 1 5.36713e-15 -1.46205e-15 1 -0.175109 -0.180268 0.967905 -0.1814 -0.164963 0.969475 -0.0792833 -0.0940547 0.992405 -0.193729 -0.327199 0.924884 -0.0253131 -0.120498 0.992391 -0.023457 -0.251034 0.967694 -0.0107485 -0.122726 0.992382 -0.0146631 -0.251815 0.967664 -0.006485 -0.12305 0.992379 -0.00251591 -0.123226 0.992375 0.00116411 -0.123281 0.992371 0.00456128 -0.123241 0.992366 0.0105277 -0.122952 0.992357 0.0131472 -0.122513 0.99238 0.401562 -0.581297 0.707702 0.295595 -0.523899 0.798845 0.352267 -0.48954 0.797658 0.0579448 -0.1068 0.992591 0.0687089 -0.100229 0.992589 0.0789737 -0.0925095 0.992575 0.102432 -0.0671661 0.99247 0.175673 -0.173718 0.969 0.192671 -0.156367 0.968725 0.111228 -0.0524983 0.992407 0.114089 -0.0463983 0.992386 0.232832 -0.0963691 0.96773 0.117889 -0.03662 0.992351 0.120571 -0.0331865 0.99215 0.116248 -0.041127 0.992368 -0.266323 -0.238797 0.933835 -0.163513 -0.190793 0.967916 -0.444879 -0.435115 0.782788 -0.151371 -0.2005 0.967929 -0.286688 -0.416052 0.862967 -0.231764 -0.301505 0.924868 -0.212923 -0.315006 0.924897 -0.261299 -0.432528 0.862926 -0.0762052 -0.239746 0.96784 -0.0475981 -0.624458 0.779607 -0.0699651 -0.621847 0.780007 -0.0536103 -0.505626 0.861085 -0.0428488 -0.248239 0.967751 -0.0328537 -0.249867 0.967723 -0.000270866 -0.383034 0.923734 -0.0119164 -0.382584 0.923844 -0.00646806 -0.25228 0.967633 0.00113732 -0.25249 0.967599 0.00816419 -0.252495 0.967564 0.0146229 -0.252336 0.967529 0.0205198 -0.252046 0.967498 0.0254901 -0.25091 0.967675 0.032427 -0.248696 0.968039 0.516869 -0.611582 0.59901 0.466789 -0.534803 0.704339 0.583258 -0.553811 0.594225 0.134448 -0.205601 0.969357 0.683832 -0.261593 0.681133 0.6664 -0.296874 0.683942 0.572751 -0.250603 0.780483 0.155898 -0.190433 0.969243 0.206728 -0.139354 0.968423 0.286601 -0.240346 0.927412 0.259486 -0.266395 0.928278 0.237718 -0.0853683 0.967576 0.35197 -0.148368 0.924177 0.241422 -0.075952 0.967443 0.237893 -0.0661512 0.969036 -0.649065 -0.605899 0.460001 -0.665557 -0.551915 0.502418 -0.628735 -0.525828 0.572885 -0.249998 -0.286704 0.924825 -0.357366 -0.508757 0.783234 -0.31155 -0.397892 0.862913 -0.118228 -0.362221 0.924564 -0.100528 -0.367778 0.924464 -0.0835934 -0.372263 0.924355 -0.0674837 -0.375767 0.924254 -0.0522412 -0.378432 0.924154 -0.0378945 -0.380381 0.924053 -0.0244539 -0.381731 0.92395 0.0104974 -0.383157 0.923624 0.0204021 -0.383019 0.923515 0.0452634 -0.506669 0.860952 0.0368578 -0.509479 0.859693 0.0294515 -0.38267 0.923416 0.0363802 -0.380679 0.923991 0.0457288 -0.37688 0.925132 0.0599109 -0.372287 0.926182 0.4547 -0.407016 0.792204 0.524548 -0.484218 0.700273 0.406659 -0.449802 0.795177 0.195144 -0.313331 0.929378 0.228337 -0.291169 0.929022 0.30931 -0.214503 0.926453 0.337133 -0.35938 0.870165 0.374786 -0.324816 0.868349 0.327377 -0.19014 0.925565 0.360018 -0.131322 0.923657 0.347077 -0.0974649 0.932758 0.366108 -0.116721 0.923223 -0.41569 -0.363046 0.833906 -0.335569 -0.378068 0.86282 -0.585676 -0.494492 0.642231 -0.592274 -0.56066 0.578681 -0.422418 -0.590293 0.687835 -0.387736 -0.486139 0.783154 -0.386265 -0.614692 0.687716 -0.326266 -0.529355 0.783156 -0.160999 -0.480239 0.862235 -0.137386 -0.487919 0.862009 -0.114769 -0.494148 0.861769 -0.0932327 -0.499055 0.861541 -0.0728321 -0.502826 0.861314 -0.0355853 -0.507607 0.860854 -0.0187571 -0.508906 0.860618 -0.00311447 -0.509646 0.860379 0.0113593 -0.509932 0.86014 0.0246803 -0.509853 0.859908 0.0561798 -0.501402 0.863389 0.0735427 -0.495235 0.865641 0.0971794 -0.487436 0.867734 0.204335 -0.443971 0.872432 0.249189 -0.420434 0.872433 0.294267 -0.391852 0.871699 0.406595 -0.29014 0.866314 0.432014 -0.257225 0.864407 0.478157 -0.177228 0.860207 0.486755 -0.157323 0.859255 0.598347 -0.196069 0.776877 0.447528 -0.126871 0.885225 -0.692713 -0.639337 0.333761 -0.722325 -0.590758 0.359517 -0.69664 -0.573397 0.431171 -0.417016 -0.461538 0.782995 -0.202859 -0.589352 0.781993 -0.173688 -0.59911 0.781601 -0.145722 -0.607047 0.78119 -0.0937982 -0.618201 0.780403 -0.0124107 -0.731667 0.68155 -0.0352924 -0.730386 0.682123 -0.0267021 -0.626204 0.779202 -0.00726674 -0.627236 0.778796 0.0107252 -0.627686 0.778393 0.0272911 -0.627668 0.778003 0.0424408 -0.627273 0.777642 0.0518081 -0.623905 0.779781 0.0634578 -0.617687 0.783859 0.0831299 -0.610519 0.787627 0.110553 -0.601549 0.791149 0.289374 -0.741951 0.60479 0.364541 -0.708034 0.604812 0.158029 -0.692633 0.703765 0.495476 -0.363648 0.788837 0.528111 -0.322258 0.785652 0.553473 -0.28433 0.782831 0.587364 -0.221222 0.778502 0.537269 -0.153691 0.829289 -0.74291 -0.604406 0.287712 -0.722315 -0.661313 0.2023 -0.758686 -0.614701 0.215727 -0.491465 -0.534599 0.687507 -0.457615 -0.563573 0.687731 -0.527567 -0.713688 0.460784 -0.518955 -0.62855 0.57932 -0.479716 -0.658882 0.579437 -0.27736 -0.672092 0.68656 -0.242169 -0.686028 0.68609 -0.207978 -0.697705 0.685531 -0.175177 -0.707215 0.684952 -0.0519842 -0.889673 0.45363 -0.0824224 -0.887003 0.454349 -0.071739 -0.816246 0.573234 -0.0861931 -0.725064 0.683266 -0.0598839 -0.728245 0.682696 0.00877834 -0.732245 0.680984 0.0481555 -0.820291 0.569916 0.0279659 -0.820806 0.570522 0.0282928 -0.732258 0.680439 0.0461427 -0.73182 0.679934 0.0559851 -0.728317 0.68295 0.0676358 -0.721949 0.688633 0.0888116 -0.714599 0.693874 0.119149 -0.705339 0.698785 0.692642 -0.546829 0.470346 0.732426 -0.588266 0.342775 0.630316 -0.613313 0.475971 0.165981 -0.783868 0.598332 0.855865 -0.47598 0.20233 0.887072 -0.416128 0.199854 0.825646 -0.454844 0.333806 0.855845 -0.398131 0.330183 0.573638 -0.432476 0.695632 0.643316 -0.337372 0.687259 0.745419 -0.337673 0.574741 0.719215 -0.384439 0.578737 0.612882 -0.382894 0.691207 0.696864 -0.231433 0.678837 0.685049 -0.199215 0.700729 0.616429 -0.177843 0.767064 -0.556596 -0.595737 0.57905 -0.570021 -0.680339 0.460667 -0.317037 -0.752003 0.57791 -0.277439 -0.767923 0.577341 -0.238905 -0.78127 0.576664 -0.201919 -0.792143 0.575967 -0.166629 -0.800796 0.575291 -0.133115 -0.807529 0.574611 -0.10147 -0.812598 0.573924 -0.04394 -0.818698 0.572541 -0.0180674 -0.820158 0.571852 0.0058951 -0.820808 0.571174 0.0580717 -0.817113 0.573546 0.0691695 -0.811438 0.580331 0.0911738 -0.804745 0.586577 0.123646 -0.796072 0.592436 0.304734 -0.818688 0.48671 0.231004 -0.843799 0.484397 0.222141 -0.766575 0.602508 0.441924 -0.6642 0.602943 0.639614 -0.494255 0.588732 0.556698 -0.677401 0.480848 0.684527 -0.437028 0.583463 0.779717 -0.262217 0.568581 0.845709 -0.28758 0.449527 0.765099 -0.296957 0.57135 0.808671 -0.371744 0.455915 0.743875 -0.217911 0.631795 -0.73727 -0.672191 0.0677712 -0.776427 -0.626102 0.0718142 -0.769799 -0.621864 0.143856 -0.610643 -0.644327 0.460388 -0.609491 -0.718841 0.334346 -0.350582 -0.816223 0.459208 -0.307375 -0.833781 0.458617 -0.265272 -0.848497 0.457913 -0.224848 -0.860476 0.457192 -0.186262 -0.870013 0.45649 -0.149601 -0.87743 0.455781 -0.114969 -0.883004 0.455067 -0.0236519 -0.891239 0.452916 -0.000564276 -0.945043 0.326945 -0.0285465 -0.944401 0.327556 0.00258993 -0.891905 0.452216 0.0267599 -0.891848 0.451544 0.0488689 -0.891226 0.450918 0.0585845 -0.888728 0.454677 0.0688046 -0.884382 0.461664 0.0911356 -0.87897 0.468089 0.870919 -0.486729 -0.0677817 0.887072 -0.416128 -0.199854 0.855865 -0.47598 -0.20233 0.387741 -0.782781 0.486734 0.473512 -0.735333 0.484842 0.58634 -0.729645 0.351886 0.665563 -0.660422 0.347661 0.742102 -0.48283 0.46493 0.780107 -0.424008 0.460055 0.829986 -0.326285 0.452396 0.835457 -0.247849 0.490492 0.793749 -0.234077 0.5614 -0.769791 -0.621859 -0.143917 -0.776411 -0.626091 -0.0720757 -0.73727 -0.672191 -0.0677712 -0.652301 -0.680353 0.334102 -0.778619 -0.627497 -1.42528e-15 -0.423638 -0.842191 0.333533 -0.376846 -0.864321 0.33307 -0.330889 -0.883132 0.332552 -0.201901 -0.92189 0.330689 -0.0912145 -0.939981 0.328809 -0.0587584 -0.942786 0.32818 0.0238243 -0.980065 0.197241 0.025207 -0.94491 0.326358 0.0487787 -0.944175 0.325813 0.0581659 -0.942502 0.3291 0.0674333 -0.939734 0.335189 0.0897811 -0.935844 0.340785 0.124682 -0.929899 0.346039 0.236211 -0.904552 0.35495 0.315059 -0.879391 0.356945 0.813957 -0.543464 0.205232 0.785257 -0.518736 0.33806 0.689008 -0.693124 0.21177 0.87824 -0.348855 0.3271 0.894654 -0.30698 0.324589 0.897821 -0.268949 0.34869 0.869941 -0.259435 0.419399 -0.758637 -0.614669 -0.215991 -0.692713 -0.639337 -0.333761 -0.742878 -0.604385 -0.287838 -0.680615 -0.70409 0.202534 -0.722315 -0.661313 -0.2023 -0.492662 -0.846349 0.202429 -0.443559 -0.873151 0.202145 -0.39491 -0.896276 0.20183 -0.3471 -0.915931 0.201475 -0.300426 -0.932375 0.201052 -0.100744 -0.992683 -0.0665684 -0.0974813 -0.975157 -0.198915 -0.137633 -0.988234 -0.0667217 -0.212793 -0.956367 0.200201 -0.172097 -0.96461 0.199775 -0.0662388 -0.995591 0.0664154 -0.0341196 -0.997219 0.0662641 -0.0341196 -0.997219 -0.0662645 -0.0974813 -0.975157 0.198915 -0.0636624 -0.978034 0.198484 -0.032182 -0.979662 0.198058 -0.003026 -0.98027 0.197641 0.0483808 -0.979235 0.196869 0.0574536 -0.978291 0.199115 0.0659287 -0.976901 0.203266 0.0881656 -0.974343 0.207079 0.123618 -0.969712 0.210661 0.324213 -0.943135 0.0733604 0.3213 -0.921527 0.218069 0.414836 -0.883374 0.218084 0.758914 -0.616928 0.208446 0.870919 -0.486729 0.0677817 0.910098 -0.364168 0.197747 0.926888 -0.320078 0.196032 0.936419 -0.282365 0.208301 0.919846 -0.276568 0.278198 -0.649065 -0.605899 -0.460001 -0.696561 -0.573343 -0.43137 -0.722237 -0.590699 -0.359789 -0.694939 -0.71586 0.0678546 -0.503729 -0.861196 0.0678169 -0.453699 -0.888578 0.0677165 -0.404117 -0.912206 0.0676045 -0.355374 -0.932285 0.0674783 -0.307771 -0.949075 0.067328 -0.262049 -0.962714 0.0671752 -0.218386 -0.973558 0.0670258 -0.176871 -0.981959 0.0668744 -0.137633 -0.988234 0.0667217 -0.100744 -0.992683 0.0665684 -0.00437275 -0.997802 0.0661161 0.0230204 -0.997556 0.0659743 0.0480719 -0.996671 0.0658424 0.0569565 -0.99615 0.0666397 0.0649846 -0.995559 0.0681124 0.0871264 -0.993772 0.0694652 0.122828 -0.989904 0.070736 0.171627 -0.982527 0.0720015 0.240009 -0.968031 0.072882 0.605962 -0.765989 -0.21464 0.519334 -0.85145 -0.0729752 0.419964 -0.90457 0.073366 0.772141 -0.63159 0.0699518 0.828276 -0.556079 0.0688118 0.92591 -0.371905 0.0661536 0.954851 -0.288883 0.0693312 0.942862 -0.326674 0.0655445 0.948019 -0.286458 0.138571 -0.665426 -0.551823 -0.502692 -0.592274 -0.56066 -0.578681 -0.628575 -0.525713 -0.573166 -0.694939 -0.71586 -0.0678546 -0.503729 -0.861196 -0.0678173 -0.453699 -0.888578 -0.0677165 -0.404117 -0.912206 -0.0676045 -0.355374 -0.932285 -0.0674783 -0.307771 -0.949075 -0.067328 -0.176871 -0.981959 -0.0668744 -0.0662388 -0.995591 -0.0664154 -0.00437275 -0.997802 -0.0661161 0.0480719 -0.996671 -0.0658424 0.0483808 -0.979235 -0.196869 0.0230204 -0.997556 -0.0659743 0.0569565 -0.99615 -0.0666397 0.0649846 -0.995559 -0.0681124 0.0871264 -0.993772 -0.0694652 0.122828 -0.989904 -0.070736 0.171627 -0.982527 -0.0720015 0.240009 -0.968031 -0.072882 0.324213 -0.943135 -0.0733604 0.419964 -0.90457 -0.0733656 0.58634 -0.729645 -0.351886 0.772141 -0.63159 -0.0699518 0.828276 -0.556079 -0.0688118 0.926888 -0.320078 -0.196032 0.942862 -0.326674 -0.0655445 0.948027 -0.286461 -0.138512 0.95712 -0.28969 -1.01914e-15 -0.680615 -0.70409 -0.202534 -0.541765 -0.815731 -0.202668 -0.492662 -0.846349 -0.202429 -0.443559 -0.873151 -0.202146 -0.39491 -0.896276 -0.20183 -0.3471 -0.915931 -0.201475 -0.300426 -0.932375 -0.201052 -0.255598 -0.945738 -0.200622 -0.04394 -0.818698 -0.572541 -0.071739 -0.816246 -0.573233 -0.0824224 -0.887003 -0.454348 -0.172097 -0.96461 -0.199775 -0.133636 -0.970774 -0.199346 -0.032182 -0.979662 -0.198058 -0.0285465 -0.9444 -0.327556 -0.0636625 -0.978034 -0.198484 -0.003026 -0.98027 -0.197641 0.0238243 -0.980065 -0.197241 0.0574536 -0.978291 -0.199115 0.0659287 -0.976901 -0.203266 0.0881656 -0.974343 -0.207079 0.123618 -0.969712 -0.210661 0.171802 -0.961556 -0.21423 0.23891 -0.946549 -0.216717 0.414836 -0.883375 -0.218084 0.404277 -0.842102 -0.356966 0.3213 -0.921527 -0.218069 0.511846 -0.831224 -0.21698 0.692642 -0.546829 -0.470346 0.665563 -0.660422 -0.347661 0.813957 -0.543464 -0.205232 0.894654 -0.30698 -0.324589 0.910098 -0.364168 -0.197747 0.855845 -0.398131 -0.330183 0.954867 -0.288888 -0.0690787 -0.479196 -0.413501 -0.774202 -0.652301 -0.680353 -0.334102 -0.518176 -0.787233 -0.334301 -0.470894 -0.816539 -0.33395 -0.423638 -0.842191 -0.333533 -0.376846 -0.864321 -0.333071 -0.330889 -0.883132 -0.332552 -0.286058 -0.898883 -0.331934 -0.243005 -0.911694 -0.331304 -0.201901 -0.92189 -0.330689 -0.162832 -0.929807 -0.330067 -0.125915 -0.935743 -0.329439 -0.0912145 -0.939981 -0.328809 -0.0587584 -0.942786 -0.32818 0.025207 -0.94491 -0.326358 0.0267599 -0.891847 -0.451544 -0.000564268 -0.945043 -0.326945 0.0487787 -0.944175 -0.325813 0.0581659 -0.942502 -0.3291 0.0674333 -0.939734 -0.335189 0.0897811 -0.935844 -0.340785 0.124682 -0.929899 -0.346039 0.171613 -0.920407 -0.351283 0.236211 -0.904552 -0.35495 0.315059 -0.879391 -0.356945 0.496683 -0.79186 -0.355336 0.808671 -0.371744 -0.455915 0.829986 -0.326285 -0.452396 0.785257 -0.518736 -0.33806 0.825646 -0.454844 -0.333806 0.87824 -0.348855 -0.3271 0.91988 -0.27658 -0.278073 0.936471 -0.282383 -0.208045 -0.610643 -0.644327 -0.460388 -0.483681 -0.744231 -0.460622 -0.439117 -0.771605 -0.460219 -0.394614 -0.795563 -0.459739 -0.350582 -0.816223 -0.459208 -0.307375 -0.833781 -0.458617 -0.265272 -0.848497 -0.457913 -0.224848 -0.860476 -0.457192 -0.149601 -0.87743 -0.455781 -0.114969 -0.883004 -0.455067 -0.0519842 -0.889673 -0.45363 -0.0236519 -0.891239 -0.452916 0.00258994 -0.891904 -0.452217 0.0488689 -0.891226 -0.450919 0.0580717 -0.817112 -0.573546 0.0481555 -0.820291 -0.569916 0.0585845 -0.888728 -0.454677 0.0688046 -0.884382 -0.461664 0.0911356 -0.87897 -0.468089 0.125085 -0.871531 -0.474118 0.170083 -0.860537 -0.480154 0.231004 -0.843799 -0.484397 0.304734 -0.818688 -0.48671 0.387741 -0.782782 -0.486734 0.473512 -0.735333 -0.484842 0.237718 -0.0853683 -0.967576 0.232832 -0.0963691 -0.96773 0.35197 -0.148368 -0.924177 0.780107 -0.424008 -0.460055 0.745419 -0.337673 -0.574741 0.845709 -0.28758 -0.449526 0.870028 -0.259465 -0.419201 0.897915 -0.268982 -0.348421 -0.585497 -0.49436 -0.642496 -0.556596 -0.595737 -0.57905 -0.43928 -0.68663 -0.579286 -0.398309 -0.7115 -0.578893 -0.357436 -0.733256 -0.578424 -0.317037 -0.752002 -0.57791 -0.277439 -0.767922 -0.577341 -0.238905 -0.78127 -0.576664 -0.059884 -0.728245 -0.682696 -0.0267021 -0.626204 -0.779202 -0.0475982 -0.624458 -0.779606 -0.10147 -0.812598 -0.573924 0.00877835 -0.732245 -0.680985 -0.0124107 -0.731666 -0.68155 -0.0180674 -0.820158 -0.571852 0.00589511 -0.820808 -0.571174 0.0279659 -0.820806 -0.570522 0.0691695 -0.811438 -0.580331 0.0911738 -0.804745 -0.586577 0.123646 -0.796072 -0.592436 0.165981 -0.783868 -0.598332 0.222141 -0.766575 -0.602508 0.289374 -0.741951 -0.60479 0.401561 -0.581297 -0.707702 0.333995 -0.620753 -0.709305 0.364541 -0.708034 -0.604812 0.441924 -0.6642 -0.602944 0.516869 -0.611582 -0.59901 0.639614 -0.494255 -0.588732 0.765099 -0.296957 -0.57135 0.779717 -0.262217 -0.568581 0.835604 -0.247898 -0.490217 0.793932 -0.234137 -0.561116 -0.422418 -0.590293 -0.687835 -0.457615 -0.563573 -0.687731 -0.491465 -0.534599 -0.687507 -0.386265 -0.614693 -0.687716 -0.313309 -0.655655 -0.686989 -0.242169 -0.686028 -0.68609 -0.0536103 -0.505627 -0.861085 -0.0699651 -0.621848 -0.780007 -0.0355853 -0.507607 -0.860853 -0.11421 -0.720646 -0.683831 -0.0861931 -0.725065 -0.683266 -0.0352925 -0.730386 -0.682122 0.0282928 -0.732258 -0.68044 0.0424408 -0.627273 -0.777642 0.0272911 -0.627668 -0.778003 0.0461427 -0.73182 -0.679934 0.0559851 -0.728317 -0.68295 0.0676358 -0.721948 -0.688633 0.0888116 -0.714599 -0.693874 0.119149 -0.705339 -0.698785 0.158029 -0.692634 -0.703765 0.208436 -0.675451 -0.707333 0.268001 -0.651986 -0.709288 0.466789 -0.534803 -0.704339 0.226379 -0.109062 -0.967914 0.327377 -0.19014 -0.925565 0.341366 -0.167987 -0.924797 0.524548 -0.484218 -0.700273 0.573638 -0.432476 -0.695632 0.683832 -0.261593 -0.681133 0.696864 -0.231433 -0.678836 0.744084 -0.217978 -0.631525 -0.387737 -0.486139 -0.783153 -0.357366 -0.508757 -0.783234 -0.417016 -0.461538 -0.782995 -0.326267 -0.529356 -0.783156 -0.100528 -0.367778 -0.924464 -0.0645573 -0.243253 -0.967812 -0.118228 -0.362221 -0.924564 -0.0674837 -0.375767 -0.924254 -0.0428488 -0.248239 -0.967751 -0.0835934 -0.372263 -0.924355 -0.0522412 -0.378432 -0.924154 -0.0378946 -0.380381 -0.924053 -0.023457 -0.251034 -0.967694 -0.11907 -0.613334 -0.780797 -0.0937982 -0.618201 -0.780403 -0.00726672 -0.627235 -0.778796 0.0113593 -0.509932 -0.86014 -0.00311446 -0.509646 -0.860379 0.0107252 -0.627686 -0.778393 0.0518081 -0.623905 -0.779781 0.0634578 -0.617687 -0.783859 0.0831299 -0.610519 -0.787627 0.110553 -0.601549 -0.791149 0.14513 -0.589315 -0.794761 0.188876 -0.573146 -0.797389 0.204335 -0.443971 -0.872432 0.162813 -0.462514 -0.871535 0.239806 -0.551683 -0.798836 0.295595 -0.5239 -0.798844 0.352267 -0.48954 -0.797659 0.406659 -0.449801 -0.795178 0.4547 -0.407016 -0.792204 0.495476 -0.363648 -0.788837 0.528111 -0.322258 -0.785652 0.587364 -0.221222 -0.778501 0.598348 -0.196069 -0.776876 0.685412 -0.199329 -0.700342 0.61671 -0.177929 -0.766818 -0.286688 -0.416052 -0.862966 -0.311551 -0.397892 -0.862913 -0.33557 -0.378068 -0.862819 -0.261299 -0.432528 -0.862926 -0.235761 -0.447239 -0.862783 -0.210381 -0.460052 -0.862608 -0.185389 -0.471012 -0.862426 -0.160999 -0.480239 -0.862236 -0.137386 -0.487919 -0.862009 -0.114769 -0.494148 -0.861769 -0.0932327 -0.499055 -0.861541 -0.0728321 -0.502826 -0.861314 -0.00027086 -0.383034 -0.923734 0.00113732 -0.25249 -0.967599 -0.0119164 -0.382585 -0.923844 -0.0187571 -0.508906 -0.860618 0.0246803 -0.509853 -0.859908 0.0294515 -0.38267 -0.923416 0.0204021 -0.383019 -0.923515 0.0368578 -0.509478 -0.859694 0.0452634 -0.506669 -0.860952 0.0561798 -0.501402 -0.863389 0.0735426 -0.495234 -0.865641 0.0971794 -0.487436 -0.867734 0.126557 -0.47669 -0.869914 0.249189 -0.420434 -0.872433 0.294267 -0.391852 -0.871699 0.337133 -0.35938 -0.870165 0.374786 -0.324816 -0.868349 0.30931 -0.214503 -0.926453 0.286601 -0.240346 -0.927412 0.406595 -0.29014 -0.866314 0.432014 -0.257225 -0.864407 0.451758 -0.22716 -0.862736 0.537886 -0.153877 -0.828855 -0.265476 -0.238072 -0.934261 -0.212923 -0.315007 -0.924897 -0.231765 -0.301505 -0.924867 -0.249998 -0.286704 -0.924825 -0.0244539 -0.381731 -0.92395 0.0104974 -0.383157 -0.923624 0.0363802 -0.380679 -0.923991 0.0457288 -0.37688 -0.925132 0.032427 -0.248696 -0.968039 0.0599109 -0.372287 -0.926182 0.0788463 -0.366324 -0.927141 0.102106 -0.357897 -0.928162 0.130121 -0.346598 -0.928945 0.161647 -0.331847 -0.92938 0.195144 -0.313331 -0.929378 0.228337 -0.291169 -0.929022 0.259486 -0.266395 -0.928278 0.111228 -0.0524983 -0.992407 0.107418 -0.0594394 -0.992436 0.447826 -0.126959 -0.885061 -0.181208 -0.164794 -0.969539 -0.126105 -0.217233 -0.96794 -0.04232 -0.115554 -0.992399 -0.1007 -0.230324 -0.96789 -0.0307359 -0.119199 -0.992395 -0.0762052 -0.239746 -0.96784 -0.0201665 -0.121489 -0.992388 -0.0534258 -0.246065 -0.96778 -0.0107485 -0.122726 -0.992382 -0.0153093 -0.122218 -0.992385 -0.0328537 -0.249867 -0.967723 -0.00646807 -0.252281 -0.967632 -0.00251592 -0.123226 -0.992375 -0.0146631 -0.251815 -0.967664 0.00816419 -0.252495 -0.967564 0.0205198 -0.252046 -0.967498 0.0105277 -0.122952 -0.992357 0.0146229 -0.252336 -0.967529 0.0254901 -0.25091 -0.967675 0.042573 -0.245875 -0.968366 0.0559167 -0.24205 -0.968651 0.0721628 -0.236431 -0.968965 0.0912875 -0.228652 -0.969219 0.11242 -0.218411 -0.96936 0.134448 -0.205601 -0.969356 0.155898 -0.190433 -0.969243 0.192671 -0.156367 -0.968725 0.0960616 -0.0755023 -0.992508 0.175673 -0.173718 -0.969 0.206728 -0.139354 -0.968423 0.217831 -0.123446 -0.968148 0.116248 -0.041127 -0.992368 0.348168 -0.0977811 -0.932318 -0.048398 -0.113114 -0.992403 -0.0364173 -0.117566 -0.992397 -0.0253131 -0.120498 -0.992391 -0.006485 -0.12305 -0.992379 0.00116411 -0.123281 -0.992371 0.00456128 -0.123241 -0.992366 0.00768125 -0.123127 -0.992361 0.0131472 -0.122513 -0.99238 0.0169137 -0.121635 -0.992431 0.0222725 -0.120421 -0.992473 0.0292416 -0.11867 -0.992503 0.037675 -0.115961 -0.992539 0.0473978 -0.112043 -0.992572 0.0579448 -0.1068 -0.992591 0.0687091 -0.100229 -0.992589 0.0789737 -0.0925095 -0.992575 0.0882311 -0.0841098 -0.992543 0.102432 -0.0671661 -0.99247 0.114089 -0.0463983 -0.992386 - - - - - - - - - - - - - - -

0 2 1 3 5 4 6 8 7 7 9 6 10 12 11 13 15 14 16 18 17 19 21 20 5 23 22 18 24 22 22 25 18 26 22 23 23 5 3 5 22 24 5 24 27 23 3 28 24 18 29 16 17 21 16 29 18 20 21 10 16 21 19 12 13 11 20 10 11 13 30 15 13 14 11 15 7 8 7 15 30 6 32 31 9 32 6 32 1 2 2 31 32 0 34 33 33 2 0 34 36 35 0 36 34 37 35 38 37 34 35 39 38 40 38 35 40 39 41 38 39 43 42 42 41 39 44 42 45 43 45 42 46 45 47 45 46 44 48 49 46 46 47 48 50 51 48 49 48 51 52 54 53 50 55 51 56 57 53 53 59 58 60 61 56 56 62 60 63 64 60 63 60 62 58 65 62 62 66 63 56 53 58 56 58 62 54 52 55 53 54 59 50 67 55 54 55 67 68 70 69 71 73 72 74 76 75 76 74 77 78 80 79 81 83 82 84 86 85 87 89 88 72 91 90 85 91 92 91 85 93 94 90 91 90 71 72 72 92 91 72 95 92 90 96 71 92 97 85 84 88 86 84 85 97 89 78 88 84 87 88 79 80 81 89 80 78 81 82 98 81 80 83 82 75 76 76 98 82 74 100 99 77 74 99 99 69 70 69 99 100 68 102 101 102 68 69 101 104 103 68 101 103 105 106 104 105 104 101 107 108 106 106 108 104 107 106 109 107 111 110 111 107 109 112 113 111 110 111 113 114 115 113 113 112 114 116 114 117 114 116 115 118 116 119 117 119 116 120 122 121 118 119 123 124 122 125 122 127 126 128 124 129 124 128 130 131 128 132 131 130 128 127 130 133 130 131 134 124 127 122 124 130 127 121 123 120 122 126 121 118 123 135 121 135 123 136 138 137 139 141 140 142 144 143 143 144 145 146 148 147 149 151 150 152 154 153 154 152 155 156 153 154 157 156 154 157 159 158 158 156 157 160 159 161 159 160 158 161 163 162 160 161 162 163 165 164 165 163 161 164 165 166 167 164 166 168 167 166 169 171 170 168 173 172 172 167 168 174 176 175 173 177 172 178 177 179 173 179 177 179 180 178 179 181 180 182 183 181 184 186 185 168 188 187 181 183 180 189 190 184 191 182 192 192 190 193 193 191 192 176 174 194 190 195 193 196 195 197 190 197 195 198 196 197 198 199 196 198 200 199 201 203 202 204 206 205 200 205 199 206 208 207 200 204 205 209 211 210 206 204 208 207 213 212 213 207 208 214 212 210 213 210 212 210 216 215 215 214 210 216 218 217 216 219 215 218 220 217 219 216 217 220 222 221 223 221 222 224 225 223 223 222 224 226 228 227 224 227 225 229 228 226 143 231 230 231 143 232 233 230 231 234 235 138 233 141 234 233 234 230 234 141 236 237 239 238 143 145 232 240 237 235 236 240 234 236 241 240 138 242 230 240 241 243 244 145 144 245 247 246 144 150 244 246 243 248 240 243 246 248 245 246 244 150 151 249 251 250 146 149 150 248 252 245 150 144 253 254 256 255 147 149 146 257 258 245 257 259 258 150 260 146 261 263 262 148 264 147 250 266 265 253 267 260 256 266 255 264 148 268 254 270 269 268 148 155 269 256 254 152 268 155 256 269 271 272 274 273 274 276 275 154 278 277 155 279 278 280 281 278 280 279 273 280 283 282 283 273 275 284 286 285 287 288 275 288 289 283 290 285 291 292 288 293 294 293 287 295 297 296 298 293 295 299 297 284 294 284 295 300 302 301 303 305 304 299 307 306 308 297 306 309 311 310 312 314 313 315 317 316 309 319 318 320 322 321 323 324 320 325 321 326 327 329 328 330 332 331 333 335 334 336 333 337 338 340 339 341 343 342 344 340 336 345 347 346 348 350 349 351 353 352 343 355 354 356 358 357 359 354 353 358 360 352 361 363 362 357 365 364 366 368 367 369 370 364 369 372 371 373 372 374 375 377 376 374 379 378 380 382 381 383 384 378 385 334 325 383 387 386 388 390 389 391 386 375 392 394 393 376 395 391 396 398 397 324 400 399 376 402 401 403 405 404 406 408 407 409 411 410 404 401 412 413 415 414 405 417 416 418 420 419 421 423 422 424 426 425 427 429 428 430 432 431 433 434 424 270 259 435 252 248 436 269 270 435 437 259 257 271 269 438 439 440 309 433 428 441 259 437 435 442 443 400 444 445 313 302 300 311 313 447 446 448 307 446 449 306 448 450 451 449 452 453 450 448 447 450 454 456 455 453 452 455 457 459 458 460 461 458 462 460 459 463 464 457 465 466 463 467 469 468 470 471 466 465 457 472 470 474 473 475 477 476 478 479 475 473 481 480 478 483 482 484 486 485 487 489 488 489 482 490 491 493 492 488 495 494 496 493 494 497 499 498 500 502 501 503 505 504 506 500 507 508 510 509 511 512 505 510 514 513 515 514 504 516 503 514 517 519 518 520 522 521 523 521 524 523 525 520 526 528 527 520 529 528 526 531 530 532 485 531 484 533 228 484 485 533 229 484 228 270 258 259 258 270 254 255 266 250 245 252 257 534 258 254 263 261 535 258 534 536 537 539 538 536 247 245 239 541 540 237 246 247 238 540 542 246 237 240 542 543 137 235 234 240 544 136 545 138 230 234 253 142 546 143 230 242 148 272 279 242 142 143 547 157 277 142 253 144 548 550 549 150 253 260 159 551 161 272 146 260 161 548 165 272 148 146 165 549 166 279 155 148 168 166 188 278 154 155 173 168 187 157 154 277 173 552 179 551 159 547 548 170 550 161 551 548 553 176 181 165 548 549 176 194 182 166 549 188 194 184 192 554 556 555 182 191 183 173 187 552 557 197 189 181 179 553 558 560 559 182 181 176 200 198 561 194 192 182 204 200 562 184 190 192 208 204 563 190 189 197 213 208 564 561 198 557 562 566 565 562 200 561 216 211 567 563 204 562 218 567 568 563 564 208 569 567 211 213 209 210 218 222 220 211 216 210 222 570 224 567 218 216 571 226 224 568 570 222 227 224 226 255 534 254 249 250 265 572 574 573 536 245 258 534 255 575 539 247 536 534 575 538 537 577 576 539 536 538 235 238 137 239 247 539 540 579 578 239 237 247 242 544 142 238 235 237 580 545 543 137 138 235 546 544 581 136 242 138 267 546 582 136 544 242 281 583 277 142 544 546 547 584 551 253 546 267 260 267 274 548 551 170 159 157 547 260 274 272 585 587 586 279 272 273 549 588 188 280 278 279 187 188 589 281 277 278 552 187 590 583 584 547 591 593 592 170 551 584 594 175 553 595 597 596 553 179 552 549 550 588 186 194 174 589 188 588 598 600 599 187 589 590 185 601 189 553 552 594 174 175 602 176 553 175 561 557 603 561 566 562 557 198 197 186 184 194 563 562 565 184 185 189 564 563 604 557 601 603 605 606 566 566 561 603 607 202 209 569 211 202 564 209 213 565 604 563 569 608 567 209 564 607 202 203 569 211 209 202 609 570 610 570 571 224 218 568 222 568 608 610 609 571 570 250 575 255 611 251 249 535 251 611 538 536 534 612 575 250 613 614 261 612 577 575 576 616 615 577 537 538 617 619 618 539 537 541 579 619 620 539 541 239 542 578 621 540 238 239 580 621 622 542 137 238 580 624 623 543 136 137 623 291 625 136 543 545 282 626 281 544 545 581 583 627 584 546 581 582 267 582 276 170 584 169 547 277 583 267 276 274 550 170 171 275 273 274 588 550 628 283 280 273 589 588 629 282 281 280 590 589 630 626 627 583 631 169 632 627 169 584 633 634 594 602 175 634 594 552 590 628 550 171 635 174 602 588 628 629 636 186 635 630 589 629 636 637 185 594 590 633 638 602 634 634 175 594 603 601 639 603 605 566 601 557 189 635 186 174 565 566 606 636 185 186 604 565 640 601 637 639 600 598 605 605 603 639 641 201 607 642 644 643 604 607 564 606 640 565 642 569 203 604 641 607 608 643 610 202 607 201 645 610 643 568 610 570 567 608 568 608 642 643 609 610 645 251 612 250 263 535 611 646 648 647 577 538 575 612 251 649 646 572 648 649 616 612 579 541 618 576 577 616 650 651 617 537 576 618 619 651 652 537 618 541 653 620 652 579 540 541 623 581 545 578 542 540 625 582 581 621 543 542 287 276 654 543 621 580 625 291 286 545 580 623 626 655 627 623 625 581 625 654 582 169 627 632 583 281 626 276 582 654 171 169 631 287 275 276 628 171 656 288 283 275 629 628 657 289 282 283 630 629 658 626 659 655 660 661 632 655 632 627 662 663 633 638 634 663 633 590 630 631 656 171 638 664 602 657 628 656 591 635 664 658 629 657 591 596 636 662 633 630 665 638 663 663 634 633 639 637 597 639 600 605 637 601 185 664 635 602 606 605 598 591 636 635 640 606 666 637 596 597 556 599 600 639 597 600 667 668 641 560 201 668 640 641 604 598 666 606 560 669 203 641 640 667 668 559 560 641 668 201 203 201 560 644 670 643 569 642 608 669 644 642 645 643 670 535 649 251 613 261 262 671 673 672 616 577 612 649 535 674 672 646 671 674 675 649 676 678 677 615 616 675 679 680 650 576 615 617 578 620 681 576 617 618 652 683 682 618 619 579 684 653 685 579 620 578 684 687 686 578 681 621 294 654 286 622 621 681 292 688 289 622 624 580 282 289 659 623 624 291 655 659 689 632 655 660 626 282 659 654 625 286 631 632 661 294 287 654 656 631 690 293 288 287 657 656 691 292 289 288 658 657 692 688 689 659 693 694 660 655 689 660 695 696 662 696 665 663 662 630 658 661 690 631 586 638 665 690 691 656 586 593 664 691 692 657 697 699 698 695 662 658 696 700 665 662 696 663 701 703 702 597 556 600 596 637 636 638 586 664 703 705 704 593 591 664 666 598 706 596 592 595 707 709 708 597 595 556 710 707 667 707 559 668 666 667 640 706 598 599 708 559 707 666 710 667 669 711 644 668 667 707 712 644 711 712 713 644 203 669 642 558 711 669 670 644 713 261 674 535 574 614 613 614 574 572 675 616 649 261 714 674 678 615 675 714 677 674 715 676 716 678 675 677 717 679 718 650 615 678 651 680 683 615 650 617 681 684 622 617 651 619 686 624 622 619 652 620 290 291 624 620 653 681 719 439 310 653 684 681 298 720 292 622 684 686 721 290 722 290 624 686 689 688 723 689 693 660 659 289 688 291 285 286 661 660 694 294 286 284 690 661 724 295 293 294 691 690 725 298 292 293 692 691 726 720 723 688 727 693 728 723 693 689 729 730 695 700 696 730 695 658 692 661 694 724 700 585 665 690 724 725 701 732 731 725 726 691 587 733 593 692 729 695 730 734 700 730 696 695 595 592 735 595 555 556 592 596 591 585 586 665 556 554 599 586 587 593 706 599 736 733 735 592 699 555 737 595 735 555 738 709 710 739 741 740 706 710 666 736 599 554 708 741 559 706 738 710 709 742 708 707 710 709 711 558 739 739 743 711 560 558 669 741 739 558 712 711 743 614 714 261 648 572 573 744 746 745 677 675 674 714 614 747 672 746 744 747 716 714 748 715 749 676 677 716 750 718 751 679 678 676 717 750 752 650 678 679 753 752 754 650 680 651 755 757 756 651 683 652 722 290 686 652 682 653 285 721 299 653 682 685 296 758 298 687 684 685 722 760 759 686 687 722 723 720 761 723 728 693 688 292 720 290 721 285 693 727 694 284 285 299 724 694 762 295 284 297 725 724 763 296 298 295 726 725 764 758 761 720 765 728 766 761 728 723 767 768 729 734 730 768 729 692 726 694 727 762 769 700 734 724 762 763 769 770 585 725 763 764 770 771 587 726 767 729 768 772 734 729 768 730 735 733 773 735 737 555 733 592 593 700 769 585 555 699 554 585 770 587 736 554 697 733 771 773 774 775 737 735 773 737 776 777 738 742 709 777 736 738 706 697 554 699 742 778 708 736 776 738 777 705 742 738 777 709 779 739 740 779 780 739 559 741 558 778 740 741 743 739 780 747 614 572 671 646 647 781 783 782 716 677 714 747 572 784 744 785 783 784 749 747 748 787 786 715 716 749 680 717 753 718 676 715 683 753 757 676 718 679 682 755 685 679 717 680 788 687 685 683 680 753 760 722 687 683 757 682 721 759 307 757 755 682 308 789 296 685 755 788 760 790 312 687 788 760 761 758 791 761 766 728 720 298 758 722 759 721 728 765 727 721 307 299 727 792 762 297 299 306 763 762 793 296 297 308 764 763 794 789 791 758 795 767 796 791 766 761 772 768 795 734 772 797 767 726 764 765 792 727 798 800 799 762 792 793 801 769 797 763 793 794 801 802 770 767 764 796 772 795 803 768 767 795 773 771 804 773 774 737 771 733 587 734 797 769 737 775 699 770 769 801 805 702 806 771 802 804 798 807 774 774 773 804 806 704 776 705 777 704 697 776 736 698 699 775 705 808 742 806 776 697 778 809 740 776 704 777 810 740 809 740 810 811 708 778 741 808 809 778 779 740 811 784 572 646 746 672 673 812 814 813 749 716 747 784 646 815 781 816 783 815 787 784 817 819 818 787 748 749 820 822 821 751 715 748 823 820 824 718 715 751 825 827 826 717 718 750 828 788 755 753 717 752 790 760 788 757 753 754 312 446 759 757 754 756 449 829 308 755 756 828 790 301 314 828 790 788 791 789 830 791 831 766 758 296 789 759 760 312 766 832 765 446 307 759 765 833 792 307 448 306 792 834 793 308 306 449 794 793 835 830 789 829 836 796 837 830 831 791 831 832 766 836 803 795 796 764 794 765 832 833 803 838 772 792 833 834 838 839 797 835 793 834 839 840 801 796 794 837 803 836 841 795 796 836 804 802 800 804 798 774 802 771 770 797 772 838 775 774 807 797 839 801 698 775 842 800 802 840 799 843 798 804 800 798 844 732 701 703 704 702 698 806 697 807 842 775 703 845 705 805 806 698 808 846 809 806 702 704 847 809 846 809 847 848 742 808 778 845 846 808 810 809 848 815 646 672 785 744 745 849 851 850 787 749 784 815 672 852 849 813 851 852 853 815 823 751 822 786 787 853 750 823 854 822 748 786 752 854 855 751 748 822 856 756 754 750 751 823 857 828 756 854 752 750 828 301 790 754 752 855 444 314 302 855 856 754 858 456 859 857 756 856 860 862 861 828 857 301 830 829 863 830 864 831 789 308 829 314 312 790 832 831 865 313 446 312 832 866 833 447 448 446 833 303 834 448 450 449 834 304 835 863 829 451 867 837 868 864 830 863 864 865 831 867 841 836 837 794 835 832 865 866 841 869 803 833 866 303 869 870 838 834 303 304 870 871 839 868 837 835 872 841 867 867 836 837 800 840 873 874 876 875 840 802 801 838 803 869 798 843 807 839 838 870 842 807 877 873 840 871 799 879 878 799 800 873 880 844 805 701 702 844 842 805 698 843 877 807 701 881 703 842 880 805 882 884 883 805 844 702 845 883 846 883 884 846 705 845 808 881 883 845 847 846 884 744 852 672 782 783 785 885 887 886 853 787 815 852 744 888 818 786 853 888 817 852 889 891 890 817 818 853 892 894 893 818 821 786 854 824 895 822 786 821 896 856 855 820 823 822 856 897 857 824 854 823 857 300 301 854 895 855 445 452 447 896 855 895 460 859 454 897 856 896 311 300 310 857 897 300 863 451 898 863 862 864 829 449 451 302 314 301 864 860 865 444 313 314 866 865 899 445 447 313 303 866 900 447 452 450 858 861 862 451 453 898 868 902 901 862 863 898 860 864 862 901 872 867 868 835 304 865 860 899 872 903 841 866 899 900 903 904 869 303 900 305 904 905 870 868 304 902 906 872 901 901 867 868 873 871 907 873 879 799 871 840 839 903 869 841 843 799 878 904 870 869 877 843 908 907 871 905 909 910 879 879 873 907 911 876 880 876 732 844 877 880 842 908 843 878 912 914 913 877 911 880 876 874 732 844 880 876 883 881 913 913 915 883 703 881 845 731 913 881 915 882 883 783 888 744 812 816 781 816 812 813 817 853 852 888 783 916 885 886 849 916 917 888 918 821 919 917 819 817 820 918 920 819 919 818 824 920 921 919 821 818 895 922 896 918 820 821 896 719 897 920 824 820 897 310 300 895 824 921 923 444 302 895 921 922 924 445 444 922 719 896 925 452 445 897 719 310 898 453 456 898 858 862 451 450 453 923 302 311 926 928 927 923 924 444 860 929 899 924 925 445 900 899 930 455 452 925 305 900 931 456 453 455 858 859 932 858 898 456 933 934 902 906 901 934 902 304 305 861 929 860 906 935 872 899 929 930 935 936 903 900 930 931 936 937 904 902 305 933 906 934 938 901 902 934 907 905 939 907 909 879 905 871 870 935 903 872 879 910 878 936 904 903 908 878 940 937 939 905 909 942 941 939 909 907 943 875 911 912 945 944 908 911 877 910 940 878 874 945 732 908 943 911 875 946 874 876 911 875 913 731 912 914 947 913 701 731 881 912 731 945 915 913 947 816 916 783 851 813 814 948 950 949 917 817 888 916 816 951 890 819 917 916 951 889 952 919 893 889 890 917 918 952 953 819 890 893 920 953 954 893 919 819 921 955 922 952 918 919 922 956 719 953 920 918 957 399 443 921 920 954 923 311 318 921 954 955 924 923 958 955 956 922 925 924 959 439 719 956 455 925 960 309 310 439 961 963 962 311 309 318 858 932 861 923 318 958 929 861 964 958 959 924 929 928 930 959 960 925 931 930 926 455 960 454 859 460 462 859 456 454 965 966 933 938 934 966 933 305 931 932 964 861 967 906 938 964 928 929 967 968 935 930 928 926 968 969 936 933 931 965 937 970 939 934 933 966 939 942 909 941 910 909 937 905 904 967 935 906 971 940 910 968 936 935 972 973 942 969 970 937 974 975 946 970 942 939 976 977 943 946 875 977 940 943 908 941 971 910 946 978 874 943 940 976 977 974 946 943 977 875 979 912 944 979 980 912 732 945 731 978 944 945 914 912 980 951 816 813 885 849 850 981 983 982 889 917 916 984 951 813 985 987 986 951 984 988 989 991 990 889 988 891 952 894 826 890 891 892 992 953 826 892 893 890 954 957 955 894 952 893 955 443 956 826 953 952 956 442 439 953 992 954 993 995 994 992 957 954 958 318 994 957 443 955 959 958 995 443 442 956 960 959 996 442 440 439 454 960 461 319 309 440 932 859 462 318 319 994 932 963 964 958 994 995 928 964 961 959 995 996 997 999 998 996 461 960 458 459 460 454 461 460 997 1000 965 1001 966 1000 965 931 926 963 932 462 1002 938 1001 963 961 964 1003 967 1002 961 927 928 1003 1004 968 965 926 997 969 1005 970 966 965 1000 938 966 1001 942 970 972 969 937 936 1002 967 938 941 942 973 967 1003 968 971 941 1006 969 1004 1005 1007 972 1008 970 1005 972 1009 1010 976 1010 974 977 971 976 940 973 1006 941 1011 974 1010 971 1009 976 978 1012 944 977 976 1010 1013 944 1012 944 1013 1014 874 978 945 975 1012 978 979 944 1014 984 813 849 1015 886 887 1016 886 1015 988 889 951 984 849 1017 1018 891 988 984 1017 1019 892 1021 1020 988 1019 1018 825 894 1020 891 1018 1021 1022 1024 1023 1021 892 891 992 1025 957 892 1020 894 322 1026 326 826 894 825 440 442 1027 826 827 992 1028 319 440 827 1025 992 1029 994 319 399 957 1025 995 1030 996 400 443 399 996 1031 461 400 1027 442 1032 1034 1033 1027 1028 440 1035 1037 1036 1028 1029 319 963 462 1038 994 1029 993 1039 1041 1040 993 1030 995 927 961 1042 1030 1031 996 472 457 458 458 461 1031 1043 1045 1044 1046 1000 998 997 926 927 1038 462 459 1043 1001 1046 962 963 1038 1047 1002 1043 962 1042 961 1048 1003 1047 927 999 997 1004 1049 1005 1000 997 998 1001 1000 1046 972 1005 1008 1004 969 968 1043 1002 1001 973 972 1007 1047 1003 1002 1006 973 1050 1004 1048 1049 1051 1008 1052 1005 1049 1008 1053 1054 1009 1011 1010 1054 1006 1009 971 973 1007 1050 1011 1055 974 1009 1006 1053 1054 1056 1011 1010 1009 1054 975 1057 1012 1012 1059 1058 946 975 978 1055 1057 975 1013 1012 1058 886 1017 849 949 1016 1015 950 1016 949 1019 988 984 1060 1017 886 1061 1018 1019 1017 1060 1062 1063 1021 1064 1019 1062 1061 1065 1020 1063 1061 1064 1018 825 1065 1026 1018 1064 1021 827 322 1025 1063 1020 1021 399 1025 320 825 1020 1065 1027 400 315 825 1026 827 1028 1027 316 322 827 1026 1029 1028 1066 320 1025 322 1067 993 1029 399 320 324 1068 1030 993 400 324 315 1069 1031 1030 1027 315 316 472 458 1031 1066 1028 316 1038 459 464 1029 1066 1067 962 1038 1036 1067 1068 993 1042 962 1037 1069 1030 1068 472 1070 465 1069 472 1031 1071 1072 999 1073 998 1072 999 927 1042 464 459 457 1073 1045 1046 1036 1038 464 1047 1044 1074 1037 962 1036 1040 1073 1072 1042 1071 999 1075 1049 1048 999 1072 998 1046 998 1073 1008 1049 1052 1048 1004 1003 1045 1043 1046 1007 1008 1051 1044 1047 1043 1050 1007 1076 1074 1075 1048 1077 1052 1078 1049 1075 1052 1056 1054 1079 1011 1056 1080 1050 1053 1006 1007 1051 1076 1081 1056 1079 1053 1050 1082 1055 1083 1057 1054 1053 1079 1084 1057 1083 1057 1059 1012 974 1055 975 1055 1080 1083 1084 1059 1057 1060 886 1016 1085 950 948 1085 987 950 1062 1019 1017 1086 1060 1016 1087 1061 1062 1060 1086 1088 1089 1064 1090 1062 1088 1087 1091 1063 1089 1061 1087 1090 1065 1091 1092 1061 1090 1064 1093 1023 337 1089 1063 1064 385 1094 333 1065 1063 1091 1095 315 324 1092 1026 1065 1096 1098 1097 326 1026 1092 1066 316 1097 321 322 326 1067 1066 1098 321 323 320 1068 1067 1099 324 323 1095 1069 1068 1100 315 1095 317 1070 472 1069 316 317 1097 1034 1102 1101 1098 1066 1097 1036 464 1103 1099 1067 1098 1104 1106 1105 1068 1099 1100 1107 1070 1108 1100 1070 1069 1109 1110 1071 1040 1072 1110 1071 1042 1037 457 465 463 1111 1073 1040 1103 464 463 1111 1112 1045 1103 1035 1036 1112 1113 1044 1037 1109 1071 1040 1110 1039 1072 1071 1110 1075 1074 1114 1075 1078 1052 1074 1048 1047 1111 1045 1073 1051 1052 1077 1112 1044 1045 1076 1051 1115 1113 1114 1074 1116 1082 1117 1114 1078 1075 1081 1079 1116 1082 1079 1053 1076 1082 1050 1115 1051 1077 1081 1118 1056 1117 1082 1076 1081 1116 1119 1116 1079 1082 1080 1120 1083 1083 1122 1121 1011 1080 1055 1118 1120 1080 1084 1083 1121 950 1086 1016 986 987 1085 1123 1125 1124 1088 1062 1060 1126 1086 950 1088 1127 1087 1086 1126 1128 1022 1090 1129 1127 1088 1128 1093 1089 1022 1087 1127 1129 1091 1093 1094 1129 1090 1087 1092 385 326 1090 1022 1089 323 321 1130 1089 1093 1091 1131 1095 323 1094 1092 1091 1132 317 1095 1094 385 1092 1133 1097 317 385 325 326 1098 1134 1099 325 1130 321 1032 1108 1135 1130 1131 323 1100 1099 1135 1095 1131 1132 1070 1100 1108 317 1132 1133 465 1070 1107 1096 1097 1133 1103 463 471 1098 1096 1134 1035 1103 1136 1099 1134 1135 1032 1137 1108 1135 1108 1100 1138 1106 1109 1039 1110 1106 1109 1037 1035 465 1107 466 1139 1141 1140 463 466 471 1142 1111 1041 1136 1103 471 1142 1143 1112 1035 1138 1109 1106 1104 1039 1109 1106 1110 1114 1113 1144 1114 1145 1078 1113 1074 1044 1111 1040 1041 1078 1146 1077 1142 1112 1111 1115 1077 1147 1143 1144 1113 1148 1117 1149 1144 1145 1114 1145 1146 1078 1148 1119 1116 1115 1117 1076 1147 1077 1146 1119 1150 1081 1149 1117 1115 1118 1151 1120 1148 1116 1117 1152 1120 1151 1120 1122 1083 1056 1118 1080 1118 1150 1151 1152 1122 1120 987 1126 950 1153 985 986 1154 985 1153 1128 1088 1086 1155 1126 987 1128 1156 1127 1157 1126 1155 1024 1129 1158 1156 1128 1157 1159 1161 1160 1127 1156 1158 355 1162 1160 1158 1129 1127 1163 1164 339 1129 1024 1022 1165 1130 325 1023 1093 1022 1131 1130 329 337 1094 1093 327 1132 1131 333 1094 337 1166 1133 1132 385 333 334 1167 1096 1133 325 334 1165 1168 1134 1096 1130 1165 329 1169 1135 1134 329 327 1131 1108 1137 1107 1132 327 1166 1107 474 466 1133 1166 1167 470 480 1170 1167 1168 1096 1136 471 1170 1169 1134 1168 1171 1173 1172 1135 1169 1032 1174 1105 1138 1175 1177 1176 1138 1035 1136 1137 474 1107 1178 1039 1104 466 474 470 1178 1179 1041 471 470 1170 1140 1142 1179 1174 1138 1136 1105 1173 1104 1138 1105 1106 1144 1143 1141 1144 1180 1145 1143 1113 1112 1041 1039 1178 1145 1181 1146 1142 1041 1179 1146 1182 1147 1140 1141 1143 1183 1149 1184 1141 1180 1144 1180 1181 1145 1183 1185 1148 1147 1149 1115 1146 1181 1182 1185 1186 1119 1184 1149 1147 1150 1187 1151 1183 1148 1149 1185 1119 1148 1187 1188 1151 1081 1150 1118 1150 1186 1187 1152 1151 1188 985 1155 987 981 1154 1153 982 1154 981 1157 1128 1126 985 1189 1155 1157 1190 1156 1191 1155 1189 1192 1158 1193 1157 1191 1190 1024 1192 1163 1190 1193 1156 1023 1163 344 1158 1156 1193 358 1194 365 1158 1192 1024 1195 1165 334 1163 1023 1024 1196 329 1165 337 1023 344 1197 1199 1198 336 337 344 1198 1166 327 336 335 333 1199 1167 1166 334 335 1195 1200 1168 1167 1165 1195 1196 1201 1169 1168 329 1196 328 1034 1032 1169 327 328 1198 1033 1137 1032 1199 1166 1198 1202 474 1137 1200 1167 1199 1203 1205 1204 1200 1201 1168 1206 1172 1207 1034 1169 1201 1208 1209 1174 1173 1105 1209 1174 1136 1170 1033 1202 1137 1173 1210 1104 473 474 1202 1211 1178 1210 470 473 480 1211 1212 1179 1208 1174 1170 1209 1172 1173 1209 1105 1174 1213 1215 1214 1141 1216 1180 1140 1143 1142 1104 1210 1178 1180 1213 1181 1179 1178 1211 1181 1214 1182 1139 1140 1212 1184 1218 1217 1139 1216 1141 1216 1213 1180 1217 1219 1183 1182 1184 1147 1181 1213 1214 1219 1220 1185 1184 1182 1218 1186 1221 1187 1217 1183 1184 1219 1185 1183 1187 1223 1222 1119 1186 1150 1186 1220 1221 1188 1187 1222 1189 985 1154 1224 983 1225 1224 982 983 1191 1157 1155 1154 1226 1189 1191 990 1190 989 1189 1226 1162 1193 1159 1191 989 990 1164 1192 1162 990 1159 1190 1160 1227 354 1190 1159 1193 1228 335 336 1193 1162 1192 1229 1195 335 1163 1192 1164 1230 1196 1195 339 344 1163 1231 328 1196 344 339 340 1232 1198 328 340 1228 336 1233 1235 1234 1228 1229 335 1233 1200 1199 1195 1229 1230 1234 1201 1200 1196 1230 1231 1102 1034 1201 328 1231 1232 1101 1033 1034 1198 1232 1197 1236 1202 1033 1199 1197 1233 1237 473 1202 1233 1234 1200 1102 1203 1204 1234 1102 1201 476 1238 1208 1172 1209 1238 1208 1170 480 1236 1033 1101 1239 1241 1240 1236 1237 1202 1171 1242 1210 473 1237 481 1242 1243 1211 1208 480 476 1207 1172 1238 1238 1209 1208 1139 1212 1244 1139 1245 1216 1212 1140 1179 1210 1173 1171 1213 1216 1246 1210 1242 1211 1247 1245 1248 1244 1212 1243 1218 1250 1249 1245 1139 1244 1245 1246 1216 1251 1217 1249 1214 1218 1182 1213 1246 1215 1251 1252 1219 1218 1214 1250 1220 1253 1221 1217 1218 1249 1251 1219 1217 1221 1254 1223 1185 1220 1186 1220 1252 1253 1223 1187 1221 982 1226 1154 1255 1225 1256 1255 1224 1225 989 1191 1189 982 1257 1226 1258 1260 1259 1261 1226 1257 1262 1264 1263 989 1261 991 1265 1267 1266 1161 990 991 1164 355 341 990 1161 1159 1268 1228 340 1159 1160 1162 1269 1229 1228 355 1164 1162 330 1230 1229 339 1164 341 1270 1231 1230 339 341 338 1271 1232 1231 340 338 1268 1272 1197 1232 1228 1268 1269 1273 1233 1197 1269 330 1229 1102 1234 1203 1230 330 1270 1101 1102 1204 1231 1270 1271 1236 1101 1274 1232 1271 1272 1237 1236 1275 1197 1272 1273 481 1237 1276 1233 1273 1235 478 1276 1277 1235 1203 1234 1278 1279 469 1207 1238 477 476 480 481 1101 1204 1274 1280 482 489 1274 1275 1236 1206 1281 1171 1276 1237 1275 1281 1282 1242 476 481 475 1283 1207 477 477 1238 476 1244 1243 1284 1244 1248 1245 1243 1212 1211 1172 1206 1171 1245 1247 1246 1242 1171 1281 1215 1246 1285 1284 1243 1282 1248 1287 1286 1284 1248 1244 1288 1289 1250 1290 1249 1289 1215 1250 1214 1246 1247 1285 1291 1251 1290 1250 1215 1288 1252 1292 1253 1249 1250 1289 1251 1249 1290 1253 1293 1254 1219 1252 1220 1252 1291 1292 1254 1221 1253 1224 1257 982 1294 1256 1295 1294 1255 1256 1261 989 1226 1296 1257 1224 1264 991 1261 1257 1296 1263 1227 1161 1266 1263 1264 1261 1194 1265 1297 1264 1266 991 1267 353 1227 1266 1161 991 338 342 348 1227 1160 1161 1268 348 1298 354 355 1160 1269 1298 332 355 343 341 1299 1301 1300 341 342 338 1270 331 1300 1268 338 348 1271 1300 1302 1269 1268 1298 1272 1302 1303 330 1269 332 1273 1303 1304 331 1270 330 1235 1304 1305 1300 1271 1270 1203 1305 1205 1302 1272 1271 1204 1205 1306 1303 1273 1272 1274 1306 1307 1304 1235 1273 1275 1307 1277 1305 1203 1235 1308 1310 1309 1283 477 479 475 481 1276 1274 1204 1306 1279 1207 1283 1275 1274 1307 1279 1311 1206 1275 1277 1276 1311 1312 1281 475 1276 478 1280 1283 479 477 475 479 1284 1282 1313 1284 1287 1248 1282 1243 1242 1207 1279 1206 1247 1248 1286 1206 1311 1281 1247 1314 1285 1313 1282 1312 1315 1316 1287 1287 1284 1313 1175 1317 1288 1318 1289 1317 1285 1288 1215 1286 1314 1247 1319 1318 1317 1288 1285 1175 1320 1292 1291 1289 1288 1317 1290 1289 1318 1292 1321 1293 1251 1291 1252 1322 1320 1291 1293 1253 1292 1255 1296 1224 1258 1295 1323 1258 1294 1295 1263 1261 1257 1324 1296 1255 1124 1125 1325 1296 1324 1326 1327 1329 1328 1326 1262 1263 1297 1330 365 1264 1262 1265 359 1331 343 1265 1266 1264 1331 350 342 1227 1266 1267 1332 1334 1333 353 354 1227 349 1335 1298 343 354 359 1335 1336 332 342 343 1331 331 1336 1299 342 350 348 1337 1339 1338 1298 348 349 1301 1339 1302 332 1298 1335 1339 1340 1303 331 332 1336 1340 1341 1304 1300 331 1299 1341 1342 1305 1301 1302 1300 1342 1343 1205 1339 1303 1302 1343 1344 1306 1340 1304 1303 1344 1345 1307 1341 1305 1304 1345 483 1277 1205 1305 1342 1280 479 482 1205 1343 1306 469 1283 1280 1344 1307 1306 1346 1348 1347 1277 1307 1345 1278 1349 1311 478 1277 483 1350 1352 1351 479 478 482 1313 1312 1353 1287 1313 1315 1312 1282 1281 469 1279 1283 1287 1316 1286 1279 1278 1311 1314 1286 1354 1353 1312 1349 1315 1356 1355 1315 1313 1353 1319 1317 1176 1318 1319 1357 1314 1175 1285 1316 1354 1286 1358 1319 1176 1314 1177 1175 1318 1322 1290 1176 1317 1175 1322 1359 1320 1360 1321 1320 1290 1322 1291 1357 1359 1322 1321 1292 1320 1294 1324 1255 1260 1258 1323 1361 1363 1362 1326 1263 1296 1324 1294 1364 1329 1262 1326 1324 1364 1328 1327 1366 1365 1329 1326 1328 1267 1194 352 1297 1262 1329 359 351 1367 1265 1262 1297 1367 1368 1331 1194 1267 1265 1368 1369 350 1267 352 353 349 1369 1370 353 351 359 1370 1371 1335 1331 359 1367 1371 1372 1336 350 1331 1368 1372 1373 1299 349 350 1369 1301 1373 1338 1335 349 1370 1374 1340 1337 1336 1335 1371 1375 1341 1374 1299 1336 1372 1376 1378 1377 1301 1299 1373 1375 1378 1342 1338 1339 1301 1378 1379 1343 1337 1340 1339 1379 1380 1344 1374 1341 1340 1380 1381 1345 1375 1342 1341 1381 490 483 1342 1378 1343 468 1280 489 1343 1379 1344 1382 1384 1383 1380 1345 1344 467 1385 1278 483 1345 1381 489 490 488 482 483 490 1353 1349 1386 1353 1356 1315 1349 1312 1311 468 469 1280 1316 1315 1355 469 467 1278 1354 1316 1387 1349 1385 1386 1388 1389 1356 1356 1353 1386 1390 1240 1177 1358 1176 1240 1354 1177 1314 1355 1387 1316 1358 1391 1319 1177 1354 1390 1240 1241 1358 1176 1177 1240 1392 1359 1393 1359 1360 1320 1318 1357 1322 1357 1391 1393 1392 1360 1359 1258 1364 1294 1394 1259 1260 1325 1259 1394 1328 1326 1324 1395 1364 1258 1396 1397 1125 1395 1366 1364 1365 1399 1398 1366 1327 1328 1400 369 1401 1327 1330 1329 360 1402 351 1330 1297 1329 1367 1402 1403 365 1194 1297 1403 1404 1368 352 1194 358 1404 1405 1369 351 352 360 1370 1405 1406 351 1402 1367 1406 1334 1371 1368 1367 1403 1334 1407 1372 1369 1368 1404 1407 1408 1373 1405 1370 1369 1338 1408 1409 1406 1371 1370 1337 1409 1410 1334 1372 1371 1374 1410 1411 1407 1373 1372 1375 1411 1377 1338 1373 1408 1412 1379 1376 1337 1338 1409 1413 1380 1412 1410 1374 1337 1414 1381 1413 1411 1375 1374 488 490 1414 1377 1378 1375 487 494 491 1378 1376 1379 1415 468 487 1379 1412 1380 1415 1416 467 1413 1381 1380 488 1414 495 1414 490 1381 1386 1385 1417 1386 1388 1356 1385 1349 1278 487 468 489 1355 1356 1389 1415 467 468 1387 1355 1418 1385 1416 1417 1384 1382 1388 1388 1386 1417 1419 1239 1390 1420 1422 1421 1387 1390 1354 1389 1418 1355 1420 1358 1241 1387 1419 1390 1391 1421 1393 1240 1390 1239 1423 1393 1421 1357 1393 1359 1319 1391 1357 1391 1420 1421 1392 1393 1423 1259 1395 1258 1124 1325 1394 1424 1426 1425 1366 1328 1364 1395 1259 1427 1424 1361 1426 1427 1399 1395 364 1330 1401 1365 1366 1399 379 372 1400 1327 1365 1401 360 356 1428 1401 1330 1327 1428 1429 1402 1330 364 365 1403 1429 1430 365 357 358 1430 346 1404 360 358 356 1405 346 1431 1402 360 1428 1406 1431 1333 1403 1402 1429 1432 1434 1433 1404 1403 1430 1332 1434 1407 1405 1404 346 1434 1435 1408 1431 1406 1405 1435 1436 1409 1333 1334 1406 1410 1436 1437 1332 1407 1334 1411 1437 1438 1434 1408 1407 1377 1438 1439 1435 1409 1408 1376 1439 1440 1436 1410 1409 1412 1440 1441 1437 1411 1410 1413 1441 1442 1438 1377 1411 1414 1442 495 1439 1376 1377 1443 1444 493 1376 1440 1412 491 1309 1415 1413 1412 1441 495 1442 1445 1442 1414 1413 1417 1416 1310 1417 1384 1388 1416 1385 467 494 487 488 1389 1388 1382 491 1415 487 1418 1389 1446 1416 1309 1310 1347 1383 1384 1417 1310 1384 1447 1448 1419 1352 1239 1448 1418 1419 1387 1382 1446 1389 1352 1449 1241 1419 1418 1447 1448 1351 1352 1419 1448 1239 1241 1239 1352 1422 1450 1421 1358 1420 1391 1449 1422 1420 1423 1421 1450 1325 1427 1259 1396 1125 1123 1451 1453 1452 1399 1366 1395 1427 1325 1454 1452 1424 1451 1454 1455 1427 1456 1458 1457 1455 1398 1399 370 1459 357 1365 1398 1400 356 1459 1460 1365 1400 1401 1428 1460 1461 364 1401 369 1429 1461 1462 357 364 370 1430 1462 345 356 357 1459 1463 1465 1464 1428 356 1460 1431 347 1466 1429 1428 1461 1333 1466 1467 1462 1430 1429 1332 1467 1433 346 1430 345 1468 1435 1432 1431 346 347 1469 1471 1470 1466 1333 1431 1468 1471 1436 1467 1332 1333 1471 1472 1437 1433 1434 1332 1472 1473 1438 1432 1435 1434 1473 1474 1439 1468 1436 1435 1474 1475 1440 1471 1437 1436 1475 1476 1441 1472 1438 1437 1442 1476 1445 1473 1439 1438 495 1445 496 1440 1439 1474 1477 1479 1478 1440 1475 1441 1480 1445 1476 1441 1476 1442 497 1482 1481 1310 1347 1384 1309 1416 1415 495 496 494 1482 1484 1483 493 491 494 1446 1382 1485 1309 492 1308 1486 1488 1487 1310 1308 1347 1489 1486 1447 1486 1351 1448 1446 1447 1418 1485 1382 1383 1487 1351 1486 1446 1489 1447 1449 1490 1422 1448 1447 1486 1491 1422 1490 1491 1492 1422 1241 1449 1420 1350 1490 1449 1450 1422 1492 1125 1454 1325 1363 1397 1396 1397 1363 1361 1455 1399 1427 1125 1493 1454 1458 1398 1455 1493 1457 1454 387 1456 1494 1455 1457 1458 370 371 1495 1398 1458 379 1459 1495 1496 379 1400 1398 1460 1496 1497 369 1400 372 1461 1497 1498 370 369 371 1462 1498 1499 1459 370 1495 345 1499 1500 1496 1460 1459 347 1500 1501 1461 1460 1497 1466 1501 1465 1462 1461 1498 1467 1465 1502 1499 345 1462 1433 1502 1503 1500 347 345 1432 1503 1504 1501 1466 347 1468 1504 1470 1465 1467 1466 1505 1472 1469 1502 1433 1467 1506 1473 1505 1503 1432 1433 1507 1474 1506 1504 1468 1432 1508 1475 1507 1470 1471 1468 1480 1476 1508 1469 1472 1471 1509 1511 1510 1505 1473 1472 1480 1511 1445 1506 1474 1473 1511 1443 496 1475 1474 1507 1508 502 1480 1508 1476 1475 1308 492 1512 1308 1346 1347 492 1309 491 496 1445 1511 1347 1348 1383 496 1443 493 1485 1383 1513 1444 1512 492 1479 1346 1514 1308 1512 1346 1515 1488 1489 1516 1518 1517 1485 1489 1446 1513 1383 1348 1487 1518 1351 1485 1515 1489 1488 1519 1487 1486 1489 1488 1490 1350 1516 1516 1520 1490 1352 1350 1449 1518 1516 1350 1491 1490 1520 1397 1493 1125 1426 1361 1362 1521 1523 1522 1457 1455 1454 1493 1397 1524 1452 1523 1521 1524 1494 1493 375 387 1525 1457 1494 1456 371 373 1526 1458 1456 378 1495 1526 1527 379 1458 378 1496 1527 1528 372 379 374 1497 1528 1529 373 371 372 1498 1529 1530 1495 371 1526 1499 1530 1531 1496 1495 1527 1500 1531 1532 1528 1497 1496 1501 1532 1464 1498 1497 1529 1533 1535 1534 1530 1499 1498 1502 1463 1533 1531 1500 1499 1503 1533 1536 1532 1501 1500 1504 1536 1537 1464 1465 1501 1470 1537 1538 1465 1463 1502 1469 1538 1539 1502 1533 1503 1505 1539 1540 1503 1536 1504 1506 1540 1541 1504 1537 1470 1507 1541 501 1470 1538 1469 1508 501 502 1469 1539 1505 1480 502 1510 1540 1506 1505 1542 1544 1543 1541 1507 1506 1509 1545 1443 1508 1507 501 1512 1444 1546 1512 1514 1346 1444 492 493 1510 1511 1480 1346 1479 1348 1511 1509 1443 1513 1348 1477 1444 1545 1546 1547 1548 1514 1512 1546 1514 1549 1550 1515 1519 1488 1550 1513 1515 1485 1477 1348 1479 1519 1551 1487 1513 1549 1515 1550 1484 1519 1515 1550 1488 1552 1516 1517 1552 1553 1516 1351 1518 1350 1551 1517 1518 1520 1516 1553 1524 1397 1361 1451 1424 1425 1554 1556 1555 1494 1457 1493 1524 1361 1557 1521 1558 1556 1524 1557 1525 374 384 1559 387 1494 1525 373 1559 1560 1456 387 383 1526 1560 1561 378 1456 383 1527 1561 368 374 378 384 1528 368 366 373 374 1559 1529 366 1562 1560 1526 373 1530 1562 361 1527 1526 1561 1531 361 362 368 1528 1527 1532 362 1563 366 1529 1528 1464 1563 1564 1562 1530 1529 1463 1564 1535 361 1531 1530 1565 1566 1534 362 1532 1531 1536 1534 1566 1563 1464 1532 1537 1566 1567 1564 1463 1464 1538 1567 1568 1535 1533 1463 1539 1568 1569 1533 1534 1536 1540 1569 1570 1536 1566 1537 1541 1570 1571 1537 1567 1538 501 1571 500 1538 1568 1539 502 500 1572 1539 1569 1540 1510 1572 1573 1540 1570 1541 1509 1573 508 1571 501 1541 1546 1545 509 1546 1547 1514 1545 1444 1443 502 1572 1510 1514 1548 1479 1510 1573 1509 1574 1481 1575 1545 508 509 513 1576 1547 1547 1546 509 1575 1483 1549 1484 1550 1483 1477 1549 1513 1478 1479 1548 1484 1577 1519 1575 1549 1477 1551 1578 1517 1549 1483 1550 1579 1517 1578 1517 1579 1580 1487 1551 1518 1577 1578 1551 1552 1517 1580 1557 1361 1424 1523 1452 1453 1581 1583 1582 1525 1494 1524 1557 1424 1584 1554 1585 1556 377 1557 1584 1586 384 383 1525 377 375 1587 1559 384 387 375 386 1588 1560 1559 1586 383 386 1589 1561 1560 1587 384 1586 1590 368 1561 1588 1559 1587 1591 1593 1592 1589 1560 1588 1594 1562 366 1589 1590 1561 1595 361 1562 367 368 1590 1596 1598 1597 367 1594 366 1599 1563 362 1594 1595 1562 1600 1564 1563 1595 363 361 1601 1535 1564 362 363 1599 1602 1534 1535 1599 1600 1563 1567 1566 1603 1600 1601 1564 1568 1567 1604 1601 1602 1535 1569 1568 1605 1602 1565 1534 1570 1569 1606 1565 1603 1566 1571 1570 1607 1603 1604 1567 500 1571 507 1604 1605 1568 1608 1609 506 1605 1606 1569 506 1572 500 1606 1607 1570 1609 1573 1572 1571 1607 507 1610 508 1573 509 513 1547 508 1545 1509 1609 1572 506 1548 1547 1576 1573 1609 1610 1478 1548 1611 508 1610 510 514 515 513 509 510 513 1612 499 497 1482 1483 1481 1478 1575 1477 1576 1611 1548 1482 1613 1484 1574 1575 1478 1577 1614 1578 1575 1481 1483 1615 1578 1614 1578 1615 1616 1519 1577 1551 1613 1614 1577 1579 1578 1616 1584 1424 1452 1558 1521 1522 1617 1619 1618 377 1525 1557 1584 1452 1620 1617 1582 1619 402 1584 1620 1586 386 1621 377 402 376 1587 1586 1622 391 375 376 1588 1587 1623 391 1621 386 1589 1588 1624 1622 1586 1621 1590 1589 1625 1622 1623 1587 367 1590 1626 1623 1624 1588 1627 1594 367 1624 1625 1589 1595 1594 1628 1625 1626 1590 363 1595 1629 1626 1627 367 1630 1599 363 1627 1628 1594 1600 1599 1596 1628 1629 1595 1601 1600 1597 1629 1630 363 1602 1601 1631 1599 1630 1596 1565 1602 1632 1600 1596 1597 1603 1565 1633 1601 1597 1631 1604 1603 1634 1602 1631 1632 1605 1604 1635 1565 1632 1633 1606 1605 1636 1603 1633 1634 1607 1606 1637 1604 1634 1635 1638 507 1607 1605 1635 1636 1639 506 507 1636 1637 1606 1640 503 1641 1637 1638 1607 1610 1609 1642 1638 1639 507 1610 516 510 1608 506 1639 513 515 1576 1609 1608 1642 1611 1576 1643 1610 1642 516 514 503 504 514 510 516 1644 1612 1574 497 1481 1612 1611 1574 1478 515 1643 1576 497 1645 1482 1611 1644 1574 1646 1648 1647 1574 1612 1481 1613 1647 1614 1647 1648 1614 1484 1613 1577 1645 1647 1613 1615 1614 1648 1521 1620 1452 1555 1556 1558 1649 1651 1650 402 377 1584 1620 1521 1652 1650 1617 1649 412 1620 1652 1653 1621 391 402 412 401 1622 1621 1654 401 395 376 1655 1623 1622 1653 391 395 1624 1623 1656 1653 1654 1621 1657 1625 1624 1655 1622 1654 1626 1625 380 1655 1656 1623 1627 1626 381 1656 1657 1624 1658 1628 1627 1657 380 1625 1629 1628 1593 380 381 1626 1630 1629 1591 1627 381 1658 1659 1596 1630 1658 1593 1628 1597 1660 1631 1593 1591 1629 1661 1663 1662 1591 1659 1630 1632 1631 1663 1596 1659 1598 1633 1632 1661 1597 1598 1660 1634 1633 1664 1631 1660 1663 1635 1634 1665 1632 1663 1661 1636 1635 1666 1633 1661 1664 1637 1636 1667 1634 1664 1665 1638 1637 1668 1635 1665 1666 1639 1638 1669 1636 1666 1667 1670 1608 1639 1637 1667 1668 1671 1642 1608 1668 1669 1638 516 1642 1641 1669 1670 1639 1672 519 517 1671 1608 1670 1643 515 1673 1642 1671 1641 1640 505 503 516 1641 503 1674 1542 1644 1542 499 1612 1643 1644 1611 1673 515 504 1675 1677 1676 1643 1674 1644 1542 1543 499 1612 1644 1542 1647 1645 1676 1676 1678 1647 1482 1645 1613 498 1676 1645 1678 1646 1647 1556 1652 1521 1581 1585 1554 1585 1581 1582 412 402 1620 1556 1679 1652 1680 395 401 1652 1679 403 1653 395 1681 403 404 412 1682 1654 1653 404 1680 401 1655 1654 1683 1680 1681 395 1684 1656 1655 1681 1682 1653 1657 1656 1685 1682 1683 1654 1686 380 1657 1683 1684 1655 1687 1689 1688 1684 1685 1656 1690 1658 381 1685 1686 1657 1691 1593 1658 1686 382 380 1692 1694 1693 382 1690 381 1659 1591 1694 1658 1690 1691 1692 1598 1659 1593 1691 1592 1695 1660 1598 1591 1592 1694 1696 1663 1660 1694 1692 1659 1661 1697 1664 1598 1692 1695 1664 1698 1665 1660 1695 1696 1665 1699 1666 1663 1696 1662 1666 1700 1667 1661 1662 1697 1667 1701 1668 1664 1697 1698 1668 1702 1669 1665 1698 1699 1703 1705 1704 1666 1699 1700 1670 1669 1705 1667 1700 1701 1671 1670 1703 1668 1701 1702 1706 1641 1671 1702 1705 1669 1707 511 1708 1703 1670 1705 1673 504 512 1671 1703 1706 1672 1708 1640 1640 1641 1706 1709 1544 1674 1675 1711 1710 1673 1674 1643 505 512 504 1543 1711 499 1673 1709 1674 1544 1712 1543 1542 1674 1544 1676 498 1675 1677 1713 1676 497 498 1645 1675 498 1711 1678 1676 1713 1585 1679 1556 1619 1582 1583 1714 428 429 403 412 1652 1585 1715 1679 1716 1680 404 417 1679 1715 1717 1681 1680 417 405 403 1718 1682 1681 405 1716 404 1719 1683 1682 1716 1717 1680 1720 1684 1683 1717 1718 1681 1721 1685 1684 1718 1719 1682 1686 1685 1722 1719 1720 1683 1723 382 1686 1684 1720 1721 1724 1690 382 1721 1722 1685 1725 1691 1690 1686 1722 1723 1726 1592 1691 382 1723 1724 1727 1694 1592 1724 1725 1690 1728 1730 1729 1691 1725 1726 1730 1695 1692 1592 1726 1727 1728 1696 1695 1694 1727 1693 1731 1662 1696 1692 1693 1730 1732 1697 1662 1728 1695 1730 1733 1698 1697 1731 1696 1728 1734 1699 1698 1732 1662 1731 1735 1700 1699 1733 1697 1732 1736 1701 1700 1734 1698 1733 1737 1702 1701 1735 1699 1734 1738 1705 1702 1700 1735 1736 1672 1739 519 1701 1736 1737 1706 1703 1739 1702 1737 1738 1672 1640 1706 1705 1738 1704 1708 505 1640 1739 1703 1704 1740 1741 1712 1672 1706 1739 1742 1743 1709 1712 1544 1743 512 1709 1673 1708 511 505 1712 1744 1543 1709 512 1742 1743 1740 1712 1709 1743 1544 1745 1675 1710 1745 1746 1675 499 1711 498 1744 1710 1711 1677 1675 1746 1715 1585 1582 1649 1617 1618 435 437 426 417 403 1679 1582 1747 1715 1748 1716 405 1715 1747 413 1749 1717 1716 413 416 417 1750 1718 1717 416 1748 405 1751 1719 1718 1716 1748 1749 1752 1720 1719 1749 1750 1717 1753 1721 1720 1718 1750 1751 1754 1722 1721 1751 1752 1719 390 1723 1722 1720 1752 1753 1755 1724 1723 1721 1753 1754 1756 1725 1724 1754 390 1722 1689 1726 1725 1723 390 1755 1757 1727 1726 1724 1755 1756 1758 1693 1727 1725 1756 1689 1759 1730 1693 1726 1689 1757 1760 1762 1761 1727 1757 1758 1760 1731 1728 1693 1758 1759 1763 1732 1731 1730 1759 1729 1764 1733 1732 1728 1729 1760 1765 1734 1733 1731 1760 1763 1766 1735 1734 1764 1732 1763 1767 1736 1735 1765 1733 1764 1768 1737 1736 1766 1734 1765 1769 1738 1737 1767 1735 1766 1770 1704 1738 1768 1736 1767 1771 1739 1704 1737 1768 1769 225 227 533 1738 1769 1770 517 1708 1672 1704 1770 1771 1772 1774 1773 519 1739 1771 524 1775 1742 1775 1740 1743 511 1742 512 1708 517 1707 1776 1740 1775 511 524 1742 1744 1777 1710 1743 1742 1775 1778 1710 1777 1710 1778 1779 1543 1744 1711 1741 1777 1744 1745 1710 1779 1747 1582 1617 1780 1650 1651 1650 1780 427 413 417 1715 1781 1747 1617 416 414 1782 413 1747 415 1748 1782 1783 413 414 416 1749 1783 1784 1748 416 1782 1750 1784 1785 1748 1783 1749 1751 1785 1786 1750 1749 1784 1752 1786 1787 1750 1785 1751 1753 1787 394 1752 1751 1786 1754 394 389 1752 1787 1753 1788 1790 1789 1754 1753 394 1755 388 1791 390 1754 389 1756 1791 1688 390 388 1755 1792 1794 1793 1756 1755 1791 1757 1687 1794 1689 1756 1688 1758 1794 1795 1757 1689 1687 1759 1795 1796 1794 1758 1757 1729 1796 1762 1759 1758 1795 1797 1763 1761 1729 1759 1796 1797 1798 1764 1760 1729 1762 1798 1799 1765 1763 1760 1761 1799 1800 1766 1764 1763 1797 1800 1801 1767 1765 1764 1798 1801 1802 1768 1766 1765 1799 1803 1805 1804 1767 1766 1800 1769 1802 1805 1768 1767 1801 1770 1805 1806 1769 1768 1802 1771 1806 1807 1805 1770 1769 519 1807 518 1771 1770 1806 517 518 1808 1771 1807 519 1707 1808 523 1776 1775 521 1707 524 511 517 1808 1707 1776 1809 1740 524 1707 523 521 522 1776 1775 524 521 1741 1810 1777 1777 1812 1811 1712 1741 1744 1809 1810 1741 1778 1777 1811 1650 1781 1617 429 427 1780 415 1814 1813 1781 415 1747 1650 1815 1781 1813 1816 414 1781 1814 415 1816 409 1782 414 415 1813 409 1817 1783 414 1816 1782 1817 408 1784 1783 1782 409 408 1818 1785 1784 1783 1817 1818 397 1786 1785 1784 408 397 393 1787 1785 1818 1786 1819 1821 1820 1787 1786 397 392 1822 389 394 1787 393 1822 1823 388 389 394 392 1823 1788 1791 388 389 1822 1788 1824 1688 1823 1791 388 1824 1793 1687 1688 1791 1788 1825 1827 1826 1687 1688 1824 1792 1825 1795 1794 1687 1793 1825 1828 1796 1792 1795 1794 1828 1829 1762 1825 1796 1795 1829 1830 1761 1828 1762 1796 1830 1831 1797 1829 1761 1762 1831 1832 1798 1830 1797 1761 1832 1833 1799 1831 1798 1797 1833 1834 1800 1832 1799 1798 1834 1835 1801 1833 1800 1799 1835 1804 1802 1801 1800 1834 1836 1806 1803 1802 1801 1835 1837 1839 1838 1805 1802 1804 1836 1840 1807 1803 1806 1805 1840 1841 518 1807 1806 1836 1841 525 1808 1840 518 1807 1776 522 1842 1841 1808 518 528 522 520 525 523 1808 1809 1843 1810 521 523 520 1844 1810 1843 1810 1812 1777 1740 1809 1741 1809 1842 1843 1844 1812 1810 1815 1650 427 441 428 1714 1845 1846 1814 1815 1814 1781 1815 427 1847 1813 1846 1848 1814 1815 1845 1848 411 1816 1813 1814 1846 1849 1851 1850 1816 1813 1848 1817 410 407 409 1816 411 1852 1854 1853 1817 409 410 406 396 1818 408 1817 407 1855 1857 1856 1818 408 406 398 1858 393 396 397 1818 392 1858 1859 393 397 398 1859 1820 1822 1858 392 393 1823 1820 1790 1822 392 1859 1860 1862 1861 1823 1822 1820 1789 1860 1824 1790 1788 1823 1860 1863 1793 1789 1824 1788 1792 1863 1827 1793 1824 1860 1864 1828 1826 1792 1793 1863 1865 1829 1864 1827 1825 1792 1866 1830 1865 1826 1828 1825 1867 1831 1866 1864 1829 1828 1868 1832 1867 1865 1830 1829 1869 1871 1870 1866 1831 1830 1868 1869 1833 1867 1832 1831 1869 1872 1834 1868 1833 1832 1872 1873 1835 1869 1834 1833 1873 1874 1804 1872 1835 1834 1803 1874 1875 1873 1804 1835 1836 1875 1876 1803 1804 1874 1876 1877 1840 1875 1836 1803 1841 1877 1878 1840 1836 1876 1878 529 525 1840 1877 1841 528 1879 522 1841 1878 525 528 529 527 529 520 525 1842 1880 1843 1843 1882 1881 1776 1842 1809 1879 1880 1842 1844 1843 1881 428 1847 427 434 433 441 1845 1884 1883 1847 1845 1815 1847 428 1885 1846 1883 1886 1884 1845 1847 1848 1886 1887 1846 1845 1883 411 1887 1888 1886 1848 1846 410 1888 1889 411 1848 1887 407 1889 1890 1888 410 411 406 1890 1891 407 410 1889 396 1891 1892 1890 406 407 398 1892 1893 396 406 1891 1858 1893 1894 1892 398 396 1859 1894 1819 1858 398 1893 1895 1897 1896 1894 1859 1858 1790 1821 1898 1819 1820 1859 1789 1898 1862 1790 1820 1821 1899 1901 1900 1898 1789 1790 1861 1899 1863 1862 1860 1789 1827 1899 1902 1861 1863 1860 1826 1902 1903 1899 1827 1863 1864 1903 1904 1827 1902 1826 1865 1904 1905 1826 1903 1864 1866 1905 1906 1864 1904 1865 1867 1906 1907 1865 1905 1866 1868 1907 1871 1906 1867 1866 1908 1872 1870 1907 1868 1867 1909 1873 1908 1871 1869 1868 1910 1874 1909 1870 1872 1869 1911 1913 1912 1908 1873 1872 1875 1910 1911 1909 1874 1873 1876 1911 1914 1875 1874 1910 1914 1915 1877 1911 1876 1875 1878 1915 1916 1877 1876 1914 529 1916 527 1877 1915 1878 1879 530 1880 529 1878 1916 1917 1880 530 1880 1882 1843 522 1879 1842 1879 526 530 1917 1882 1880 433 1885 428 1918 424 434 1884 1920 1919 1885 1884 1847 1921 1885 433 1883 1919 422 1884 1885 1920 1886 422 423 1919 1883 1884 1887 423 419 422 1886 1883 1888 419 420 423 1887 1886 1889 420 1851 419 1888 1887 1890 1851 1849 420 1889 1888 1891 1849 1854 1851 1890 1889 1892 1854 1852 1849 1891 1890 1893 1852 1855 1854 1892 1891 1894 1855 1856 1852 1893 1892 1819 1856 1922 1855 1894 1893 1821 1922 1897 1856 1819 1894 1898 1897 1895 1922 1821 1819 1862 1895 1923 1897 1898 1821 1861 1923 1901 1895 1862 1898 1924 1902 1900 1923 1861 1862 1924 1926 1925 1901 1899 1861 1903 1924 1925 1900 1902 1899 1904 1925 1927 1924 1903 1902 1905 1927 1928 1903 1925 1904 1906 1928 1929 1904 1927 1905 1907 1929 1930 1905 1928 1906 1871 1930 1931 1906 1929 1907 1870 1931 1932 1907 1930 1871 1908 1932 1933 1871 1931 1870 1909 1933 1934 1870 1932 1908 1910 1934 1913 1933 1909 1908 1935 1936 219 1934 1910 1909 1914 1912 1838 1911 1910 1913 1915 1838 1839 1912 1914 1911 1916 1839 1774 1915 1914 1838 527 1774 532 1915 1839 1916 527 1916 1774 531 1937 530 528 526 1879 526 532 531 1917 530 1937 424 1921 433 426 1918 1938 432 1920 1921 1921 1920 1885 425 432 1921 430 1919 1920 432 430 1920 1939 422 1919 430 1939 1919 1940 232 145 1939 421 422 1941 419 423 421 1941 423 1942 151 149 1941 418 419 1943 1851 420 418 1943 420 1944 264 268 1943 1850 1851 1945 1854 1849 1850 1945 1849 1946 1947 153 1945 1853 1854 1948 1855 1852 1853 1948 1852 1949 1951 1950 1948 1857 1855 1951 1922 1856 1856 1857 1951 1949 1897 1922 1951 1949 1922 1923 1895 1952 1949 1896 1897 1953 1955 1954 1895 1896 1952 1955 1901 1923 1923 1952 1955 1953 1900 1901 1901 1955 1953 1956 1924 1900 1953 1956 1900 1927 1925 1957 1956 1926 1924 1928 1927 1958 1926 1957 1925 1929 1928 1959 1957 1958 1927 1930 1929 1960 1958 1959 1928 1931 1930 1961 1959 1960 1929 1932 1931 1962 1960 1961 1930 1933 1932 1963 1961 1962 1931 1964 1966 1965 1932 1962 1963 1966 1934 1933 1933 1963 1966 1964 1913 1934 1934 1966 1964 1967 1912 1913 1964 1967 1913 1968 1838 1912 1967 1968 1912 1969 221 223 1968 1837 1838 1773 1774 1839 1837 1773 1839 532 1774 1772 531 486 1970 527 532 526 532 1772 485 1937 531 1970 1918 426 424 435 1938 438 432 425 436 424 425 1921 437 436 425 241 236 139 432 436 431 139 1939 430 431 139 430 421 1939 140 1939 139 140 1971 1941 421 421 140 1971 418 1941 1940 1941 1971 1940 1972 1943 418 418 1940 1972 1850 1943 1942 1943 1972 1942 1973 1945 1850 1850 1942 1973 1853 1945 1944 1945 1973 1944 1947 1948 1853 1944 1947 1853 1857 1948 1946 1948 1947 1946 1974 1951 1857 1946 1974 1857 1950 162 1975 1951 1974 1950 1896 1949 1975 1949 1950 1975 1976 1952 1896 1896 1975 1976 1977 1955 1952 1952 1976 1977 1954 177 1978 1955 1977 1954 1956 1953 1978 1953 1954 1978 1926 1956 1979 1956 1978 1979 1957 1926 1980 1926 1979 1980 1958 1957 1981 1957 1980 1981 1959 1958 1982 1958 1981 1982 1960 1959 1983 1959 1982 1983 1961 1960 1984 1960 1983 1984 1962 1961 1985 1961 1984 1985 1986 1963 1962 1962 1985 1986 1987 1966 1963 1986 1987 1963 1965 212 1988 1966 1987 1965 1967 1964 1988 1964 1965 1988 1936 1968 1967 1988 1936 1967 1837 1968 1935 1968 1936 1935 1989 1773 1837 1837 1935 1989 1969 1772 1773 1989 1969 1773 485 1772 533 533 1772 1969 486 531 485 1938 435 426 269 435 438 252 437 257 426 437 425 252 436 437 431 248 243 248 431 436 241 431 243 241 139 431 141 139 236 141 233 140 1971 233 231 233 1971 140 232 1971 231 232 1940 1971 1972 145 244 145 1972 1940 151 1972 244 151 1942 1972 1973 149 147 149 1973 1942 264 1973 147 264 1944 1973 268 152 1947 268 1947 1944 153 1947 152 153 156 1946 156 158 1974 156 1974 1946 1950 158 160 158 1950 1974 162 1950 160 162 163 1975 163 164 1976 163 1976 1975 1977 164 167 164 1977 1976 172 1977 167 1977 172 1954 177 1954 172 177 178 1978 1978 178 1979 178 180 1979 180 183 1980 180 1980 1979 183 191 1981 183 1981 1980 191 193 1982 191 1982 1981 193 195 1983 193 1983 1982 195 196 1984 195 1984 1983 196 199 1985 196 1985 1984 199 205 1986 199 1986 1985 205 206 1987 205 1987 1986 1965 206 207 206 1965 1987 212 1965 207 212 214 1988 214 215 1936 214 1936 1988 219 1936 215 219 217 1935 1989 217 220 217 1989 1935 221 1989 220 221 1969 1989 225 1969 223 225 533 1969 533 227 228

-
-
-
- - - - -0.00634989 -0.06435 -0.0304482 -0.00627141 -0.06435 -0.0294549 -0.00634989 -0.05065 -0.0304482 7.77651e-19 -0.06435 -0.0368 7.77651e-19 -0.05065 -0.0368 0.000993594 -0.05065 -0.0367218 -0.00627141 -0.05065 -0.0294549 -0.00603851 -0.06435 -0.028486 -0.00565695 -0.06435 -0.0275656 -0.00603851 -0.05065 -0.028486 -0.00513614 -0.06435 -0.0267163 -0.00565695 -0.05065 -0.0275656 -0.00513614 -0.05065 -0.0267163 -0.00448892 -0.06435 -0.0259589 -0.00373125 -0.06435 -0.025312 -0.00448892 -0.05065 -0.0259589 -0.00288179 -0.06435 -0.0247917 -0.00373125 -0.05065 -0.025312 -0.00288179 -0.05065 -0.0247917 -0.00196146 -0.06435 -0.0244106 -0.000993594 -0.06435 -0.0241782 -0.00196146 -0.05065 -0.0244106 -1.5553e-18 -0.06435 -0.0241 -0.000993594 -0.05065 -0.0241782 -1.5553e-18 -0.05065 -0.0241 -0.00627199 -0.05065 -0.0314417 -0.00603963 -0.05065 -0.0324107 -0.00627199 -0.06435 -0.0314417 -0.0056585 -0.05065 -0.0333315 -0.00603963 -0.06435 -0.0324107 -0.0056585 -0.06435 -0.0333315 -0.00513798 -0.05065 -0.0341814 -0.00449089 -0.05065 -0.0349393 -0.00513798 -0.06435 -0.0341814 -0.00373316 -0.05065 -0.0355867 -0.00449089 -0.06435 -0.0349393 -0.00373316 -0.06435 -0.0355867 -0.00288346 -0.05065 -0.0361076 -0.00196271 -0.05065 -0.0364891 -0.00288346 -0.06435 -0.0361076 -0.000993594 -0.05065 -0.0367218 -0.00196271 -0.06435 -0.0364891 -0.000993594 -0.06435 -0.0367218 0.00196146 -0.06435 -0.0364894 0.000993594 -0.06435 -0.0367218 0.00196146 -0.05065 -0.0364894 0.00448892 -0.06435 -0.0349411 0.00373125 -0.06435 -0.035588 0.00448892 -0.05065 -0.0349411 0.00288179 -0.06435 -0.0361083 0.00288179 -0.05065 -0.0361083 0.00373125 -0.05065 -0.035588 0.00565695 -0.06435 -0.0333344 0.00603851 -0.05065 -0.032414 0.00603851 -0.06435 -0.032414 0.00513614 -0.05065 -0.0341837 0.00565695 -0.05065 -0.0333344 0.00513614 -0.06435 -0.0341837 0.00627199 -0.05065 -0.0294583 0.00627199 -0.06435 -0.0294583 0.00634989 -0.06435 -0.0304518 0.00634989 -0.05065 -0.0304518 0.00627141 -0.06435 -0.0314451 0.00627141 -0.05065 -0.0314451 0.00513798 -0.06435 -0.0267186 0.0056585 -0.06435 -0.0275685 0.00513798 -0.05065 -0.0267186 0.00603963 -0.06435 -0.0284893 0.00603963 -0.05065 -0.0284893 0.0056585 -0.05065 -0.0275685 0.00373316 -0.06435 -0.0253133 0.00449089 -0.06435 -0.0259607 0.00373316 -0.05065 -0.0253133 0.00449089 -0.05065 -0.0259607 0.00288346 -0.05065 -0.0247924 0.00288346 -0.06435 -0.0247924 0.00196271 -0.05065 -0.0244109 0.00196271 -0.06435 -0.0244109 0.000993594 -0.06435 -0.0241782 0.000993594 -0.05065 -0.0241782 0.00344683 -0.06435 -0.0298422 0.00603963 -0.06435 -0.0284893 0.00328892 -0.06435 -0.0292529 -0.000607769 -0.06435 -0.0270032 0 -0.06435 -0.02695 -0.000993594 -0.06435 -0.0241782 0.000993594 -0.06435 -0.0241782 -1.5553e-18 -0.06435 -0.0241 0.00268116 -0.06435 -0.0282002 0.00303109 -0.06435 -0.0287 0.00513798 -0.06435 -0.0267186 0.00288346 -0.06435 -0.0247924 0.00196271 -0.06435 -0.0244109 0.00119707 -0.06435 -0.0271611 0.00175 -0.06435 -0.0274189 0.00373316 -0.06435 -0.0253133 0.00224976 -0.06435 -0.0277688 0.00449089 -0.06435 -0.0259607 0.000607769 -0.06435 -0.0270032 -0.00196146 -0.06435 -0.0244106 -0.00119707 -0.06435 -0.0271611 0.0056585 -0.06435 -0.0275685 -0.00373125 -0.06435 -0.025312 -0.00224976 -0.06435 -0.0277688 -0.00175 -0.06435 -0.0274189 -0.00288179 -0.06435 -0.0247917 -0.00448892 -0.06435 -0.0259589 0.0035 -0.06435 -0.03045 0.00627199 -0.06435 -0.0294583 -0.00268116 -0.06435 -0.0282002 -0.00513614 -0.06435 -0.0267163 0.00627141 -0.06435 -0.0314451 0.00344683 -0.06435 -0.0310578 -0.00565695 -0.06435 -0.0275656 -0.00303109 -0.06435 -0.0287 0.00328892 -0.06435 -0.0316471 0.00565695 -0.06435 -0.0333344 0.00603851 -0.06435 -0.032414 0.00303109 -0.06435 -0.0322 0.00513614 -0.06435 -0.0341837 0.00268116 -0.06435 -0.0326998 0.00224976 -0.06435 -0.0331312 0.00448892 -0.06435 -0.0349411 -0.00328892 -0.06435 -0.0292529 -0.00603851 -0.06435 -0.028486 -0.00627141 -0.06435 -0.0294549 -0.00344683 -0.06435 -0.0298422 -0.0035 -0.06435 -0.03045 -0.00627199 -0.06435 -0.0314417 -0.00344683 -0.06435 -0.0310578 -0.00634989 -0.06435 -0.0304482 -0.00603963 -0.06435 -0.0324107 -0.00328892 -0.06435 -0.0316471 -1.12569e-18 -0.06435 -0.03395 7.77651e-19 -0.06435 -0.0368 0.000993594 -0.06435 -0.0367218 -0.00196271 -0.06435 -0.0364891 -0.000993594 -0.06435 -0.0367218 -0.000607769 -0.06435 -0.0338968 -0.00303109 -0.06435 -0.0322 -0.0056585 -0.06435 -0.0333315 -0.00119707 -0.06435 -0.0337389 -0.00175 -0.06435 -0.0334811 -0.00288346 -0.06435 -0.0361076 -0.00449089 -0.06435 -0.0349393 -0.00373316 -0.06435 -0.0355867 -0.00224976 -0.06435 -0.0331312 0.00634989 -0.06435 -0.0304518 -0.00268116 -0.06435 -0.0326998 -0.00513798 -0.06435 -0.0341814 0.00119707 -0.06435 -0.0337389 0.000607769 -0.06435 -0.0338968 0.00196146 -0.06435 -0.0364894 0.00373125 -0.06435 -0.035588 0.00175 -0.06435 -0.0334811 0.00288179 -0.06435 -0.0361083 -1.5553e-18 -0.05065 -0.0241 0.00603851 -0.05065 -0.032414 0.00565695 -0.05065 -0.0333344 0.00196271 -0.05065 -0.0244109 0.00288346 -0.05065 -0.0247924 0.00634989 -0.05065 -0.0304518 0.00373316 -0.05065 -0.0253133 0.00627199 -0.05065 -0.0294583 0.00627141 -0.05065 -0.0314451 0.0056585 -0.05065 -0.0275685 0.00449089 -0.05065 -0.0259607 0.00513798 -0.05065 -0.0267186 0.00603963 -0.05065 -0.0284893 0.000993594 -0.05065 -0.0241782 -0.000993594 -0.05065 -0.0241782 0.00513614 -0.05065 -0.0341837 -0.00196146 -0.05065 -0.0244106 -0.00288179 -0.05065 -0.0247917 0.00448892 -0.05065 -0.0349411 0.00373125 -0.05065 -0.035588 -0.00373125 -0.05065 -0.025312 0.00288179 -0.05065 -0.0361083 0.00196146 -0.05065 -0.0364894 -0.00448892 -0.05065 -0.0259589 -0.00513614 -0.05065 -0.0267163 0.000993594 -0.05065 -0.0367218 -0.00565695 -0.05065 -0.0275656 -0.00603851 -0.05065 -0.028486 7.77651e-19 -0.05065 -0.0368 -0.00196271 -0.05065 -0.0364891 -0.00288346 -0.05065 -0.0361076 -0.00634989 -0.05065 -0.0304482 -0.000993594 -0.05065 -0.0367218 -0.00627141 -0.05065 -0.0294549 -0.00449089 -0.05065 -0.0349393 -0.00513798 -0.05065 -0.0341814 -0.0056585 -0.05065 -0.0333315 -0.00603963 -0.05065 -0.0324107 -0.00627199 -0.05065 -0.0314417 -0.00373316 -0.05065 -0.0355867 -0.0035 -0.06435 -0.03045 -0.0035 -0.07735 -0.03045 -0.00344683 -0.07735 -0.0298422 4.28626e-19 -0.07735 -0.03395 -1.12569e-18 -0.06435 -0.03395 0.000607769 -0.06435 -0.0338968 -0.00328892 -0.07735 -0.0292529 -0.00344683 -0.06435 -0.0298422 -0.00303109 -0.07735 -0.0287 -0.00328892 -0.06435 -0.0292529 -0.00303109 -0.06435 -0.0287 -0.00268116 -0.07735 -0.0282002 -0.00224976 -0.07735 -0.0277688 -0.00268116 -0.06435 -0.0282002 -0.00175 -0.07735 -0.0274189 -0.00224976 -0.06435 -0.0277688 -0.00175 -0.06435 -0.0274189 -0.00119707 -0.07735 -0.0271611 -0.000607769 -0.07735 -0.0270032 -0.00119707 -0.06435 -0.0271611 -8.57253e-19 -0.07735 -0.02695 -0.000607769 -0.06435 -0.0270032 0 -0.06435 -0.02695 -0.00344683 -0.06435 -0.0310578 -0.00328892 -0.06435 -0.0316471 -0.00344683 -0.07735 -0.0310578 -0.00328892 -0.07735 -0.0316471 -0.00303109 -0.06435 -0.0322 -0.00268116 -0.06435 -0.0326998 -0.00303109 -0.07735 -0.0322 -0.00224976 -0.06435 -0.0331312 -0.00268116 -0.07735 -0.0326998 -0.00224976 -0.07735 -0.0331312 -0.00175 -0.06435 -0.0334811 -0.00119707 -0.06435 -0.0337389 -0.00175 -0.07735 -0.0334811 -0.000607769 -0.06435 -0.0338968 -0.00119707 -0.07735 -0.0337389 -0.000607769 -0.07735 -0.0338968 0.00119707 -0.07735 -0.0337389 0.000607769 -0.07735 -0.0338968 0.00119707 -0.06435 -0.0337389 0.00268116 -0.07735 -0.0326998 0.00224976 -0.07735 -0.0331312 0.00268116 -0.06435 -0.0326998 0.00175 -0.07735 -0.0334811 0.00175 -0.06435 -0.0334811 0.00224976 -0.06435 -0.0331312 0.00328892 -0.07735 -0.0316471 0.00344683 -0.06435 -0.0310578 0.00344683 -0.07735 -0.0310578 0.00303109 -0.06435 -0.0322 0.00328892 -0.06435 -0.0316471 0.00303109 -0.07735 -0.0322 0.00328892 -0.06435 -0.0292529 0.00328892 -0.07735 -0.0292529 0.00344683 -0.07735 -0.0298422 0.00344683 -0.06435 -0.0298422 0.0035 -0.07735 -0.03045 0.0035 -0.06435 -0.03045 0.00224976 -0.07735 -0.0277688 0.00268116 -0.07735 -0.0282002 0.00224976 -0.06435 -0.0277688 0.00303109 -0.07735 -0.0287 0.00303109 -0.06435 -0.0287 0.00268116 -0.06435 -0.0282002 0.00175 -0.06435 -0.0274189 0.00175 -0.07735 -0.0274189 0.00119707 -0.06435 -0.0271611 0.00119707 -0.07735 -0.0271611 0.000607769 -0.07735 -0.0270032 0.000607769 -0.06435 -0.0270032 0.00328892 -0.07735 -0.0316471 -0.00175 -0.07735 -0.0274189 0.00303109 -0.07735 -0.0322 0.00119707 -0.07735 -0.0271611 0.00328892 -0.07735 -0.0292529 0.00303109 -0.07735 -0.0287 0.0035 -0.07735 -0.03045 0.00344683 -0.07735 -0.0298422 -8.57253e-19 -0.07735 -0.02695 0.00344683 -0.07735 -0.0310578 -0.000607769 -0.07735 -0.0270032 -0.00119707 -0.07735 -0.0271611 0.00268116 -0.07735 -0.0282002 0.00175 -0.07735 -0.0274189 0.000607769 -0.07735 -0.0270032 0.00224976 -0.07735 -0.0277688 -0.00224976 -0.07735 -0.0277688 -0.00268116 -0.07735 -0.0282002 0.00268116 -0.07735 -0.0326998 0.00224976 -0.07735 -0.0331312 -0.00303109 -0.07735 -0.0287 0.00175 -0.07735 -0.0334811 -0.00328892 -0.07735 -0.0292529 -0.00344683 -0.07735 -0.0298422 0.00119707 -0.07735 -0.0337389 0.000607769 -0.07735 -0.0338968 -0.0035 -0.07735 -0.03045 -0.00344683 -0.07735 -0.0310578 4.28626e-19 -0.07735 -0.03395 -0.00303109 -0.07735 -0.0322 -0.00268116 -0.07735 -0.0326998 -0.00175 -0.07735 -0.0334811 -0.00328892 -0.07735 -0.0316471 -0.00119707 -0.07735 -0.0337389 -0.000607769 -0.07735 -0.0338968 -0.00224976 -0.07735 -0.0331312 - - - - - - - - - - -1 0 1.19249e-08 -0.987688 0 0.156435 -1 0 1.19249e-08 -8.74228e-08 0 -1 1.50996e-07 0 -1 0.156434 0 -0.987688 -0.987688 0 0.156435 -0.951056 0 0.309017 -0.891007 0 0.45399 -0.951056 0 0.309017 -0.809017 0 0.587785 -0.891006 0 0.453991 -0.809017 0 0.587785 -0.707107 0 0.707107 -0.587785 0 0.809017 -0.707107 0 0.707107 -0.453991 0 0.891007 -0.587785 0 0.809017 -0.453991 0 0.891007 -0.309017 0 0.951057 -0.156434 0 0.987688 -0.309017 0 0.951057 1.74846e-07 0 1 -0.156434 0 0.987688 -3.01992e-07 0 1 -0.987688 0 -0.156435 -0.951057 0 -0.309017 -0.987688 0 -0.156435 -0.891006 0 -0.453991 -0.951056 0 -0.309017 -0.891007 0 -0.45399 -0.809017 0 -0.587785 -0.707107 0 -0.707107 -0.809017 0 -0.587785 -0.587785 0 -0.809017 -0.707107 0 -0.707107 -0.587785 0 -0.809017 -0.453991 0 -0.891006 -0.309017 0 -0.951057 -0.453991 0 -0.891007 -0.156435 0 -0.987688 -0.309017 0 -0.951057 -0.156434 0 -0.987688 0.309017 0 -0.951056 0.156434 0 -0.987688 0.309017 0 -0.951056 0.707107 0 -0.707107 0.587785 0 -0.809017 0.707107 0 -0.707107 0.45399 0 -0.891007 0.453991 0 -0.891006 0.587785 0 -0.809017 0.891007 0 -0.45399 0.951057 0 -0.309017 0.951056 0 -0.309017 0.809017 0 -0.587785 0.891007 0 -0.45399 0.809017 0 -0.587785 0.987688 0 0.156434 0.987688 0 0.156434 1 0 -4.37114e-08 1 0 -4.37114e-08 0.987688 0 -0.156434 0.987688 0 -0.156435 0.809017 0 0.587785 0.891007 0 0.453991 0.809017 0 0.587785 0.951057 0 0.309017 0.951056 0 0.309017 0.891007 0 0.453991 0.587785 0 0.809017 0.707107 0 0.707107 0.587785 0 0.809017 0.707107 0 0.707107 0.453991 0 0.891007 0.453991 0 0.891007 0.309017 0 0.951057 0.309017 0 0.951057 0.156434 0 0.987688 0.156434 0 0.987688 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 1.19249e-08 -1 0 1.19249e-08 -0.984808 0 0.173648 -8.74228e-08 0 -1 -8.74228e-08 0 -1 0.173648 0 -0.984808 -0.939693 0 0.34202 -0.984808 0 0.173648 -0.866025 0 0.5 -0.939693 0 0.34202 -0.866025 0 0.5 -0.766044 0 0.642788 -0.642788 0 0.766044 -0.766044 0 0.642788 -0.5 0 0.866026 -0.642788 0 0.766044 -0.5 0 0.866026 -0.34202 0 0.939693 -0.173648 0 0.984808 -0.34202 0 0.939693 1.74846e-07 0 1 -0.173648 0 0.984808 1.74846e-07 0 1 -0.984808 0 -0.173648 -0.939693 0 -0.34202 -0.984808 0 -0.173648 -0.939692 0 -0.342021 -0.866025 0 -0.5 -0.766045 0 -0.642788 -0.866025 0 -0.5 -0.642788 0 -0.766044 -0.766045 0 -0.642788 -0.642788 0 -0.766044 -0.5 0 -0.866026 -0.34202 0 -0.939693 -0.5 0 -0.866025 -0.173648 0 -0.984808 -0.34202 0 -0.939693 -0.173648 0 -0.984808 0.34202 0 -0.939693 0.173648 0 -0.984808 0.34202 0 -0.939693 0.766044 0 -0.642788 0.642788 0 -0.766044 0.766044 0 -0.642788 0.5 0 -0.866025 0.5 0 -0.866025 0.642788 0 -0.766044 0.939693 0 -0.34202 0.984808 0 -0.173648 0.984808 0 -0.173648 0.866025 0 -0.5 0.939693 0 -0.34202 0.866025 0 -0.5 0.939693 0 0.34202 0.939693 0 0.34202 0.984808 0 0.173648 0.984808 0 0.173648 1 0 -4.37114e-08 1 0 7.54979e-08 0.642788 0 0.766044 0.766044 0 0.642788 0.642788 0 0.766044 0.866025 0 0.5 0.866025 0 0.5 0.766044 0 0.642788 0.5 0 0.866025 0.5 0 0.866025 0.34202 0 0.939693 0.34202 0 0.939693 0.173648 0 0.984808 0.173648 0 0.984808 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 - - - - - - - - - - - - - - -

0 1 2 3 4 5 6 1 7 1 6 2 8 9 7 6 7 9 8 10 11 11 9 8 12 10 13 10 12 11 14 15 13 12 13 15 14 16 17 17 15 14 18 16 19 16 18 17 20 21 19 18 19 21 20 22 23 23 21 20 22 24 23 25 0 2 26 27 25 0 25 27 26 28 29 29 27 26 30 28 31 28 30 29 32 33 31 30 31 33 32 34 35 35 33 32 36 34 37 34 36 35 38 39 37 36 37 39 38 40 41 41 39 38 42 40 4 40 42 41 43 44 45 42 4 3 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 72 71 74 75 70 70 72 74 75 76 77 76 75 74 78 77 79 76 79 77 24 22 78 78 79 24 64 66 73 64 73 71 65 67 69 65 69 66 68 59 58 67 59 68 61 60 62 58 60 61 53 63 54 63 62 54 57 56 52 56 53 52 46 48 55 46 55 57 47 49 51 47 51 48 50 43 45 49 43 50 5 44 3 45 44 5 80 81 82 83 84 85 86 87 84 88 89 90 91 92 93 91 94 95 95 96 97 92 86 98 83 99 100 97 88 90 89 82 101 102 103 104 105 104 100 103 102 106 80 107 108 109 106 110 111 107 112 110 113 114 115 116 117 116 118 119 120 121 122 123 113 124 124 125 126 127 128 129 125 130 127 131 132 129 133 134 135 136 137 138 139 132 140 141 142 143 144 145 146 143 136 141 107 111 147 148 149 144 138 141 136 137 133 138 149 148 139 134 133 137 150 151 152 153 154 155 146 145 142 145 143 142 148 144 146 140 149 139 131 140 132 128 131 129 130 128 127 126 125 127 123 124 126 114 113 123 109 110 114 103 106 109 105 102 104 99 105 100 85 99 83 87 85 84 98 86 84 93 92 98 94 91 93 96 95 94 88 97 96 101 90 89 81 101 82 108 81 80 147 108 107 117 111 112 118 116 115 115 117 112 120 119 118 121 153 122 120 122 119 154 150 155 121 154 153 152 151 135 155 150 152 133 135 151 156 157 158 159 160 161 162 163 160 159 161 164 165 166 167 168 166 165 163 162 168 162 166 168 169 159 164 160 163 161 157 169 164 170 156 158 156 169 157 171 172 170 170 158 171 173 172 174 171 174 172 173 175 176 175 173 174 176 175 177 178 179 177 176 177 179 178 180 179 181 182 180 180 178 181 183 182 184 181 184 182 185 186 187 183 188 189 190 191 192 193 194 195 190 193 195 193 190 192 194 187 186 194 186 195 189 188 185 189 185 187 188 183 184 196 197 198 199 200 201 202 203 198 196 198 203 202 204 205 205 203 202 206 204 207 204 206 205 208 209 207 206 207 209 208 210 211 211 209 208 212 210 213 210 212 211 214 215 213 212 213 215 214 216 217 217 215 214 216 218 217 219 197 196 219 220 221 221 197 219 222 220 223 220 222 221 224 225 223 222 223 225 224 226 227 227 225 224 228 226 229 226 228 227 230 231 229 228 229 231 230 232 233 233 231 230 234 232 200 232 234 233 235 236 237 234 200 199 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 256 256 258 262 263 264 265 264 263 262 266 265 267 264 267 265 218 216 266 266 267 218 261 257 259 257 261 258 260 251 250 259 251 260 253 252 254 250 252 253 245 255 246 255 254 246 249 248 244 248 245 244 238 240 247 238 247 249 239 241 243 239 243 240 242 235 237 241 235 242 201 236 199 237 236 201 268 269 270 271 272 273 274 275 276 277 278 279 280 281 273 271 282 272 273 281 271 283 281 280 275 272 282 278 274 276 276 275 282 279 268 277 278 277 274 269 284 270 279 269 268 285 286 284 270 284 286 287 286 285 287 288 289 288 287 285 288 290 289 290 291 292 292 289 290 293 291 294 291 293 292 295 296 294 293 294 296 297 298 299 300 301 302 301 297 299 298 303 299 302 295 300 301 300 297 295 302 296

-
-
-
- - - - 0.0513252 -0.00578297 0.0338 0.0515687 -0.00289604 0.0338 0.0339214 0.00194938 0.0338 0.00372053 0.0171267 0.0338 0.00428573 0.0167052 0.0338 0.0142518 0.0181966 0.0338 0.0142986 0.0496314 0.0338 0.0114932 0.050355 0.0338 0.00244698 0.0177212 0.0338 0.00310238 0.0174627 0.0338 0.0086517 0.0509202 0.0338 0.0170589 0.0487516 0.0338 0.00176856 0.0179122 0.0338 0.0197656 0.0477184 0.0338 0.00578297 0.0513252 0.0338 0.00477383 0.0161967 0.0338 0.00107681 0.0180466 0.0338 -0.00363413 0 0.0338 0.000937106 0.00737202 0.0338 0.000133051 0.00724719 0.0338 0.00289604 0.0515687 0.0338 0.0249841 0.0452053 0.0338 0.0224101 0.046535 0.0338 0.0159922 0.0181966 0.0338 0.00037774 0.0181339 0.0338 0.0094368 0.0144728 0.0338 -3.16265e-18 0.05165 0.0338 -0.000325052 0.0181818 0.0338 0.00516655 0.0156121 0.0338 -0.00102951 0.0181966 0.0338 0.0252099 0.015799 0.0338 0.0259604 0.0166107 0.0338 -0.00289604 0.0515687 0.0338 0.0241523 0.0139831 0.0338 0.0246228 0.0149221 0.0338 -0.00578297 0.0513252 0.0338 0.00545697 0.0149713 0.0338 -0.0086517 0.0509202 0.0338 -0.0057489 0.0181966 0.0338 0.0261292 0.0136399 0.0338 0.0258488 0.0129341 0.0338 0.0281571 0.0111636 0.0338 -0.0142986 0.0496314 0.0338 -0.0170589 0.0487516 0.0338 0.0234688 0.00468321 0.0338 0.0159922 0 0.0338 0.0237765 0.0036897 0.0338 -0.0249841 0.0452053 0.0338 -0.0274795 0.0437333 0.0338 -0.0189791 0.0181966 0.0338 0.00495061 0.00977776 0.0338 0.013977 0 0.0338 0.010532 0.013055 0.0338 0.0322939 0.000471276 0.0338 0.050355 -0.0114932 0.0338 0.0329013 0.000877502 0.0338 -0.0214802 0.0181966 0.0338 -0.0298884 0.0421237 0.0338 -0.0237543 0.0181966 0.0338 0.0301081 -0.000205768 0.0338 0.046535 -0.0224101 0.0338 0.0308973 -7.03595e-05 0.0338 -0.0344168 0.0385124 0.0338 -0.0365221 0.0365221 0.0338 0.0365221 -0.0365221 0.0338 0.0385124 -0.0344168 0.0338 0.00938754 -0.0260201 0.0338 -0.03665 0.0181966 0.0338 -0.0344078 0.0181966 0.0338 -0.0421237 0.0298884 0.0338 -0.0452053 0.0249841 0.0338 -0.046535 0.0224101 0.0338 -0.050355 0.0114932 0.0338 -0.0496314 0.0142986 0.0338 0.0298884 -0.0421237 0.0338 0.00938754 -0.032763 0.0338 0.0274795 -0.0437333 0.0338 -0.0301265 -1.59872e-17 0.0338 -0.0509202 0.0086517 0.0338 -0.0513252 0.00578297 0.0338 0.0197656 -0.0477184 0.0338 0.0224101 -0.046535 0.0338 -0.05165 -1.34493e-17 0.0338 -0.0515687 -0.00289604 0.0338 0.00849321 -0.032763 0.0338 0.0114932 -0.050355 0.0338 -0.050355 -0.0114932 0.0338 -0.0496314 -0.0142986 0.0338 0.00578297 -0.0513252 0.0338 0.0086517 -0.0509202 0.0338 0.00484504 -0.032763 0.0338 -0.0477184 -0.0197656 0.0338 -0.046535 -0.0224101 0.0338 2.95159e-05 -0.032763 0.0338 0.00289604 -0.0515687 0.0338 0.00412043 -0.032763 0.0338 -0.0437333 -0.0274795 0.0338 -0.0280356 0 0.0338 -0.00366973 -0.0299605 0.0338 -0.000754132 -0.032763 0.0338 -0.0033851 -0.0298609 0.0338 -0.0090732 -0.0260201 0.0338 -0.0365221 -0.0365221 0.0338 -0.0344168 -0.0385124 0.0338 -0.00311413 -0.0297284 0.0338 -0.0224101 -0.046535 0.0338 -0.0090732 -0.032763 0.0338 -0.0249841 -0.0452053 0.0338 -0.0322032 -0.0403816 0.0338 -0.0298884 -0.0421237 0.0338 -0.00239555 -0.0269778 0.0338 -0.00228793 -0.0272153 0.0338 -0.000754132 -0.0260201 0.0338 -0.00565673 -0.032763 0.0338 -0.00644038 -0.032763 0.0338 -0.00578297 -0.0513252 0.0338 -0.0421237 -0.0298884 0.0338 -0.0403816 -0.0322032 0.0338 -0.00265026 -0.0293629 0.0338 -0.00286378 -0.0295598 0.0338 -0.0452053 -0.0249841 0.0338 0.00482659 -0.0280593 0.0338 0.00480815 -0.0271048 0.0338 0.00477125 -0.0271048 0.0338 -0.0487516 -0.0170589 0.0338 -0.0509202 -0.0086517 0.0338 -0.0513252 -0.00578297 0.0338 -0.0515687 0.00289604 0.0338 0.0142986 -0.0496314 0.0338 0.0170589 -0.0487516 0.0338 0.0249841 -0.0452053 0.0338 -0.0487516 0.0170589 0.0338 9.48795e-18 -0.05165 0.0338 -0.0477184 0.0197656 0.0338 -0.0437333 0.0274795 0.0338 0.0344168 -0.0385124 0.0338 0.0403816 -0.0322032 0.0338 -0.0403816 0.0322032 0.0338 0.0421237 -0.0298884 0.0338 0.0487516 -0.0170589 0.0338 0.0316259 0.000155322 0.0338 -0.0385124 0.0344168 0.0338 -0.0322032 0.0403816 0.0338 0.0496314 -0.0142986 0.0338 0.0509202 -0.0086517 0.0338 0.033448 0.001374 0.0338 -0.0274795 -0.0437333 0.0338 0.05165 3.16265e-18 0.0338 0.0343087 0.00259224 0.0338 -0.0168644 0.0181966 0.0338 0.0335854 0.00985697 0.0338 0.0340936 0.00922214 0.0338 0.0335914 0.0164402 0.0338 0.00531729 0.0104509 0.0338 0.0055792 0.0111949 0.0338 -0.0114932 0.050355 0.0338 0.00573635 0.0120098 0.0338 0.00578873 0.0128957 0.0338 0.0322032 -0.0403816 0.0338 -0.0197656 0.0477184 0.0338 -0.0224101 0.046535 0.0338 0.0298884 0.0421237 0.0338 0.0274795 0.0437333 0.0338 -0.00396281 -0.0300312 0.0338 -0.00426076 -0.0300775 0.0338 -0.030226 0.00642396 0.0338 -0.0297787 0.0050827 0.0338 -0.0283626 0.00515881 0.0338 -0.0279121 0.00649564 0.0338 -0.0287529 0.00381933 0.0338 -0.0293977 0.00376711 0.0338 -0.029083 0.00247719 0.0338 -0.00233969 -0.0288903 0.0338 -0.00224264 -0.0286146 0.0338 0.0513252 0.00578297 0.0338 0.0349542 0.00492572 0.0338 0.0515687 0.00289604 0.0338 -0.00828955 -0.032763 0.0338 -0.0114932 -0.050355 0.0338 -0.0086517 -0.0509202 0.0338 -0.0142986 -0.0496314 0.0338 -0.00289604 -0.0515687 0.0338 0.00484504 -0.0289304 0.0338 0.0477184 -0.0197656 0.0338 0.0509202 0.0086517 0.0338 0.0349407 0.00681107 0.0338 0.0349972 0.00583851 0.0338 0.00871901 -0.0316562 0.0338 0.00867769 -0.0308563 0.0338 0.00868211 -0.0316562 0.0338 0.00865407 -0.0298896 0.0338 0.0050059 -0.0260201 0.0338 0.00865407 -0.0260201 0.0338 0.032986 0.018351 0.0338 0.0421237 0.0298884 0.0338 0.0403816 0.0322032 0.0338 -0.0189791 0 0.0338 0.0277942 0.0177913 0.0338 0.0268218 0.0172748 0.0338 0.00575703 0.0135997 0.0338 0.00564964 0.0142947 0.0338 0.0237932 0.01299 0.0338 0.0140019 0.0145435 0.0338 0.0134931 0.0154824 0.0338 0.0254737 0.0114624 0.0338 0.0263001 0.0102453 0.0338 0.0268541 0.0106389 0.0338 0.0385124 0.0344168 0.0338 0.0322479 0.0184293 0.0338 0.0297203 0.0113385 0.0338 0.0305091 0.0112973 0.0338 0.0296032 0.0165484 0.0338 0.0477184 0.0197656 0.0338 0.046535 0.0224101 0.0338 0.0335914 0.0182205 0.0338 0.013977 0.0129674 0.0338 0.0487516 0.0170589 0.0338 0.0496314 0.0142986 0.0338 0.034489 0.00850288 0.0338 0.0437333 -0.0274795 0.0338 0.0452053 -0.0249841 0.0338 0.0292583 -0.000250905 0.0338 0.0347713 0.00769919 0.0338 0.050355 0.0114932 0.0338 0.00390296 0.00864426 0.0338 0.00322738 0.00818929 0.0338 0.00447917 0.00917555 0.0338 0.00249613 0.0078317 0.0338 0.00172803 0.00756305 0.0338 -0.000677562 0.00717761 0.0338 -0.00149149 0.00715676 0.0338 -0.00363413 0.00715676 0.0338 0.00412043 -0.0260201 0.0338 -0.0057489 0 0.0338 -0.00469156 -0.0260201 0.0338 -0.00443052 -0.0260256 0.0338 -0.0385124 -0.0344168 0.0338 -0.00417009 -0.0260433 0.0338 -0.00391104 -0.0260757 0.0338 -0.00365471 -0.0261255 0.0338 -0.00340331 -0.0261963 0.0338 -0.00316045 -0.026292 0.0338 -0.00293139 -0.0264165 0.0338 -0.00272195 -0.0265727 0.0338 -0.00254107 -0.0267612 0.0338 -0.00456114 -0.0301033 0.0338 -0.00217674 -0.0277235 0.0338 -0.00221653 -0.027466 0.0338 -0.00216499 -0.0279844 0.0338 -0.0021844 -0.0283127 0.0338 -0.00247557 -0.0291398 0.0338 -0.00486275 -0.030111 0.0338 -0.0170589 -0.0487516 0.0338 -0.0197656 -0.0477184 0.0338 -0.00565673 -0.030111 0.0338 -0.00644038 -0.0260201 0.0338 -0.00883543 0.00191564 0.0338 -0.00883543 0 0.0338 -0.0168644 0.00191564 0.0338 0.023213 0.00988515 0.0338 0.0231455 0.0088326 0.0338 0.0253597 0.010711 0.0338 0.0346099 0.00330258 0.0338 0.0140765 0.01603 0.0338 -0.00828955 -0.0260201 0.0338 0.00300472 -0.0260201 0.0338 0.00300472 -0.0267167 0.0338 2.95159e-05 -0.0291842 0.0338 0.00282468 -0.0291842 0.0338 2.95159e-05 -0.0267167 0.0338 0.00282468 -0.0298808 0.0338 2.95159e-05 -0.0298808 0.0338 0.0329214 0.0166128 0.0338 0.0312401 0.0111739 0.0338 0.0319132 0.0109681 0.0338 0.0325284 0.01068 0.0338 0.0242092 0.00274331 0.0338 0.0247798 0.00187183 0.0338 0.0258111 0.00976431 0.0338 0.0252826 0.0099551 0.0338 0.0253872 0.00919585 0.0338 0.0232688 0.00570376 0.0338 0.0231577 0.0067375 0.0338 0.0365221 0.0365221 0.0338 0.031377 0.0184554 0.0338 0.023125 0.00777804 0.0338 0.0274833 0.0154856 0.0338 0.0269304 0.0149288 0.0338 0.0289062 0.0112948 0.0338 0.0344168 0.0385124 0.0338 0.0300718 0.0183816 0.0338 0.0256329 0.0122059 0.0338 0.0288775 0.0181603 0.0338 0.0235274 0.0119686 0.0338 0.0233365 0.0109325 0.0338 0.0274731 0.010945 0.0338 0.0322032 0.0403816 0.0338 0.0264858 0.0143109 0.0338 0.0452053 0.0249841 0.0338 0.0437333 0.0274795 0.0338 0.028113 0.0159411 0.0338 0.0252398 0.00919585 0.0338 0.0288197 0.0162954 0.0338 0.0314009 0.0167509 0.0338 0.0304636 0.0167003 0.0338 0.0330858 0.0103097 0.0338 0.0321912 0.0167164 0.0338 0.0348251 0.00408041 0.0338 0.0283495 -0.00019194 0.0338 0.0275057 -1.50454e-05 0.0338 0.0267268 0.000279779 0.0338 0.0253639 0.00122322 0.0338 0.0260129 0.000692532 0.0338 -2.93915e-18 0.048 0.019 2.93915e-18 0.048 0.0318 -0.00279095 0.0479188 0.019 0.0479188 -0.00279095 0.0318 0.048 5.8783e-18 0.0318 0.048 5.8783e-18 0.019 -0.00279095 0.0479188 0.0318 -0.00557246 0.0476754 0.019 -0.00833511 0.0472708 0.019 -0.00557246 0.0476754 0.0318 -0.00833511 0.0472708 0.0318 -0.0110696 0.0467062 0.019 -0.0110696 0.0467062 0.0318 -0.0137666 0.0459835 0.019 -0.016417 0.0451052 0.019 -0.0137666 0.0459835 0.0318 -0.016417 0.0451052 0.0318 -0.0190118 0.0440744 0.019 -0.0190118 0.0440744 0.0318 -0.0215424 0.0428944 0.019 -0.024 0.0415692 0.019 -0.0215424 0.0428944 0.0318 -0.024 0.0415692 0.0318 -0.0263764 0.0401034 0.019 -0.0263764 0.0401034 0.0318 -0.0286636 0.0385019 0.019 -0.0308538 0.0367701 0.019 -0.0286636 0.0385019 0.0318 -0.0308538 0.0367701 0.0318 -0.0329396 0.0349139 0.019 -0.0329396 0.0349139 0.0318 -0.0349139 0.0329396 0.019 -0.0367701 0.0308538 0.019 -0.0349139 0.0329396 0.0318 -0.0367701 0.0308538 0.0318 -0.0385019 0.0286636 0.019 -0.0385019 0.0286636 0.0318 -0.0401034 0.0263764 0.019 -0.0415692 0.024 0.019 -0.0401034 0.0263764 0.0318 -0.0415692 0.024 0.0318 -0.0428944 0.0215424 0.019 -0.0428944 0.0215424 0.0318 -0.0440744 0.0190118 0.019 -0.0451052 0.016417 0.019 -0.0440744 0.0190118 0.0318 -0.0451052 0.016417 0.0318 -0.0459835 0.0137666 0.019 -0.0459835 0.0137666 0.0318 -0.0467062 0.0110696 0.019 -0.0472708 0.00833511 0.019 -0.0467062 0.0110696 0.0318 -0.0472708 0.00833511 0.0318 -0.0476754 0.00557246 0.019 -0.0476754 0.00557246 0.0318 -0.0479188 0.00279095 0.019 -0.048 0 0.019 -0.0479188 0.00279095 0.0318 -0.048 0 0.0318 0.00279095 0.0479188 0.0318 0.00279095 0.0479188 0.019 0.00557246 0.0476754 0.0318 0.00557246 0.0476754 0.019 0.00833511 0.0472708 0.0318 0.0110696 0.0467062 0.0318 0.00833511 0.0472708 0.019 0.0110696 0.0467062 0.019 0.0137666 0.0459835 0.0318 0.0137666 0.0459835 0.019 0.016417 0.0451052 0.0318 0.0190118 0.0440744 0.0318 0.016417 0.0451052 0.019 0.0190118 0.0440744 0.019 0.0215424 0.0428944 0.0318 0.0215424 0.0428944 0.019 0.024 0.0415692 0.0318 0.0263764 0.0401034 0.0318 0.024 0.0415692 0.019 0.0263764 0.0401034 0.019 0.0286636 0.0385019 0.0318 0.0286636 0.0385019 0.019 0.0308538 0.0367701 0.0318 0.0329396 0.0349139 0.0318 0.0308538 0.0367701 0.019 0.0329396 0.0349139 0.019 0.0349139 0.0329396 0.0318 0.0349139 0.0329396 0.019 0.0367701 0.0308538 0.0318 0.0385019 0.0286636 0.0318 0.0367701 0.0308538 0.019 0.0385019 0.0286636 0.019 0.0401034 0.0263764 0.0318 0.0401034 0.0263764 0.019 0.0415692 0.024 0.0318 0.0428944 0.0215424 0.0318 0.0415692 0.024 0.019 0.0428944 0.0215424 0.019 0.0440744 0.0190118 0.0318 0.0440744 0.0190118 0.019 0.0451052 0.016417 0.0318 0.0459835 0.0137666 0.0318 0.0451052 0.016417 0.019 0.0459835 0.0137666 0.019 0.0467062 0.0110696 0.0318 0.0467062 0.0110696 0.019 0.0472708 0.00833511 0.0318 0.0476754 0.00557246 0.0318 0.0472708 0.00833511 0.019 0.0476754 0.00557246 0.019 0.0479188 0.00279095 0.0318 0.0479188 0.00279095 0.019 0.0467062 -0.0110696 0.0318 0.0472708 -0.00833511 0.0318 0.0472708 -0.00833511 0.019 0.0476754 -0.00557246 0.0318 0.0479188 -0.00279095 0.019 0.0476754 -0.00557246 0.019 0.0451052 -0.016417 0.019 0.0440744 -0.0190118 0.0318 0.0451052 -0.016417 0.0318 0.0467062 -0.0110696 0.019 0.0459835 -0.0137666 0.019 0.0459835 -0.0137666 0.0318 0.0415692 -0.024 0.0318 0.0415692 -0.024 0.019 0.0401034 -0.0263764 0.0318 0.0428944 -0.0215424 0.0318 0.0440744 -0.0190118 0.019 0.0428944 -0.0215424 0.019 0.0349139 -0.0329396 0.0318 0.0367701 -0.0308538 0.0318 0.0367701 -0.0308538 0.019 0.0385019 -0.0286636 0.019 0.0385019 -0.0286636 0.0318 0.0401034 -0.0263764 0.019 0.0308538 -0.0367701 0.019 0.0286636 -0.0385019 0.0318 0.0308538 -0.0367701 0.0318 0.0349139 -0.0329396 0.019 0.0329396 -0.0349139 0.019 0.0329396 -0.0349139 0.0318 0.024 -0.0415692 0.0318 0.024 -0.0415692 0.019 0.0215424 -0.0428944 0.0318 0.0263764 -0.0401034 0.0318 0.0286636 -0.0385019 0.019 0.0263764 -0.0401034 0.019 0.0137666 -0.0459835 0.0318 0.016417 -0.0451052 0.0318 0.016417 -0.0451052 0.019 0.0190118 -0.0440744 0.019 0.0190118 -0.0440744 0.0318 0.0215424 -0.0428944 0.019 0.00833511 -0.0472708 0.019 0.00557246 -0.0476754 0.0318 0.00833511 -0.0472708 0.0318 0.0137666 -0.0459835 0.019 0.0110696 -0.0467062 0.019 0.0110696 -0.0467062 0.0318 -1.88907e-16 -0.048 0.0318 8.81746e-18 -0.048 0.019 -0.00279095 -0.0479188 0.0318 0.00279095 -0.0479188 0.0318 0.00557246 -0.0476754 0.019 0.00279095 -0.0479188 0.019 -0.0110696 -0.0467062 0.0318 -0.00833511 -0.0472708 0.0318 -0.00833511 -0.0472708 0.019 -0.00557246 -0.0476754 0.019 -0.00557246 -0.0476754 0.0318 -0.00279095 -0.0479188 0.019 -0.016417 -0.0451052 0.019 -0.0190118 -0.0440744 0.0318 -0.016417 -0.0451052 0.0318 -0.0110696 -0.0467062 0.019 -0.0137666 -0.0459835 0.019 -0.0137666 -0.0459835 0.0318 -0.024 -0.0415692 0.0318 -0.024 -0.0415692 0.019 -0.0263764 -0.0401034 0.0318 -0.0215424 -0.0428944 0.0318 -0.0190118 -0.0440744 0.019 -0.0215424 -0.0428944 0.019 -0.0329396 -0.0349139 0.0318 -0.0308538 -0.0367701 0.0318 -0.0308538 -0.0367701 0.019 -0.0286636 -0.0385019 0.019 -0.0286636 -0.0385019 0.0318 -0.0263764 -0.0401034 0.019 -0.0367701 -0.0308538 0.0318 -0.0349139 -0.0329396 0.0318 -0.0349139 -0.0329396 0.019 -0.0329396 -0.0349139 0.019 -0.0367701 -0.0308538 0.019 -0.0385019 -0.0286636 0.0318 -0.0385019 -0.0286636 0.019 -0.0401034 -0.0263764 0.0318 -0.0415692 -0.024 0.0318 -0.0401034 -0.0263764 0.019 -0.0415692 -0.024 0.019 -0.0428944 -0.0215424 0.0318 -0.0428944 -0.0215424 0.019 -0.0440744 -0.0190118 0.0318 -0.0451052 -0.016417 0.0318 -0.0440744 -0.0190118 0.019 -0.0451052 -0.016417 0.019 -0.0459835 -0.0137666 0.0318 -0.0459835 -0.0137666 0.019 -0.0467062 -0.0110696 0.0318 -0.0472708 -0.00833511 0.0318 -0.0467062 -0.0110696 0.019 -0.0472708 -0.00833511 0.019 -0.0476754 -0.00557246 0.0318 -0.0476754 -0.00557246 0.019 -0.0479188 -0.00279095 0.0318 -0.0479188 -0.00279095 0.019 9.48795e-18 -0.05165 0.0338 -0.00289604 -0.0515687 0.0338 3.16265e-18 -0.05165 0.019 0.05165 3.16265e-18 0.0338 0.05165 9.48795e-18 0.019 0.0515687 0.00289604 0.019 -0.00289604 -0.0515687 0.019 -0.00578297 -0.0513252 0.0338 -0.0086517 -0.0509202 0.0338 -0.00578297 -0.0513252 0.019 -0.0114932 -0.050355 0.0338 -0.0086517 -0.0509202 0.019 -0.0114932 -0.050355 0.019 -0.0142986 -0.0496314 0.0338 -0.0170589 -0.0487516 0.0338 -0.0142986 -0.0496314 0.019 -0.0197656 -0.0477184 0.0338 -0.0170589 -0.0487516 0.019 -0.0197656 -0.0477184 0.019 -0.0224101 -0.046535 0.0338 -0.0249841 -0.0452053 0.0338 -0.0224101 -0.046535 0.019 -0.0274795 -0.0437333 0.0338 -0.0249841 -0.0452053 0.019 -0.0274795 -0.0437333 0.019 -0.0298884 -0.0421237 0.0338 -0.0322032 -0.0403816 0.0338 -0.0298884 -0.0421237 0.019 -0.0344168 -0.0385124 0.0338 -0.0322032 -0.0403816 0.019 -0.0344168 -0.0385124 0.019 -0.0365221 -0.0365221 0.0338 -0.0385124 -0.0344168 0.0338 -0.0365221 -0.0365221 0.019 -0.0403816 -0.0322032 0.0338 -0.0385124 -0.0344168 0.019 -0.0403816 -0.0322032 0.019 -0.0421237 -0.0298884 0.0338 -0.0437333 -0.0274795 0.0338 -0.0421237 -0.0298884 0.019 -0.0452053 -0.0249841 0.0338 -0.0437333 -0.0274795 0.019 -0.0452053 -0.0249841 0.019 -0.046535 -0.0224101 0.0338 -0.0477184 -0.0197656 0.0338 -0.046535 -0.0224101 0.019 -0.0487516 -0.0170589 0.0338 -0.0477184 -0.0197656 0.019 -0.0487516 -0.0170589 0.019 -0.0496314 -0.0142986 0.0338 -0.050355 -0.0114932 0.0338 -0.0496314 -0.0142986 0.019 -0.0509202 -0.0086517 0.0338 -0.050355 -0.0114932 0.019 -0.0509202 -0.0086517 0.019 -0.0513252 -0.00578297 0.0338 -0.0515687 -0.00289604 0.0338 -0.0513252 -0.00578297 0.019 -0.05165 -1.34493e-17 0.0338 -0.0515687 -0.00289604 0.019 -0.05165 -9.48795e-18 0.019 0.00289604 -0.0515687 0.019 0.00578297 -0.0513252 0.019 0.00289604 -0.0515687 0.0338 0.0086517 -0.0509202 0.019 0.00578297 -0.0513252 0.0338 0.0086517 -0.0509202 0.0338 0.0114932 -0.050355 0.019 0.0142986 -0.0496314 0.019 0.0114932 -0.050355 0.0338 0.0170589 -0.0487516 0.019 0.0142986 -0.0496314 0.0338 0.0170589 -0.0487516 0.0338 0.0197656 -0.0477184 0.019 0.0224101 -0.046535 0.019 0.0197656 -0.0477184 0.0338 0.0249841 -0.0452053 0.019 0.0224101 -0.046535 0.0338 0.0249841 -0.0452053 0.0338 0.0274795 -0.0437333 0.019 0.0298884 -0.0421237 0.019 0.0274795 -0.0437333 0.0338 0.0322032 -0.0403816 0.019 0.0298884 -0.0421237 0.0338 0.0322032 -0.0403816 0.0338 0.0344168 -0.0385124 0.019 0.0365221 -0.0365221 0.019 0.0344168 -0.0385124 0.0338 0.0385124 -0.0344168 0.019 0.0365221 -0.0365221 0.0338 0.0385124 -0.0344168 0.0338 0.0403816 -0.0322032 0.019 0.0421237 -0.0298884 0.019 0.0403816 -0.0322032 0.0338 0.0437333 -0.0274795 0.019 0.0421237 -0.0298884 0.0338 0.0437333 -0.0274795 0.0338 0.0452053 -0.0249841 0.019 0.046535 -0.0224101 0.019 0.0452053 -0.0249841 0.0338 0.0477184 -0.0197656 0.019 0.046535 -0.0224101 0.0338 0.0477184 -0.0197656 0.0338 0.0487516 -0.0170589 0.019 0.0496314 -0.0142986 0.019 0.0487516 -0.0170589 0.0338 0.050355 -0.0114932 0.019 0.0496314 -0.0142986 0.0338 0.050355 -0.0114932 0.0338 0.0509202 -0.0086517 0.019 0.0513252 -0.00578297 0.019 0.0509202 -0.0086517 0.0338 0.0515687 -0.00289604 0.019 0.0513252 -0.00578297 0.0338 0.0515687 -0.00289604 0.0338 0.0513252 0.00578297 0.0338 0.0515687 0.00289604 0.0338 0.0513252 0.00578297 0.019 0.0496314 0.0142986 0.0338 0.050355 0.0114932 0.0338 0.0496314 0.0142986 0.019 0.0509202 0.0086517 0.0338 0.0509202 0.0086517 0.019 0.050355 0.0114932 0.019 0.0477184 0.0197656 0.0338 0.046535 0.0224101 0.019 0.046535 0.0224101 0.0338 0.0487516 0.0170589 0.019 0.0477184 0.0197656 0.019 0.0487516 0.0170589 0.0338 0.0421237 0.0298884 0.019 0.0421237 0.0298884 0.0338 0.0437333 0.0274795 0.0338 0.0437333 0.0274795 0.019 0.0452053 0.0249841 0.0338 0.0452053 0.0249841 0.019 0.0365221 0.0365221 0.0338 0.0385124 0.0344168 0.0338 0.0365221 0.0365221 0.019 0.0403816 0.0322032 0.0338 0.0403816 0.0322032 0.019 0.0385124 0.0344168 0.019 0.0322032 0.0403816 0.0338 0.0298884 0.0421237 0.019 0.0298884 0.0421237 0.0338 0.0344168 0.0385124 0.019 0.0322032 0.0403816 0.019 0.0344168 0.0385124 0.0338 0.0224101 0.046535 0.019 0.0224101 0.046535 0.0338 0.0249841 0.0452053 0.0338 0.0249841 0.0452053 0.019 0.0274795 0.0437333 0.0338 0.0274795 0.0437333 0.019 0.0142986 0.0496314 0.0338 0.0170589 0.0487516 0.0338 0.0142986 0.0496314 0.019 0.0197656 0.0477184 0.0338 0.0197656 0.0477184 0.019 0.0170589 0.0487516 0.019 0.0086517 0.0509202 0.0338 0.00578297 0.0513252 0.019 0.00578297 0.0513252 0.0338 0.0114932 0.050355 0.019 0.0086517 0.0509202 0.019 0.0114932 0.050355 0.0338 -0.00289604 0.0515687 0.019 -0.00289604 0.0515687 0.0338 -3.16265e-18 0.05165 0.0338 3.16265e-18 0.05165 0.019 0.00289604 0.0515687 0.0338 0.00289604 0.0515687 0.019 -0.0114932 0.050355 0.0338 -0.0086517 0.0509202 0.0338 -0.0114932 0.050355 0.019 -0.00578297 0.0513252 0.0338 -0.00578297 0.0513252 0.019 -0.0086517 0.0509202 0.019 -0.0170589 0.0487516 0.0338 -0.0197656 0.0477184 0.019 -0.0197656 0.0477184 0.0338 -0.0142986 0.0496314 0.019 -0.0170589 0.0487516 0.019 -0.0142986 0.0496314 0.0338 -0.0274795 0.0437333 0.019 -0.0274795 0.0437333 0.0338 -0.0249841 0.0452053 0.0338 -0.0249841 0.0452053 0.019 -0.0224101 0.046535 0.0338 -0.0224101 0.046535 0.019 -0.0344168 0.0385124 0.0338 -0.0322032 0.0403816 0.0338 -0.0344168 0.0385124 0.019 -0.0298884 0.0421237 0.0338 -0.0298884 0.0421237 0.019 -0.0322032 0.0403816 0.019 -0.0385124 0.0344168 0.0338 -0.0365221 0.0365221 0.0338 -0.0385124 0.0344168 0.019 -0.0365221 0.0365221 0.019 -0.0403816 0.0322032 0.019 -0.0403816 0.0322032 0.0338 -0.0421237 0.0298884 0.019 -0.0421237 0.0298884 0.0338 -0.0437333 0.0274795 0.0338 -0.0437333 0.0274795 0.019 -0.0452053 0.0249841 0.019 -0.0452053 0.0249841 0.0338 -0.046535 0.0224101 0.019 -0.046535 0.0224101 0.0338 -0.0477184 0.0197656 0.0338 -0.0477184 0.0197656 0.019 -0.0487516 0.0170589 0.019 -0.0487516 0.0170589 0.0338 -0.0496314 0.0142986 0.019 -0.0496314 0.0142986 0.0338 -0.050355 0.0114932 0.0338 -0.050355 0.0114932 0.019 -0.0509202 0.0086517 0.019 -0.0509202 0.0086517 0.0338 -0.0513252 0.00578297 0.019 -0.0513252 0.00578297 0.0338 -0.0515687 0.00289604 0.0338 -0.0515687 0.00289604 0.019 0.0401034 0.0263764 0.019 0.0437333 0.0274795 0.019 0.0415692 0.024 0.019 0.0286636 0.0385019 0.019 0.0263764 0.0401034 0.019 0.0298884 0.0421237 0.019 0.0274795 0.0437333 0.019 0.024 0.0415692 0.019 0.0215424 0.0428944 0.019 0.0190118 0.0440744 0.019 0.0224101 0.046535 0.019 0.0249841 0.0452053 0.019 0.016417 0.0451052 0.019 0.0197656 0.0477184 0.019 0.0322032 0.0403816 0.019 0.0308538 0.0367701 0.019 0.0137666 0.0459835 0.019 0.0170589 0.0487516 0.019 0.0344168 0.0385124 0.019 0.0329396 0.0349139 0.019 0.0110696 0.0467062 0.019 0.0142986 0.0496314 0.019 0.0365221 0.0365221 0.019 0.0349139 0.0329396 0.019 0.00833511 0.0472708 0.019 0.0114932 0.050355 0.019 0.0367701 0.0308538 0.019 0.0385124 0.0344168 0.019 0.00557246 0.0476754 0.019 0.0086517 0.0509202 0.019 0.0403816 0.0322032 0.019 0.0385019 0.0286636 0.019 0.00578297 0.0513252 0.019 0.00279095 0.0479188 0.019 0.0421237 0.0298884 0.019 0.00289604 0.0515687 0.019 -2.93915e-18 0.048 0.019 0.0452053 0.0249841 0.019 3.16265e-18 0.05165 0.019 -0.00289604 0.0515687 0.019 0.0440744 0.0190118 0.019 0.0428944 0.0215424 0.019 0.046535 0.0224101 0.019 -0.00279095 0.0479188 0.019 -0.00578297 0.0513252 0.019 0.0477184 0.0197656 0.019 0.0487516 0.0170589 0.019 0.0451052 0.016417 0.019 -0.00557246 0.0476754 0.019 -0.0086517 0.0509202 0.019 0.0467062 0.0110696 0.019 0.0459835 0.0137666 0.019 0.0496314 0.0142986 0.019 -0.00833511 0.0472708 0.019 -0.0114932 0.050355 0.019 0.050355 0.0114932 0.019 0.0509202 0.0086517 0.019 0.0472708 0.00833511 0.019 -0.0110696 0.0467062 0.019 0.0479188 0.00279095 0.019 0.0476754 0.00557246 0.019 0.0513252 0.00578297 0.019 -0.0215424 0.0428944 0.019 -0.0224101 0.046535 0.019 -0.0190118 0.0440744 0.019 -0.016417 0.0451052 0.019 -0.0170589 0.0487516 0.019 -0.0137666 0.0459835 0.019 -0.0286636 0.0385019 0.019 -0.0298884 0.0421237 0.019 -0.0263764 0.0401034 0.019 0.0513252 -0.00578297 0.019 0.0509202 -0.0086517 0.019 0.0476754 -0.00557246 0.019 0.0477184 -0.0197656 0.019 0.0440744 -0.0190118 0.019 0.0451052 -0.016417 0.019 -0.0365221 0.0365221 0.019 -0.0329396 0.0349139 0.019 -0.0349139 0.0329396 0.019 0.0415692 -0.024 0.019 0.0437333 -0.0274795 0.019 0.0401034 -0.0263764 0.019 -0.0421237 0.0298884 0.019 -0.0385019 0.0286636 0.019 -0.0401034 0.0263764 0.019 0.0349139 -0.0329396 0.019 0.0367701 -0.0308538 0.019 0.0385124 -0.0344168 0.019 -0.0428944 0.0215424 0.019 -0.0440744 0.0190118 0.019 -0.046535 0.0224101 0.019 -0.0496314 0.0142986 0.019 -0.0459835 0.0137666 0.019 -0.0467062 0.0110696 0.019 -0.0513252 0.00578297 0.019 -0.0476754 0.00557246 0.019 -0.0479188 0.00279095 0.019 0.0322032 -0.0403816 0.019 0.0286636 -0.0385019 0.019 0.0308538 -0.0367701 0.019 -0.0479188 -0.00279095 0.019 -0.0513252 -0.00578297 0.019 -0.0515687 -0.00289604 0.019 0.024 -0.0415692 0.019 0.0249841 -0.0452053 0.019 0.0215424 -0.0428944 0.019 -0.0467062 -0.0110696 0.019 -0.050355 -0.0114932 0.019 -0.0472708 -0.00833511 0.019 0.0137666 -0.0459835 0.019 0.016417 -0.0451052 0.019 0.0170589 -0.0487516 0.019 -0.0440744 -0.0190118 0.019 -0.0477184 -0.0197656 0.019 -0.0451052 -0.016417 0.019 0.0086517 -0.0509202 0.019 0.00833511 -0.0472708 0.019 0.0114932 -0.050355 0.019 -0.0415692 -0.024 0.019 -0.0401034 -0.0263764 0.019 -0.0437333 -0.0274795 0.019 0.00289604 -0.0515687 0.019 3.16265e-18 -0.05165 0.019 8.81746e-18 -0.048 0.019 -0.0385124 -0.0344168 0.019 -0.0367701 -0.0308538 0.019 -0.0349139 -0.0329396 0.019 -0.00557246 -0.0476754 0.019 -0.0086517 -0.0509202 0.019 -0.00833511 -0.0472708 0.019 -0.0286636 -0.0385019 0.019 -0.0322032 -0.0403816 0.019 -0.0308538 -0.0367701 0.019 -0.016417 -0.0451052 0.019 -0.0137666 -0.0459835 0.019 -0.0170589 -0.0487516 0.019 -0.0249841 -0.0452053 0.019 -0.024 -0.0415692 0.019 -0.0215424 -0.0428944 0.019 -0.0298884 -0.0421237 0.019 -0.0263764 -0.0401034 0.019 -0.0274795 -0.0437333 0.019 -0.0190118 -0.0440744 0.019 -0.0197656 -0.0477184 0.019 -0.0224101 -0.046535 0.019 -0.0329396 -0.0349139 0.019 -0.0365221 -0.0365221 0.019 -0.0344168 -0.0385124 0.019 -0.0114932 -0.050355 0.019 -0.0110696 -0.0467062 0.019 -0.0142986 -0.0496314 0.019 -0.0385019 -0.0286636 0.019 -0.0421237 -0.0298884 0.019 -0.0403816 -0.0322032 0.019 -0.00289604 -0.0515687 0.019 -0.00279095 -0.0479188 0.019 -0.00578297 -0.0513252 0.019 -0.046535 -0.0224101 0.019 -0.0428944 -0.0215424 0.019 -0.0452053 -0.0249841 0.019 0.00578297 -0.0513252 0.019 0.00557246 -0.0476754 0.019 0.00279095 -0.0479188 0.019 -0.0487516 -0.0170589 0.019 -0.0459835 -0.0137666 0.019 0.0110696 -0.0467062 0.019 -0.0496314 -0.0142986 0.019 -0.0509202 -0.0086517 0.019 0.0142986 -0.0496314 0.019 0.0197656 -0.0477184 0.019 0.0190118 -0.0440744 0.019 -0.0476754 -0.00557246 0.019 -0.05165 -9.48795e-18 0.019 -0.048 0 0.019 0.0224101 -0.046535 0.019 0.0263764 -0.0401034 0.019 0.0274795 -0.0437333 0.019 -0.0515687 0.00289604 0.019 -0.0509202 0.0086517 0.019 -0.0472708 0.00833511 0.019 0.0298884 -0.0421237 0.019 0.0329396 -0.0349139 0.019 0.0344168 -0.0385124 0.019 -0.050355 0.0114932 0.019 -0.0451052 0.016417 0.019 -0.0487516 0.0170589 0.019 0.0365221 -0.0365221 0.019 0.0403816 -0.0322032 0.019 0.0385019 -0.0286636 0.019 -0.0477184 0.0197656 0.019 -0.0452053 0.0249841 0.019 -0.0415692 0.024 0.019 0.0421237 -0.0298884 0.019 0.0428944 -0.0215424 0.019 0.0452053 -0.0249841 0.019 -0.0437333 0.0274795 0.019 -0.0367701 0.0308538 0.019 -0.0403816 0.0322032 0.019 0.046535 -0.0224101 0.019 0.0459835 -0.0137666 0.019 0.0487516 -0.0170589 0.019 -0.0385124 0.0344168 0.019 -0.0344168 0.0385124 0.019 -0.0308538 0.0367701 0.019 0.0467062 -0.0110696 0.019 0.0496314 -0.0142986 0.019 0.0472708 -0.00833511 0.019 0.050355 -0.0114932 0.019 -0.0322032 0.0403816 0.019 -0.0274795 0.0437333 0.019 -0.024 0.0415692 0.019 0.0479188 -0.00279095 0.019 -0.0249841 0.0452053 0.019 -0.0197656 0.0477184 0.019 0.0515687 -0.00289604 0.019 0.05165 9.48795e-18 0.019 0.048 5.8783e-18 0.019 0.0515687 0.00289604 0.019 -0.0142986 0.0496314 0.019 0.0451052 -0.016417 0.0318 -0.0190118 0.0440744 0.0318 -0.016417 0.0451052 0.0318 0.0367701 0.0308538 0.0318 0.0308538 0.0367701 0.0318 0.0329396 0.0349139 0.0318 0.0349139 0.0329396 0.0318 0.0385019 0.0286636 0.0318 0.0286636 0.0385019 0.0318 0.0263764 0.0401034 0.0318 0.0401034 0.0263764 0.0318 0.0415692 0.024 0.0318 0.024 0.0415692 0.0318 0.0428944 0.0215424 0.0318 0.0215424 0.0428944 0.0318 0.0190118 0.0440744 0.0318 0.0440744 0.0190118 0.0318 0.0451052 0.016417 0.0318 0.016417 0.0451052 0.0318 0.0459835 0.0137666 0.0318 0.0137666 0.0459835 0.0318 0.0110696 0.0467062 0.0318 0.0467062 0.0110696 0.0318 0.0472708 0.00833511 0.0318 0.00833511 0.0472708 0.0318 0.0476754 0.00557246 0.0318 0.00557246 0.0476754 0.0318 0.00279095 0.0479188 0.0318 0.0479188 0.00279095 0.0318 0.048 5.8783e-18 0.0318 2.93915e-18 0.048 0.0318 -0.00557246 0.0476754 0.0318 0.0479188 -0.00279095 0.0318 0.0476754 -0.00557246 0.0318 -0.00279095 0.0479188 0.0318 0.0459835 -0.0137666 0.0318 -0.0137666 0.0459835 0.0318 0.0467062 -0.0110696 0.0318 0.0472708 -0.00833511 0.0318 -0.0110696 0.0467062 0.0318 -0.00833511 0.0472708 0.0318 -0.0263764 0.0401034 0.0318 -0.024 0.0415692 0.0318 0.0415692 -0.024 0.0318 0.0440744 -0.0190118 0.0318 0.0428944 -0.0215424 0.0318 -0.0215424 0.0428944 0.0318 0.0367701 -0.0308538 0.0318 -0.0329396 0.0349139 0.0318 -0.0308538 0.0367701 0.0318 0.0401034 -0.0263764 0.0318 0.0385019 -0.0286636 0.0318 -0.0286636 0.0385019 0.0318 -0.0367701 0.0308538 0.0318 0.0308538 -0.0367701 0.0318 -0.0385019 0.0286636 0.0318 -0.0349139 0.0329396 0.0318 0.0349139 -0.0329396 0.0318 0.0329396 -0.0349139 0.0318 -0.0428944 0.0215424 0.0318 -0.0415692 0.024 0.0318 0.024 -0.0415692 0.0318 0.0263764 -0.0401034 0.0318 -0.0401034 0.0263764 0.0318 0.0286636 -0.0385019 0.0318 0.0190118 -0.0440744 0.0318 -0.0440744 0.0190118 0.0318 0.0215424 -0.0428944 0.0318 0.0110696 -0.0467062 0.0318 -0.0467062 0.0110696 0.0318 0.0137666 -0.0459835 0.0318 0.016417 -0.0451052 0.0318 -0.0459835 0.0137666 0.0318 -0.0451052 0.016417 0.0318 0.00557246 -0.0476754 0.0318 0.00279095 -0.0479188 0.0318 -0.0479188 0.00279095 0.0318 -0.0472708 0.00833511 0.0318 0.00833511 -0.0472708 0.0318 -0.0476754 0.00557246 0.0318 -0.0476754 -0.00557246 0.0318 -0.00279095 -0.0479188 0.0318 -0.00557246 -0.0476754 0.0318 -0.0479188 -0.00279095 0.0318 -0.048 0 0.0318 -1.88907e-16 -0.048 0.0318 -0.0137666 -0.0459835 0.0318 -0.0459835 -0.0137666 0.0318 -0.0110696 -0.0467062 0.0318 -0.00833511 -0.0472708 0.0318 -0.0467062 -0.0110696 0.0318 -0.0472708 -0.00833511 0.0318 -0.0190118 -0.0440744 0.0318 -0.0215424 -0.0428944 0.0318 -0.0428944 -0.0215424 0.0318 -0.0451052 -0.016417 0.0318 -0.016417 -0.0451052 0.0318 -0.0440744 -0.0190118 0.0318 -0.0385019 -0.0286636 0.0318 -0.0263764 -0.0401034 0.0318 -0.0286636 -0.0385019 0.0318 -0.0401034 -0.0263764 0.0318 -0.0415692 -0.024 0.0318 -0.024 -0.0415692 0.0318 -0.0308538 -0.0367701 0.0318 -0.0349139 -0.0329396 0.0318 -0.0367701 -0.0308538 0.0318 -0.0329396 -0.0349139 0.0318 -0.0189791 0.0181966 0.0338 -0.0189791 0 0.0328 -0.0189791 0.0181966 0.0328 -0.0189791 0 0.0338 -0.0189791 0 0.0338 -0.00883543 0 0.0338 -0.00883543 0 0.0328 -0.0189791 0 0.0328 -0.00883543 0 0.0338 -0.00883543 0.00191564 0.0338 -0.00883543 0.00191564 0.0328 -0.00883543 0 0.0328 -0.00883543 0.00191564 0.0338 -0.0168644 0.00191564 0.0328 -0.00883543 0.00191564 0.0328 -0.0168644 0.00191564 0.0338 -0.0168644 0.00191564 0.0338 -0.0168644 0.0181966 0.0338 -0.0168644 0.0181966 0.0328 -0.0168644 0.00191564 0.0328 -0.0168644 0.0181966 0.0338 -0.0189791 0.0181966 0.0328 -0.0168644 0.0181966 0.0328 -0.0189791 0.0181966 0.0338 -0.0168644 0.00191564 0.0328 -0.00883543 0 0.0328 -0.00883543 0.00191564 0.0328 -0.0189791 0.0181966 0.0328 -0.0189791 0 0.0328 -0.0168644 0.0181966 0.0328 0.013977 0 0.0338 0.0159922 0 0.0338 0.0159922 0 0.0328 0.013977 0 0.0328 0.0159922 0 0.0338 0.0159922 0.0181966 0.0338 0.0159922 0.0181966 0.0328 0.0159922 0 0.0328 0.0159922 0.0181966 0.0338 0.0142518 0.0181966 0.0328 0.0159922 0.0181966 0.0328 0.0142518 0.0181966 0.0338 0.0094368 0.0144728 0.0338 0.0094368 0.0144728 0.0328 0.0142518 0.0181966 0.0328 0.0142518 0.0181966 0.0338 0.010532 0.013055 0.0338 0.010532 0.013055 0.0328 0.0094368 0.0144728 0.0328 0.0094368 0.0144728 0.0338 0.0134931 0.0154824 0.0338 0.0134931 0.0154824 0.0328 0.010532 0.013055 0.0328 0.010532 0.013055 0.0338 0.0140765 0.01603 0.0338 0.0140765 0.01603 0.0328 0.0134931 0.0154824 0.0328 0.0134931 0.0154824 0.0338 0.013977 0.0129674 0.0338 0.0140019 0.0145435 0.0328 0.0140019 0.0145435 0.0338 0.013977 0.0129674 0.0328 0.0140765 0.01603 0.0328 0.0140765 0.01603 0.0338 0.013977 0.0129674 0.0338 0.013977 0 0.0328 0.013977 0.0129674 0.0328 0.013977 0 0.0338 0.0140765 0.01603 0.0328 0.0142518 0.0181966 0.0328 0.0134931 0.0154824 0.0328 0.0159922 0.0181966 0.0328 0.0094368 0.0144728 0.0328 0.010532 0.013055 0.0328 0.0140019 0.0145435 0.0328 0.013977 0.0129674 0.0328 0.0159922 0 0.0328 0.013977 0 0.0328 -0.0090732 -0.0260201 0.0338 -0.0090732 -0.032763 0.0328 -0.0090732 -0.0260201 0.0328 -0.0090732 -0.032763 0.0338 -0.0090732 -0.032763 0.0338 -0.00828955 -0.032763 0.0338 -0.00828955 -0.032763 0.0328 -0.0090732 -0.032763 0.0328 -0.00828955 -0.032763 0.0338 -0.00828955 -0.0260201 0.0338 -0.00828955 -0.0260201 0.0328 -0.00828955 -0.032763 0.0328 -0.00828955 -0.0260201 0.0338 -0.0090732 -0.0260201 0.0328 -0.00828955 -0.0260201 0.0328 -0.0090732 -0.0260201 0.0338 -0.0090732 -0.0260201 0.0328 -0.00828955 -0.032763 0.0328 -0.00828955 -0.0260201 0.0328 -0.0090732 -0.032763 0.0328 -0.000754132 -0.032763 0.0338 2.95159e-05 -0.032763 0.0338 2.95159e-05 -0.032763 0.0328 -0.000754132 -0.032763 0.0328 2.95159e-05 -0.032763 0.0338 2.95159e-05 -0.0298808 0.0338 2.95159e-05 -0.0298808 0.0328 2.95159e-05 -0.032763 0.0328 2.95159e-05 -0.0298808 0.0338 0.00282468 -0.0298808 0.0338 0.00282468 -0.0298808 0.0328 2.95159e-05 -0.0298808 0.0328 0.00282468 -0.0298808 0.0338 0.00282468 -0.0291842 0.0338 0.00282468 -0.0291842 0.0328 0.00282468 -0.0298808 0.0328 0.00282468 -0.0291842 0.0338 2.95159e-05 -0.0291842 0.0328 0.00282468 -0.0291842 0.0328 2.95159e-05 -0.0291842 0.0338 2.95159e-05 -0.0291842 0.0338 2.95159e-05 -0.0267167 0.0338 2.95159e-05 -0.0267167 0.0328 2.95159e-05 -0.0291842 0.0328 2.95159e-05 -0.0267167 0.0338 0.00300472 -0.0267167 0.0338 0.00300472 -0.0267167 0.0328 2.95159e-05 -0.0267167 0.0328 0.00300472 -0.0267167 0.0338 0.00300472 -0.0260201 0.0338 0.00300472 -0.0260201 0.0328 0.00300472 -0.0267167 0.0328 0.00300472 -0.0260201 0.0338 -0.000754132 -0.0260201 0.0328 0.00300472 -0.0260201 0.0328 -0.000754132 -0.0260201 0.0338 -0.000754132 -0.0260201 0.0338 -0.000754132 -0.032763 0.0328 -0.000754132 -0.0260201 0.0328 -0.000754132 -0.032763 0.0338 2.95159e-05 -0.0298808 0.0328 -0.000754132 -0.032763 0.0328 2.95159e-05 -0.032763 0.0328 2.95159e-05 -0.0291842 0.0328 0.00282468 -0.0298808 0.0328 0.00282468 -0.0291842 0.0328 2.95159e-05 -0.0267167 0.0328 -0.000754132 -0.0260201 0.0328 0.00300472 -0.0267167 0.0328 0.00300472 -0.0260201 0.0328 -0.00494982 -0.029438 0.0338 -0.00565673 -0.029438 0.0328 -0.00494982 -0.029438 0.0328 -0.00565673 -0.029438 0.0338 -0.00565673 -0.029438 0.0338 -0.00565673 -0.026699 0.0338 -0.00565673 -0.026699 0.0328 -0.00565673 -0.029438 0.0328 -0.00565673 -0.026699 0.0338 -0.00478011 -0.026699 0.0338 -0.00478011 -0.026699 0.0328 -0.00565673 -0.026699 0.0328 -0.00397077 -0.0267813 0.0338 -0.00397141 -0.026782 0.0328 -0.00417115 -0.0267424 0.0328 -0.00377508 -0.0268387 0.0338 -0.00377605 -0.0268395 0.0328 -0.0035886 -0.0269191 0.0328 -0.00358853 -0.0269191 0.0338 -0.00341499 -0.0270259 0.0338 -0.00341499 -0.0270259 0.0328 -0.0041708 -0.0267418 0.0338 -0.00437321 -0.0267171 0.0328 -0.00437305 -0.0267167 0.0338 -0.00457637 -0.0267031 0.0328 -0.00457635 -0.0267031 0.0338 -0.00478011 -0.026699 0.0328 -0.00478011 -0.026699 0.0338 -0.00302873 -0.0276019 0.0338 -0.00307368 -0.0274675 0.0328 -0.00307381 -0.0274681 0.0338 -0.00299868 -0.0277399 0.0338 -0.00302846 -0.0276015 0.0328 -0.00299843 -0.0277396 0.0328 -0.0029818 -0.0278801 0.0338 -0.00297668 -0.0280213 0.0338 -0.0029818 -0.02788 0.0328 -0.00297668 -0.0280213 0.0328 -0.00313537 -0.0273404 0.0328 -0.00321372 -0.0272229 0.0328 -0.00313525 -0.0273409 0.0338 -0.00330742 -0.0271176 0.0328 -0.00321342 -0.0272232 0.0338 -0.00330741 -0.0271176 0.0338 -0.00341499 -0.0270259 0.0328 -0.00341499 -0.0270259 0.0338 -0.00314062 -0.0287608 0.0338 -0.00307626 -0.0286214 0.0328 -0.00307602 -0.0286221 0.0338 -0.00322396 -0.028889 0.0338 -0.00314058 -0.0287601 0.0328 -0.00322365 -0.0288885 0.0328 -0.003325 -0.0290033 0.0338 -0.0034423 -0.0291016 0.0338 -0.00332498 -0.0290032 0.0328 -0.0034423 -0.0291016 0.0328 -0.00302968 -0.0284758 0.0328 -0.00299897 -0.0283261 0.0328 -0.00302933 -0.0284763 0.0338 -0.00298184 -0.0281742 0.0328 -0.00299868 -0.0283263 0.0338 -0.00298184 -0.0281742 0.0338 -0.00297668 -0.0280213 0.0328 -0.00297668 -0.0280213 0.0338 -0.00233969 -0.0288903 0.0338 -0.00224264 -0.0286146 0.0338 -0.00233969 -0.0288903 0.0328 -0.00224264 -0.0286146 0.0328 -0.0021844 -0.0283127 0.0338 -0.00216499 -0.0279844 0.0338 -0.0021844 -0.0283127 0.0328 -0.00216499 -0.0279844 0.0328 -0.00247557 -0.0291398 0.0328 -0.00265026 -0.0293629 0.0328 -0.00247557 -0.0291398 0.0338 -0.00265026 -0.0293629 0.0338 -0.00286378 -0.0295598 0.0328 -0.00286378 -0.0295598 0.0338 -0.00316045 -0.026292 0.0338 -0.00293139 -0.0264165 0.0328 -0.00293139 -0.0264165 0.0338 -0.00340331 -0.0261963 0.0338 -0.00316045 -0.026292 0.0328 -0.00340331 -0.0261963 0.0328 -0.00365471 -0.0261255 0.0338 -0.00391104 -0.0260757 0.0338 -0.00365471 -0.0261255 0.0328 -0.00417009 -0.0260433 0.0338 -0.00391104 -0.0260757 0.0328 -0.00417009 -0.0260433 0.0328 -0.00443052 -0.0260256 0.0338 -0.00469156 -0.0260201 0.0338 -0.00443052 -0.0260256 0.0328 -0.00469156 -0.0260201 0.0328 -0.00272195 -0.0265727 0.0328 -0.00254107 -0.0267612 0.0328 -0.00272195 -0.0265727 0.0338 -0.00239555 -0.0269778 0.0328 -0.00254107 -0.0267612 0.0338 -0.00239555 -0.0269778 0.0338 -0.00228793 -0.0272153 0.0328 -0.00221653 -0.027466 0.0328 -0.00228793 -0.0272153 0.0338 -0.00217674 -0.0277235 0.0328 -0.00221653 -0.027466 0.0338 -0.00217674 -0.0277235 0.0338 -0.00216499 -0.0279844 0.0328 -0.00216499 -0.0279844 0.0338 -0.00469156 -0.0260201 0.0338 -0.00644038 -0.0260201 0.0328 -0.00469156 -0.0260201 0.0328 -0.00644038 -0.0260201 0.0338 -0.00644038 -0.0260201 0.0338 -0.00644038 -0.032763 0.0328 -0.00644038 -0.0260201 0.0328 -0.00644038 -0.032763 0.0338 -0.00644038 -0.032763 0.0338 -0.00565673 -0.032763 0.0338 -0.00565673 -0.032763 0.0328 -0.00644038 -0.032763 0.0328 -0.00565673 -0.032763 0.0338 -0.00565673 -0.030111 0.0338 -0.00565673 -0.030111 0.0328 -0.00565673 -0.032763 0.0328 -0.00565673 -0.030111 0.0338 -0.00486275 -0.030111 0.0338 -0.00486275 -0.030111 0.0328 -0.00565673 -0.030111 0.0328 -0.00366973 -0.0299605 0.0338 -0.00366973 -0.0299605 0.0328 -0.00396281 -0.0300312 0.0328 -0.0033851 -0.0298609 0.0338 -0.0033851 -0.0298609 0.0328 -0.00311413 -0.0297284 0.0328 -0.00311413 -0.0297284 0.0338 -0.00286378 -0.0295598 0.0338 -0.00286378 -0.0295598 0.0328 -0.00396281 -0.0300312 0.0338 -0.00426076 -0.0300775 0.0328 -0.00426076 -0.0300775 0.0338 -0.00456114 -0.0301033 0.0328 -0.00456114 -0.0301033 0.0338 -0.00486275 -0.030111 0.0328 -0.00486275 -0.030111 0.0338 -0.00436329 -0.029406 0.0338 -0.00416938 -0.0293775 0.0328 -0.00416944 -0.0293775 0.0338 -0.00455828 -0.0294245 0.0338 -0.00436303 -0.0294065 0.0328 -0.00455811 -0.029425 0.0328 -0.00475385 -0.029435 0.0338 -0.00494982 -0.029438 0.0338 -0.00475383 -0.029435 0.0328 -0.00494982 -0.029438 0.0328 -0.00397758 -0.0293366 0.0328 -0.00379088 -0.0292787 0.0338 -0.00397811 -0.0293358 0.0338 -0.00378953 -0.02928 0.0328 -0.00361058 -0.0292022 0.0328 -0.00361066 -0.0292022 0.0338 -0.0034423 -0.0291016 0.0328 -0.0034423 -0.0291016 0.0338 -0.00302846 -0.0276015 0.0328 -0.00299843 -0.0277396 0.0328 -0.00228793 -0.0272153 0.0328 -0.00221653 -0.027466 0.0328 -0.0029818 -0.02788 0.0328 -0.00321372 -0.0272229 0.0328 -0.00313537 -0.0273404 0.0328 -0.00293139 -0.0264165 0.0328 -0.00254107 -0.0267612 0.0328 -0.00239555 -0.0269778 0.0328 -0.00330742 -0.0271176 0.0328 -0.00272195 -0.0265727 0.0328 -0.00316045 -0.026292 0.0328 -0.00307368 -0.0274675 0.0328 -0.00217674 -0.0277235 0.0328 -0.00216499 -0.0279844 0.0328 -0.00341499 -0.0270259 0.0328 -0.00340331 -0.0261963 0.0328 -0.0035886 -0.0269191 0.0328 -0.00377605 -0.0268395 0.0328 -0.00365471 -0.0261255 0.0328 -0.00391104 -0.0260757 0.0328 -0.00322365 -0.0288885 0.0328 -0.00332498 -0.0290032 0.0328 -0.00311413 -0.0297284 0.0328 -0.00437321 -0.0267171 0.0328 -0.00417009 -0.0260433 0.0328 -0.00443052 -0.0260256 0.0328 -0.00469156 -0.0260201 0.0328 -0.00478011 -0.026699 0.0328 -0.00457637 -0.0267031 0.0328 -0.00378953 -0.02928 0.0328 -0.00366973 -0.0299605 0.0328 -0.00361058 -0.0292022 0.0328 -0.00565673 -0.030111 0.0328 -0.00486275 -0.030111 0.0328 -0.00494982 -0.029438 0.0328 -0.00565673 -0.032763 0.0328 -0.00644038 -0.032763 0.0328 -0.00426076 -0.0300775 0.0328 -0.00396281 -0.0300312 0.0328 -0.00416938 -0.0293775 0.0328 -0.00565673 -0.029438 0.0328 -0.00417115 -0.0267424 0.0328 -0.00397141 -0.026782 0.0328 -0.00475383 -0.029435 0.0328 -0.00456114 -0.0301033 0.0328 -0.00455811 -0.029425 0.0328 -0.0034423 -0.0291016 0.0328 -0.0033851 -0.0298609 0.0328 -0.00644038 -0.0260201 0.0328 -0.00565673 -0.026699 0.0328 -0.00314058 -0.0287601 0.0328 -0.00286378 -0.0295598 0.0328 -0.00307626 -0.0286214 0.0328 -0.00265026 -0.0293629 0.0328 -0.00247557 -0.0291398 0.0328 -0.00224264 -0.0286146 0.0328 -0.00298184 -0.0281742 0.0328 -0.00299897 -0.0283261 0.0328 -0.00297668 -0.0280213 0.0328 -0.0021844 -0.0283127 0.0328 -0.00233969 -0.0288903 0.0328 -0.00302968 -0.0284758 0.0328 -0.00397758 -0.0293366 0.0328 -0.00436303 -0.0294065 0.0328 0.0308045 0.00178421 0.0338 0.0303252 0.00162933 0.0338 0.0308045 0.00178421 0.0328 0.0303252 0.00162933 0.0328 0.0298018 0.0015364 0.0338 0.0292344 0.00150543 0.0338 0.0298018 0.0015364 0.0328 0.0292344 0.00150543 0.0328 0.0312398 0.00200104 0.0328 0.0316311 0.00227983 0.0328 0.0312398 0.00200104 0.0338 0.0316311 0.00227983 0.0338 0.0319784 0.00262056 0.0328 0.0319784 0.00262056 0.0338 0.0281277 0.00166722 0.0328 0.0281277 0.00166722 0.0338 0.0276225 0.00186946 0.0338 0.0271495 0.0021526 0.0338 0.0276225 0.00186946 0.0328 0.0271495 0.0021526 0.0328 0.028665 0.00154588 0.0328 0.028665 0.00154588 0.0338 0.0292344 0.00150543 0.0328 0.0292344 0.00150543 0.0338 0.0263395 0.00291478 0.0328 0.0263395 0.00291478 0.0338 0.0260126 0.00338211 0.0338 0.0257376 0.00390694 0.0338 0.0260126 0.00338211 0.0328 0.0257376 0.00390694 0.0328 0.0267185 0.00250494 0.0328 0.0267185 0.00250494 0.0338 0.0271495 0.0021526 0.0328 0.0271495 0.0021526 0.0338 0.0252951 0.00546105 0.0328 0.0254611 0.00466453 0.0328 0.0252951 0.00546105 0.0338 0.0252398 0.00629651 0.0338 0.0252398 0.00629651 0.0328 0.0254611 0.00466453 0.0338 0.0257376 0.00390694 0.0328 0.0257376 0.00390694 0.0338 0.0253782 0.00715277 0.0328 0.0253782 0.00715277 0.0338 0.0255512 0.00756896 0.0338 0.0257934 0.00797717 0.0338 0.0255512 0.00756896 0.0328 0.0257934 0.00797717 0.0328 0.0252744 0.00672863 0.0328 0.0252744 0.00672863 0.0338 0.0252398 0.00629651 0.0328 0.0252398 0.00629651 0.0338 0.0264421 0.00869902 0.0328 0.0264421 0.00869902 0.0338 0.0268377 0.00899498 0.0338 0.0272809 0.00924763 0.0338 0.0268377 0.00899498 0.0328 0.0272809 0.00924763 0.0328 0.026094 0.00835975 0.0328 0.026094 0.00835975 0.0338 0.0257934 0.00797717 0.0328 0.0257934 0.00797717 0.0338 0.0286084 0.00965828 0.0328 0.0279241 0.00950429 0.0328 0.0286084 0.00965828 0.0338 0.0293339 0.00970961 0.0338 0.0293339 0.00970961 0.0328 0.0279241 0.00950429 0.0338 0.0272809 0.00924763 0.0328 0.0272809 0.00924763 0.0338 0.0310096 0.00941372 0.0338 0.0310075 0.00941313 0.0328 0.0306033 0.009552 0.0328 0.0313915 0.00922102 0.0338 0.0313897 0.00922145 0.0328 0.0317393 0.00897474 0.0328 0.0317394 0.00897467 0.0338 0.0320461 0.00867612 0.0338 0.0320461 0.00867612 0.0328 0.0306049 0.00955315 0.0338 0.0301857 0.00964343 0.0328 0.0301867 0.00964446 0.0338 0.0297615 0.00969441 0.0328 0.0297616 0.00969441 0.0338 0.0293339 0.00970961 0.0328 0.0293339 0.00970961 0.0338 0.0326272 0.00772603 0.0328 0.0328088 0.00715851 0.0338 0.0328088 0.00715851 0.0328 0.0329178 0.00652934 0.0328 0.0329178 0.00652934 0.0338 0.0329541 0.00583851 0.0338 0.0329541 0.00583851 0.0328 0.0326272 0.00772603 0.0338 0.032373 0.0082319 0.0328 0.032373 0.0082319 0.0338 0.0320461 0.00867612 0.0328 0.0320461 0.00867612 0.0338 0.0233365 0.0109325 0.0338 0.0235274 0.0119686 0.0328 0.0235274 0.0119686 0.0338 0.023213 0.00988515 0.0338 0.0233365 0.0109325 0.0328 0.023213 0.00988515 0.0328 0.0231455 0.0088326 0.0338 0.023125 0.00777804 0.0338 0.0231455 0.0088326 0.0328 0.023125 0.00777804 0.0328 0.0237932 0.01299 0.0328 0.0241523 0.0139831 0.0328 0.0237932 0.01299 0.0338 0.0246228 0.0149221 0.0328 0.0241523 0.0139831 0.0338 0.0246228 0.0149221 0.0338 0.0252099 0.015799 0.0328 0.0252099 0.015799 0.0338 0.0234688 0.00468321 0.0338 0.0237765 0.0036897 0.0338 0.0234688 0.00468321 0.0328 0.0237765 0.0036897 0.0328 0.0242092 0.00274331 0.0338 0.0247798 0.00187183 0.0338 0.0242092 0.00274331 0.0328 0.0247798 0.00187183 0.0328 0.0232688 0.00570376 0.0328 0.0231577 0.0067375 0.0328 0.0232688 0.00570376 0.0338 0.0231577 0.0067375 0.0338 0.023125 0.00777804 0.0328 0.023125 0.00777804 0.0338 0.0267268 0.000279779 0.0338 0.0275057 -1.50454e-05 0.0338 0.0267268 0.000279779 0.0328 0.0275057 -1.50454e-05 0.0328 0.0283495 -0.00019194 0.0338 0.0292583 -0.000250905 0.0338 0.0283495 -0.00019194 0.0328 0.0292583 -0.000250905 0.0328 0.0260129 0.000692532 0.0328 0.0253639 0.00122322 0.0328 0.0260129 0.000692532 0.0338 0.0253639 0.00122322 0.0338 0.0247798 0.00187183 0.0328 0.0247798 0.00187183 0.0338 0.0316259 0.000155322 0.0338 0.0322939 0.000471276 0.0338 0.0316259 0.000155322 0.0328 0.0322939 0.000471276 0.0328 0.0329013 0.000877502 0.0338 0.033448 0.001374 0.0338 0.0329013 0.000877502 0.0328 0.033448 0.001374 0.0328 0.0308973 -7.03595e-05 0.0328 0.0301081 -0.000205768 0.0328 0.0308973 -7.03595e-05 0.0338 0.0301081 -0.000205768 0.0338 0.0292583 -0.000250905 0.0328 0.0292583 -0.000250905 0.0338 0.0346099 0.00330258 0.0338 0.0348251 0.00408041 0.0338 0.0346099 0.00330258 0.0328 0.0348251 0.00408041 0.0328 0.0349542 0.00492572 0.0338 0.0349972 0.00583851 0.0338 0.0349542 0.00492572 0.0328 0.0349972 0.00583851 0.0328 0.0343087 0.00259224 0.0328 0.0339214 0.00194938 0.0328 0.0343087 0.00259224 0.0338 0.0339214 0.00194938 0.0338 0.033448 0.001374 0.0328 0.033448 0.001374 0.0338 0.0347713 0.00769919 0.0328 0.034489 0.00850288 0.0338 0.034489 0.00850288 0.0328 0.0340936 0.00922214 0.0328 0.0340936 0.00922214 0.0338 0.0335854 0.00985697 0.0338 0.0335854 0.00985697 0.0328 0.0347713 0.00769919 0.0338 0.0349407 0.00681107 0.0328 0.0349407 0.00681107 0.0338 0.0349972 0.00583851 0.0328 0.0349972 0.00583851 0.0338 0.0319132 0.0109681 0.0338 0.0312401 0.0111739 0.0338 0.0319132 0.0109681 0.0328 0.0312401 0.0111739 0.0328 0.0305091 0.0112973 0.0338 0.0297203 0.0113385 0.0338 0.0305091 0.0112973 0.0328 0.0297203 0.0113385 0.0328 0.0325284 0.01068 0.0328 0.0330858 0.0103097 0.0328 0.0325284 0.01068 0.0338 0.0330858 0.0103097 0.0338 0.0335854 0.00985697 0.0328 0.0335854 0.00985697 0.0338 0.0268541 0.0106389 0.0338 0.0268541 0.0106389 0.0328 0.0274731 0.010945 0.0328 0.0263001 0.0102453 0.0338 0.0263001 0.0102453 0.0328 0.0258111 0.00976431 0.0328 0.0258111 0.00976431 0.0338 0.0253872 0.00919585 0.0338 0.0253872 0.00919585 0.0328 0.0274731 0.010945 0.0338 0.0281571 0.0111636 0.0328 0.0281571 0.0111636 0.0338 0.0289062 0.0112948 0.0328 0.0289062 0.0112948 0.0338 0.0297203 0.0113385 0.0328 0.0297203 0.0113385 0.0338 0.0253872 0.00919585 0.0338 0.0252398 0.00919585 0.0328 0.0253872 0.00919585 0.0328 0.0252398 0.00919585 0.0338 0.0258488 0.0129341 0.0338 0.0256329 0.0122059 0.0328 0.0256329 0.0122059 0.0338 0.0261292 0.0136399 0.0338 0.0258488 0.0129341 0.0328 0.0261292 0.0136399 0.0328 0.0264858 0.0143109 0.0338 0.0269304 0.0149288 0.0338 0.0264858 0.0143109 0.0328 0.0269304 0.0149288 0.0328 0.0254737 0.0114624 0.0328 0.0253597 0.010711 0.0328 0.0254737 0.0114624 0.0338 0.0252826 0.0099551 0.0328 0.0253597 0.010711 0.0338 0.0252826 0.0099551 0.0338 0.0252398 0.00919585 0.0328 0.0252398 0.00919585 0.0338 0.0288197 0.0162954 0.0338 0.0296032 0.0165484 0.0338 0.0288197 0.0162954 0.0328 0.0296032 0.0165484 0.0328 0.0304636 0.0167003 0.0338 0.0314009 0.0167509 0.0338 0.0304636 0.0167003 0.0328 0.0314009 0.0167509 0.0328 0.028113 0.0159411 0.0328 0.0274833 0.0154856 0.0328 0.028113 0.0159411 0.0338 0.0274833 0.0154856 0.0338 0.0269304 0.0149288 0.0328 0.0269304 0.0149288 0.0338 0.0329214 0.0166128 0.0328 0.0321912 0.0167164 0.0328 0.0329214 0.0166128 0.0338 0.0335914 0.0164402 0.0338 0.0335914 0.0164402 0.0328 0.0321912 0.0167164 0.0338 0.0314009 0.0167509 0.0328 0.0314009 0.0167509 0.0338 0.0335914 0.0164402 0.0338 0.0335914 0.0182205 0.0338 0.0335914 0.0182205 0.0328 0.0335914 0.0164402 0.0328 0.0322479 0.0184293 0.0328 0.032986 0.018351 0.0328 0.0322479 0.0184293 0.0338 0.031377 0.0184554 0.0338 0.031377 0.0184554 0.0328 0.032986 0.018351 0.0338 0.0335914 0.0182205 0.0328 0.0335914 0.0182205 0.0338 0.0277942 0.0177913 0.0338 0.0268218 0.0172748 0.0338 0.0277942 0.0177913 0.0328 0.0268218 0.0172748 0.0328 0.0259604 0.0166107 0.0338 0.0252099 0.015799 0.0338 0.0259604 0.0166107 0.0328 0.0252099 0.015799 0.0328 0.0288775 0.0181603 0.0328 0.0300718 0.0183816 0.0328 0.0288775 0.0181603 0.0338 0.0300718 0.0183816 0.0338 0.031377 0.0184554 0.0328 0.031377 0.0184554 0.0338 0.0326854 0.00390054 0.0338 0.0326842 0.00390241 0.0328 0.032811 0.00437622 0.0328 0.0325072 0.00344307 0.0338 0.0325067 0.00344509 0.0328 0.0322725 0.00301384 0.0328 0.0322724 0.00301372 0.0338 0.0319784 0.00262056 0.0338 0.0319784 0.00262056 0.0328 0.0328123 0.00437496 0.0338 0.032894 0.00485963 0.0328 0.032895 0.00485897 0.0338 0.0329403 0.00534786 0.0328 0.0329403 0.0053478 0.0338 0.0329541 0.00583851 0.0328 0.0329541 0.00583851 0.0338 0.0322939 0.000471276 0.0328 0.0316311 0.00227983 0.0328 0.0316259 0.000155322 0.0328 0.0276225 0.00186946 0.0328 0.0267268 0.000279779 0.0328 0.0275057 -1.50454e-05 0.0328 0.0271495 0.0021526 0.0328 0.0267185 0.00250494 0.0328 0.0308045 0.00178421 0.0328 0.0312398 0.00200104 0.0328 0.0281277 0.00166722 0.0328 0.0283495 -0.00019194 0.0328 0.0308973 -7.03595e-05 0.0328 0.028665 0.00154588 0.0328 0.0292583 -0.000250905 0.0328 0.0292344 0.00150543 0.0328 0.0298018 0.0015364 0.0328 0.0252398 0.00919585 0.0328 0.0255512 0.00756896 0.0328 0.0257934 0.00797717 0.0328 0.0301081 -0.000205768 0.0328 0.0268377 0.00899498 0.0328 0.0272809 0.00924763 0.0328 0.0268541 0.0106389 0.0328 0.0303252 0.00162933 0.0328 0.0289062 0.0112948 0.0328 0.0286084 0.00965828 0.0328 0.0293339 0.00970961 0.0328 0.0274731 0.010945 0.0328 0.0279241 0.00950429 0.0328 0.0281571 0.0111636 0.0328 0.0329013 0.000877502 0.0328 0.0319784 0.00262056 0.0328 0.0301857 0.00964343 0.0328 0.0305091 0.0112973 0.0328 0.0297203 0.0113385 0.0328 0.033448 0.001374 0.0328 0.0325067 0.00344509 0.0328 0.0322725 0.00301384 0.0328 0.0326272 0.00772603 0.0328 0.0328088 0.00715851 0.0328 0.0340936 0.00922214 0.0328 0.0346099 0.00330258 0.0328 0.0348251 0.00408041 0.0328 0.032894 0.00485963 0.0328 0.0329178 0.00652934 0.0328 0.0329541 0.00583851 0.0328 0.0349407 0.00681107 0.0328 0.0325284 0.01068 0.0328 0.0320461 0.00867612 0.0328 0.0330858 0.0103097 0.0328 0.0347713 0.00769919 0.0328 0.034489 0.00850288 0.0328 0.0349972 0.00583851 0.0328 0.0349542 0.00492572 0.0328 0.032373 0.0082319 0.0328 0.0335854 0.00985697 0.0328 0.0329403 0.00534786 0.0328 0.0317393 0.00897474 0.0328 0.0313897 0.00922145 0.0328 0.0312401 0.0111739 0.0328 0.0310075 0.00941313 0.0328 0.0319132 0.0109681 0.0328 0.0322479 0.0184293 0.0328 0.031377 0.0184554 0.0328 0.0321912 0.0167164 0.0328 0.0306033 0.009552 0.0328 0.0326842 0.00390241 0.0328 0.0339214 0.00194938 0.0328 0.0343087 0.00259224 0.0328 0.0263395 0.00291478 0.0328 0.0260129 0.000692532 0.0328 0.0288775 0.0181603 0.0328 0.0288197 0.0162954 0.0328 0.0296032 0.0165484 0.0328 0.0256329 0.0122059 0.0328 0.0258488 0.0129341 0.0328 0.0241523 0.0139831 0.0328 0.0254737 0.0114624 0.0328 0.0237932 0.01299 0.0328 0.0235274 0.0119686 0.0328 0.0253597 0.010711 0.0328 0.0233365 0.0109325 0.0328 0.0260126 0.00338211 0.0328 0.0253639 0.00122322 0.0328 0.0252826 0.0099551 0.0328 0.023213 0.00988515 0.0328 0.0246228 0.0149221 0.0328 0.0247798 0.00187183 0.0328 0.0257376 0.00390694 0.0328 0.0242092 0.00274331 0.0328 0.0252398 0.00629651 0.0328 0.0252744 0.00672863 0.0328 0.0231577 0.0067375 0.0328 0.0234688 0.00468321 0.0328 0.0252951 0.00546105 0.0328 0.0232688 0.00570376 0.0328 0.0254611 0.00466453 0.0328 0.0237765 0.0036897 0.0328 0.0231455 0.0088326 0.0328 0.023125 0.00777804 0.0328 0.0252099 0.015799 0.0328 0.0261292 0.0136399 0.0328 0.0264858 0.0143109 0.0328 0.0274833 0.0154856 0.0328 0.0277942 0.0177913 0.0328 0.0268218 0.0172748 0.0328 0.0269304 0.0149288 0.0328 0.0259604 0.0166107 0.0328 0.028113 0.0159411 0.0328 0.0304636 0.0167003 0.0328 0.0314009 0.0167509 0.0328 0.032986 0.018351 0.0328 0.0329214 0.0166128 0.0328 0.0335914 0.0182205 0.0328 0.0335914 0.0164402 0.0328 0.0300718 0.0183816 0.0328 0.0297615 0.00969441 0.0328 0.0258111 0.00976431 0.0328 0.026094 0.00835975 0.0328 0.0264421 0.00869902 0.0328 0.0253872 0.00919585 0.0328 0.0253782 0.00715277 0.0328 0.0263001 0.0102453 0.0328 0.032811 0.00437622 0.0328 -0.00172646 0.00897283 0.0338 -0.00363413 0.00897283 0.0328 -0.00172646 0.00897283 0.0328 -0.00363413 0.00897283 0.0338 -0.00363413 0.00897283 0.0338 -0.00363413 0.0163646 0.0338 -0.00363413 0.0163646 0.0328 -0.00363413 0.00897283 0.0328 -0.00363413 0.0163646 0.0338 -0.00126846 0.0163646 0.0338 -0.00126846 0.0163646 0.0328 -0.00363413 0.0163646 0.0328 0.00111487 0.0160901 0.0338 0.000645872 0.0162 0.0328 0.000646041 0.0162 0.0338 0.00157287 0.0159398 0.0338 0.00111348 0.0160885 0.0328 0.00156973 0.0159374 0.0328 0.00200762 0.0157383 0.0338 0.00241546 0.0154824 0.0338 0.00200744 0.0157384 0.0328 0.00241546 0.0154824 0.0328 0.000170985 0.0162773 0.0328 -0.000307322 0.0163277 0.0328 0.000171727 0.0162785 0.0338 -0.000787309 0.0163563 0.0328 -0.00030682 0.0163289 0.0338 -0.000787259 0.0163563 0.0338 -0.00126846 0.0163646 0.0328 -0.00126846 0.0163646 0.0338 0.00345784 0.0139278 0.0338 0.00333654 0.0142905 0.0328 0.00333617 0.014289 0.0338 0.00353892 0.0135555 0.0338 0.00345858 0.013929 0.0328 0.0035396 0.0135562 0.0328 0.00358449 0.0131773 0.0338 0.00359829 0.0127961 0.0338 0.00358448 0.0131773 0.0328 0.00359829 0.0127961 0.0328 0.00317006 0.0146336 0.0328 0.00295862 0.0149507 0.0328 0.00317038 0.0146322 0.0338 0.00270575 0.0152349 0.0328 0.00295942 0.0149499 0.0338 0.00270578 0.0152349 0.0338 0.00241546 0.0154824 0.0328 0.00241546 0.0154824 0.0338 0.00315589 0.0108005 0.0338 0.00332956 0.0111766 0.0328 0.00333023 0.0111749 0.0338 0.00293099 0.0104546 0.0338 0.003156 0.0108023 0.0328 0.00293182 0.0104557 0.0328 0.0026583 0.0101462 0.0338 0.00234178 0.00988086 0.0338 0.00265837 0.0101462 0.0328 0.00234178 0.00988086 0.0328 0.00345526 0.0115695 0.0328 0.00353815 0.0119736 0.0328 0.00345621 0.0115683 0.0338 0.00358438 0.0123835 0.0328 0.00353892 0.011973 0.0338 0.00358438 0.0123834 0.0338 0.00359829 0.0127961 0.0328 0.00359829 0.0127961 0.0338 0.00531729 0.0104509 0.0338 0.0055792 0.0111949 0.0338 0.00531729 0.0104509 0.0328 0.0055792 0.0111949 0.0328 0.00573635 0.0120098 0.0338 0.00578873 0.0128957 0.0338 0.00573635 0.0120098 0.0328 0.00578873 0.0128957 0.0328 0.00495061 0.00977776 0.0328 0.00447917 0.00917555 0.0328 0.00495061 0.00977776 0.0338 0.00447917 0.00917555 0.0338 0.00390296 0.00864426 0.0328 0.00390296 0.00864426 0.0338 0.00310238 0.0174627 0.0338 0.00372053 0.0171267 0.0328 0.00372053 0.0171267 0.0338 0.00244698 0.0177212 0.0338 0.00310238 0.0174627 0.0328 0.00244698 0.0177212 0.0328 0.00176856 0.0179122 0.0338 0.00107681 0.0180466 0.0338 0.00176856 0.0179122 0.0328 0.00037774 0.0181339 0.0338 0.00107681 0.0180466 0.0328 0.00037774 0.0181339 0.0328 -0.000325052 0.0181818 0.0338 -0.00102951 0.0181966 0.0338 -0.000325052 0.0181818 0.0328 -0.00102951 0.0181966 0.0328 0.00428573 0.0167052 0.0328 0.00477383 0.0161967 0.0328 0.00428573 0.0167052 0.0338 0.00516655 0.0156121 0.0328 0.00477383 0.0161967 0.0338 0.00516655 0.0156121 0.0338 0.00545697 0.0149713 0.0328 0.00564964 0.0142947 0.0328 0.00545697 0.0149713 0.0338 0.00575703 0.0135997 0.0328 0.00564964 0.0142947 0.0338 0.00575703 0.0135997 0.0338 0.00578873 0.0128957 0.0328 0.00578873 0.0128957 0.0338 -0.00102951 0.0181966 0.0338 -0.0057489 0.0181966 0.0328 -0.00102951 0.0181966 0.0328 -0.0057489 0.0181966 0.0338 -0.0057489 0.0181966 0.0338 -0.0057489 0 0.0328 -0.0057489 0.0181966 0.0328 -0.0057489 0 0.0338 -0.0057489 0 0.0338 -0.00363413 0 0.0338 -0.00363413 0 0.0328 -0.0057489 0 0.0328 -0.00363413 0 0.0338 -0.00363413 0.00715676 0.0338 -0.00363413 0.00715676 0.0328 -0.00363413 0 0.0328 -0.00363413 0.00715676 0.0338 -0.00149149 0.00715676 0.0338 -0.00149149 0.00715676 0.0328 -0.00363413 0.00715676 0.0328 0.00172803 0.00756305 0.0338 0.00172803 0.00756305 0.0328 0.000937106 0.00737202 0.0328 0.00249613 0.0078317 0.0338 0.00249613 0.0078317 0.0328 0.00322738 0.00818929 0.0328 0.00322738 0.00818929 0.0338 0.00390296 0.00864426 0.0338 0.00390296 0.00864426 0.0328 0.000937106 0.00737202 0.0338 0.000133051 0.00724719 0.0328 0.000133051 0.00724719 0.0338 -0.000677562 0.00717761 0.0328 -0.000677562 0.00717761 0.0338 -0.00149149 0.00715676 0.0328 -0.00149149 0.00715676 0.0338 -0.000143634 0.00905927 0.0338 0.00037966 0.00913632 0.0328 0.000379487 0.00913628 0.0338 -0.00066985 0.00900928 0.0338 -0.00014292 0.00905792 0.0328 -0.000669392 0.00900803 0.0328 -0.00119761 0.00898099 0.0338 -0.00172646 0.00897283 0.0338 -0.00119756 0.00898099 0.0328 -0.00172646 0.00897283 0.0328 0.000897244 0.00924671 0.0328 0.00140108 0.00940283 0.0338 0.000895814 0.00924863 0.0338 0.00140472 0.00939941 0.0328 0.00188764 0.00960933 0.0328 0.00188744 0.00960923 0.0338 0.00234178 0.00988086 0.0328 0.00234178 0.00988086 0.0338 0.0035396 0.0135562 0.0328 0.00545697 0.0149713 0.0328 0.00345858 0.013929 0.0328 0.00564964 0.0142947 0.0328 0.00358448 0.0131773 0.0328 0.00295862 0.0149507 0.0328 0.00317006 0.0146336 0.0328 0.00372053 0.0171267 0.0328 0.00477383 0.0161967 0.0328 0.00516655 0.0156121 0.0328 0.00270575 0.0152349 0.0328 0.00310238 0.0174627 0.0328 0.00428573 0.0167052 0.0328 0.00244698 0.0177212 0.0328 0.00241546 0.0154824 0.0328 0.00578873 0.0128957 0.0328 0.00359829 0.0127961 0.0328 0.00573635 0.0120098 0.0328 0.00200744 0.0157384 0.0328 0.00176856 0.0179122 0.0328 0.00156973 0.0159374 0.0328 0.00265837 0.0101462 0.0328 0.00322738 0.00818929 0.0328 0.00293182 0.0104557 0.0328 0.000170985 0.0162773 0.0328 -0.000325052 0.0181818 0.0328 -0.000307322 0.0163277 0.0328 -0.00102951 0.0181966 0.0328 -0.00126846 0.0163646 0.0328 -0.000787309 0.0163563 0.0328 0.00140472 0.00939941 0.0328 0.00172803 0.00756305 0.0328 0.00188764 0.00960933 0.0328 -0.00363413 0.00715676 0.0328 -0.00149149 0.00715676 0.0328 -0.00172646 0.00897283 0.0328 -0.00363413 0 0.0328 -0.0057489 0 0.0328 0.000133051 0.00724719 0.0328 0.000937106 0.00737202 0.0328 0.00037966 0.00913632 0.0328 -0.00363413 0.00897283 0.0328 0.000645872 0.0162 0.0328 0.00037774 0.0181339 0.0328 0.00107681 0.0180466 0.0328 0.00111348 0.0160885 0.0328 -0.00119756 0.00898099 0.0328 -0.000677562 0.00717761 0.0328 -0.000669392 0.00900803 0.0328 0.00234178 0.00988086 0.0328 0.00249613 0.0078317 0.0328 -0.0057489 0.0181966 0.0328 -0.00363413 0.0163646 0.0328 0.00390296 0.00864426 0.0328 0.003156 0.0108023 0.0328 0.00447917 0.00917555 0.0328 0.00495061 0.00977776 0.0328 0.00332956 0.0111766 0.0328 0.0055792 0.0111949 0.0328 0.00358438 0.0123835 0.0328 0.00353815 0.0119736 0.0328 0.00575703 0.0135997 0.0328 0.00333654 0.0142905 0.0328 0.00531729 0.0104509 0.0328 0.00345526 0.0115695 0.0328 0.000897244 0.00924671 0.0328 -0.00014292 0.00905792 0.0328 0.00849321 -0.032763 0.0338 0.00938754 -0.032763 0.0338 0.00938754 -0.032763 0.0328 0.00849321 -0.032763 0.0328 0.00938754 -0.032763 0.0338 0.00938754 -0.0260201 0.0338 0.00938754 -0.0260201 0.0328 0.00938754 -0.032763 0.0328 0.00938754 -0.0260201 0.0338 0.00865407 -0.0260201 0.0328 0.00938754 -0.0260201 0.0328 0.00865407 -0.0260201 0.0338 0.00865407 -0.0260201 0.0338 0.00865407 -0.0298896 0.0328 0.00865407 -0.0260201 0.0328 0.00865407 -0.0298896 0.0338 0.00867769 -0.0308563 0.0338 0.00867769 -0.0308563 0.0328 0.00865407 -0.0298896 0.0328 0.00865407 -0.0298896 0.0338 0.00871901 -0.0316562 0.0338 0.00871901 -0.0316562 0.0328 0.00867769 -0.0308563 0.0328 0.00867769 -0.0308563 0.0338 0.00871901 -0.0316562 0.0338 0.00868211 -0.0316562 0.0328 0.00871901 -0.0316562 0.0328 0.00868211 -0.0316562 0.0338 0.0050059 -0.0260201 0.0338 0.0050059 -0.0260201 0.0328 0.00868211 -0.0316562 0.0328 0.00868211 -0.0316562 0.0338 0.0050059 -0.0260201 0.0338 0.00412043 -0.0260201 0.0328 0.0050059 -0.0260201 0.0328 0.00412043 -0.0260201 0.0338 0.00412043 -0.0260201 0.0338 0.00412043 -0.032763 0.0328 0.00412043 -0.0260201 0.0328 0.00412043 -0.032763 0.0338 0.00412043 -0.032763 0.0338 0.00484504 -0.032763 0.0338 0.00484504 -0.032763 0.0328 0.00412043 -0.032763 0.0328 0.00484504 -0.032763 0.0338 0.00484504 -0.0289304 0.0338 0.00484504 -0.0289304 0.0328 0.00484504 -0.032763 0.0328 0.00477125 -0.0271048 0.0338 0.00482659 -0.0280593 0.0328 0.00482659 -0.0280593 0.0338 0.00477125 -0.0271048 0.0328 0.00484504 -0.0289304 0.0328 0.00484504 -0.0289304 0.0338 0.00477125 -0.0271048 0.0338 0.00480815 -0.0271048 0.0338 0.00480815 -0.0271048 0.0328 0.00477125 -0.0271048 0.0328 0.00849321 -0.032763 0.0338 0.00849321 -0.032763 0.0328 0.00480815 -0.0271048 0.0328 0.00480815 -0.0271048 0.0338 0.00865407 -0.0298896 0.0328 0.00938754 -0.0260201 0.0328 0.00865407 -0.0260201 0.0328 0.00484504 -0.0289304 0.0328 0.00412043 -0.0260201 0.0328 0.00412043 -0.032763 0.0328 0.00938754 -0.032763 0.0328 0.00867769 -0.0308563 0.0328 0.00849321 -0.032763 0.0328 0.00871901 -0.0316562 0.0328 0.00868211 -0.0316562 0.0328 0.00484504 -0.032763 0.0328 0.00480815 -0.0271048 0.0328 0.0050059 -0.0260201 0.0328 0.00477125 -0.0271048 0.0328 0.00482659 -0.0280593 0.0328 -0.0214802 0.0181966 0.0338 -0.0237543 0.0181966 0.0328 -0.0214802 0.0181966 0.0328 -0.0237543 0.0181966 0.0338 -0.0279121 0.00649564 0.0338 -0.0279121 0.00649564 0.0328 -0.0237543 0.0181966 0.0328 -0.0237543 0.0181966 0.0338 -0.0287529 0.00381933 0.0328 -0.0283626 0.00515881 0.0328 -0.0287529 0.00381933 0.0338 -0.029083 0.00247719 0.0338 -0.029083 0.00247719 0.0328 -0.0283626 0.00515881 0.0338 -0.0279121 0.00649564 0.0328 -0.0279121 0.00649564 0.0338 -0.0297787 0.0050827 0.0328 -0.0293977 0.00376711 0.0328 -0.0297787 0.0050827 0.0338 -0.030226 0.00642396 0.0338 -0.030226 0.00642396 0.0328 -0.0293977 0.00376711 0.0338 -0.029083 0.00247719 0.0328 -0.029083 0.00247719 0.0338 -0.0344078 0.0181966 0.0338 -0.0344078 0.0181966 0.0328 -0.030226 0.00642396 0.0328 -0.030226 0.00642396 0.0338 -0.0344078 0.0181966 0.0338 -0.03665 0.0181966 0.0328 -0.0344078 0.0181966 0.0328 -0.03665 0.0181966 0.0338 -0.0301265 -1.59872e-17 0.0338 -0.0301265 -1.59872e-17 0.0328 -0.03665 0.0181966 0.0328 -0.03665 0.0181966 0.0338 -0.0301265 -1.59872e-17 0.0338 -0.0280356 0 0.0338 -0.0280356 0 0.0328 -0.0301265 -1.59872e-17 0.0328 -0.0214802 0.0181966 0.0338 -0.0214802 0.0181966 0.0328 -0.0280356 0 0.0328 -0.0280356 0 0.0338 -0.0214802 0.0181966 0.0328 -0.0237543 0.0181966 0.0328 -0.0279121 0.00649564 0.0328 -0.029083 0.00247719 0.0328 -0.0280356 0 0.0328 -0.0287529 0.00381933 0.0328 -0.0283626 0.00515881 0.0328 -0.0301265 -1.59872e-17 0.0328 -0.0293977 0.00376711 0.0328 -0.0297787 0.0050827 0.0328 -0.030226 0.00642396 0.0328 -0.0344078 0.0181966 0.0328 -0.03665 0.0181966 0.0328 -0.00457635 -0.0267031 0.0338 -0.00455828 -0.0294245 0.0338 -0.00436329 -0.029406 0.0338 -0.00494982 -0.029438 0.0338 -0.00565673 -0.026699 0.0338 -0.00565673 -0.029438 0.0338 -0.00416944 -0.0293775 0.0338 -0.0041708 -0.0267418 0.0338 -0.00437305 -0.0267167 0.0338 -0.00302873 -0.0276019 0.0338 -0.00341499 -0.0270259 0.0338 -0.00358853 -0.0269191 0.0338 -0.00397077 -0.0267813 0.0338 -0.00298184 -0.0281742 0.0338 -0.00297668 -0.0280213 0.0338 -0.00307602 -0.0286221 0.0338 -0.0034423 -0.0291016 0.0338 -0.00314062 -0.0287608 0.0338 -0.00379088 -0.0292787 0.0338 -0.00361066 -0.0292022 0.0338 -0.00299868 -0.0283263 0.0338 -0.00322396 -0.028889 0.0338 -0.003325 -0.0290033 0.0338 -0.00302933 -0.0284763 0.0338 -0.0029818 -0.0278801 0.0338 -0.00377508 -0.0268387 0.0338 -0.00313525 -0.0273409 0.0338 -0.00321342 -0.0272232 0.0338 -0.00330741 -0.0271176 0.0338 -0.00307381 -0.0274681 0.0338 -0.00299868 -0.0277399 0.0338 -0.00397811 -0.0293358 0.0338 -0.00478011 -0.026699 0.0338 -0.00475385 -0.029435 0.0338 0.0313915 0.00922102 0.0338 0.032373 0.0082319 0.0338 0.0320461 0.00867612 0.0338 0.0271495 0.0021526 0.0338 0.0281277 0.00166722 0.0338 0.028665 0.00154588 0.0338 0.0276225 0.00186946 0.0338 0.0263395 0.00291478 0.0338 0.0292344 0.00150543 0.0338 0.032895 0.00485897 0.0338 0.0312398 0.00200104 0.0338 0.0316311 0.00227983 0.0338 0.0319784 0.00262056 0.0338 0.0308045 0.00178421 0.0338 0.0322724 0.00301372 0.0338 0.0325072 0.00344307 0.0338 0.0303252 0.00162933 0.0338 0.0326854 0.00390054 0.0338 0.0328123 0.00437496 0.0338 0.0298018 0.0015364 0.0338 0.0329403 0.0053478 0.0338 0.0257376 0.00390694 0.0338 0.0260126 0.00338211 0.0338 0.0297616 0.00969441 0.0338 0.0329541 0.00583851 0.0338 0.0329178 0.00652934 0.0338 0.0317394 0.00897467 0.0338 0.0306049 0.00955315 0.0338 0.0326272 0.00772603 0.0338 0.0310096 0.00941372 0.0338 0.0328088 0.00715851 0.0338 0.0301867 0.00964446 0.0338 0.0286084 0.00965828 0.0338 0.0293339 0.00970961 0.0338 0.0254611 0.00466453 0.0338 0.0268377 0.00899498 0.0338 0.0252951 0.00546105 0.0338 0.0272809 0.00924763 0.0338 0.0279241 0.00950429 0.0338 0.0264421 0.00869902 0.0338 0.026094 0.00835975 0.0338 0.0255512 0.00756896 0.0338 0.0252398 0.00629651 0.0338 0.0257934 0.00797717 0.0338 0.0253782 0.00715277 0.0338 0.0252744 0.00672863 0.0338 0.0267185 0.00250494 0.0338 -0.000787259 0.0163563 0.0338 -0.000143634 0.00905927 0.0338 -0.00030682 0.0163289 0.0338 -0.00172646 0.00897283 0.0338 -0.00363413 0.0163646 0.0338 -0.00363413 0.00897283 0.0338 0.000895814 0.00924863 0.0338 0.000171727 0.0162785 0.0338 0.000379487 0.00913628 0.0338 0.00345784 0.0139278 0.0338 0.00241546 0.0154824 0.0338 0.00200762 0.0157383 0.0338 0.00358438 0.0123834 0.0338 0.00359829 0.0127961 0.0338 0.00111487 0.0160901 0.0338 0.00333023 0.0111749 0.0338 0.00234178 0.00988086 0.0338 0.00315589 0.0108005 0.0338 0.00140108 0.00940283 0.0338 0.00188744 0.00960923 0.0338 0.00353892 0.011973 0.0338 0.00293099 0.0104546 0.0338 0.0026583 0.0101462 0.0338 0.00345621 0.0115683 0.0338 0.00358449 0.0131773 0.0338 0.000646041 0.0162 0.0338 0.00317038 0.0146322 0.0338 0.00295942 0.0149499 0.0338 0.00270578 0.0152349 0.0338 0.00333617 0.014289 0.0338 0.00157287 0.0159398 0.0338 0.00353892 0.0135555 0.0338 -0.00126846 0.0163646 0.0338 -0.00066985 0.00900928 0.0338 -0.00119761 0.00898099 0.0338 - - - - - - - - - - 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 7.54979e-08 -1 0 -4.37114e-08 -1 -0 0.0581449 -0.998308 0 -0.998308 0.058145 0 -1 8.74228e-08 0 -1 8.74228e-08 0 0.0581449 -0.998308 0 0.116093 -0.993238 0 0.173648 -0.984808 0 0.116093 -0.993238 0 0.173648 -0.984808 0 0.230616 -0.973045 0 0.230616 -0.973045 0 0.286803 -0.95799 0 0.34202 -0.939693 0 0.286803 -0.95799 0 0.34202 -0.939693 0 0.39608 -0.918216 0 0.39608 -0.918216 0 0.448799 -0.893633 0 0.5 -0.866025 0 0.448799 -0.893633 0 0.5 -0.866025 0 0.549509 -0.835488 0 0.549509 -0.835488 0 0.597159 -0.802123 0 0.642788 -0.766044 0 0.597159 -0.802123 0 0.642788 -0.766044 0 0.686242 -0.727374 0 0.686242 -0.727374 0 0.727374 -0.686242 0 0.766044 -0.642788 0 0.727374 -0.686242 0 0.766044 -0.642788 0 0.802123 -0.597159 0 0.802123 -0.597159 0 0.835488 -0.549509 0 0.866025 -0.5 0 0.835488 -0.549509 0 0.866025 -0.5 0 0.893633 -0.448799 0 0.893633 -0.448799 0 0.918216 -0.39608 0 0.939693 -0.34202 0 0.918216 -0.39608 0 0.939693 -0.34202 0 0.95799 -0.286803 0 0.95799 -0.286803 0 0.973045 -0.230616 0 0.984808 -0.173648 0 0.973045 -0.230616 0 0.984808 -0.173648 0 0.993238 -0.116093 0 0.993238 -0.116093 0 0.998308 -0.0581448 0 1 4.57162e-13 0 0.998308 -0.0581448 0 1 2.03021e-28 0 -0.0581448 -0.998308 -0 -0.0581449 -0.998308 -0 -0.116093 -0.993238 -0 -0.116093 -0.993238 -0 -0.173648 -0.984808 -0 -0.230616 -0.973045 -0 -0.173648 -0.984808 -0 -0.230616 -0.973045 -0 -0.286803 -0.95799 -0 -0.286803 -0.95799 -0 -0.34202 -0.939693 -0 -0.39608 -0.918216 -0 -0.34202 -0.939693 -0 -0.39608 -0.918216 -0 -0.448799 -0.893633 -0 -0.448799 -0.893633 -0 -0.5 -0.866025 -0 -0.549509 -0.835488 -0 -0.5 -0.866025 -0 -0.549509 -0.835488 -0 -0.597159 -0.802123 -0 -0.597159 -0.802123 -0 -0.642788 -0.766044 -0 -0.686242 -0.727374 -0 -0.642788 -0.766044 -0 -0.686242 -0.727374 -0 -0.727374 -0.686242 -0 -0.727374 -0.686242 -0 -0.766044 -0.642788 -0 -0.802123 -0.597159 -0 -0.766044 -0.642788 -0 -0.802123 -0.597159 -0 -0.835488 -0.549509 -0 -0.835488 -0.549509 -0 -0.866025 -0.5 -0 -0.893633 -0.448799 -0 -0.866025 -0.5 -0 -0.893633 -0.448799 -0 -0.918216 -0.39608 -0 -0.918216 -0.39608 -0 -0.939693 -0.34202 -0 -0.95799 -0.286803 -0 -0.939693 -0.34202 -0 -0.95799 -0.286803 -0 -0.973045 -0.230616 -0 -0.973045 -0.230616 -0 -0.984808 -0.173648 -0 -0.993238 -0.116093 -0 -0.984808 -0.173648 -0 -0.993238 -0.116093 -0 -0.998308 -0.0581448 -0 -0.998308 -0.0581448 -0 -0.973045 0.230616 0 -0.984808 0.173648 0 -0.984808 0.173648 0 -0.993238 0.116093 0 -0.998308 0.0581447 0 -0.993238 0.116093 0 -0.939693 0.34202 0 -0.918216 0.39608 0 -0.939693 0.34202 0 -0.973045 0.230616 0 -0.957989 0.286803 0 -0.95799 0.286803 0 -0.866025 0.5 0 -0.866025 0.5 0 -0.835488 0.549509 0 -0.893633 0.448799 0 -0.918216 0.39608 0 -0.893633 0.448799 0 -0.727374 0.686242 0 -0.766044 0.642788 0 -0.766044 0.642788 0 -0.802123 0.597158 0 -0.802123 0.597159 0 -0.835488 0.549509 0 -0.642788 0.766045 0 -0.597159 0.802123 0 -0.642788 0.766045 0 -0.727374 0.686241 0 -0.686242 0.727374 0 -0.686242 0.727374 0 -0.5 0.866025 0 -0.5 0.866025 0 -0.448799 0.893633 0 -0.549509 0.835488 0 -0.597159 0.802123 0 -0.549509 0.835488 0 -0.286803 0.95799 0 -0.342021 0.939692 0 -0.34202 0.939693 0 -0.39608 0.918216 0 -0.39608 0.918216 0 -0.448799 0.893633 0 -0.173648 0.984808 0 -0.116093 0.993238 0 -0.173648 0.984808 0 -0.286803 0.95799 0 -0.230616 0.973045 0 -0.230616 0.973045 0 1.19249e-08 1 0 1.19249e-08 1 0 0.0581451 0.998308 0 -0.0581451 0.998308 0 -0.116093 0.993238 0 -0.0581446 0.998308 0 0.230616 0.973045 0 0.173648 0.984808 0 0.173648 0.984808 0 0.116093 0.993238 0 0.116093 0.993238 0 0.0581447 0.998308 0 0.34202 0.939693 0 0.39608 0.918216 0 0.34202 0.939693 0 0.230616 0.973045 0 0.286803 0.957989 0 0.286803 0.957989 0 0.5 0.866025 0 0.5 0.866025 0 0.549509 0.835488 0 0.448799 0.893633 0 0.39608 0.918216 0 0.448799 0.893633 0 0.686242 0.727374 0 0.642788 0.766044 0 0.642788 0.766044 0 0.597159 0.802123 0 0.597159 0.802123 0 0.549509 0.835488 0 0.766044 0.642788 0 0.727374 0.686242 0 0.727374 0.686242 0 0.686241 0.727374 0 0.766045 0.642787 0 0.802123 0.597159 0 0.802123 0.597158 0 0.835488 0.549509 0 0.866026 0.5 0 0.835488 0.549509 0 0.866025 0.5 0 0.893633 0.448799 0 0.893633 0.448799 0 0.918216 0.39608 0 0.939693 0.34202 0 0.918216 0.39608 0 0.939693 0.34202 0 0.95799 0.286803 0 0.95799 0.286803 0 0.973045 0.230616 0 0.984808 0.173648 0 0.973045 0.230616 0 0.984808 0.173648 0 0.993238 0.116093 0 0.993238 0.116093 0 0.998308 0.058145 0 0.998308 0.058145 0 -1.19249e-08 -1 0 -0.0560705 -0.998427 0 -1.19249e-08 -1 0 1 -8.74228e-08 0 1 -8.74228e-08 0 0.998427 0.0560704 0 -0.0560705 -0.998427 0 -0.111965 -0.993712 0 -0.167506 -0.985871 0 -0.111965 -0.993712 0 -0.222521 -0.974928 0 -0.167506 -0.985871 0 -0.222521 -0.974928 0 -0.276836 -0.960917 0 -0.330279 -0.943883 0 -0.276835 -0.960917 0 -0.382684 -0.923879 0 -0.330279 -0.943883 0 -0.382684 -0.923879 0 -0.433884 -0.900969 0 -0.483719 -0.875224 0 -0.433883 -0.900969 0 -0.532032 -0.846724 0 -0.483719 -0.875223 0 -0.532032 -0.846724 0 -0.578671 -0.815561 0 -0.62349 -0.781831 0 -0.578672 -0.815561 0 -0.666346 -0.745642 0 -0.62349 -0.781832 0 -0.666346 -0.745642 0 -0.707107 -0.707107 0 -0.745642 -0.666346 0 -0.707107 -0.707107 0 -0.781831 -0.62349 0 -0.745642 -0.666347 0 -0.781831 -0.62349 0 -0.815561 -0.578671 0 -0.846724 -0.532032 0 -0.815561 -0.578671 0 -0.875223 -0.483719 0 -0.846724 -0.532032 0 -0.875223 -0.483719 0 -0.900969 -0.433884 0 -0.92388 -0.382683 0 -0.900969 -0.433884 0 -0.943883 -0.330279 0 -0.92388 -0.382683 0 -0.943883 -0.330279 0 -0.960917 -0.276835 0 -0.974928 -0.222521 0 -0.960917 -0.276835 0 -0.985871 -0.167506 0 -0.974928 -0.222521 0 -0.985871 -0.167506 0 -0.993712 -0.111964 0 -0.998427 -0.0560708 0 -0.993712 -0.111965 0 -1 1.74846e-07 0 -0.998427 -0.0560703 0 -1 1.74846e-07 0 0.0560705 -0.998427 0 0.111965 -0.993712 0 0.0560705 -0.998427 0 0.167506 -0.985871 0 0.111965 -0.993712 0 0.167506 -0.985871 0 0.222521 -0.974928 0 0.276836 -0.960917 0 0.222521 -0.974928 0 0.330279 -0.943883 0 0.276836 -0.960917 0 0.330279 -0.943883 0 0.382683 -0.92388 0 0.433884 -0.900969 0 0.382684 -0.92388 0 0.483719 -0.875223 0 0.433884 -0.900969 0 0.483719 -0.875224 0 0.532032 -0.846724 0 0.578672 -0.815561 0 0.532032 -0.846724 0 0.62349 -0.781832 0 0.578671 -0.815561 0 0.62349 -0.781831 0 0.666347 -0.745642 0 0.707107 -0.707107 0 0.666346 -0.745642 0 0.745642 -0.666346 0 0.707107 -0.707107 0 0.745642 -0.666346 0 0.781832 -0.62349 0 0.815561 -0.578671 0 0.781831 -0.62349 0 0.846724 -0.532032 0 0.815561 -0.578671 0 0.846724 -0.532032 0 0.875223 -0.483719 0 0.900969 -0.433884 0 0.875223 -0.483719 0 0.923879 -0.382684 0 0.900969 -0.433884 0 0.92388 -0.382683 0 0.943883 -0.330279 0 0.960917 -0.276835 0 0.943883 -0.330279 0 0.974928 -0.222521 0 0.960917 -0.276835 0 0.974928 -0.222521 0 0.985871 -0.167506 0 0.993712 -0.111965 0 0.985871 -0.167506 0 0.998427 -0.0560703 0 0.993712 -0.111964 0 0.998427 -0.0560706 0 0.993712 0.111964 0 0.998427 0.0560704 0 0.993712 0.111964 0 0.960917 0.276836 0 0.974928 0.222521 0 0.960917 0.276836 0 0.985871 0.167506 0 0.985871 0.167506 0 0.974928 0.222521 0 0.92388 0.382683 0 0.900969 0.433884 0 0.900969 0.433884 0 0.943883 0.330279 0 0.92388 0.382683 0 0.943883 0.330279 0 0.815561 0.578671 0 0.815561 0.578671 0 0.846724 0.532032 0 0.846724 0.532032 0 0.875223 0.483719 0 0.875223 0.483719 0 0.707107 0.707107 0 0.745642 0.666347 0 0.707107 0.707107 0 0.781832 0.62349 0 0.781831 0.62349 0 0.745642 0.666347 0 0.62349 0.781832 0 0.578671 0.815561 0 0.578671 0.815561 0 0.666347 0.745642 0 0.62349 0.781832 0 0.666347 0.745642 0 0.433884 0.900969 0 0.433884 0.900969 0 0.483719 0.875223 0 0.483719 0.875223 0 0.532032 0.846724 0 0.532032 0.846724 0 0.276836 0.960917 0 0.330279 0.943883 0 0.276836 0.960917 0 0.382683 0.92388 0 0.382683 0.92388 0 0.330279 0.943883 0 0.167506 0.985871 0 0.111964 0.993712 0 0.111964 0.993712 0 0.222521 0.974928 0 0.167506 0.985871 0 0.222521 0.974928 0 -0.0560704 0.998427 0 -0.0560704 0.998427 0 4.37114e-08 1 0 -7.54979e-08 1 0 0.0560704 0.998427 0 0.0560704 0.998427 0 -0.222521 0.974928 0 -0.167506 0.985871 0 -0.222521 0.974928 0 -0.111964 0.993712 0 -0.111964 0.993712 0 -0.167506 0.985871 0 -0.330279 0.943883 0 -0.382683 0.92388 0 -0.382683 0.92388 0 -0.276835 0.960917 0 -0.330279 0.943883 0 -0.276835 0.960917 0 -0.532032 0.846724 0 -0.532032 0.846724 0 -0.483719 0.875223 0 -0.483719 0.875223 0 -0.433884 0.900969 0 -0.433884 0.900969 0 -0.666347 0.745642 0 -0.62349 0.781832 0 -0.666347 0.745642 0 -0.578671 0.815561 0 -0.578671 0.815561 0 -0.62349 0.781832 0 -0.745642 0.666347 0 -0.707107 0.707107 0 -0.745642 0.666347 0 -0.707107 0.707107 0 -0.781831 0.62349 0 -0.781831 0.62349 0 -0.815561 0.578671 0 -0.815561 0.578671 0 -0.846724 0.532032 0 -0.846724 0.532032 0 -0.875223 0.483719 0 -0.875223 0.483719 0 -0.900969 0.433884 0 -0.900969 0.433884 0 -0.92388 0.382683 0 -0.92388 0.382683 0 -0.943883 0.330279 0 -0.943883 0.330279 0 -0.960917 0.276836 0 -0.960917 0.276836 0 -0.974928 0.222521 0 -0.974928 0.222521 0 -0.985871 0.167506 0 -0.985871 0.167506 0 -0.993712 0.111964 0 -0.993712 0.111964 0 -0.998427 0.0560705 0 -0.998427 0.0560705 0 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.611764 -0.79104 0 0.611764 -0.79104 0 0.611764 -0.79104 0 0.611764 -0.79104 0 0.791383 0.611321 0 0.791383 0.611321 0 0.791383 0.611321 0 0.791383 0.611321 0 -0.659484 0.751719 0 -0.659484 0.751719 0 -0.630681 0.776042 0 -0.630681 0.776042 0 -0.712484 0.701689 0 -0.712484 0.701689 0 -0.659484 0.751719 0 -0.659484 0.751719 0 1 -2.00187e-12 0 0.999472 -0.0324926 0 0.999472 -0.0324926 0 1 -1.80161e-22 0 0.997624 -0.0688967 0 0.997624 -0.0688967 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0.234828 0.972037 0 0.234659 0.972078 0 0.156514 0.987676 0 0.332694 0.943035 0 0.332639 0.943054 0 0.454136 0.890932 0 0.454085 0.890958 0 0.597839 0.801616 0 0.597839 0.801616 0 0.156662 0.987652 0 0.0936821 0.995602 0 0.0937726 0.995594 0 0.0424414 0.999099 0 0.0424367 0.999099 0 0 1 0 0 1 0 0.964505 0.264065 0 0.926563 0.37614 0 0.926437 0.376449 0 0.986616 0.163061 0 0.964543 0.263925 0 0.986621 0.163032 0 0.997169 0.0751935 0 1 0 0 0.99717 0.0751805 0 1 6.89159e-23 0 0.869118 0.494605 0 0.791713 0.610893 0 0.868883 0.495018 0 0.698603 0.715509 0 0.791458 0.611224 0 0.69859 0.715522 0 0.597839 0.801616 0 0.597839 0.801616 0 0.876297 -0.481771 0 0.932451 -0.361295 0 0.932556 -0.361026 0 0.796839 -0.604192 0 0.876054 -0.482213 0 0.796525 -0.604605 0 0.697058 -0.717014 0 0.585725 -0.81051 0 0.697035 -0.717037 0 0.585725 -0.81051 0 0.968167 -0.250305 0 0.988206 -0.153132 0 0.96819 -0.250217 0 0.997536 -0.0701581 0 0.988206 -0.153133 0 0.997537 -0.070145 0 1 0 0 1 0 0 -0.914111 0.405463 0 -0.965719 0.25959 0 -0.914111 0.405463 0 -0.965719 0.25959 0 -0.992497 0.122271 0 -1 0 0 -0.992497 0.122271 0 -1 0 0 -0.83569 0.549201 0 -0.734369 0.67875 0 -0.83569 0.549201 0 -0.734369 0.67875 0 -0.619322 0.785137 0 -0.619322 0.785137 0 -0.418628 -0.908158 0 -0.535457 -0.844563 0 -0.535547 -0.844505 0 -0.315809 -0.948823 0 -0.418481 -0.908226 0 -0.315787 -0.94883 0 -0.228647 -0.973509 0 -0.155741 -0.987798 0 -0.228706 -0.973496 0 -0.0947839 -0.995498 0 -0.155813 -0.987787 0 -0.0948364 -0.995493 0 -0.0435113 -0.999053 0 0 -1 0 -0.0435039 -0.999053 0 0 -1 0 -0.659565 -0.751648 0 -0.777285 -0.629149 0 -0.659901 -0.751352 0 -0.873491 -0.48684 0 -0.777866 -0.62843 0 -0.873946 -0.486023 0 -0.939823 -0.341663 0 -0.978014 -0.208538 0 -0.93998 -0.341229 0 -0.995524 -0.0945069 0 -0.978029 -0.20847 0 -0.995525 -0.0945009 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.280042 0.959988 0 -0.280074 0.959978 0 -0.191518 0.981489 0 -0.382868 0.923803 0 -0.383041 0.923731 0 -0.498177 0.867075 0 -0.498143 0.867095 0 -0.619322 0.785137 0 -0.619322 0.785137 0 -0.191562 0.981481 0 -0.116593 0.99318 0 -0.116645 0.993174 0 -0.0534283 0.998572 0 -0.0534215 0.998572 0 0 1 0 0 1 0 0.118816 -0.992916 0 0.176232 -0.984349 0 0.176253 -0.984345 0 0.0719046 -0.997411 0 0.118946 -0.992901 0 0.0720254 -0.997403 0 0.0329174 -0.999458 0 0 -1 0 0.032914 -0.999458 0 2.47077e-15 -1 0 0.247536 -0.968879 0 0.336729 -0.941602 0 0.247335 -0.96893 0 0.337006 -0.941503 0 0.449169 -0.893447 0 0.449222 -0.89342 0 0.585725 -0.81051 0 0.585725 -0.81051 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.376485 -0.926423 0 0.239914 -0.970794 0 0.376485 -0.926423 0 0.239914 -0.970794 0 0.112864 -0.99361 0 0 -1 0 0.112864 -0.99361 0 0 -1 0 0.514226 -0.857655 0 0.642664 -0.766148 0 0.514226 -0.857655 0 0.642664 -0.766148 0 0.752577 -0.658505 0 0.752577 -0.658505 0 -0.296457 -0.955046 0 -0.296457 -0.955046 0 -0.444476 -0.895791 0 -0.577869 -0.816129 0 -0.444476 -0.895791 0 -0.577869 -0.816129 0 -0.144661 -0.989481 0 -0.144661 -0.989481 0 0 -1 0 -3.29447e-08 -1 0 -0.779054 -0.626957 0 -0.779054 -0.626957 0 -0.854985 -0.518653 0 -0.912044 -0.410092 0 -0.854985 -0.518653 0 -0.912044 -0.410092 0 -0.685295 -0.728266 0 -0.685295 -0.728266 0 -0.577869 -0.816129 0 -0.577869 -0.816129 0 -0.990934 -0.134346 0 -0.961772 -0.273853 0 -0.990934 -0.134346 0 -1 0 0 -1 0 0 -0.961772 -0.273853 0 -0.912044 -0.410092 0 -0.912044 -0.410092 0 -0.949803 0.31285 0 -0.949803 0.31285 0 -0.893129 0.4498 0 -0.825108 0.564975 0 -0.893129 0.4498 0 -0.825108 0.564975 0 -0.987189 0.159557 0 -0.987189 0.159557 0 -1 0 0 -1 3.78313e-08 0 -0.649449 0.760405 0 -0.649449 0.760405 0 -0.547343 0.836908 0 -0.443387 0.89633 0 -0.547343 0.836908 0 -0.443387 0.89633 0 -0.743804 0.668398 0 -0.743804 0.668398 0 -0.825108 0.564975 0 -0.825108 0.564975 0 -0.144117 0.989561 0 -0.295518 0.955337 0 -0.144117 0.989561 0 0 1 0 1.41149e-22 1 0 -0.295518 0.955337 0 -0.443387 0.89633 0 -0.443387 0.89633 0 0.385222 0.922824 0 0.385603 0.922665 0 0.266893 0.963726 0 0.51288 0.85846 0 0.513386 0.858158 0 0.639215 0.769028 0 0.639181 0.769056 0 0.75123 0.66004 0 0.75123 0.66004 0 0.26675 0.963766 0 0.162797 0.98666 0 0.162793 0.98666 0 0.0743037 0.997236 0 0.0742887 0.997237 0 0 1 0 0 1 0 0.926529 0.376222 0 0.971764 0.235955 0 0.971764 0.235955 0 0.993997 0.109404 0 0.993997 0.109404 0 1 0 0 1 0 0 0.92653 0.376222 0 0.85307 0.521797 0 0.85307 0.521797 0 0.75123 0.66004 0 0.75123 0.66004 0 0.989209 -0.14651 0 0.976779 -0.214249 0 0.976773 -0.214278 0 0.995987 -0.0894952 0 0.989198 -0.146587 0 0.995978 -0.089593 0 0.99915 -0.0412263 0 1 0 0 0.99915 -0.0412212 0 1 2.81046e-16 0 0.955555 -0.294812 0 0.92095 -0.389682 0 0.95557 -0.294764 0 0.866822 -0.498618 0 0.92091 -0.389775 0 0.866797 -0.498661 0 0.786646 -0.617405 0 0.786646 -0.617405 0 0.97051 0.241062 0 0.93537 0.353671 0 0.970502 0.241094 0 0.93527 0.353934 0 0.87665 0.481129 0 0.788674 0.614811 0 0.876625 0.481173 0 0.788674 0.614811 0 0.989352 0.14554 0 0.997818 0.0660227 0 0.989343 0.145604 0 0.997819 0.0660111 0 1 0 0 1 2.60692e-08 0 0.428311 0.903631 0 0.279145 0.960249 0 0.428311 0.903631 0 0.279145 0.960249 0 0.133377 0.991065 0 0 1 0 0.133377 0.991065 0 0 1 0 0.569154 0.822231 0 0.691176 0.722687 0 0.569154 0.822231 0 0.691176 0.722687 0 0.788674 0.614811 0 0.788674 0.614811 0 -0.361591 0.932337 0 -0.492754 0.870169 0 -0.361591 0.932337 0 -0.492754 0.870169 0 -0.616113 0.787658 0 -0.723758 0.690054 0 -0.616113 0.787658 0 -0.723758 0.690054 0 -0.231442 0.972849 0 -0.109489 0.993988 0 -0.231442 0.972849 0 -0.109489 0.993988 0 0 1 0 0 1 0 -0.944735 0.327834 0 -0.978237 0.207489 0 -0.944735 0.327834 0 -0.978237 0.207489 0 -0.995241 0.0974449 0 -1 0 0 -0.995241 0.0974449 0 -1 0 0 -0.891257 0.453498 0 -0.816729 0.577021 0 -0.891257 0.453498 0 -0.816729 0.577021 0 -0.723758 0.690054 0 -0.723758 0.690054 0 -0.966144 -0.258002 0 -0.91363 -0.406546 0 -0.91363 -0.406546 0 -0.831809 -0.555061 0 -0.831809 -0.555061 0 -0.72393 -0.689874 0 -0.72393 -0.689874 0 -0.966144 -0.258002 0 -0.992711 -0.120519 0 -0.992711 -0.120519 0 -1 0 0 -1 -3.31709e-08 0 -0.357915 -0.933754 0 -0.228287 -0.973594 0 -0.357915 -0.933754 0 -0.228287 -0.973594 0 -0.107683 -0.994185 0 0 -1 0 -0.107683 -0.994185 0 0 -1 0 -0.489605 -0.871944 0 -0.614409 -0.788987 0 -0.489605 -0.871944 0 -0.614409 -0.788987 0 -0.72393 -0.689874 0 -0.72393 -0.689874 0 0.512254 -0.858834 0 0.512254 -0.858834 0 0.373544 -0.927612 0 0.642531 -0.76626 0 0.642531 -0.76626 0 0.754485 -0.656318 0 0.754485 -0.656318 0 0.842499 -0.538698 0 0.842499 -0.538698 0 0.373544 -0.927612 0 0.237139 -0.971476 0 0.237139 -0.971476 0 0.111203 -0.993798 0 0.111203 -0.993798 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.946481 0.322758 0 -0.969762 0.244053 0 -0.969769 0.244025 0 -0.90912 0.416535 0 -0.946509 0.322678 0 -0.909104 0.416569 0 -0.850669 0.525702 0 -0.76307 0.646316 0 -0.85064 0.525748 0 -0.76307 0.646316 0 -0.983962 0.178378 0 -0.99235 0.123454 0 -0.983945 0.17847 0 -0.997021 0.0771288 0 -0.992337 0.12356 0 -0.997021 0.077124 0 -0.999291 0.0376515 0 -0.999291 0.0376515 0 -0.377428 0.926039 0 -0.239152 0.970982 0 -0.377428 0.926039 0 -0.239152 0.970982 0 -0.111908 0.993719 0 0 1 0 -0.111908 0.993719 0 0 1 0 -0.518239 0.855236 0 -0.650264 0.759708 0 -0.518239 0.855236 0 -0.650265 0.759708 0 -0.76307 0.646316 0 -0.76307 0.646316 0 0.193492 0.981102 0 0.0904312 0.995903 0 0.193492 0.981102 0 0.307925 0.951411 0 0.307925 0.951411 0 0.0904312 0.995903 0 0 1 0 1.50458e-08 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.0647702 -0.9979 0 -0.153622 -0.98813 0 -0.0647702 -0.9979 0 0 -1 0 2.78554e-16 -1 0 -0.153622 -0.98813 0 -0.279092 -0.960264 0 -0.279092 -0.960265 0 0.395601 -0.918423 0 0.541332 -0.840809 0 0.395601 -0.918423 0 0.541332 -0.840809 0 0.675289 -0.737553 0 0.786646 -0.617405 0 0.675289 -0.737553 0 0.786646 -0.617405 0 0.25089 -0.968015 0 0.11727 -0.9931 0 0.25089 -0.968015 0 0.11727 -0.9931 0 0 -1 0 0 -1 0 0.951423 -0.307888 0 0.951387 -0.307998 0 0.977436 -0.21123 0 0.908357 -0.418196 0 0.908233 -0.418466 0 0.842879 -0.538103 0 0.842902 -0.538067 0 0.752577 -0.658505 0 0.752577 -0.658505 0 0.977435 -0.211239 0 0.991688 -0.128666 0 0.991682 -0.128709 0 0.998263 -0.0589134 0 0.998264 -0.0589049 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0.268977 0.963147 0 0.193501 0.9811 0 0.193476 0.981105 0 0.360791 0.932647 0 0.268851 0.963182 0 0.360713 0.932677 0 0.470966 0.882151 0 0.597839 0.801616 0 0.471014 0.882126 0 0.597839 0.801616 0 0.131375 0.991333 0 0.0798834 0.996804 0 0.131481 0.991319 0 0.0366888 0.999327 0 0.0799942 0.996795 0 0.0366847 0.999327 0 0 1 0 0 1 0 0.964505 0.264065 0 0.926563 0.37614 0 0.926437 0.376449 0 0.986616 0.163061 0 0.964543 0.263925 0 0.986621 0.163032 0 0.997169 0.0751935 0 1 0 0 0.99717 0.0751805 0 1 -1.80629e-23 0 0.869118 0.494605 0 0.791713 0.610893 0 0.868883 0.495018 0 0.698603 0.715509 0 0.791458 0.611224 0 0.69859 0.715522 0 0.597839 0.801616 0 0.597839 0.801616 0 0.876297 -0.481771 0 0.932451 -0.361295 0 0.932556 -0.361026 0 0.796839 -0.604192 0 0.876054 -0.482213 0 0.796525 -0.604605 0 0.697058 -0.717014 0 0.585725 -0.81051 0 0.697035 -0.717037 0 0.585725 -0.81051 0 0.968167 -0.250305 0 0.988206 -0.153132 0 0.96819 -0.250217 0 0.997536 -0.0701581 0 0.988206 -0.153133 0 0.997537 -0.070145 0 1 0 0 1 0 0 -0.914111 0.405463 0 -0.965719 0.25959 0 -0.914111 0.405463 0 -0.965719 0.25959 0 -0.992497 0.122271 0 -1 0 0 -0.992497 0.122271 0 -1 0 0 -0.83569 0.549201 0 -0.734369 0.67875 0 -0.83569 0.549201 0 -0.734369 0.67875 0 -0.619322 0.785137 0 -0.619322 0.785137 0 -0.418628 -0.908158 0 -0.535457 -0.844563 0 -0.535547 -0.844505 0 -0.315809 -0.948823 0 -0.418481 -0.908225 0 -0.315787 -0.94883 0 -0.228647 -0.973509 0 -0.155741 -0.987798 0 -0.228706 -0.973496 0 -0.0947839 -0.995498 0 -0.155813 -0.987787 0 -0.0948364 -0.995493 0 -0.0435113 -0.999053 0 0 -1 0 -0.0435039 -0.999053 0 0 -1 0 -0.659565 -0.751648 0 -0.777285 -0.629149 0 -0.659901 -0.751352 0 -0.873491 -0.48684 0 -0.777866 -0.62843 0 -0.873946 -0.486023 0 -0.939823 -0.341663 0 -0.978014 -0.208538 0 -0.93998 -0.341229 0 -0.995524 -0.0945069 0 -0.978029 -0.20847 0 -0.995525 -0.0945009 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.280042 0.959988 0 -0.280074 0.959978 0 -0.191518 0.981489 0 -0.382868 0.923803 0 -0.383041 0.923731 0 -0.498177 0.867075 0 -0.498143 0.867095 0 -0.619322 0.785137 0 -0.619322 0.785137 0 -0.191562 0.981481 0 -0.116593 0.99318 0 -0.116645 0.993174 0 -0.0534283 0.998572 0 -0.0534215 0.998572 0 0 1 0 0 1 0 0.118816 -0.992916 0 0.176232 -0.984349 0 0.176253 -0.984345 0 0.0719046 -0.997411 0 0.118946 -0.992901 0 0.0720254 -0.997403 0 0.0329174 -0.999458 0 0 -1 0 0.032914 -0.999458 0 0 -1 0 0.247536 -0.968879 0 0.336729 -0.941602 0 0.247335 -0.96893 0 0.337006 -0.941503 0 0.449169 -0.893447 0 0.449222 -0.89342 0 0.585725 -0.81051 0 0.585725 -0.81051 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 0.998848 0.0479796 0 0.998848 0.0479796 0 0.999537 -0.0304427 0 0.999537 -0.0304427 0 0.997459 0.071247 0 0.997459 0.071247 0 0.998848 0.0479796 0 0.998848 0.0479796 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.837576 -0.546321 0 -0.837576 -0.546321 0 -0.837576 -0.546321 0 -0.837576 -0.546321 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.997268 -0.0738717 0 -0.999184 -0.0403874 0 -0.999184 -0.0403874 0 -0.997268 -0.0738717 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0.837954 0.545741 0 0.837954 0.545741 0 0.837954 0.545741 0 0.837954 0.545741 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.942278 -0.334832 0 0.942278 -0.334832 0 0.942278 -0.334832 0 0.942278 -0.334832 0 0.965757 -0.259448 0 0.95403 -0.299712 0 0.965757 -0.259448 0 0.97596 -0.217951 0 0.97596 -0.217951 0 0.95403 -0.299712 0 0.940935 -0.338587 0 0.940935 -0.338587 0 -0.954672 -0.297659 0 -0.966159 -0.257949 0 -0.954672 -0.297659 0 -0.942409 -0.334463 0 -0.942409 -0.334463 0 -0.966159 -0.257949 0 -0.976568 -0.21521 0 -0.976568 -0.21521 0 -0.942317 -0.33472 0 -0.942317 -0.33472 0 -0.942317 -0.33472 0 -0.942317 -0.33472 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.941336 0.337472 0 0.941336 0.337472 0 0.941336 0.337472 0 0.941336 0.337472 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.940811 0.338931 0 -0.940811 0.338931 0 -0.940811 0.338931 0 -0.940811 0.338931 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 - - - - - - - - - - - - - - -

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

+ + +

0 2 1 3 1 4 1 3 0 4 6 5 5 3 4 7 8 6 5 6 8 9 7 10 7 9 8 11 12 9 9 10 11 13 12 14 11 14 12 13 16 15 16 13 14 17 18 15 15 16 17 19 18 20 17 20 18 19 22 21 22 19 20 23 24 21 21 22 23 25 24 26 23 26 24 25 28 27 28 25 26 29 30 27 27 28 29 31 30 32 29 32 30 33 31 32 34 36 35 34 35 2 0 34 2 37 39 38 40 35 36 37 41 39 42 41 40 40 36 42 42 39 41 43 37 38 44 46 45 46 47 43 43 38 46 47 46 44 45 48 44 49 51 50 48 52 51 52 48 45 51 52 50 53 49 54 50 54 49 55 53 56 56 53 54 57 55 56 58 60 59 61 62 57 55 57 62 60 58 63 60 63 61 61 63 62 64 65 59 58 59 65 66 67 64 64 67 65 68 70 69 71 72 69 70 73 69 69 72 68 72 71 74 75 73 76 77 74 78 71 78 74 79 81 80 81 77 80 79 82 81 83 85 84 79 83 82 86 88 87 85 90 89 91 93 92 94 96 95 97 99 98 99 97 93 100 98 101 99 101 98 102 103 100 100 101 102 103 105 104 105 103 102 106 104 107 105 107 104 108 109 106 106 107 108 109 111 110 111 109 108 112 110 113 111 113 110 92 93 97 91 92 96 96 94 91 87 88 94 87 94 95 86 89 90 86 90 88 82 83 84 89 84 85 70 76 73 80 77 78 114 75 115 76 115 75 114 117 116 117 114 115 118 120 119 117 121 116 118 121 120 116 121 118 122 123 119 119 120 122 124 126 125 122 127 123 128 130 129 128 127 130 123 127 128 131 133 132 129 130 134 134 131 132 134 132 129 133 131 124 125 133 124 126 135 125 135 137 136 126 137 135 138 136 139 136 137 139 140 142 141 142 140 143 144 146 145 144 147 146 148 146 147 149 144 145 149 145 150 151 152 150 150 152 149 153 155 154 156 155 157 155 156 154 158 159 157 156 157 159 158 160 159 154 161 153 153 161 162 163 164 162 162 161 163 164 166 165 166 164 163 166 167 165 165 167 168 169 171 170 172 170 173 171 173 170 174 175 172 172 173 174 176 175 174 176 177 175 171 169 178 179 180 178 178 169 179 180 182 181 182 180 179 182 183 181 181 183 184 185 187 186 188 186 189 187 189 186 190 191 188 188 189 190 192 191 190 192 193 191 187 185 194 195 196 194 194 185 195 196 198 197 198 196 195 198 199 197 197 199 200 201 203 202 204 203 205 203 204 202 206 207 205 204 205 207 206 208 207 202 209 201 201 209 210 211 212 210 210 209 211 212 214 213 214 212 211 214 215 213 213 215 216 217 219 218 220 219 221 219 220 218 222 223 221 220 221 223 222 224 223 218 225 217 217 225 226 227 228 226 226 225 227 228 230 229 230 228 227 230 231 229 229 231 232 233 235 234 236 235 237 235 236 234 238 239 237 236 237 239 238 240 239 234 241 233 233 241 242 243 244 242 242 241 243 244 246 245 246 244 243 246 247 245 245 247 248 249 251 250 252 250 253 251 253 250 254 255 252 252 253 254 256 255 254 256 257 255 251 249 258 259 260 258 258 249 259 260 262 261 262 260 259 262 263 261 261 263 264 265 267 266 268 266 269 267 269 266 270 271 268 268 269 270 272 271 270 272 273 271 267 265 274 275 276 274 274 265 275 276 278 277 278 276 275 278 279 277 277 279 280 281 283 282 284 282 285 283 285 282 286 287 284 284 285 286 288 287 286 288 289 287 283 281 290 291 292 290 290 281 291 292 294 293 294 292 291 294 295 293 293 295 296 297 299 298 300 298 301 299 301 298 302 303 300 300 301 302 304 303 302 304 305 303 299 297 306 307 308 306 306 297 307 308 310 309 310 308 307 310 311 309 309 311 312 313 315 314 316 314 317 315 317 314 318 319 316 316 317 318 320 319 318 320 321 319 315 313 322 323 324 322 322 313 323 324 326 325 326 324 323 326 327 325 325 327 328 329 331 330 332 330 333 331 333 330 334 335 332 332 333 334 336 335 334 336 337 335 331 329 338 339 340 338 338 329 339 340 342 341 342 340 339 342 343 341 341 343 344 345 347 346 348 350 349 348 351 350 352 349 353 350 353 349 354 355 352 352 353 354 355 357 356 357 355 354 358 360 359 357 361 356 362 364 363 365 367 366 368 370 369 371 373 372 374 376 375 377 379 378 380 381 377 381 380 373 377 378 380 374 371 372 371 381 373 376 374 372 368 375 370 370 375 376 363 364 369 369 364 368 365 366 362 363 365 362 367 347 345 366 367 345 346 360 358 346 347 360 356 361 359 361 358 359 457 459 458 460 462 461 463 461 464 464 461 465 461 462 465 463 466 461 466 467 461 468 470 469 471 469 470 470 473 472 473 470 468 474 472 475 472 473 475 476 478 477 479 481 480 482 484 483 485 486 483 483 486 482 487 488 483 483 488 485 483 489 487 490 492 491 459 494 493 460 495 462 458 459 496 459 493 496 497 498 459 457 497 459 499 501 500 502 504 503 505 506 500 500 508 507 506 508 500 509 500 507 509 511 510 507 511 509 512 502 513 514 516 515 517 518 501 519 514 520 519 516 514 521 514 522 521 520 514 513 522 514 523 476 489 524 526 525 527 493 528 502 461 529 529 461 467 502 503 461 504 502 512 513 531 530 512 513 530 501 514 515 531 513 514 501 518 532 501 532 514 517 501 499 500 534 533 499 500 533 510 490 509 534 500 509 490 491 509 490 493 527 492 490 527 493 494 535 528 493 535 476 459 536 536 459 498 476 477 459 478 476 523 481 479 537 489 539 538 523 489 538 481 483 484 539 489 483 481 537 540 481 540 483 480 481 470 470 542 541 480 470 541 474 525 472 542 470 472 526 543 525 525 543 472 525 462 524 495 544 462 462 544 524 545 547 546 546 548 545 549 551 550 550 552 549 553 555 554 554 556 553 557 559 558 557 560 559 561 563 562 561 564 563 565 567 566 566 568 565 569 571 570 572 574 573 575 577 576 574 572 578 575 580 579 581 583 582 578 585 584 586 588 587 584 590 589 591 593 592 589 595 594 596 598 597 599 594 600 601 603 602 604 606 605 607 609 608 610 612 611 613 615 614 616 618 617 619 621 620 622 624 623 625 626 623 627 629 628 627 630 622 629 621 619 631 617 626 611 612 632 612 618 633 621 635 634 610 637 636 638 635 614 613 640 639 641 609 636 642 607 643 601 644 640 645 646 603 576 577 574 605 606 647 645 569 570 648 569 598 649 647 606 650 652 651 599 653 597 649 651 647 651 649 650 642 643 604 642 604 605 607 608 643 609 641 608 636 637 641 610 611 637 612 633 632 618 616 633 617 631 616 626 625 631 623 624 625 622 630 624 627 628 630 629 619 628 621 634 620 635 638 634 614 615 638 613 639 615 640 644 639 601 602 644 603 646 602 645 570 646 569 648 571 598 596 648 597 653 596 599 600 653 594 595 600 589 590 595 584 585 590 578 572 585 574 577 573 580 575 576 582 579 580 581 588 583 582 583 579 587 591 586 581 587 588 592 593 652 586 591 592 651 652 593 654 656 655 657 658 655 654 655 658 657 660 659 659 658 657 661 660 662 660 661 659 663 664 662 661 662 664 663 666 665 665 664 663 667 666 668 666 667 665 668 670 669 667 668 669 670 672 671 672 670 668 673 671 674 672 674 671 675 676 673 673 674 675 676 678 677 678 676 675 679 677 680 678 680 677 681 682 679 679 680 681 682 684 683 684 682 681 685 683 686 684 686 683 687 688 685 685 686 687 688 690 689 690 688 687 691 689 692 690 692 689 693 694 691 691 692 693 694 696 695 696 694 693 697 695 698 696 698 695 699 700 697 697 698 699 654 701 656 702 701 703 701 702 656 704 705 703 702 703 705 704 707 706 706 705 704 708 707 709 707 708 706 710 711 709 708 709 711 710 713 712 712 711 710 714 713 715 713 714 712 716 717 715 714 715 717 718 719 717 717 716 718 719 721 720 721 719 718 722 720 723 721 723 720 724 725 722 722 723 724 725 727 726 727 725 724 728 726 729 727 729 726 730 731 728 728 729 730 731 733 732 733 731 730 734 732 735 733 735 732 736 737 734 734 735 736 737 739 738 739 737 736 740 738 741 739 741 738 742 743 740 740 741 742 743 745 744 745 743 742 699 744 746 745 746 744 699 746 700 747 749 748 750 752 751 753 754 752 755 747 750 755 750 756 757 747 748 747 757 758 750 751 756 750 747 758 759 751 752 760 752 754 760 759 752 761 753 752 753 761 762 762 763 753 764 766 765 767 766 768 764 768 766 767 770 769 767 768 771 770 767 771 767 769 772 769 774 773 772 769 775 769 773 775 776 765 766 777 778 766 776 766 778 779 778 780 778 777 780 781 783 782 782 784 781 781 784 785 784 786 785 787 789 788 788 790 787 791 790 792 790 788 792 793 795 794 794 796 793 793 796 797 796 798 797 799 801 800 800 802 799 799 802 803 802 804 803 805 807 806 806 808 805 809 808 810 808 806 810 811 813 812 812 814 811 811 814 815 814 816 815 817 819 818 820 817 818 821 823 822 824 820 818 825 827 826 825 822 827 826 827 828 828 827 829 817 827 819 824 830 820 819 827 823 831 823 821 827 822 823 823 831 832 832 833 823 834 836 835 837 839 838 838 835 840 840 837 838 841 842 838 841 838 839 842 844 843 838 842 845 843 845 842 835 847 846 846 840 835 847 835 836 848 849 836 848 836 834 849 850 836 851 853 852 854 855 852 853 857 856 858 857 853 856 860 859 859 853 856 856 862 861 860 856 861 852 863 851 851 858 853 852 864 863 865 854 852 855 864 852 854 865 866 866 867 854 868 870 869 871 873 872 874 875 870 869 876 868 874 870 868 877 879 878 877 878 880 879 877 881 869 877 876 872 877 880 877 872 873 873 876 877 873 871 882 873 882 883 883 884 873 885 887 886 888 890 889 891 885 892 890 893 885 887 885 891 894 886 895 894 885 886 896 895 886 890 897 893 885 893 892 888 898 890 890 898 897 899 888 889 888 899 900 900 901 888 902 904 903 905 907 906 908 904 909 904 908 903 910 911 909 908 909 911 912 910 913 912 911 910 914 913 915 910 915 913 916 917 914 914 915 916 917 919 918 919 917 916 920 918 921 919 921 918 922 923 920 920 921 922 924 923 922 923 924 925 902 903 926 927 928 926 902 926 928 927 930 929 929 928 927 931 930 932 930 931 929 933 931 934 932 934 931 933 934 935 935 937 936 936 933 935 938 937 939 937 938 936 940 941 939 938 939 941 940 943 942 942 941 940 942 945 944 945 942 943 907 944 906 945 906 944 946 948 947 905 950 949 951 953 952 954 946 955 956 958 957 959 958 960 961 963 962 964 966 965 967 969 968 970 963 971 972 974 973 974 976 975 977 978 976 975 976 978 977 980 979 979 978 977 981 980 982 980 981 979 983 984 982 981 982 984 983 925 924 924 984 983 972 973 967 973 974 975 969 970 968 973 969 967 971 963 961 968 970 971 964 962 966 961 962 964 957 965 956 965 966 956 959 960 951 960 958 956 953 955 952 951 952 959 954 948 946 953 954 955 950 948 949 947 948 950 905 949 907 985 987 986 988 990 989 985 992 991 991 987 985 993 992 994 992 993 991 995 996 994 993 994 996 995 998 997 997 996 995 998 999 997 1000 999 1001 998 1001 999 1002 1003 1000 1000 1001 1002 1003 1005 1004 1005 1003 1002 1006 1004 1007 1005 1007 1004 1008 1009 1006 1006 1007 1008 1010 1009 1008 1010 1011 1009 1012 986 987 986 1014 1013 1014 986 1012 1015 1013 1016 1014 1016 1013 1017 1018 1015 1015 1016 1017 1018 1020 1019 1020 1018 1017 1021 1019 1022 1020 1022 1019 1023 1024 1021 1021 1022 1023 1024 1026 1025 1026 1024 1023 1027 1025 1028 1026 1028 1025 1029 1030 1027 1027 1028 1029 1030 1032 1031 1032 1030 1029 988 1031 1033 1032 1033 1031 1034 1036 1035 988 1033 990 1037 1039 1038 1040 1042 1041 1043 1045 1044 1046 1048 1047 1049 1051 1050 1052 1054 1053 1055 1057 1056 1058 1060 1059 1061 1063 1062 1064 1066 1065 1067 1064 1068 1069 1065 1070 1066 1070 1065 1069 1070 1071 1072 1069 1071 1072 1074 1073 1074 1072 1071 1075 1073 1076 1074 1076 1073 1077 1010 1075 1075 1076 1077 1011 1010 1077 1059 1067 1068 1067 1066 1064 1062 1060 1058 1058 1059 1068 1061 1056 1063 1062 1063 1060 1055 1051 1057 1061 1055 1056 1049 1050 1052 1057 1051 1049 1053 1054 1044 1052 1050 1054 1048 1045 1043 1045 1053 1044 1037 1046 1047 1047 1048 1043 1039 1041 1038 1037 1038 1046 1040 1034 1042 1039 1040 1041 1035 1036 989 1042 1034 1035 988 989 1036 1078 1080 1079 1081 1078 1082 1079 1082 1078 1083 1084 1081 1081 1082 1083 1083 1085 1084 1085 1087 1086 1088 1085 1089 1085 1090 1087 1085 1086 1089 1091 1084 1088 1085 1088 1084 1092 1084 1093 1084 1091 1093 1094 1084 1092 1095 1097 1096 1098 1095 1096 1096 1097 1099 1096 1100 1098 1100 1096 1101 1102 1101 1096 1102 1104 1103 1099 1097 1105 1097 1106 1105 1103 1101 1102 1107 1108 1102 1104 1102 1108 1109 1108 1110 1108 1107 1110 1111 1108 1109 1112 1114 1113 1114 1115 1113 1115 1114 1116 1117 1118 1112 1119 1112 1113 1112 1118 1120 1112 1119 1117 1121 1118 1122 1118 1123 1122 1124 1116 1114 1118 1121 1120 1125 1126 1114 1124 1114 1126 1127 1126 1128 1126 1125 1128 1129 1131 1130 1129 1133 1132 1133 1129 1130 1132 1133 1134 1134 1136 1135 1135 1132 1134 1136 1138 1137 1139 1136 1140 1136 1141 1140 1136 1137 1141 1142 1135 1139 1136 1139 1135 1143 1135 1144 1135 1142 1144 1145 1135 1143 1146 1148 1147 1149 1150 1146 1146 1150 1148 1151 1149 1146 1146 1147 1152 1147 1154 1153 1155 1151 1146 1155 1157 1156 1156 1151 1155 1147 1153 1152 1158 1159 1155 1157 1155 1159 1160 1159 1161 1159 1158 1161 1162 1159 1160 1163 1165 1164 1166 1168 1167 1169 1165 1170 1165 1169 1164 1171 1172 1170 1169 1170 1172 1171 1174 1173 1173 1172 1171 1175 1174 1176 1174 1175 1173 1177 1178 1176 1175 1176 1178 1177 1180 1179 1179 1178 1177 1181 1180 1182 1180 1181 1179 1183 1184 1182 1181 1182 1184 1183 1186 1185 1185 1184 1183 1186 1187 1185 1188 1163 1164 1189 1190 1188 1163 1188 1190 1189 1192 1191 1191 1190 1189 1193 1192 1194 1192 1193 1191 1195 1196 1194 1193 1194 1196 1195 1198 1197 1197 1196 1195 1199 1198 1200 1198 1199 1197 1201 1202 1200 1199 1200 1202 1201 1204 1203 1203 1202 1201 1205 1204 1168 1204 1205 1203 1206 1208 1207 1205 1168 1166 1209 1211 1210 1212 1214 1213 1215 1217 1216 1218 1220 1219 1221 1223 1222 1224 1226 1225 1227 1229 1228 1230 1232 1231 1233 1235 1234 1236 1234 1235 1237 1238 1233 1233 1234 1237 1238 1240 1239 1240 1238 1237 1241 1239 1242 1240 1242 1239 1187 1186 1241 1241 1242 1187 1227 1228 1236 1227 1236 1235 1229 1230 1231 1229 1231 1228 1232 1223 1221 1230 1223 1232 1224 1222 1226 1221 1222 1224 1217 1225 1216 1225 1226 1216 1219 1220 1215 1220 1217 1215 1209 1210 1218 1209 1218 1219 1211 1212 1213 1211 1213 1210 1214 1206 1207 1212 1206 1214 1167 1208 1166 1207 1208 1167 1243 1245 1244 1246 1248 1247 1249 1250 1244 1244 1250 1243 1251 1244 1252 1251 1249 1244 1253 1252 1244 1254 1256 1255 1257 1258 1254 1259 1261 1260 1262 1259 1260 1263 1264 1260 1263 1260 1261 1265 1266 1260 1265 1260 1264 1267 1268 1260 1269 1271 1270 1271 1273 1272 1271 1275 1274 1271 1274 1276 1273 1271 1277 1271 1272 1275 1271 1254 1277 1270 1279 1278 1280 1282 1281 1283 1285 1284 1286 1280 1287 1286 1282 1280 1280 1289 1288 1287 1280 1288 1280 1270 1289 1285 1290 1284 1291 1246 1247 1246 1293 1292 1294 1295 1246 1294 1246 1291 1296 1284 1246 1296 1246 1295 1297 1285 1283 1298 1299 1283 1244 1301 1300 1302 1299 1303 1299 1298 1303 1304 1299 1305 1299 1302 1305 1299 1304 1306 1299 1308 1307 1246 1309 1280 1260 1311 1310 1284 1313 1312 1290 1313 1284 1246 1312 1293 1284 1312 1246 1292 1309 1246 1280 1315 1314 1309 1315 1280 1270 1280 1316 1314 1316 1280 1270 1316 1279 1278 1269 1270 1271 1318 1317 1269 1318 1271 1254 1271 1319 1317 1319 1271 1254 1319 1257 1258 1256 1254 1266 1255 1320 1255 1266 1254 1266 1321 1267 1320 1321 1266 1266 1267 1260 1268 1311 1260 1244 1310 1322 1310 1244 1260 1253 1324 1323 1322 1301 1244 1253 1300 1324 1244 1300 1253 1299 1253 1325 1323 1325 1253 1299 1325 1326 1299 1326 1308 1283 1299 1327 1307 1327 1299 1297 1283 1328 1283 1327 1328 1329 1331 1330 1332 1330 1331 1333 1331 1329 1330 1332 1334 1335 1337 1336 1335 1336 1338 1339 1340 1337 1335 1339 1337 1338 1342 1341 1338 1336 1342 1343 1341 1342 1340 1339 1344 1339 1345 1344 1346 1341 1343 1347 1346 1343 1347 1348 1346 1349 1348 1347 1345 1350 1344 1351 1350 1345 1352 1353 1351 1353 1350 1351 1354 1356 1355 1352 1358 1357 1352 1357 1353 1359 1361 1360 1359 1358 1361 1357 1358 1359 1362 1363 1360 1362 1360 1361 1363 1355 1356 1362 1355 1363 1364 1366 1365 1365 1367 1364 1368 1370 1369 1364 1371 1366 1372 1367 1373 1369 1370 1374 1375 1377 1376 1368 1378 1371 1369 1378 1368 1379 1376 1380 1370 1377 1374 1375 1376 1379 1381 1383 1382 1381 1382 1380 1382 1379 1380 1375 1374 1377 1384 1383 1385 1384 1385 1386 1383 1381 1385 1384 1386 1387 1387 1389 1388 1390 1389 1387 1391 1388 1389 1386 1390 1387 1371 1378 1366 1373 1367 1365 1392 1372 1393 1393 1372 1373 1394 1395 1392 1392 1393 1394 1395 1397 1396 1397 1395 1394 1398 1396 1399 1397 1399 1396 1400 1401 1398 1398 1399 1400 1401 1403 1402 1403 1401 1400 1404 1402 1405 1403 1405 1402 1406 1407 1404 1404 1405 1406 1407 1409 1408 1409 1407 1406 1410 1408 1411 1409 1411 1408 1412 1410 1411

@@ -336,31 +163,11 @@ - + - 6.245e-17 1 0 0 -1 6.245e-17 0 0 0 0 1 0 0 0 0 1 + -1 5.97682e-29 -1.249e-16 0.0055865 -2.35922e-16 2.33487e-16 1 -1.20714e-17 5.99403e-29 1 -2.33487e-16 -0.0363488 0 0 0 1 - - 6.245e-17 1 0 0 -1 6.245e-17 0 0 0 0 1 0 0 0 0 1 - - - - 6.245e-17 1 0 0 -1 6.245e-17 0 0 0 0 1 0 0 0 0 1 - - - - 6.245e-17 1 0 0 -1 6.245e-17 0 0 0 0 1 0 0 0 0 1 - - - - 6.245e-17 1 0 0 -1 6.245e-17 0 0 0 0 1 0 0 0 0 1 - - - - 6.245e-17 1 0 0 -1 6.245e-17 0 0 0 0 1 0 0 0 0 1 - - @@ -370,56 +177,14 @@ - + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + diff --git a/src/tsukuba2022/params/VLP16db.yaml b/src/tsukuba2022/params/VLP16db.yaml new file mode 100644 index 0000000..4717aea --- /dev/null +++ b/src/tsukuba2022/params/VLP16db.yaml @@ -0,0 +1,51 @@ +lasers: +- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, + focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 0, rot_correction: 0.0, + vert_correction: -0.2617993877991494, vert_offset_correction: 0.0} +- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, + focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 1, rot_correction: 0.0, + vert_correction: 0.017453292519943295, vert_offset_correction: 0.0} +- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, + focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 2, rot_correction: 0.0, + vert_correction: -0.22689280275926285, vert_offset_correction: 0.0} +- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, + focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 3, rot_correction: 0.0, + vert_correction: 0.05235987755982989, vert_offset_correction: 0.0} +- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, + focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 4, rot_correction: 0.0, + vert_correction: -0.19198621771937624, vert_offset_correction: 0.0} +- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, + focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 5, rot_correction: 0.0, + vert_correction: 0.08726646259971647, vert_offset_correction: 0.0} +- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, + focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 6, rot_correction: 0.0, + vert_correction: -0.15707963267948966, vert_offset_correction: 0.0} +- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, + focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 7, rot_correction: 0.0, + vert_correction: 0.12217304763960307, vert_offset_correction: 0.0} +- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, + focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 8, rot_correction: 0.0, + vert_correction: -0.12217304763960307, vert_offset_correction: 0.0} +- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, + focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 9, rot_correction: 0.0, + vert_correction: 0.15707963267948966, vert_offset_correction: 0.0} +- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, + focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 10, rot_correction: 0.0, + vert_correction: -0.08726646259971647, vert_offset_correction: 0.0} +- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, + focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 11, rot_correction: 0.0, + vert_correction: 0.19198621771937624, vert_offset_correction: 0.0} +- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, + focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 12, rot_correction: 0.0, + vert_correction: -0.05235987755982989, vert_offset_correction: 0.0} +- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, + focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 13, rot_correction: 0.0, + vert_correction: 0.22689280275926285, vert_offset_correction: 0.0} +- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, + focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 14, rot_correction: 0.0, + vert_correction: -0.017453292519943295, vert_offset_correction: 0.0} +- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, + focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 15, rot_correction: 0.0, + vert_correction: 0.2617993877991494, vert_offset_correction: 0.0} +num_lasers: 16 +distance_resolution: 0.002 diff --git a/src/tsukuba2022/params/base_global_planner_params.yaml b/src/tsukuba2022/params/base_global_planner_params.yaml new file mode 100644 index 0000000..267db3d --- /dev/null +++ b/src/tsukuba2022/params/base_global_planner_params.yaml @@ -0,0 +1,17 @@ +base_global_planner: global_planner/GlobalPlanner + +GlobalPlanner: + allow_unknown: true + default_tolerance: 0.0 + visualize_potential: false + use_dijkstra: true + use_quadratic: true + use_grid_path: false + old_navfn_behavior: false + lethal_cost: 253 + neutral_cost: 66 + cost_factor: 0.55 + publish_potential: false + orientation_mode: 0 + orientation_window_size: 1 + outline_map: true \ No newline at end of file diff --git a/src/tsukuba2022/params/base_local_planner_params.yaml b/src/tsukuba2022/params/base_local_planner_params.yaml new file mode 100644 index 0000000..9ac04fc --- /dev/null +++ b/src/tsukuba2022/params/base_local_planner_params.yaml @@ -0,0 +1,33 @@ +base_local_planner: base_local_planner/TrajectoryPlannerROS + +TrajectoryPlannerROS: + # Robot Configuration Parameters + holonomic_robot: false + acc_lim_x: 3.5 + acc_lim_theta: 1.0 #1.5 + max_vel_x: 2.0 + min_vel_x: 0.1 + max_vel_theta: 0.3 + min_vel_theta: -0.3 #-0.4 + min_in_place_vel_theta: 0.3 #0.2 + escape_vel: -0.2 + + # Goal Tolerance Parameters + yaw_goal_tolerance: 0.5 + xy_goal_tolerance: 0.4 + + # Forward Simulation Parameters + sim_time: 3 + sim_granularity: 0.05 + vx_samples: 7 + vtheta_samples: 30 + + # Trajectory Scoring Parameters + dwa: true + meter_scoring: true + path_distance_bias: 0.4 #0.7 + goal_distance_bias: 1.0 #0.8 + occdist_scale : 0.05 #0.01 + heading_lookahead: 0.325 + heading_scoring: true + heading_scoring_timestep: 1.2 diff --git a/src/tsukuba2022/params/costmap_common_params.yaml b/src/tsukuba2022/params/costmap_common_params.yaml new file mode 100644 index 0000000..13b542b --- /dev/null +++ b/src/tsukuba2022/params/costmap_common_params.yaml @@ -0,0 +1,18 @@ +#max_obstacle_height: 0.60 # assume something like an arm is mounted on top of the robot +#obstacle_range: 4.0 #2.5 +#raytrace_range: 3.0 +#inflation_radius: 0.25 +#update_frequency: 2 + +#width: 5.0 +#height: 5.0 +#resolution: 0.15 + + +#observation_sources: scan point_cloud + +#scan: {data_type: LaserScan, topic: /scan, marking: true, clearing: true, inf_is_valid: true, min_obstacle_height: 0.08, max_obstacle_height: 1.0} + +#point_cloud: {data_type: PointCloud, topic: /filtered_cloud, marking: true, clearing: true} + + diff --git a/src/tsukuba2022/params/dwa_local_planner_params.yaml b/src/tsukuba2022/params/dwa_local_planner_params.yaml new file mode 100644 index 0000000..5d40319 --- /dev/null +++ b/src/tsukuba2022/params/dwa_local_planner_params.yaml @@ -0,0 +1,32 @@ +base_local_planner: dwa_local_planner/DWAPlannerROS + +DWAPlannerROS: + # Robot Configuration Parameters + holonomic_robot: false + acc_lim_x: 0.8 + acc_lim_theta: 0.2 + max_vel_x: 1.0 + min_vel_x: -0.1 + max_vel_trans: 1.0 + min_vel_trans: -0.1 + max_rot_vel: 0.4 #0.1 #0.8 + min_rot_vel: -0.4 #-0.1 #-0.8 + + # Goal Tolerance Parameters + yaw_goal_tolerance: 0.3 + xy_goal_tolerance: 0.1 + + # Forward Simulation Parameters + sim_time: 1.0 + sim_granularity: 0.03 + vx_samples: 3 + vth_samples: 16 + + # Trajectory Scoring Parameters + path_distance_bias: 36 + goal_distance_bias: 24 + occdist_scale : 0.01 + forward_point_destance: 0.325 + stop_time_buffer: 0.2 + scaling_speed: 0.25 + max_scaling_factor: 0.2 diff --git a/src/tsukuba2022/params/foot_print.yaml b/src/tsukuba2022/params/foot_print.yaml new file mode 100644 index 0000000..9b61904 --- /dev/null +++ b/src/tsukuba2022/params/foot_print.yaml @@ -0,0 +1 @@ +footprint: [ [0.25, 0.45], [0.25, -0.45], [-0.65, -0.45], [-0.65, 0.45] ] diff --git a/src/tsukuba2022/params/global_costmap_params.yaml b/src/tsukuba2022/params/global_costmap_params.yaml new file mode 100644 index 0000000..79eb8ec --- /dev/null +++ b/src/tsukuba2022/params/global_costmap_params.yaml @@ -0,0 +1,24 @@ +global_costmap: + map_topic: map #map_for_costmap + global_frame: map + robot_base_frame: base_footprint + update_frequency: 1.0 + publish_frequency: 1.0 + transform_tolerance: 1.0 + always_send_full_costmap: false + rolling_window: false + resolution: 0.1 + + plugins: + - {name: static_layer, type: "costmap_2d::StaticLayer"} + - {name: inflater_layer, type: "costmap_2d::InflationLayer"} + + static_layer: + map_topic: map + subscribe_to_updates: true + lethal_cost_threshold: 50 + track_unknown_space: false + + inflater_layer: + inflation_radius: 1.5 + cost_scaling_factor: 2.0 diff --git a/src/tsukuba2022/params/gmapping_common_params.yaml b/src/tsukuba2022/params/gmapping_common_params.yaml new file mode 100644 index 0000000..0261dbb --- /dev/null +++ b/src/tsukuba2022/params/gmapping_common_params.yaml @@ -0,0 +1,35 @@ +inverted_laser: false +throttle_scans: 1 +base_frame: base_footprint +map_frame: map +odom_frame: odom +map_update_interval: 2.0 +maxUrange: 40.0 +sigma: 0.05 +kernelSize: 1 +lstep: 0.05 +astep: 0.05 +iterations: 5 +lsigma: 0.075 +ogain: 3.0 +lskip: 1 +minimumScore: 0.0 +srr: 0.01 +srt: 0.02 +str: 0.01 +stt: 0.02 +linearUpdate: 0.5 +angularUpdate: 0.2 +temporalUpdate: -1.0 +resampleThreshold: 0.5 +particles: 20 +xmin: -60.0 +ymin: -60.0 +xmax: 60.0 +ymax: 60.0 +delta: 0.05 +llsamplerange: 0.01 +llsamplestep: 0.01 +lasamplerange: 0.005 +transform_publish_period: 0.05 +occ_thresh: 0.2 diff --git a/src/tsukuba2022/params/local_costmap_params.yaml b/src/tsukuba2022/params/local_costmap_params.yaml new file mode 100644 index 0000000..dae69df --- /dev/null +++ b/src/tsukuba2022/params/local_costmap_params.yaml @@ -0,0 +1,36 @@ +local_costmap: + global_frame: map + robot_base_frame: base_footprint + update_frequency: 5.0 + publish_frequency: 5.0 + rolling_window: true + resolution: 0.1 + width: 10.0 + height: 10.0 + always_send_full_costmap: true + transform_tolerance: 1.0 + + plugins: + - {name: obstacle_layer, type: "costmap_2d::ObstacleLayer"} + - {name: inflater_layer, type: "costmap_2d::InflationLayer"} + + obstacle_layer: + observation_sources: scan + scan: + data_type: LaserScan + topic: /scan + sensor_frame: velodyne_link + marking: true + clearing: true + inf_is_valid: true + max_obstacle_height: 2.5 + min_obstacle_height: 0.0 + obstacle_range: 8 + raytrace_range: 8 + observation_persistence: 0.0 + + inflater_layer: + inflation_radius: 0.2 + cost_scaling_factor: 3.0 + +# https://answers.ros.org/question/326867/local_costmap-not-showing-every-obstacle/ diff --git a/src/tsukuba2022/params/localization_params.yaml b/src/tsukuba2022/params/localization_params.yaml new file mode 100644 index 0000000..58cc5f4 --- /dev/null +++ b/src/tsukuba2022/params/localization_params.yaml @@ -0,0 +1,30 @@ +odom_model_type: diff +odom_alpha5: 0.1 +transform_tolerance: 0.5 #0.2 +gui_publish_rate: 10.0 +laser_max_beams: 30 +min_particles: 100 +max_particles: 5000 +kld_err: 0.05 +kld_z: 0.99 +odom_alpha1: 0.2 +odom_alpha2: 0.2 +odom_alpha4: 0.4 +laser_z_hit: 0.5 +laser_z_short: 0.05 +laser_z_max: 0.05 +laser_z_rand: 0.5 +laser_sigma_hit: 0.2 +laser_lambda_short: 0.1 +laser_lambda_short: 0.1 +laser_model_type: likelihood_field +laser_likelihood_max_dist: 2.0 +update_min_d: 0.2 +update_min_a: 0.5 +odom_frame_id: odom +base_frame_od: base_footprint +resample_interval: 1 +recovery_alpha_slow: 0.0 +recovery_alpha_fast: 0.0 + +reset_th_alpha: 0.003 diff --git a/src/tsukuba2022/params/move_base_params.yaml b/src/tsukuba2022/params/move_base_params.yaml new file mode 100644 index 0000000..5acfd08 --- /dev/null +++ b/src/tsukuba2022/params/move_base_params.yaml @@ -0,0 +1,15 @@ +# Move base node parameters. For full documentation of the parameters in this file, please see +# +# http://www.ros.org/wiki/move_base +# + +shutdown_costmaps: true + +controller_frequency: 6 +controller_patience: 3.0 + +planner_frequency: 0.5 +planner_patience: 5.0 + +oscillation_timeout: 10.0 +oscillation_distance: 0.2 diff --git a/src/tsukuba2022/params/pointcloud_to_laserscan_params.yaml b/src/tsukuba2022/params/pointcloud_to_laserscan_params.yaml index 3687b3d..4df1b20 100644 --- a/src/tsukuba2022/params/pointcloud_to_laserscan_params.yaml +++ b/src/tsukuba2022/params/pointcloud_to_laserscan_params.yaml @@ -1,7 +1,7 @@ target_frame: velodyne_link # Leave disabled to output scan in pointcloud frame transform_tolerance: 0.01 min_height: -0.7 #-0.4 -max_height: 1.5 +max_height: 0.3 #1.5 angle_min: -2.3565 angle_max: 2.3565 angle_increment: 0.008711645 @@ -14,4 +14,4 @@ # 0 : Detect number of cores # 1 : Single threaded # 2->inf : Parallelism level -concurrency_level: 1 \ No newline at end of file +concurrency_level: 1 diff --git a/src/tsukuba2022/params/recovery_params.yaml b/src/tsukuba2022/params/recovery_params.yaml new file mode 100644 index 0000000..92afe1a --- /dev/null +++ b/src/tsukuba2022/params/recovery_params.yaml @@ -0,0 +1,4 @@ +recovery_behaviors: [{name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery}, + {name: simple_lead_out, type: simple_lead_out/SimpleLeadOut}, + {name: rotate_recovery, type: rotate_recovery/RotateRecovery}, + {name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery}] diff --git a/src/tsukuba2022/params/segmentation_params.yaml b/src/tsukuba2022/params/segmentation_params.yaml index ec4aeb1..2a6b3af 100644 --- a/src/tsukuba2022/params/segmentation_params.yaml +++ b/src/tsukuba2022/params/segmentation_params.yaml @@ -5,15 +5,15 @@ n_bins: 200 ## number of radial bins. n_segments: 720 ## number of radial segments. -max_dist_to_line: 0.1 ## maximum vertical distance of point to line to be considered ground. +max_dist_to_line: 0.35 #0.1 ## maximum vertical distance of point to line to be considered ground. -sensor_height: 1.205 # sensor height above ground. +sensor_height: 1.0 #1.205 # sensor height above ground. min_slope: 0.0 # minimum slope of a ground line. -max_slope: 1.5 ## maximum slope of a ground line. -max_fit_error: 0.05 # maximum error of a point during line fit. -long_threshold: 2.0 ## distance between points after which they are considered far from each other. -max_long_height: 0.2 # maximum height change to previous point in long line. -max_start_height: 0.3 ## maximum difference to estimated ground height to start a new line. +max_slope: 3.0 ## maximum slope of a ground line. +max_fit_error: 0.15 #0.05 # maximum error of a point during line fit. +long_threshold: 10.0 ## distance between points after which they are considered far from each other. +max_long_height: 0.3 # maximum height change to previous point in long line. +max_start_height: 0.5 ## maximum difference to estimated ground height to start a new line. line_search_angle: 0.2 ## how far to search in angular direction to find a line [rad]. gravity_aligned_frame: "" # Frame which has its z axis aligned with gravity. (Sensor frame if empty.) diff --git a/src/tsukuba2022/params/teb_local_planner_params.yaml b/src/tsukuba2022/params/teb_local_planner_params.yaml new file mode 100644 index 0000000..3198655 --- /dev/null +++ b/src/tsukuba2022/params/teb_local_planner_params.yaml @@ -0,0 +1,78 @@ +base_local_planner: teb_local_planner/TebLocalPlannerROS + +TebLocalPlannerROS: + + odom_topic: odom + map_frame: /map + + # Trajectory + teb_autosize: True + dt_ref: 0.5 #0.3 + dt_hysteresis: 0.1 + global_plan_overwrite_orientation: True + max_global_plan_lookahead_dist: 2.0 + feasibility_check_no_poses: 5 + + # Robot + max_vel_x: 1.6 + max_vel_x_backwards: 0.2 + max_vel_theta: 0.4 + acc_lim_x: 2.0 + acc_lim_theta: 1.0 + min_turning_radius: 0.0 + footprint_model: # types: "point", "circular", "two_circles", "line", "polygon" + type: "polygon" + # radius: 0.2 # for type "circular" + # line_start: [-0.3, 0.0] # for type "line" + # line_end: [0.3, 0.0] # for type "line" + # front_offset: 0.2 # for type "two_circles" + # front_radius: 0.2 # for type "two_circles" + # rear_offset: 0.2 # for type "two_circles" + # rear_radius: 0.2 # for type "two_circles" + vertices: [ [0.25, 0.4], [0.25, -0.4], [-0.65, -0.4], [-0.65, 0.4] ] # for type "polygon" + + # GoalTolerance + xy_goal_tolerance: 0.3 + yaw_goal_tolerance: 0.3 + free_goal_vel: False + + # Obstacles + min_obstacle_dist: 0.4 + inflation_dist: 0.0 #0.6 + include_costmap_obstacles: True + costmap_obstacles_behind_robot_dist: 1.0 + obstacle_poses_affected: 30 + costmap_converter_plugin: "" + costmap_converter_spin_thread: True + costmap_converter_rate: 5 + + # Optimization + no_inner_iterations: 4 #5 + no_outer_iterations: 3 #4 + optimization_activate: True + optimization_verbose: False + penalty_epsilon: 0.1 + weight_max_vel_x: 1000 #2 + weight_max_vel_theta: 1000 #1 + weight_acc_lim_x: 100 #1 + weight_acc_lim_theta: 100 #1 + weight_kinematics_nh: 1000 + weight_kinematics_forward_drive: 100 #1 + weight_kinematics_turning_radius: 1 + weight_optimaltime: 1 + weight_obstacle: 50 + weight_dynamic_obstacle: 10 # not in use yet + selection_alternative_time_cost: False # not in use yet + + # Homotopy Class Planner + enable_homotopy_class_planning: True + enable_multithreading: True + simple_exploration: False + max_number_classes: 3 #4 + roadmap_graph_no_samples: 15 + roadmap_graph_area_width: 5 + h_signature_prescaler: 0.5 + h_signature_threshold: 0.1 + obstacle_keypoint_offset: 0.1 + obstacle_heading_threshold: 0.45 + visualize_hc_graph: False \ No newline at end of file diff --git a/src/tsukuba2022/rviz_cfg/teb_nav.rviz b/src/tsukuba2022/rviz_cfg/teb_nav.rviz new file mode 100644 index 0000000..2f214d7 --- /dev/null +++ b/src/tsukuba2022/rviz_cfg/teb_nav.rviz @@ -0,0 +1,386 @@ +Panels: + - Class: rviz/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: ~ + Splitter Ratio: 0.5 + Tree Height: 538 + - 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: LaserScan + - Class: orne_rviz_plugins/StateTriggerPanel + Name: StateTriggerPanel +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: /map + Unreliable: false + Use Timestamp: false + 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 + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + hokuyo_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + imu_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + left_caster_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + left_wheel: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + right_caster_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + right_wheel: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + velodyne_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 0; 255; 0 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 170; 0; 0 + Min Color: 0; 85; 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 5 + Size (m): 0.10000000149011612 + Style: Points + Topic: /scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.30000001192092896 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: Particles + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Arrow (Flat) + Topic: /particlecloud + Unreliable: false + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 25; 255; 0 + Enabled: true + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.30000001192092896 + Line Style: Lines + Line Width: 0.029999999329447746 + Name: Global Plan + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Queue Size: 10 + Radius: 0.029999999329447746 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: /move_base/TebLocalPlannerROS/global_plan + Unreliable: false + Value: true + - Alpha: 0.5 + Buffer Length: 1 + Class: rviz/Path + Color: 255; 255; 0 + Enabled: true + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.30000001192092896 + Line Style: Billboards + Line Width: 0.10000000149011612 + Name: Local Plan + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Queue Size: 10 + Radius: 0.029999999329447746 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: /move_base/TebLocalPlannerROS/local_plan + Unreliable: false + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: costmap + Draw Behind: true + Enabled: true + Name: GlobalCostmap + Topic: /move_base/global_costmap/costmap + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: costmap + Draw Behind: false + Enabled: true + Name: LocalCostmap + Topic: /move_base/local_costmap/costmap + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.30000001192092896 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 0; 0; 127 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: Waypoints + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Arrow (Flat) + Topic: /waypoints + Unreliable: false + Value: true + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Class: rviz/Pose + Color: 0; 0; 127 + Enabled: false + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Name: Pose + Queue Size: 10 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Shape: Arrow + Topic: /move_base_simple/goal + Unreliable: false + Value: false + - Alpha: 1 + Class: rviz/PointStamped + Color: 204; 41; 204 + Enabled: false + History Length: 10 + Name: PointStamped + Queue Size: 10 + Radius: 0.20000000298023224 + Topic: /target_point + Unreliable: false + Value: false + - Alpha: 1 + Class: rviz/PointStamped + Color: 239; 41; 41 + Enabled: false + History Length: 1 + Name: PointStamped + Queue Size: 10 + Radius: 0.4000000059604645 + Topic: /filtered_target_point + Unreliable: false + Value: false + - Class: rviz/Marker + Enabled: true + Marker Topic: /move_base/TebLocalPlannerROS/teb_markers + Name: Teb Marker + Namespaces: + PointObstacles: true + RobotFootprintModel: true + TebContainer: true + Queue Size: 100 + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.30000001192092896 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 0; 0; 255 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: Teb Poses + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Arrow (Flat) + Topic: /move_base/TebLocalPlannerROS/teb_poses + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: map + Frame Rate: 10 + 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/ThirdPersonFollower + Distance: 29.42242431640625 + 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: -1.3679986000061035 + Y: 0.15001505613327026 + Z: 0 + Focal Shape Fixed Size: false + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 1.5647963285446167 + Target Frame: base_link + Yaw: 3.135395050048828 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 786 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd000000040000000000000193000002b7fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005d00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003e00000257000000cb00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000002200530074006100740065005400720069006700670065007200500061006e0065006c010000029b0000005a0000004100ffffff000000010000010f000002b3fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003e000002b3000000a500fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005e00000003bfc0100000002fb0000000800540069006d00650000000000000005e00000039300fffffffb0000000800540069006d0065010000000000000450000000000000000000000369000002b700000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + StateTriggerPanel: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1282 + X: 218 + Y: 21 diff --git a/src/tsukuba2022/scripts/rename.sh b/src/tsukuba2022/scripts/rename.sh old mode 100644 new mode 100755 diff --git a/src/tsukuba2022/urdf/orange2022.gazebo b/src/tsukuba2022/urdf/orange2022.gazebo new file mode 100644 index 0000000..ae2b002 --- /dev/null +++ b/src/tsukuba2022/urdf/orange2022.gazebo @@ -0,0 +1,63 @@ + + + + + + cmd_vel + odom + base_link + odom + world + + true + false + false + + true + + true + + 30 + left_wheel_hinge + right_wheel_hinge + 0.670 + 0.192 + 1 + 10 + na + false + + + + + + + 5.0 + 5.0 + 1000000.0 + 100.0 + 0.001 + 1.0 + + + + + 5.0 + 5.0 + 1000000.0 + 100.0 + 0.001 + 1.0 + + + + + 0.0 + 0.0 + + + + 0.0 + 0.0 + + diff --git a/src/tsukuba2022/urdf/orange2022.xacro b/src/tsukuba2022/urdf/orange2022.xacro new file mode 100644 index 0000000..622cff8 --- /dev/null +++ b/src/tsukuba2022/urdf/orange2022.xacro @@ -0,0 +1,179 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + left_wheel + base_link + + + + + + + right_wheel + base_link + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/tsukuba2022/urdf/sensors/imu.urdf.xacro b/src/tsukuba2022/urdf/sensors/imu.urdf.xacro index dc674a6..2c54901 100644 --- a/src/tsukuba2022/urdf/sensors/imu.urdf.xacro +++ b/src/tsukuba2022/urdf/sensors/imu.urdf.xacro @@ -45,7 +45,7 @@ 0 0 0 - Gazebo/Turquoise + Gazebo/White diff --git a/src/tsukuba2022/world/hoseicourse.world b/src/tsukuba2022/world/hoseicourse.world index 55401b4..be81612 100644 --- a/src/tsukuba2022/world/hoseicourse.world +++ b/src/tsukuba2022/world/hoseicourse.world @@ -25,4 +25,4 @@ Course - \ No newline at end of file + diff --git a/src/turtlebot3/ISSUE_TEMPLATE.md b/src/turtlebot3/ISSUE_TEMPLATE.md new file mode 100644 index 0000000..c36cfc2 --- /dev/null +++ b/src/turtlebot3/ISSUE_TEMPLATE.md @@ -0,0 +1,57 @@ +ISSUE TEMPLATE ver. 0.4.0 + +1. Which TurtleBot3 platform do you use? + + - [ ] Burger + - [ ] Waffle + - [ ] Waffle Pi + +2. Which ROS is working with TurtleBot3? + + - [ ] ROS 1 Kinetic Kame + - [ ] ROS 1 Melodic Morenia + - [ ] ROS 1 Noetic Ninjemys + - [ ] ROS 2 Dashing Diademata + - [ ] ROS 2 Eloquent Elusor + - [ ] ROS 2 Foxy Fitzroy + - [ ] etc (Please specify your ROS Version here) + +3. Which SBC(Single Board Computer) is working on TurtleBot3? + + - [ ] Intel Joule 570x + - [ ] Raspberry Pi 3B+ + - [ ] Raspberry Pi 4 + - [ ] etc (Please specify your SBC here) + +4. Which OS you installed on SBC? + + - [ ] Raspbian distributed by ROBOTIS + - [ ] Ubuntu MATE (16.04/18.04/20.04) + - [ ] Ubuntu preinstalled server (18.04/20.04) + - [ ] etc (Please specify your OS here) + +5. Which OS you installed on Remote PC? + + - [ ] Ubuntu 16.04 LTS (Xenial Xerus) + - [ ] Ubuntu 18.04 LTS (Bionic Beaver) + - [ ] Ubuntu 20.04 LTS (Focal Fossa) + - [ ] Windows 10 + - [ ] MAC OS X (Specify version) + - [ ] etc (Please specify your OS here) + +6. Specify the software and firmware version(Can be found from Bringup messages) + + - Software version: [x.x.x] + - Firmware version: [x.x.x] + +7. Specify the commands or instructions to reproduce the issue. + + - HERE + +8. Copy and Paste the error messages on terminal. + + - HERE + +9. Please describe the issue in detail. + + - HERE diff --git a/src/turtlebot3/LICENSE b/src/turtlebot3/LICENSE new file mode 100644 index 0000000..8dada3e --- /dev/null +++ b/src/turtlebot3/LICENSE @@ -0,0 +1,201 @@ + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "{}" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright {yyyy} {name of copyright owner} + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. diff --git a/src/turtlebot3/README.md b/src/turtlebot3/README.md new file mode 100644 index 0000000..6febf35 --- /dev/null +++ b/src/turtlebot3/README.md @@ -0,0 +1,53 @@ +# TurtleBot3 + + +[![kinetic-devel Status](https://github.com/ROBOTIS-GIT/turtlebot3/workflows/kinetic-devel/badge.svg)](https://github.com/ROBOTIS-GIT/turtlebot3/tree/kinetic-devel) + +[![melodic-devel Status](https://github.com/ROBOTIS-GIT/turtlebot3/workflows/melodic-devel/badge.svg)](https://github.com/ROBOTIS-GIT/turtlebot3/tree/melodic-devel) + +[![noetic-devel Status](https://github.com/ROBOTIS-GIT/turtlebot3/workflows/noetic-devel/badge.svg)](https://github.com/ROBOTIS-GIT/turtlebot3/tree/noetic-devel) + +[![dashing-devel Status](https://github.com/ROBOTIS-GIT/turtlebot3/workflows/dashing-devel/badge.svg)](https://github.com/ROBOTIS-GIT/turtlebot3/tree/dashing-devel) + +[![foxy-devel Status](https://github.com/ROBOTIS-GIT/turtlebot3/workflows/foxy-devel/badge.svg)](https://github.com/ROBOTIS-GIT/turtlebot3/tree/foxy-devel) + +[![galactic-devel Status](https://github.com/ROBOTIS-GIT/turtlebot3/workflows/galactic-devel/badge.svg)](https://github.com/ROBOTIS-GIT/turtlebot3/tree/galactic-devel) + +## ROBOTIS e-Manual for TurtleBot3 +- [ROBOTIS e-Manual for TurtleBot3](http://turtlebot3.robotis.com/) + +## Wiki for turtlebot3 Packages +- http://wiki.ros.org/turtlebot3 (metapackage) +- http://wiki.ros.org/turtlebot3_bringup +- http://wiki.ros.org/turtlebot3_description +- http://wiki.ros.org/turtlebot3_example +- http://wiki.ros.org/turtlebot3_navigation +- http://wiki.ros.org/turtlebot3_slam +- http://wiki.ros.org/turtlebot3_teleop + +## Open Source related to TurtleBot3 +- [turtlebot3](https://github.com/ROBOTIS-GIT/turtlebot3) +- [turtlebot3_msgs](https://github.com/ROBOTIS-GIT/turtlebot3_msgs) +- [turtlebot3_simulations](https://github.com/ROBOTIS-GIT/turtlebot3_simulations) +- [turtlebot3_applications_msgs](https://github.com/ROBOTIS-GIT/turtlebot3_applications_msgs) +- [turtlebot3_applications](https://github.com/ROBOTIS-GIT/turtlebot3_applications) +- [turtlebot3_autorace](https://github.com/ROBOTIS-GIT/turtlebot3_autorace) +- [turtlebot3_deliver](https://github.com/ROBOTIS-GIT/turtlebot3_deliver) +- [hls_lfcd_lds_driver](https://github.com/ROBOTIS-GIT/hls_lfcd_lds_driver) +- [turtlebot3_manipulation](https://github.com/ROBOTIS-GIT/turtlebot3_manipulation.git) +- [turtlebot3_manipulation_simulations](https://github.com/ROBOTIS-GIT/turtlebot3_manipulation_simulations.git) +- [open_manipulator_msgs](https://github.com/ROBOTIS-GIT/open_manipulator_msgs) +- [open_manipulator](https://github.com/ROBOTIS-GIT/open_manipulator) +- [open_manipulator_simulations](https://github.com/ROBOTIS-GIT/open_manipulator_simulations) +- [open_manipulator_perceptions](https://github.com/ROBOTIS-GIT/open_manipulator_perceptions) +- [dynamixel_sdk](https://github.com/ROBOTIS-GIT/DynamixelSDK) +- [OpenCR-Hardware](https://github.com/ROBOTIS-GIT/OpenCR-Hardware) +- [OpenCR](https://github.com/ROBOTIS-GIT/OpenCR) + +## Documents and Videos related to TurtleBot3 +- [ROBOTIS e-Manual for TurtleBot3](http://turtlebot3.robotis.com/) +- [ROBOTIS e-Manual for OpenManipulator](http://emanual.robotis.com/docs/en/platform/openmanipulator/) +- [ROBOTIS e-Manual for Dynamixel SDK](http://emanual.robotis.com/docs/en/software/dynamixel/dynamixel_sdk/overview/) +- [Website for TurtleBot Series](http://www.turtlebot.com/) +- [e-Book for TurtleBot3](https://community.robotsource.org/t/download-the-ros-robot-programming-book-for-free/51/) +- [Videos for TurtleBot3 ](https://www.youtube.com/playlist?list=PLRG6WP3c31_XI3wlvHlx2Mp8BYqgqDURU) diff --git a/src/turtlebot3/turtlebot3/CHANGELOG.rst b/src/turtlebot3/turtlebot3/CHANGELOG.rst new file mode 100644 index 0000000..7a5e478 --- /dev/null +++ b/src/turtlebot3/turtlebot3/CHANGELOG.rst @@ -0,0 +1,155 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package turtlebot3 +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.2.6 (2022-02-24) +------------------ +* add LDS-02 support +* Use OpenCV for Picam(Noetic only) +* Fix teleop_key on Windows 10 +* Contributors: Rushikesh Kamalapurkar, Ashe Kim, Will Son + +1.2.5 (2020-12-30) +------------------ +* Python 2/3 compatibility fix +* Rectify IMU update rate to 0 on Gazebo +* Contributors: Sean Yen, PinkDraconian + +1.2.4 (2020-09-29) +------------------ +* Package info updated +* Contributors: Will Son + +1.2.3 (2020-03-03) +------------------ +* Updated inertial data in turtlebot3_waffle_for_open_manipulator.urdf.xacro, turtlebot3_waffle_pi_for_open_manipulator.urdf.xacro +* Added turtlebot3_manipulation_slam.launch for TurtleBot3 SLAM with OpenMANIPULATOR +* Contributors: Ryan Shim, Will Son + +1.2.2 (2019-08-20) +------------------ +* Fixed `dwa local planner params` for dwa_local_planner 1.16.2 `#415 `_ +* This patch only applies to ROS 1 Melodic. +* Contributors: atinfinity, Kayman + +1.2.1 (2019-08-20) +------------------ +* Fixed typo `#436 `_ +* Fixed ROS_ASSERT bug `#416 `_ +* Deleted '/' to sync tf2 `#402 `_ +* Added turtlebot3_remote.launch to turtlebot3_model.launch `#389 `_ +* Contributors: Jonathan Hechtbauer, Pallav Bhalla, ant, Ryan Shim, Kayman, Darby Lim, Gilbert, Pyo + +1.2.0 (2019-01-22) +------------------ +* changed math.ceil() operation `#373 `_ +* fixed TypeError integers +* fixed read of scanned samples when there isn't 360 +* updated map.yaml `#348 `_ +* added an additional argument move_forward_only to prohibit backward locomotion in navigation `#339 `_ +* fixed typo `#280 `_ +* added windows port `#358 `_ +* Contributors: Gilbert, Darby Lim, linzhibo, oiz5201618, yoshimalucky, Steven Macenski, Eduardo Avelar, Sean Yen, Pyo + +1.1.0 (2018-07-23) +------------------ +* added bringup to load multiple robot simply #251 +* added arguments for multiple robot +* added odometrySource +* modified camera topic name +* modified base_scan update_rate and add param on diff_drive #258 +* modified the laser scanner update_rate in the gazebo xacro files #258 +* modified origin of collision in Waffle URDF +* updated turtlebot3_diagnostic node +* updated firmware version from 1.2.0 to 1.2.2 +* updated get firmware version +* updated version check function +* updated warn msg for version check +* deleted unused get_scan function #227 +* Contributors: Darby Lim, Gilbert, Eduardo Avelar, shtseng, Pyo + +1.0.0 (2018-05-29) +------------------ +* added cartographer +* added hector mapping +* added karto SLAM +* added frontier_exploration +* added launch files to run various SLAMs +* added robot model for OpenManipulator and turtlebot3_autorace +* added exec python nodes like marker_server in catkin_install_python +* added frameName for imu on gazebo (however, there is no effect.) +* added variable to check version only once (turtlebot3_bringup) +* modified global names `#211 `_ from FurqanHabibi/fix_global_topic_name +* modified gmapping parameters +* modified navigation parameters +* modified version check and firmware version (turtlebot3_bringup) +* modified robot names +* modified range of lidar, lidar position, scan param +* modified camera position and fixed slip bug +* modified waffle_pi stl files +* modified initial value, profile function, limit velocity msg (teleop) +* merged pull request `#154 `_ `#153 `_ `#148 `_ `#147 `_ `#146 `_ `#145 `_ +* Contributors: Darby Lim, Leon Jung, Gilbert, KurtE, ncnynl, FurqanHabibi, skasperski, ihadzic, Pyo + +0.2.1 (2018-03-14) +------------------ +* added install directory +* refactoring for release +* Contributors: Pyo + +0.2.0 (2018-03-12) +------------------ +* added turtlebot3_rpicamera.launch for raspberry pi camera +* added waffle pi model (urdf and gazebo) +* added verion check function +* added diagnostics node +* added scripts for reload rules +* added example package +* modified firmware version +* modified param config +* modified topic of gazebo plugin +* modified r200 tf tree +* modified gazebo imu link +* removed the large bag file and added download command from other site +* refactoring for release +* Contributors: Darby Lim, Gilbert, Leon Jung, Pyo + +0.1.6 (2017-08-14) +------------------ +* fixed typo +* fixed xacro.py deprecation +* modified file location +* updated nav param +* updated SLAM param +* updated model.launch +* updated IMU link +* updated gazebo config +* Contributors: Darby Lim, Hunter L. Allen + +0.1.5 (2017-05-25) +------------------ +* updated turtlebot3 waffle URDF +* changed the node name from hlds_laser_publisher to turtlebot3_lds +* modified bag and map files +* added SLAM bag file +* Contributors: Darby Lim, Pyo + +0.1.4 (2017-05-23) +------------------ +* modified launch file name +* added teleop package +* Contributors: Darby Lim + +0.1.3 (2017-04-24) +------------------ +* Detached turtlebot3_msgs package from turtlebot3 package for uploading to rosdistro +* modified the package information for release +* modified SLAM param +* modified the description, authors, depend option and delete the core package +* modified the turtlebot bringup files +* modified pkg setting for turtlebot3_core +* modified the navigation package and turtlebot3 node for demo +* modified the wheel speed gain +* added Intel RealSense R200 +* added LDS sensor +* Contributors: Darby Lim, Leon Jung, Pyo diff --git a/src/turtlebot3/turtlebot3/CMakeLists.txt b/src/turtlebot3/turtlebot3/CMakeLists.txt new file mode 100644 index 0000000..64469eb --- /dev/null +++ b/src/turtlebot3/turtlebot3/CMakeLists.txt @@ -0,0 +1,4 @@ +cmake_minimum_required(VERSION 3.0.2) +project(turtlebot3) +find_package(catkin REQUIRED) +catkin_metapackage() diff --git a/src/turtlebot3/turtlebot3/package.xml b/src/turtlebot3/turtlebot3/package.xml new file mode 100644 index 0000000..e766173 --- /dev/null +++ b/src/turtlebot3/turtlebot3/package.xml @@ -0,0 +1,29 @@ + + + turtlebot3 + 1.2.6 + + ROS packages for the Turtlebot3 (meta package) + + Apache 2.0 + BSD + Pyo + Darby Lim + Gilbert + HanCheol Cho + Ashe Kim + Leon Jung + Will Son + http://wiki.ros.org/turtlebot3 + http://turtlebot3.robotis.com + https://github.com/ROBOTIS-GIT/turtlebot3 + https://github.com/ROBOTIS-GIT/turtlebot3/issues + catkin + turtlebot3_bringup + turtlebot3_description + turtlebot3_example + turtlebot3_navigation + turtlebot3_slam + turtlebot3_teleop + + diff --git a/src/turtlebot3/turtlebot3_teleop/CHANGELOG.rst b/src/turtlebot3/turtlebot3_teleop/CHANGELOG.rst new file mode 100644 index 0000000..d266a37 --- /dev/null +++ b/src/turtlebot3/turtlebot3_teleop/CHANGELOG.rst @@ -0,0 +1,73 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package turtlebot3_teleop +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.2.6 (2022-02-24) +------------------ +* Fix teleop_key on Windows 10 +* Contributors: Rushikesh Kamalapurkar + +1.2.5 (2020-12-30) +------------------ +* Python 2/3 compatibility fix +* Contributors: Sean Yen + +1.2.4 (2020-09-29) +------------------ +* Package info updated +* Contributors: Will Son + +1.2.3 (2020-03-03) +------------------ +* none + +1.2.2 (2019-08-20) +------------------ +* none + +1.2.1 (2019-08-20) +------------------ +* none + +1.2.0 (2019-01-22) +------------------ +* added windows port `#358 `_ +* Contributors: Sean Yen, Taehun Lim + +1.1.0 (2018-07-23) +------------------ +* none + +1.0.0 (2018-05-29) +------------------ +* added constrain to limit velocity +* modified initial value, profile function, limit velocity msg +* modified global names `#211 `_ from FurqanHabibi/fix_global_topic_name +* Contributors: Darby Lim, Muhammad Furqan Habibi, Pyo + +0.2.1 (2018-03-14) +------------------ +* none + +0.2.0 (2018-03-12) +------------------ +* refactoring for release +* Contributors: Pyo + +0.1.6 (2017-08-14) +------------------ +* none + +0.1.5 (2017-05-25) +------------------ +* none + +0.1.4 (2017-05-23) +------------------ +* modified launch file name +* added teleop package +* Contributors: Darby Lim + +0.1.3 (2017-04-24) +------------------ +* none diff --git a/src/turtlebot3/turtlebot3_teleop/CMakeLists.txt b/src/turtlebot3/turtlebot3_teleop/CMakeLists.txt new file mode 100644 index 0000000..48a5b1e --- /dev/null +++ b/src/turtlebot3/turtlebot3_teleop/CMakeLists.txt @@ -0,0 +1,53 @@ +################################################################################ +# Set minimum required version of cmake, project name and compile options +################################################################################ +cmake_minimum_required(VERSION 3.0.2) +project(turtlebot3_teleop) + +################################################################################ +# Find catkin packages and libraries for catkin and system dependencies +################################################################################ +find_package(catkin REQUIRED COMPONENTS + rospy + geometry_msgs +) + +################################################################################ +# Setup for python modules and scripts +################################################################################ +catkin_python_setup() + +################################################################################ +# Declare ROS messages, services and actions +################################################################################ + +################################################################################ +# Declare ROS dynamic reconfigure parameters +################################################################################ + +################################################################################ +# Declare catkin specific configuration to be passed to dependent projects +################################################################################ +catkin_package( + CATKIN_DEPENDS rospy geometry_msgs +) + +################################################################################ +# Build +################################################################################ + +################################################################################ +# Install +################################################################################ +catkin_install_python(PROGRAMS + nodes/turtlebot3_teleop_key + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +################################################################################ +# Test +################################################################################ diff --git a/src/turtlebot3/turtlebot3_teleop/launch/turtlebot3_teleop_key.launch b/src/turtlebot3/turtlebot3_teleop/launch/turtlebot3_teleop_key.launch new file mode 100644 index 0000000..b6753ab --- /dev/null +++ b/src/turtlebot3/turtlebot3_teleop/launch/turtlebot3_teleop_key.launch @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/src/turtlebot3/turtlebot3_teleop/nodes/turtlebot3_teleop_key b/src/turtlebot3/turtlebot3_teleop/nodes/turtlebot3_teleop_key new file mode 100755 index 0000000..f6b5d7d --- /dev/null +++ b/src/turtlebot3/turtlebot3_teleop/nodes/turtlebot3_teleop_key @@ -0,0 +1,202 @@ +#!/usr/bin/env python + +# Copyright (c) 2011, Willow Garage, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# * Neither the name of the Willow Garage, Inc. nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +import rospy +from geometry_msgs.msg import Twist +import sys, select, os +if os.name == 'nt': + import msvcrt, time +else: + import tty, termios + +BURGER_MAX_LIN_VEL = 1.6 +BURGER_MAX_ANG_VEL = 2.84 + +WAFFLE_MAX_LIN_VEL = 0.26 +WAFFLE_MAX_ANG_VEL = 1.82 + +LIN_VEL_STEP_SIZE = 0.1 +ANG_VEL_STEP_SIZE = 0.1 + +msg = """ +Control Your TurtleBot3! +--------------------------- +Moving around: + w + a s d + x + +w/x : increase/decrease linear velocity (Burger : ~ 0.22, Waffle and Waffle Pi : ~ 0.26) +a/d : increase/decrease angular velocity (Burger : ~ 2.84, Waffle and Waffle Pi : ~ 1.82) + +space key, s : force stop + +CTRL-C to quit +""" + +e = """ +Communications Failed +""" + +def getKey(): + if os.name == 'nt': + timeout = 0.1 + startTime = time.time() + while(1): + if msvcrt.kbhit(): + if sys.version_info[0] >= 3: + return msvcrt.getch().decode() + else: + return msvcrt.getch() + elif time.time() - startTime > timeout: + return '' + + tty.setraw(sys.stdin.fileno()) + rlist, _, _ = select.select([sys.stdin], [], [], 0.1) + if rlist: + key = sys.stdin.read(1) + else: + key = '' + + termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings) + return key + +def vels(target_linear_vel, target_angular_vel): + return "currently:\tlinear vel %s\t angular vel %s " % (target_linear_vel,target_angular_vel) + +def makeSimpleProfile(output, input, slop): + if input > output: + output = min( input, output + slop ) + elif input < output: + output = max( input, output - slop ) + else: + output = input + + return output + +def constrain(input, low, high): + if input < low: + input = low + elif input > high: + input = high + else: + input = input + + return input + +def checkLinearLimitVelocity(vel): + if turtlebot3_model == "burger": + vel = constrain(vel, -BURGER_MAX_LIN_VEL, BURGER_MAX_LIN_VEL) + elif turtlebot3_model == "waffle" or turtlebot3_model == "waffle_pi": + vel = constrain(vel, -WAFFLE_MAX_LIN_VEL, WAFFLE_MAX_LIN_VEL) + else: + vel = constrain(vel, -BURGER_MAX_LIN_VEL, BURGER_MAX_LIN_VEL) + + return vel + +def checkAngularLimitVelocity(vel): + if turtlebot3_model == "burger": + vel = constrain(vel, -BURGER_MAX_ANG_VEL, BURGER_MAX_ANG_VEL) + elif turtlebot3_model == "waffle" or turtlebot3_model == "waffle_pi": + vel = constrain(vel, -WAFFLE_MAX_ANG_VEL, WAFFLE_MAX_ANG_VEL) + else: + vel = constrain(vel, -BURGER_MAX_ANG_VEL, BURGER_MAX_ANG_VEL) + + return vel + +if __name__=="__main__": + if os.name != 'nt': + settings = termios.tcgetattr(sys.stdin) + + rospy.init_node('turtlebot3_teleop') + pub = rospy.Publisher('cmd_vel', Twist, queue_size=10) + + turtlebot3_model = rospy.get_param("model", "burger") + + status = 0 + target_linear_vel = 0.0 + target_angular_vel = 0.0 + control_linear_vel = 0.0 + control_angular_vel = 0.0 + + try: + print(msg) + while not rospy.is_shutdown(): + key = getKey() + if key == 'w' : + target_linear_vel = checkLinearLimitVelocity(target_linear_vel + LIN_VEL_STEP_SIZE) + status = status + 1 + print(vels(target_linear_vel,target_angular_vel)) + elif key == 'x' : + target_linear_vel = checkLinearLimitVelocity(target_linear_vel - LIN_VEL_STEP_SIZE) + status = status + 1 + print(vels(target_linear_vel,target_angular_vel)) + elif key == 'a' : + target_angular_vel = checkAngularLimitVelocity(target_angular_vel + ANG_VEL_STEP_SIZE) + status = status + 1 + print(vels(target_linear_vel,target_angular_vel)) + elif key == 'd' : + target_angular_vel = checkAngularLimitVelocity(target_angular_vel - ANG_VEL_STEP_SIZE) + status = status + 1 + print(vels(target_linear_vel,target_angular_vel)) + elif key == ' ' or key == 's' : + target_linear_vel = 0.0 + control_linear_vel = 0.0 + target_angular_vel = 0.0 + control_angular_vel = 0.0 + print(vels(target_linear_vel, target_angular_vel)) + else: + if (key == '\x03'): + break + + if status == 20 : + print(msg) + status = 0 + + twist = Twist() + + control_linear_vel = makeSimpleProfile(control_linear_vel, target_linear_vel, (LIN_VEL_STEP_SIZE/2.0)) + twist.linear.x = control_linear_vel; twist.linear.y = 0.0; twist.linear.z = 0.0 + + control_angular_vel = makeSimpleProfile(control_angular_vel, target_angular_vel, (ANG_VEL_STEP_SIZE/2.0)) + twist.angular.x = 0.0; twist.angular.y = 0.0; twist.angular.z = control_angular_vel + + pub.publish(twist) + + except: + print(e) + + finally: + twist = Twist() + twist.linear.x = 0.0; twist.linear.y = 0.0; twist.linear.z = 0.0 + twist.angular.x = 0.0; twist.angular.y = 0.0; twist.angular.z = 0.0 + pub.publish(twist) + + if os.name != 'nt': + termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings) diff --git a/src/turtlebot3/turtlebot3_teleop/package.xml b/src/turtlebot3/turtlebot3_teleop/package.xml new file mode 100644 index 0000000..5deb078 --- /dev/null +++ b/src/turtlebot3/turtlebot3_teleop/package.xml @@ -0,0 +1,20 @@ + + + turtlebot3_teleop + 1.2.6 + + Provides teleoperation using keyboard for TurtleBot3. + + BSD + Melonee Wise + Darby Lim + Pyo + Will Son + http://wiki.ros.org/turtlebot3_teleop + http://turtlebot3.robotis.com + https://github.com/ROBOTIS-GIT/turtlebot3 + https://github.com/ROBOTIS-GIT/turtlebot3/issues + catkin + rospy + geometry_msgs + diff --git a/src/turtlebot3/turtlebot3_teleop/setup.py b/src/turtlebot3/turtlebot3_teleop/setup.py new file mode 100644 index 0000000..0621677 --- /dev/null +++ b/src/turtlebot3/turtlebot3_teleop/setup.py @@ -0,0 +1,12 @@ +## ! DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD + +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup + +# fetch values from package.xml +setup_args = generate_distutils_setup( + packages=['turtlebot3_teleop'], + package_dir={'': 'src'} +) + +setup(**setup_args) diff --git a/src/turtlebot3/turtlebot3_teleop/src/turtlebot3_teleop/__init__.py b/src/turtlebot3/turtlebot3_teleop/src/turtlebot3_teleop/__init__.py new file mode 100644 index 0000000..e69de29 --- /dev/null +++ b/src/turtlebot3/turtlebot3_teleop/src/turtlebot3_teleop/__init__.py diff --git a/src/velodyne/velodyne/CHANGELOG.rst b/src/velodyne/velodyne/CHANGELOG.rst index a0b4d68..813f4b7 100644 --- a/src/velodyne/velodyne/CHANGELOG.rst +++ b/src/velodyne/velodyne/CHANGELOG.rst @@ -1,6 +1,9 @@ Change history ============== +1.7.0 (2022-07-08) +------------------ + 1.6.1 (2020-11-09) ------------------ diff --git a/src/velodyne/velodyne/package.xml b/src/velodyne/velodyne/package.xml index a81a960..7c3389c 100644 --- a/src/velodyne/velodyne/package.xml +++ b/src/velodyne/velodyne/package.xml @@ -1,7 +1,7 @@ velodyne - 1.6.1 + 1.7.0 Basic ROS support for the Velodyne 3D LIDARs. diff --git a/src/velodyne/velodyne_driver/CHANGELOG.rst b/src/velodyne/velodyne_driver/CHANGELOG.rst index 1215fbf..37af3d6 100644 --- a/src/velodyne/velodyne_driver/CHANGELOG.rst +++ b/src/velodyne/velodyne_driver/CHANGELOG.rst @@ -1,6 +1,25 @@ Change history ============== +1.7.0 (2022-07-08) +------------------ +* Fix non-responsive node on packet timeout (`#466 `_) + * No abort on packet timeout + Changed getPacket() to return 0 on timeout and 1 on success. + * Removed trailing whitespace +* reuse Velodyne UDP port (`#427 `_) +* add missing include to pcap.h that prevents tests from being built (`#406 `_) +* PCAP timestamps & PCAP+GPS timestamps (`#384 `_) + * Add pcap_time param and implement gps_time with it + * If gps_time == true, ignore pcap_time +* Add support for the velodyne Alpha Prime (`#370 `_) + * Add support for the velodyne Alpha Prime + * Change packet rate for the VLS128 according to the times specified in the manual + * Organize setup functions to avoid code duplication. Add a constant for the model ID of the VLS128. + * Use the defined constants to calculate the time offset of the points for the VLS128 + Co-authored-by: jugo +* Contributors: HMellor, Institute for Autonomous Systems Technology, JKaniarz, Nagy Dániel Zoltán, Sebastian Scherer + 1.6.1 (2020-11-09) ------------------ diff --git a/src/velodyne/velodyne_driver/package.xml b/src/velodyne/velodyne_driver/package.xml index 4d6f21a..bd82707 100644 --- a/src/velodyne/velodyne_driver/package.xml +++ b/src/velodyne/velodyne_driver/package.xml @@ -1,7 +1,7 @@ velodyne_driver - 1.6.1 + 1.7.0 ROS device driver for Velodyne 3D LIDARs. diff --git a/src/velodyne/velodyne_driver/src/driver/driver.cc b/src/velodyne/velodyne_driver/src/driver/driver.cc index f3b4a72..be9ef29 100644 --- a/src/velodyne/velodyne_driver/src/driver/driver.cc +++ b/src/velodyne/velodyne_driver/src/driver/driver.cc @@ -220,8 +220,9 @@ while(true) { int rc = input_->getPacket(&tmp_packet, config_.time_offset); - if (rc == 0) break; // got a full packet? + if (rc == 1) break; // got a full packet? if (rc < 0) return false; // end of file reached? + if (rc == 0) continue; //timeout? } scan->packets.push_back(tmp_packet); @@ -255,8 +256,9 @@ { // keep reading until full packet received int rc = input_->getPacket(&scan->packets[i], config_.time_offset); - if (rc == 0) break; // got a full packet? + if (rc == 1) break; // got a full packet? if (rc < 0) return false; // end of file reached? + if (rc == 0) continue; //timeout? } } } diff --git a/src/velodyne/velodyne_driver/src/lib/input.cc b/src/velodyne/velodyne_driver/src/lib/input.cc index 76ee219..ba49c1f 100644 --- a/src/velodyne/velodyne_driver/src/lib/input.cc +++ b/src/velodyne/velodyne_driver/src/lib/input.cc @@ -189,7 +189,7 @@ if (retval == 0) // poll() timeout? { ROS_WARN("Velodyne poll() timeout"); - return -1; + return 0; } if ((fds[0].revents & POLLERR) || (fds[0].revents & POLLHUP) @@ -243,7 +243,7 @@ pkt->stamp = rosTimeFromGpsTimestamp(&(pkt->data[1200])); } - return 0; + return 1; } //////////////////////////////////////////////////////////////////////// @@ -339,7 +339,7 @@ pkt->stamp = rosTimeFromGpsTimestamp(&(pkt->data[1200]), header); } empty_ = false; - return 0; // success + return 1; // success } if (empty_) // no data in file? diff --git a/src/velodyne/velodyne_laserscan/CHANGELOG.rst b/src/velodyne/velodyne_laserscan/CHANGELOG.rst index 00db0c5..a48de9a 100644 --- a/src/velodyne/velodyne_laserscan/CHANGELOG.rst +++ b/src/velodyne/velodyne_laserscan/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package velodyne_laserscan ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.7.0 (2022-07-08) +------------------ + 1.6.1 (2020-11-09) ------------------ diff --git a/src/velodyne/velodyne_laserscan/package.xml b/src/velodyne/velodyne_laserscan/package.xml index 205d49d..47a88c5 100644 --- a/src/velodyne/velodyne_laserscan/package.xml +++ b/src/velodyne/velodyne_laserscan/package.xml @@ -1,7 +1,7 @@ velodyne_laserscan - 1.6.1 + 1.7.0 Extract a single ring of a Velodyne PointCloud2 and publish it as a LaserScan message diff --git a/src/velodyne/velodyne_msgs/CHANGELOG.rst b/src/velodyne/velodyne_msgs/CHANGELOG.rst index 7d0d1ab..fd70ea0 100644 --- a/src/velodyne/velodyne_msgs/CHANGELOG.rst +++ b/src/velodyne/velodyne_msgs/CHANGELOG.rst @@ -1,6 +1,9 @@ Change history ============== +1.7.0 (2022-07-08) +------------------ + 1.6.1 (2020-11-09) ------------------ diff --git a/src/velodyne/velodyne_msgs/package.xml b/src/velodyne/velodyne_msgs/package.xml index f585130..1e46bf2 100644 --- a/src/velodyne/velodyne_msgs/package.xml +++ b/src/velodyne/velodyne_msgs/package.xml @@ -1,7 +1,7 @@ velodyne_msgs - 1.6.1 + 1.7.0 ROS message definitions for Velodyne 3D LIDARs. diff --git a/src/velodyne/velodyne_pcl/CHANGELOG.rst b/src/velodyne/velodyne_pcl/CHANGELOG.rst index 6c4c260..ebad296 100644 --- a/src/velodyne/velodyne_pcl/CHANGELOG.rst +++ b/src/velodyne/velodyne_pcl/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package velodyne_pcl ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.7.0 (2022-07-08) +------------------ +* Use std::uint16_t to reduce build warnings from PCL (`#449 `_) +* Contributors: icolwell-as + 1.6.1 (2020-11-09) ------------------ * Fix typo in velodyne_pcl/point_types.h (`#357 `_) diff --git a/src/velodyne/velodyne_pcl/package.xml b/src/velodyne/velodyne_pcl/package.xml index b8bd708..a57d315 100644 --- a/src/velodyne/velodyne_pcl/package.xml +++ b/src/velodyne/velodyne_pcl/package.xml @@ -1,7 +1,7 @@ velodyne_pcl - 1.6.1 + 1.7.0 The velodyne_pcl package Josh Whitley diff --git a/src/velodyne/velodyne_pointcloud/CHANGELOG.rst b/src/velodyne/velodyne_pointcloud/CHANGELOG.rst index 58741ab..c6e3427 100644 --- a/src/velodyne/velodyne_pointcloud/CHANGELOG.rst +++ b/src/velodyne/velodyne_pointcloud/CHANGELOG.rst @@ -1,6 +1,36 @@ Change history ============== +1.7.0 (2022-07-08) +------------------ +* build timings in offline setup (`#428 `_) + Currently when using the offline setup, it does not build the per-point timing offsets which means when unpacking the packets in the offline mode, you cannot timestamp each point with its packet time. + This commit does the following: + - call buildTimings from setupOffline function + - add model to setupOffline interface + - set config model param which is needed by buildTimings +* vls128: add line only once all four banks are processed (`#413 `_) +* PCAP timestamps & PCAP+GPS timestamps (`#384 `_) + * Add pcap_time param and implement gps_time with it + * If gps_time == true, ignore pcap_time +* Fixed row_step=0 when init_width=0 (dense cloud) (`#404 `_) + The PointCloud2 msg will be then valid: http://docs.ros.org/en/melodic/api/sensor_msgs/html/msg/PointCloud2.html + Referred issues: + * https://answers.ros.org/question/377470/rtabmap-icp_odometrycpp453callbackcloud-fatal-error/ + * http://official-rtab-map-forum.67519.x6.nabble.com/Condition-scan3dMsg-data-size-scan3dMsg-row-step-scan3dMsg-height-not-met-td7852.html +* Fix accidental integer division (`#391 `_) + Intensity values for VLP-16 were being calculated incorrectly. +* Add VLS128 launch and calibration file (`#382 `_) +* Fixing incorrect type in velodyne_pointcloud. +* Fixing typo. +* Add support for the velodyne Alpha Prime (`#370 `_) + * Add support for the velodyne Alpha Prime + * Change packet rate for the VLS128 according to the times specified in the manual + * Organize setup functions to avoid code duplication. Add a constant for the model ID of the VLS128. + * Use the defined constants to calculate the time offset of the points for the VLS128 + Co-authored-by: jugo +* Contributors: Daisuke Nishimatsu, HMellor, Institute for Autonomous Systems Technology, Joshua Whitley, Martin Valgur, Nick Charron, Sebastian Scherer, matlabbe + 1.6.1 (2020-11-09) ------------------ * Add invalid points in organized cloud (`#360 `_) diff --git a/src/velodyne/velodyne_pointcloud/include/velodyne_pointcloud/rawdata.h b/src/velodyne/velodyne_pointcloud/include/velodyne_pointcloud/rawdata.h index 76b4262..95e9453 100644 --- a/src/velodyne/velodyne_pointcloud/include/velodyne_pointcloud/rawdata.h +++ b/src/velodyne/velodyne_pointcloud/include/velodyne_pointcloud/rawdata.h @@ -176,12 +176,14 @@ * through a communication overhead. * * @param calibration_file path to the calibration file + * @param model sensor model type * @param max_range_ cutoff for maximum range * @param min_range_ cutoff for minimum range * @returns 0 if successful; * errno value for failure */ - int setupOffline(std::string calibration_file, double max_range_, double min_range_); + int setupOffline(std::string calibration_file, std::string model, double max_range_, + double min_range_); void unpack(const velodyne_msgs::VelodynePacket& pkt, DataContainerBase& data, const ros::Time& scan_start_time); diff --git a/src/velodyne/velodyne_pointcloud/package.xml b/src/velodyne/velodyne_pointcloud/package.xml index 639e00a..89c8315 100644 --- a/src/velodyne/velodyne_pointcloud/package.xml +++ b/src/velodyne/velodyne_pointcloud/package.xml @@ -1,7 +1,7 @@ velodyne_pointcloud - 1.6.1 + 1.7.0 Point cloud conversions for Velodyne 3D LIDARs. diff --git a/src/velodyne/velodyne_pointcloud/src/lib/calibration.cc b/src/velodyne/velodyne_pointcloud/src/lib/calibration.cc index 4940a4f..9f19dd4 100644 --- a/src/velodyne/velodyne_pointcloud/src/lib/calibration.cc +++ b/src/velodyne/velodyne_pointcloud/src/lib/calibration.cc @@ -188,8 +188,7 @@ calibration.laser_corrections[next_index].laser_ring = ring; next_angle = min_seen; if (calibration.ros_info) { - ROS_INFO("laser_ring[%2u] = %2u, angle = %+.6f", - next_index, ring, next_angle); + //ROS_INFO("laser_ring[%2u] = %2u, angle = %+.6f", next_index, ring, next_angle); } } } diff --git a/src/velodyne/velodyne_pointcloud/src/lib/rawdata.cc b/src/velodyne/velodyne_pointcloud/src/lib/rawdata.cc index 2600bca..e870db4 100644 --- a/src/velodyne/velodyne_pointcloud/src/lib/rawdata.cc +++ b/src/velodyne/velodyne_pointcloud/src/lib/rawdata.cc @@ -202,12 +202,12 @@ if (timing_offsets.size()){ // ROS_INFO("VELODYNE TIMING TABLE:"); - for (size_t x = 0; x < timing_offsets.size(); ++x){ - for (size_t y = 0; y < timing_offsets[x].size(); ++y){ - printf("%04.3f ", timing_offsets[x][y] * 1e6); - } - printf("\n"); - } + // for (size_t x = 0; x < timing_offsets.size(); ++x){ + // for (size_t y = 0; y < timing_offsets[x].size(); ++y){ + // printf("%04.3f ", timing_offsets[x][y] * 1e6); + // } + // printf("\n"); + // } return true; } else{ @@ -253,9 +253,13 @@ } /** Set up for offline operation */ - int RawData::setupOffline(std::string calibration_file, double max_range_, double min_range_) + int RawData::setupOffline(std::string calibration_file, std::string model, + double max_range_, double min_range_) { + config_.model = model; + buildTimings(); + config_.max_range = max_range_; config_.min_range = min_range_; ROS_INFO_STREAM("data ranges to publish: [" @@ -313,7 +317,7 @@ } } else{ - ROS_WARN("No Azimuth Cache configured for model %s", config_.model.c_str()); + // ROS_WARN("No Azimuth Cache configured for model %s", config_.model.c_str()); } } @@ -676,7 +680,7 @@ // some packets contain an angle overflow where azimuth_diff < 0 if(raw_azimuth_diff < 0)//raw->blocks[block+1].rotation - raw->blocks[block].rotation < 0) { - ROS_WARN_STREAM_THROTTLE(60, "Packet containing angle overflow, first angle: " << raw->blocks[block].rotation << " second angle: " << raw->blocks[block+1].rotation); + // ROS_WARN_STREAM_THROTTLE(60, "Packet containing angle overflow, first angle: " << raw->blocks[block].rotation << " second angle: " << raw->blocks[block+1].rotation); // if last_azimuth_diff was not zero, we can assume that the velodyne's speed did not change very much and use the same difference if(last_azimuth_diff > 0){ azimuth_diff = last_azimuth_diff; diff --git a/src/waypoint_navigation/README.md b/src/waypoint_navigation/README.md new file mode 100644 index 0000000..693cfbc --- /dev/null +++ b/src/waypoint_navigation/README.md @@ -0,0 +1,8 @@ +- Python 3.8.10 +- Tkinter 8.6 +- Pillow 9.2.0 +- ruamel.yaml 0.17.21 + +waypoint_manager 参考 +- https://imagingsolution.net/category/program/python/tkinter/ +- https://daeudaeu.com/tkinter-mousewheel/ diff --git a/src/waypoint_navigation/orne_rviz_plugins/CMakeLists.txt b/src/waypoint_navigation/orne_rviz_plugins/CMakeLists.txt new file mode 100644 index 0000000..54a4b6d --- /dev/null +++ b/src/waypoint_navigation/orne_rviz_plugins/CMakeLists.txt @@ -0,0 +1,52 @@ +cmake_minimum_required(VERSION 2.8.3) +project(orne_rviz_plugins) +find_package(catkin REQUIRED COMPONENTS rviz std_srvs) +catkin_package() +include_directories(${catkin_INCLUDE_DIRS}) +link_directories(${catkin_LIBRARY_DIRS}) + +## This setting causes Qt's "MOC" generation to happen automatically. +set(CMAKE_AUTOMOC ON) + +## This plugin includes Qt widgets, so we must include Qt. +## We'll use the version that rviz used so they are compatible. +if(rviz_QT_VERSION VERSION_LESS "5") + message(STATUS "Using Qt4 based on the rviz_QT_VERSION: ${rviz_QT_VERSION}") + find_package(Qt4 ${rviz_QT_VERSION} EXACT REQUIRED QtCore QtGui) + ## pull in all required include dirs, define QT_LIBRARIES, etc. + include(${QT_USE_FILE}) +else() + message(STATUS "Using Qt5 based on the rviz_QT_VERSION: ${rviz_QT_VERSION}") + find_package(Qt5 ${rviz_QT_VERSION} EXACT REQUIRED Core Widgets) + ## make target_link_libraries(${QT_LIBRARIES}) pull in all required dependencies + set(QT_LIBRARIES Qt5::Widgets) +endif() + +add_definitions(-DQT_NO_KEYWORDS) + +set(SOURCE_FILES + src/state_trigger_panel.cpp + ${MOC_FILES} +) + +add_library(${PROJECT_NAME} ${SOURCE_FILES}) + +target_link_libraries(${PROJECT_NAME} ${QT_LIBRARIES} ${catkin_LIBRARIES}) + +install(TARGETS + ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(FILES + plugin_description.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + +install(DIRECTORY media/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/media) + +install(DIRECTORY icons/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/icons) + diff --git a/src/waypoint_navigation/orne_rviz_plugins/icons/classes/Imu.png b/src/waypoint_navigation/orne_rviz_plugins/icons/classes/Imu.png new file mode 100644 index 0000000..7d90110 --- /dev/null +++ b/src/waypoint_navigation/orne_rviz_plugins/icons/classes/Imu.png Binary files differ diff --git a/src/waypoint_navigation/orne_rviz_plugins/icons/classes/PlantFlag.png b/src/waypoint_navigation/orne_rviz_plugins/icons/classes/PlantFlag.png new file mode 100644 index 0000000..d11c0ee --- /dev/null +++ b/src/waypoint_navigation/orne_rviz_plugins/icons/classes/PlantFlag.png Binary files differ diff --git a/src/waypoint_navigation/orne_rviz_plugins/icons/classes/Teleop.png b/src/waypoint_navigation/orne_rviz_plugins/icons/classes/Teleop.png new file mode 100644 index 0000000..d96e6c1 --- /dev/null +++ b/src/waypoint_navigation/orne_rviz_plugins/icons/classes/Teleop.png Binary files differ diff --git a/src/waypoint_navigation/orne_rviz_plugins/media/flag.dae b/src/waypoint_navigation/orne_rviz_plugins/media/flag.dae new file mode 100644 index 0000000..e56a734 --- /dev/null +++ b/src/waypoint_navigation/orne_rviz_plugins/media/flag.dae @@ -0,0 +1,323 @@ + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///u/hersh/flag.blend + + 2011-03-16T15:32:31.374173 + 2011-03-16T15:32:31.374204 + Z_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.04706 0.37059 0.44706 1 + + + 0.09412 0.74118 0.89412 1 + + + 0.50000 0.50000 0.50000 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.5 + + + + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.50000 0.00000 0.00000 1 + + + 1.00000 0.00000 0.00000 1 + + + 0.50000 0.50000 0.50000 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.50000 0.50000 0.50000 1 + + + 1.00000 1.00000 1.00000 1 + + + 0.50000 0.50000 0.50000 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + + + + + + 0.70711 0.70711 -0.01000 0.83147 0.55557 -0.01000 0.92388 0.38268 -0.01000 0.98079 0.19509 -0.01000 1.00000 0.00000 -0.01000 0.98079 -0.19509 -0.01000 0.92388 -0.38268 -0.01000 0.83147 -0.55557 -0.01000 0.70711 -0.70711 -0.01000 0.55557 -0.83147 -0.01000 0.38268 -0.92388 -0.01000 0.19509 -0.98079 -0.01000 -0.00000 -1.00000 -0.01000 -0.19509 -0.98079 -0.01000 -0.38268 -0.92388 -0.01000 -0.55557 -0.83147 -0.01000 -0.70711 -0.70711 -0.01000 -0.83147 -0.55557 -0.01000 -0.92388 -0.38268 -0.01000 -0.98079 -0.19509 -0.01000 -1.00000 0.00000 -0.01000 -0.98079 0.19509 -0.01000 -0.92388 0.38268 -0.01000 -0.83147 0.55557 -0.01000 -0.70711 0.70711 -0.01000 -0.55557 0.83147 -0.01000 -0.38268 0.92388 -0.01000 -0.19509 0.98079 -0.01000 0.00000 1.00000 -0.01000 0.19509 0.98078 -0.01000 0.38269 0.92388 -0.01000 0.55557 0.83147 -0.01000 0.70711 0.70711 0.01000 0.83147 0.55557 0.01000 0.92388 0.38268 0.01000 0.98079 0.19509 0.01000 1.00000 -0.00000 0.01000 0.98078 -0.19509 0.01000 0.92388 -0.38268 0.01000 0.83147 -0.55557 0.01000 0.70711 -0.70711 0.01000 0.55557 -0.83147 0.01000 0.38268 -0.92388 0.01000 0.19509 -0.98079 0.01000 0.00000 -1.00000 0.01000 -0.19509 -0.98079 0.01000 -0.38268 -0.92388 0.01000 -0.55557 -0.83147 0.01000 -0.70710 -0.70711 0.01000 -0.83147 -0.55557 0.01000 -0.92388 -0.38269 0.01000 -0.98078 -0.19509 0.01000 -1.00000 -0.00000 0.01000 -0.98079 0.19509 0.01000 -0.92388 0.38268 0.01000 -0.83147 0.55557 0.01000 -0.70711 0.70710 0.01000 -0.55558 0.83147 0.01000 -0.38269 0.92388 0.01000 -0.19510 0.98078 0.01000 -0.00001 1.00000 0.01000 0.19508 0.98079 0.01000 0.38268 0.92388 0.01000 0.55556 0.83147 0.01000 0.00000 0.00000 -0.01000 0.00000 0.00000 0.01000 + + + + + + + + + + -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.77301 0.63439 0.00000 0.88192 0.47140 -0.00000 0.95694 0.29028 -0.00000 0.99518 0.09802 -0.00000 0.99518 -0.09802 -0.00000 0.95694 -0.29029 -0.00000 0.88192 -0.47140 -0.00000 0.77301 -0.63439 -0.00000 0.63439 -0.77301 -0.00000 0.47140 -0.88192 -0.00000 0.29028 -0.95694 -0.00000 0.09802 -0.99518 -0.00000 -0.09802 -0.99518 -0.00000 -0.29028 -0.95694 -0.00000 -0.47140 -0.88192 -0.00000 -0.63439 -0.77301 0.00000 -0.77301 -0.63439 0.00000 -0.88192 -0.47140 0.00000 -0.95694 -0.29029 -0.00000 -0.99518 -0.09802 -0.00000 -0.99518 0.09802 -0.00000 -0.95694 0.29028 -0.00000 -0.88192 0.47139 -0.00000 -0.77301 0.63439 -0.00000 -0.63440 0.77301 -0.00000 -0.47140 0.88192 -0.00000 -0.29029 0.95694 -0.00000 -0.09802 0.99518 -0.00000 0.09801 0.99519 -0.00000 0.29028 0.95694 -0.00000 0.47139 0.88192 -0.00000 0.63439 0.77301 0.00003 + + + + + + + + + + 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 + + + + + + + + + + + + + + +

64 0 0 0 0 1 1 0 2 65 1 3 33 1 4 32 1 5 64 2 6 1 2 7 2 2 8 65 3 9 34 3 10 33 3 11 64 4 12 2 4 13 3 4 14 65 5 15 35 5 16 34 5 17 64 6 18 3 6 19 4 6 20 65 7 21 36 7 22 35 7 23 64 8 24 4 8 25 5 8 26 65 9 27 37 9 28 36 9 29 64 10 30 5 10 31 6 10 32 65 11 33 38 11 34 37 11 35 64 12 36 6 12 37 7 12 38 65 13 39 39 13 40 38 13 41 64 14 42 7 14 43 8 14 44 65 15 45 40 15 46 39 15 47 64 16 48 8 16 49 9 16 50 65 17 51 41 17 52 40 17 53 64 18 54 9 18 55 10 18 56 65 19 57 42 19 58 41 19 59 64 20 60 10 20 61 11 20 62 65 21 63 43 21 64 42 21 65 64 22 66 11 22 67 12 22 68 65 23 69 44 23 70 43 23 71 64 24 72 12 24 73 13 24 74 65 25 75 45 25 76 44 25 77 64 26 78 13 26 79 14 26 80 65 27 81 46 27 82 45 27 83 64 28 84 14 28 85 15 28 86 65 29 87 47 29 88 46 29 89 64 30 90 15 30 91 16 30 92 65 31 93 48 31 94 47 31 95 64 32 96 16 32 97 17 32 98 65 33 99 49 33 100 48 33 101 64 34 102 17 34 103 18 34 104 65 35 105 50 35 106 49 35 107 64 36 108 18 36 109 19 36 110 65 37 111 51 37 112 50 37 113 64 38 114 19 38 115 20 38 116 65 39 117 52 39 118 51 39 119 64 40 120 20 40 121 21 40 122 65 41 123 53 41 124 52 41 125 64 42 126 21 42 127 22 42 128 65 43 129 54 43 130 53 43 131 64 44 132 22 44 133 23 44 134 65 45 135 55 45 136 54 45 137 64 46 138 23 46 139 24 46 140 65 47 141 56 47 142 55 47 143 64 48 144 24 48 145 25 48 146 65 49 147 57 49 148 56 49 149 64 50 150 25 50 151 26 50 152 65 51 153 58 51 154 57 51 155 64 52 156 26 52 157 27 52 158 65 53 159 59 53 160 58 53 161 64 54 162 27 54 163 28 54 164 65 55 165 60 55 166 59 55 167 64 56 168 28 56 169 29 56 170 65 57 171 61 57 172 60 57 173 64 58 174 29 58 175 30 58 176 65 59 177 62 59 178 61 59 179 64 60 180 30 60 181 31 60 182 65 61 183 63 61 184 62 61 185 31 62 186 0 62 187 64 62 188 65 63 189 32 63 190 63 63 191 0 64 192 32 64 193 33 64 194 33 64 195 1 64 196 0 64 197 1 65 198 33 65 199 34 65 200 34 65 201 2 65 202 1 65 203 2 66 204 34 66 205 35 66 206 35 66 207 3 66 208 2 66 209 3 67 210 35 67 211 36 67 212 36 67 213 4 67 214 3 67 215 4 68 216 36 68 217 37 68 218 37 68 219 5 68 220 4 68 221 5 69 222 37 69 223 38 69 224 38 69 225 6 69 226 5 69 227 6 70 228 38 70 229 39 70 230 39 70 231 7 70 232 6 70 233 7 71 234 39 71 235 40 71 236 40 71 237 8 71 238 7 71 239 8 72 240 40 72 241 41 72 242 41 72 243 9 72 244 8 72 245 9 73 246 41 73 247 42 73 248 42 73 249 10 73 250 9 73 251 10 74 252 42 74 253 43 74 254 43 74 255 11 74 256 10 74 257 11 75 258 43 75 259 44 75 260 44 75 261 12 75 262 11 75 263 12 76 264 44 76 265 45 76 266 45 76 267 13 76 268 12 76 269 13 77 270 45 77 271 46 77 272 46 77 273 14 77 274 13 77 275 14 78 276 46 78 277 47 78 278 47 78 279 15 78 280 14 78 281 15 79 282 47 79 283 48 79 284 48 79 285 16 79 286 15 79 287 16 80 288 48 80 289 49 80 290 49 80 291 17 80 292 16 80 293 17 81 294 49 81 295 50 81 296 50 81 297 18 81 298 17 81 299 18 82 300 50 82 301 51 82 302 51 82 303 19 82 304 18 82 305 19 83 306 51 83 307 52 83 308 52 83 309 20 83 310 19 83 311 20 84 312 52 84 313 53 84 314 53 84 315 21 84 316 20 84 317 21 85 318 53 85 319 54 85 320 54 85 321 22 85 322 21 85 323 22 86 324 54 86 325 55 86 326 55 86 327 23 86 328 22 86 329 23 87 330 55 87 331 56 87 332 56 87 333 24 87 334 23 87 335 24 88 336 56 88 337 57 88 338 57 88 339 25 88 340 24 88 341 25 89 342 57 89 343 58 89 344 58 89 345 26 89 346 25 89 347 26 90 348 58 90 349 59 90 350 59 90 351 27 90 352 26 90 353 27 91 354 59 91 355 60 91 356 60 91 357 28 91 358 27 91 359 28 92 360 60 92 361 61 92 362 61 92 363 29 92 364 28 92 365 29 93 366 61 93 367 62 93 368 62 93 369 30 93 370 29 93 371 30 94 372 62 94 373 63 94 374 63 94 375 31 94 376 30 94 377 32 95 378 0 95 379 31 95 380 31 95 381 63 95 382 32 95 383

+
+
+
+ + + + 1.00000 0.00000 0.00621 -1.00000 -0.00000 -0.99379 -1.00000 0.00000 1.00621 -1.00000 0.05590 1.00621 -1.00000 0.05590 -0.99379 1.00000 0.05590 0.00621 + + + + + + + + + + 0.00000 -1.00000 0.00000 0.44721 0.00000 -0.89443 -1.00000 0.00000 0.00000 0.44721 0.00000 0.89443 -0.00000 1.00000 -0.00000 + + + + + + + + + + + + + + +

1 0 0 0 2 0 0 1 1 1 4 1 4 1 5 1 0 1 1 2 2 2 3 2 3 2 4 2 1 2 2 3 0 3 5 3 5 3 3 3 2 3 3 4 5 4 4 4

+
+
+
+ + + + 0.03536 0.03536 -1.00000 0.04157 0.02778 -1.00000 0.04619 0.01913 -1.00000 0.04904 0.00975 -1.00000 0.05000 0.00000 -1.00000 0.04904 -0.00975 -1.00000 0.04619 -0.01913 -1.00000 0.04157 -0.02778 -1.00000 0.03536 -0.03536 -1.00000 0.02778 -0.04157 -1.00000 0.01913 -0.04619 -1.00000 0.00975 -0.04904 -1.00000 -0.00000 -0.05000 -1.00000 -0.00975 -0.04904 -1.00000 -0.01913 -0.04619 -1.00000 -0.02778 -0.04157 -1.00000 -0.03536 -0.03536 -1.00000 -0.04157 -0.02778 -1.00000 -0.04619 -0.01913 -1.00000 -0.04904 -0.00975 -1.00000 -0.05000 0.00000 -1.00000 -0.04904 0.00975 -1.00000 -0.04619 0.01913 -1.00000 -0.04157 0.02778 -1.00000 -0.03536 0.03536 -1.00000 -0.02778 0.04157 -1.00000 -0.01913 0.04619 -1.00000 -0.00975 0.04904 -1.00000 0.00000 0.05000 -1.00000 0.00975 0.04904 -1.00000 0.01913 0.04619 -1.00000 0.02778 0.04157 -1.00000 0.03536 0.03536 1.00000 0.04157 0.02778 1.00000 0.04619 0.01913 1.00000 0.04904 0.00975 1.00000 0.05000 -0.00000 1.00000 0.04904 -0.00975 1.00000 0.04619 -0.01913 1.00000 0.04157 -0.02778 1.00000 0.03536 -0.03536 1.00000 0.02778 -0.04157 1.00000 0.01913 -0.04619 1.00000 0.00975 -0.04904 1.00000 0.00000 -0.05000 1.00000 -0.00975 -0.04904 1.00000 -0.01913 -0.04619 1.00000 -0.02778 -0.04157 1.00000 -0.03536 -0.03536 1.00000 -0.04157 -0.02778 1.00000 -0.04619 -0.01913 1.00000 -0.04904 -0.00975 1.00000 -0.05000 -0.00000 1.00000 -0.04904 0.00975 1.00000 -0.04619 0.01913 1.00000 -0.04157 0.02778 1.00000 -0.03536 0.03536 1.00000 -0.02778 0.04157 1.00000 -0.01913 0.04619 1.00000 -0.00975 0.04904 1.00000 -0.00000 0.05000 1.00000 0.00975 0.04904 1.00000 0.01913 0.04619 1.00000 0.02778 0.04157 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 + + + + + + + + + + -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.77301 0.63439 0.00000 0.88192 0.47140 0.00000 0.95694 0.29028 -0.00000 0.99518 0.09802 -0.00000 0.99518 -0.09802 -0.00000 0.95694 -0.29029 -0.00000 0.88192 -0.47140 -0.00000 0.77301 -0.63439 -0.00000 0.63439 -0.77301 0.00000 0.47140 -0.88192 -0.00000 0.29028 -0.95694 -0.00000 0.09802 -0.99518 -0.00000 -0.09802 -0.99518 -0.00000 -0.29028 -0.95694 -0.00000 -0.47140 -0.88192 -0.00000 -0.63439 -0.77301 -0.00000 -0.77301 -0.63439 -0.00000 -0.88192 -0.47140 0.00000 -0.95694 -0.29029 0.00000 -0.99518 -0.09802 -0.00000 -0.99518 0.09802 -0.00000 -0.95694 0.29028 -0.00000 -0.88192 0.47140 -0.00000 -0.77301 0.63439 -0.00000 -0.63440 0.77301 -0.00000 -0.47140 0.88192 0.00000 -0.29029 0.95694 -0.00000 -0.09802 0.99518 -0.00000 0.09801 0.99519 -0.00000 0.29028 0.95694 -0.00000 0.47139 0.88192 -0.00000 0.63439 0.77301 0.00000 + + + + + + + + + + 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 0.00000 0.00000 1.00000 0.00000 1.00000 1.00000 1.00000 1.00000 0.00000 1.00000 0.00000 0.00000 + + + + + + + + + + + + + + +

64 0 0 0 0 1 1 0 2 65 1 3 33 1 4 32 1 5 64 2 6 1 2 7 2 2 8 65 3 9 34 3 10 33 3 11 64 4 12 2 4 13 3 4 14 65 5 15 35 5 16 34 5 17 64 6 18 3 6 19 4 6 20 65 7 21 36 7 22 35 7 23 64 8 24 4 8 25 5 8 26 65 9 27 37 9 28 36 9 29 64 10 30 5 10 31 6 10 32 65 11 33 38 11 34 37 11 35 64 12 36 6 12 37 7 12 38 65 13 39 39 13 40 38 13 41 64 14 42 7 14 43 8 14 44 65 15 45 40 15 46 39 15 47 64 16 48 8 16 49 9 16 50 65 17 51 41 17 52 40 17 53 64 18 54 9 18 55 10 18 56 65 19 57 42 19 58 41 19 59 64 20 60 10 20 61 11 20 62 65 21 63 43 21 64 42 21 65 64 22 66 11 22 67 12 22 68 65 23 69 44 23 70 43 23 71 64 24 72 12 24 73 13 24 74 65 25 75 45 25 76 44 25 77 64 26 78 13 26 79 14 26 80 65 27 81 46 27 82 45 27 83 64 28 84 14 28 85 15 28 86 65 29 87 47 29 88 46 29 89 64 30 90 15 30 91 16 30 92 65 31 93 48 31 94 47 31 95 64 32 96 16 32 97 17 32 98 65 33 99 49 33 100 48 33 101 64 34 102 17 34 103 18 34 104 65 35 105 50 35 106 49 35 107 64 36 108 18 36 109 19 36 110 65 37 111 51 37 112 50 37 113 64 38 114 19 38 115 20 38 116 65 39 117 52 39 118 51 39 119 64 40 120 20 40 121 21 40 122 65 41 123 53 41 124 52 41 125 64 42 126 21 42 127 22 42 128 65 43 129 54 43 130 53 43 131 64 44 132 22 44 133 23 44 134 65 45 135 55 45 136 54 45 137 64 46 138 23 46 139 24 46 140 65 47 141 56 47 142 55 47 143 64 48 144 24 48 145 25 48 146 65 49 147 57 49 148 56 49 149 64 50 150 25 50 151 26 50 152 65 51 153 58 51 154 57 51 155 64 52 156 26 52 157 27 52 158 65 53 159 59 53 160 58 53 161 64 54 162 27 54 163 28 54 164 65 55 165 60 55 166 59 55 167 64 56 168 28 56 169 29 56 170 65 57 171 61 57 172 60 57 173 64 58 174 29 58 175 30 58 176 65 59 177 62 59 178 61 59 179 64 60 180 30 60 181 31 60 182 65 61 183 63 61 184 62 61 185 31 62 186 0 62 187 64 62 188 65 63 189 32 63 190 63 63 191 0 64 192 32 64 193 33 64 194 33 64 195 1 64 196 0 64 197 1 65 198 33 65 199 34 65 200 34 65 201 2 65 202 1 65 203 2 66 204 34 66 205 35 66 206 35 66 207 3 66 208 2 66 209 3 67 210 35 67 211 36 67 212 36 67 213 4 67 214 3 67 215 4 68 216 36 68 217 37 68 218 37 68 219 5 68 220 4 68 221 5 69 222 37 69 223 38 69 224 38 69 225 6 69 226 5 69 227 6 70 228 38 70 229 39 70 230 39 70 231 7 70 232 6 70 233 7 71 234 39 71 235 40 71 236 40 71 237 8 71 238 7 71 239 8 72 240 40 72 241 41 72 242 41 72 243 9 72 244 8 72 245 9 73 246 41 73 247 42 73 248 42 73 249 10 73 250 9 73 251 10 74 252 42 74 253 43 74 254 43 74 255 11 74 256 10 74 257 11 75 258 43 75 259 44 75 260 44 75 261 12 75 262 11 75 263 12 76 264 44 76 265 45 76 266 45 76 267 13 76 268 12 76 269 13 77 270 45 77 271 46 77 272 46 77 273 14 77 274 13 77 275 14 78 276 46 78 277 47 78 278 47 78 279 15 78 280 14 78 281 15 79 282 47 79 283 48 79 284 48 79 285 16 79 286 15 79 287 16 80 288 48 80 289 49 80 290 49 80 291 17 80 292 16 80 293 17 81 294 49 81 295 50 81 296 50 81 297 18 81 298 17 81 299 18 82 300 50 82 301 51 82 302 51 82 303 19 82 304 18 82 305 19 83 306 51 83 307 52 83 308 52 83 309 20 83 310 19 83 311 20 84 312 52 84 313 53 84 314 53 84 315 21 84 316 20 84 317 21 85 318 53 85 319 54 85 320 54 85 321 22 85 322 21 85 323 22 86 324 54 86 325 55 86 326 55 86 327 23 86 328 22 86 329 23 87 330 55 87 331 56 87 332 56 87 333 24 87 334 23 87 335 24 88 336 56 88 337 57 88 338 57 88 339 25 88 340 24 88 341 25 89 342 57 89 343 58 89 344 58 89 345 26 89 346 25 89 347 26 90 348 58 90 349 59 90 350 59 90 351 27 90 352 26 90 353 27 91 354 59 91 355 60 91 356 60 91 357 28 91 358 27 91 359 28 92 360 60 92 361 61 92 362 61 92 363 29 92 364 28 92 365 29 93 366 61 93 367 62 93 368 62 93 369 30 93 370 29 93 371 30 94 372 62 94 373 63 94 374 63 94 375 31 94 376 30 94 377 32 95 378 0 95 379 31 95 380 31 95 381 63 95 382 32 95 383

+
+
+
+
+ + + + -0.29478 -1.99835 2.70248 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + 0.00334 -0.00071 0.00118 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + 0.22856 0.00372 1.80362 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 0.18803 0.18803 0.18803 + + + + + + + + + + + + 0.00580 0.01041 0.99794 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/src/waypoint_navigation/orne_rviz_plugins/package.xml b/src/waypoint_navigation/orne_rviz_plugins/package.xml new file mode 100644 index 0000000..55c71fc --- /dev/null +++ b/src/waypoint_navigation/orne_rviz_plugins/package.xml @@ -0,0 +1,22 @@ + + orne_rviz_plugins + 0.0.1 + + The orne_rviz_plugins package + + Daiki Maekawa + BSD + + Daiki Maekawa + + catkin + rviz + std_srvs + rviz + std_srvs + + + + + + diff --git a/src/waypoint_navigation/orne_rviz_plugins/plugin_description.xml b/src/waypoint_navigation/orne_rviz_plugins/plugin_description.xml new file mode 100644 index 0000000..ccb9e11 --- /dev/null +++ b/src/waypoint_navigation/orne_rviz_plugins/plugin_description.xml @@ -0,0 +1,9 @@ + + + + TODO + + + diff --git a/src/waypoint_navigation/orne_rviz_plugins/src/state_trigger_panel.cpp b/src/waypoint_navigation/orne_rviz_plugins/src/state_trigger_panel.cpp new file mode 100644 index 0000000..7e2a334 --- /dev/null +++ b/src/waypoint_navigation/orne_rviz_plugins/src/state_trigger_panel.cpp @@ -0,0 +1,63 @@ +#include + +#include +#include +#include +#include +#include +#include +#include + +#include + +#include "state_trigger_panel.h" + +namespace orne_rviz_plugins +{ + +StateTriggerPanel::StateTriggerPanel( QWidget* parent ) + : rviz::Panel( parent ) +{ + start_client_ = nh_.serviceClient("start_wp_nav", false); + resume_client_ = nh_.serviceClient("resume_nav", false); + + start_nav_button_ = new QPushButton("StartWaypointsNavigation"); + resume_nav_button_ = new QPushButton("ResumeWaypointsNavigation"); + + QHBoxLayout* layout = new QHBoxLayout; + layout->addWidget(start_nav_button_); + layout->addWidget(resume_nav_button_); + setLayout( layout ); + + connect(start_nav_button_, SIGNAL(clicked()), this, SLOT(pushStartNavigation())); + connect(resume_nav_button_, SIGNAL(clicked()), this, SLOT(pushResumeNavigation())); +} + +void StateTriggerPanel::save( rviz::Config config ) const +{ + rviz::Panel::save( config ); +} + +void StateTriggerPanel::load( const rviz::Config& config ) +{ + rviz::Panel::load( config ); +} + +void StateTriggerPanel::pushStartNavigation() { + ROS_INFO("Service call: start waypoints navigation"); + + std_srvs::Trigger trigger; + start_client_.call(trigger); +} + +void StateTriggerPanel::pushResumeNavigation() { + ROS_INFO("Service call: resume waypoints navigation"); + + std_srvs::Trigger trigger; + resume_client_.call(trigger); +} + +} // end namespace orne_rviz_plugins + +#include +PLUGINLIB_EXPORT_CLASS(orne_rviz_plugins::StateTriggerPanel,rviz::Panel ) diff --git a/src/waypoint_navigation/orne_rviz_plugins/src/state_trigger_panel.h b/src/waypoint_navigation/orne_rviz_plugins/src/state_trigger_panel.h new file mode 100644 index 0000000..461b3a0 --- /dev/null +++ b/src/waypoint_navigation/orne_rviz_plugins/src/state_trigger_panel.h @@ -0,0 +1,38 @@ +#ifndef STATE_TRIGGER_PANEL_H +#define STATE_TRIGGER_PANEL_H + +#ifndef Q_MOC_RUN +# include + +# include +#endif + +class QPushButton; + +namespace orne_rviz_plugins +{ + +class StateTriggerPanel: public rviz::Panel +{ +Q_OBJECT +public: + StateTriggerPanel( QWidget* parent = 0 ); + + virtual void load( const rviz::Config& config ); + virtual void save( rviz::Config config ) const; + +public Q_SLOTS: + void pushStartNavigation(); + void pushResumeNavigation(); + +protected: + ros::NodeHandle nh_; + ros::ServiceClient start_client_, resume_client_; + QPushButton *start_nav_button_; + QPushButton *resume_nav_button_; + +}; + +} // end namespace orne_rviz_plugins + +#endif // STATE_TRIGGER_PANEL_H diff --git a/src/waypoint_navigation/waypoint_manager/CMakeLists.txt b/src/waypoint_navigation/waypoint_manager/CMakeLists.txt new file mode 100644 index 0000000..2941813 --- /dev/null +++ b/src/waypoint_navigation/waypoint_manager/CMakeLists.txt @@ -0,0 +1,202 @@ +cmake_minimum_required(VERSION 3.0.2) +project(waypoint_manager) + +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend tag for "message_generation" +## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependency has been pulled in +## but can be declared for certainty nonetheless: +## * add a exec_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# std_msgs # Or other packages containing msgs +# ) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +## Generate dynamic reconfigure parameters in the 'cfg' folder +# generate_dynamic_reconfigure_options( +# cfg/DynReconf1.cfg +# cfg/DynReconf2.cfg +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if your package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES waypoint_manager +# CATKIN_DEPENDS other_catkin_pkg +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( +# include +# ${catkin_INCLUDE_DIRS} +) + +## Declare a C++ library +# add_library(${PROJECT_NAME} +# src/${PROJECT_NAME}/waypoint_manager.cpp +# ) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Declare a C++ executable +## With catkin_make all packages are built within a single CMake context +## The recommended prefix ensures that target names across packages don't collide +# add_executable(${PROJECT_NAME}_node src/waypoint_manager_node.cpp) + +## Rename C++ executable without prefix +## The above recommended prefix causes long target names, the following renames the +## target back to the shorter version for ease of user use +## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") + +## Add cmake target dependencies of the executable +## same as for the library above +# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Specify libraries to link a library or executable target against +# target_link_libraries(${PROJECT_NAME}_node +# ${catkin_LIBRARIES} +# ) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# catkin_install_python(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html +# install(TARGETS ${PROJECT_NAME}_node +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark libraries for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html +# install(TARGETS ${PROJECT_NAME} +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_waypoint_manager.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/src/waypoint_navigation/waypoint_manager/launch/start_manager.launch b/src/waypoint_navigation/waypoint_manager/launch/start_manager.launch new file mode 100644 index 0000000..e69de29 --- /dev/null +++ b/src/waypoint_navigation/waypoint_manager/launch/start_manager.launch diff --git a/src/waypoint_navigation/waypoint_manager/package.xml b/src/waypoint_navigation/waypoint_manager/package.xml new file mode 100644 index 0000000..e77ca19 --- /dev/null +++ b/src/waypoint_navigation/waypoint_manager/package.xml @@ -0,0 +1,59 @@ + + + waypoint_manager + 0.0.0 + The waypoint_manager package + + + + + ubuntu + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + + + + + + + + diff --git a/src/waypoint_navigation/waypoint_manager/scripts/lib/__init__.py b/src/waypoint_navigation/waypoint_manager/scripts/lib/__init__.py new file mode 100644 index 0000000..e69de29 --- /dev/null +++ b/src/waypoint_navigation/waypoint_manager/scripts/lib/__init__.py diff --git a/src/waypoint_navigation/waypoint_manager/scripts/lib/__pycache__/__init__.cpython-38.pyc b/src/waypoint_navigation/waypoint_manager/scripts/lib/__pycache__/__init__.cpython-38.pyc new file mode 100644 index 0000000..0227a91 --- /dev/null +++ b/src/waypoint_navigation/waypoint_manager/scripts/lib/__pycache__/__init__.cpython-38.pyc Binary files differ diff --git a/src/waypoint_navigation/waypoint_manager/scripts/lib/__pycache__/mymaplib.cpython-38.pyc b/src/waypoint_navigation/waypoint_manager/scripts/lib/__pycache__/mymaplib.cpython-38.pyc new file mode 100644 index 0000000..5048aa5 --- /dev/null +++ b/src/waypoint_navigation/waypoint_manager/scripts/lib/__pycache__/mymaplib.cpython-38.pyc Binary files differ diff --git a/src/waypoint_navigation/waypoint_manager/scripts/lib/__pycache__/waypointlib.cpython-38.pyc b/src/waypoint_navigation/waypoint_manager/scripts/lib/__pycache__/waypointlib.cpython-38.pyc new file mode 100644 index 0000000..f8c3b92 --- /dev/null +++ b/src/waypoint_navigation/waypoint_manager/scripts/lib/__pycache__/waypointlib.cpython-38.pyc Binary files differ diff --git a/src/waypoint_navigation/waypoint_manager/scripts/lib/mymaplib.py b/src/waypoint_navigation/waypoint_manager/scripts/lib/mymaplib.py new file mode 100644 index 0000000..884b300 --- /dev/null +++ b/src/waypoint_navigation/waypoint_manager/scripts/lib/mymaplib.py @@ -0,0 +1,85 @@ +import numpy as np +from PIL import Image, ImageTk +from pathlib import Path + + +class MyMap(): + + def __init__(self, path: Path, map_yaml): + if map_yaml["image"][0] == "/": + img_path = map_yaml["image"] + else: + img_path = path.with_name(map_yaml["image"]).resolve() + self.pil_img = Image.open(img_path).convert("RGBA") + self.tk_img = ImageTk.PhotoImage(self.pil_img) + self.origin = map_yaml["origin"] + self.resolution = map_yaml["resolution"] + self.img_origin = [-self.origin[0]/self.resolution, self.origin[1]/self.resolution+self.height()] + self.mat_affine = np.eye(3) + return + + + def translate(self, x, y): + self.affine_tf(x, y, 1) + return + + + def scale_at(self, x, y, scale): + self.affine_tf(-x, -y, 1) + self.affine_tf(0, 0, scale) + self.affine_tf(x, y, 1) + return + + + def affine_tf(self, x, y, scale): + x = float(x) + y = float(y) + scale = float(scale) + mat = np.array([[scale,0,x], [0,scale,y], [0,0,1]]) + self.mat_affine = np.dot(mat, self.mat_affine) + return + + + def get_draw_image(self, canvas_size): + mat_inv = np.linalg.inv(self.mat_affine) + img = self.pil_img.transform(canvas_size, + Image.Transform.AFFINE, tuple(mat_inv.flatten()), + Image.Resampling.NEAREST, + fillcolor="#0000" + ) + self.tk_img = ImageTk.PhotoImage(image=img) + return self.tk_img + + + def real2image(self, real_x, real_y): + img_x = self.img_origin[0] + real_x / self.resolution + img_y = self.img_origin[1] - real_y / self.resolution + return img_x, img_y + + + def image2real(self, img_x, img_y): + real_x = (img_x - self.img_origin[0]) * self.resolution + real_y = -(img_y - self.img_origin[1]) * self.resolution + real_x = round(real_x, 6) + real_y = round(real_y, 6) + return real_x, real_y + + + def transform(self, img_x, img_y): + mat = [img_x, img_y, 1] + tf_mat = np.dot(self.mat_affine, mat) + return tf_mat[0], tf_mat[1] + + + def inv_transform(self, x, y): + mat = [x, y, 1] + inv_affine = np.linalg.inv(self.mat_affine) + inv = np.dot(inv_affine, mat) + return inv[0], inv[1] + + + def width(self): + return self.pil_img.width + + def height(self): + return self.pil_img.height \ No newline at end of file diff --git a/src/waypoint_navigation/waypoint_manager/scripts/lib/waypointlib.py b/src/waypoint_navigation/waypoint_manager/scripts/lib/waypointlib.py new file mode 100644 index 0000000..ab54d33 --- /dev/null +++ b/src/waypoint_navigation/waypoint_manager/scripts/lib/waypointlib.py @@ -0,0 +1,118 @@ +import numpy as np +import quaternion + + +class WaypointList(): + def __init__(self, wp_yaml): + self.waypoints = [] + for point in wp_yaml["waypoints"]: + wp = {} + for key, val in point["point"].items(): + wp[key] = val + self.append(wp) + + self.point_keys = self.waypoints[0].keys() + self.number_dict = {} + return + + + def append(self, waypoint: dict, id=None): + self.waypoints.append(waypoint) + if id: self.set_id(len(self.waypoints), id) + return len(self.waypoints) + + + def insert(self, num, waypoint: dict, id=None): + self.waypoints.insert(num-1, waypoint) + for i, n in self.number_dict.items(): + self.number_dict[i] = n+1 if (n>=num) else n + if id: self.set_id(num, id) + return + + + def remove(self, id): + num = self.get_num(str(id)) + self.waypoints.pop(num-1) + self.number_dict.pop(str(id)) + for i, n in self.number_dict.items(): + self.number_dict[i] = n-1 if (n>num) else n + return + + + def set_waypoint_val(self, id, key, val): + self.waypoints[self.get_num(id)-1][key] = val + return + + + def get_waypoint(self, id=None, num=None): + if id: return self.waypoints[self.get_num(str(id)) - 1] + if num: return self.waypoints[num-1] + return self.waypoints + + + def get_id_list(self): + return self.number_dict.keys() + + + def set_id(self, num, id): + self.number_dict[str(id)] = num + return + + + def get_num(self, id): + return self.number_dict[str(id)] + + + + +class FinishPose(): + def __init__(self, wp_yaml): + super().__init__() + + self.header = {} + for key, val in wp_yaml["finish_pose"]["header"].items(): + self.header[key] = val + + self.position = {} + for key, val in wp_yaml["finish_pose"]["pose"]["position"].items(): + self.position[key] = val + + self.orientation = {} + for key, val in wp_yaml["finish_pose"]["pose"]["orientation"].items(): + self.orientation[key] = val + + self.x = self.position["x"] + self.y = self.position["y"] + self.yaw = self.get_euler() + self.id = None + return + + + def get_euler(self): + o = self.orientation + q = np.quaternion(o["x"], o["y"], o["z"], o["w"]) + return quaternion.as_euler_angles(q)[1] + + + +def get_waypoint_yaml(waypoints: WaypointList, finish_pose: FinishPose): + s = ["waypoints:" + "\n"] + for point in waypoints.get_waypoint(): + s.append("- point: {") + for i, (key, val) in enumerate(point.items()): + if (i != 0): s.append(", ") + s.append(key + ": " + str(val).lower()) + s.append("}" + "\n") + + s.append("finish_pose:" + "\n") + seq, stamp, frame = (finish_pose.header["seq"], finish_pose.header["stamp"], finish_pose.header["frame_id"]) + s.append(" header: {" + "seq: {}, stamp: {}, frame_id: {}".format(seq,stamp,frame) + "}" + "\n") + s.append(" pose:" + "\n") + p = finish_pose.position + s.append(" position: {" + "x: {}, y: {}, z: {}".format(p["x"], p["y"], p["z"]) + "}" + "\n") + o = finish_pose.orientation + s.append(" orientation: {" + "x: {}, y: {}, z: {}, w: {}".format(o["x"],o["y"],o["z"],o["w"]) + "}") + return "".join(s) + + + \ No newline at end of file diff --git a/src/waypoint_navigation/waypoint_manager/scripts/manager_GUI.py b/src/waypoint_navigation/waypoint_manager/scripts/manager_GUI.py new file mode 100755 index 0000000..9bd2d1f --- /dev/null +++ b/src/waypoint_navigation/waypoint_manager/scripts/manager_GUI.py @@ -0,0 +1,705 @@ +import tkinter as tk +import tkinter.filedialog +import math +import ruamel.yaml +from pathlib import Path +from lib.mymaplib import MyMap +from lib.waypointlib import WaypointList, FinishPose, get_waypoint_yaml + + + + +class Application(tk.Frame): + + def __init__(self, master): + super().__init__(master) # スーパークラスのコンストラクタを実行 + self.master.title("Waypoints Manager") + + #### 画面上部のメニューを作成 #### + self.menu_bar = tk.Menu(self) # メニューバーを配置 + self.file_menu = tk.Menu(self.menu_bar, tearoff=tk.OFF) # バーに追加するメニューを作成 + self.menu_bar.add_cascade(label="File", menu=self.file_menu) # Fileメニューとしてバーに追加 + self.open_menu = tk.Menu(self.file_menu, tearoff=tk.OFF) # Openメニュー + self.open_menu.add_command(label="Map", command=self.menu_open_map) + self.open_menu.add_command(label="Waypoints", command=self.menu_open_waypoints, state=tk.DISABLED) + self.file_menu.add_cascade(label="Open", menu=self.open_menu) + self.file_menu.add_command(label="Save", command=self.menu_save, #コールバック関数を設定 + accelerator="Ctrl+S", state=tk.DISABLED + ) + self.file_menu.add_command(label="Save As", command=self.menu_saveas, + accelerator="Ctrl+Shift+S", state=tk.DISABLED + ) + self.file_menu.add_separator() + self.file_menu.add_command(label="Exit", command=self.menu_exit, accelerator="Ctrl+Q") + self.bind_all("", self.menu_save) #キーボードショートカットを設定 + self.bind_all("", self.menu_saveas) + self.bind_all("", self.menu_exit) + self.master.config(menu=self.menu_bar) # 大元に作成したメニューバーを設定 + + #### 画面上部に、システムからのメッセージを表示するラベルを配置 #### + self.msg_label = tk.Label(self.master, text="Please open map file ", anchor=tk.E) + self.msg_label.pack(fill=tk.X, padx=5) + + #### 画面下部に、カーソルの座標やピクセル情報を表示するステータスバーを表示 #### + self.status_bar = tk.Frame(self.master) + self.mouse_position = tk.Label(self.status_bar, relief=tk.SUNKEN, + text=" (x, y) = ", anchor=tk.W, font=("", 15) + ) + self.mouse_position.pack(side=tk.LEFT, padx=3) + self.waypoint_num = tk.Label(self.status_bar, relief=tk.SUNKEN, + text=" Waypoint No. -----", anchor=tk.W, font=("", 15) + ) + self.waypoint_num.pack(side=tk.RIGHT, padx=3) + self.status_bar.pack(side=tk.BOTTOM, fill=tk.X) + + #### 右クリックしたときに表示するポップアップメニューを作成 #### + self.popup_menu = tk.Menu(self, tearoff=tk.OFF) + self.popup_menu.add_command(label="Add waypoint here", command=self.add_waypoint_here, state=tk.DISABLED) + self.right_click_coord = None # 右クリックしたときの座標を保持する変数 + + #### canvasを配置、サイズを取得 #### + self.canvas = tk.Canvas(self.master, bg="#034") # 画像を描画するcanvas + self.canvas.pack(expand=True, fill=tk.BOTH) # canvasを配置 + self.update() # 情報の更新をする(canvasのサイズなどの情報が更新される) + self.canv_w = self.canvas.winfo_width() # canvasの幅を取得 + self.canv_h = self.canvas.winfo_height() # canvasの高さを取得 + + #### イベントに対するコールバックを設定 #### + self.master.bind("", self.mouse_move) + self.master.bind("", self.mouse_wheel) + self.master.bind("", self.left_click_move) + self.master.bind("", self.left_click) + self.master.bind("", self.left_click_release) + self.master.bind("", self.right_click) + self.master.bind("", self.ctrl_left_click) + self.master.bind("", self.ctrl_right_click) + self.master.bind("", self.window_resize_callback) + + #### その他必要になる変数 #### + self.mymap = None + self.waypoints = None + self.finish_pose = None + self.waypoints_filepath = None + self.editing_waypoint_id = None # 編集中のウェイポイントを示す図形のオブジェクトID + self.moving_waypoint = False # ウェイポイントをDnDで動かしている最中かどうか + self.old_click_point = None # 最後にカーソルのあった座標を保持 + self.wp_info_win = None # ウェイポイント情報を表示するウィンドウ + self.point_rad = 10 # 画像上に示すポイントの半径ピクセル + return + + + + """ + ############################### + メニューコールバック関数 + ############################### + """ + """ + +++++ File -> Open -> Map +++++ + """ + def menu_open_map(self): + map_path = tkinter.filedialog.askopenfilename( + parent=self.master, + title="Select map yaml file", + initialdir=str(Path(".")), + filetypes=[("YAML", ".yaml")] + ) + if not map_path: return + + with open(map_path) as file: # .yamlを読み込む + map_yaml = ruamel.yaml.YAML().load(file) + self.mymap = MyMap(Path(map_path), map_yaml) + ## キャンバスサイズに合わせて画像を表示 + scale = 1 + offset_x = 0 + offset_y = 0 + if (self.canv_w / self.canv_h) > (self.mymap.width() / self.mymap.height()): + # canvasの方が横長 画像をcanvasの縦に合わせてリサイズ + scale = self.canv_h / self.mymap.height() + offset_x = (self.canv_w - self.mymap.width()*scale) / 2 + else: + # canvasの方が縦長 画像をcanvasの横に合わせてリサイズ + scale = self.canv_w / self.mymap.width() + offset_y = (self.canv_h - self.mymap.height()*scale) / 2 + + self.mymap.scale_at(0, 0, scale) + self.mymap.translate(offset_x, offset_y) + self.draw_image() # 画像を描画 + self.plot_origin() # 原点を示す円を描画 + self.master.title(Path(map_path).name + " - " + self.master.title()) + self.open_menu.entryconfigure("Map", state=tk.DISABLED) + self.open_menu.entryconfigure("Waypoints", state=tk.NORMAL) + self.message("Please open waypoints file ") + return + + + """ + +++++ File -> Open -> Waypionts +++++ + """ + def menu_open_waypoints(self): + filepath = tkinter.filedialog.askopenfilename( + parent=self.master, + title="Select map yaml file", + initialdir=str(Path(".")), + filetypes=[("YAML", ".yaml")] + ) + if not filepath: return + with open(filepath) as file: + wp_yaml = ruamel.yaml.YAML().load(file) + self.waypoints = WaypointList(wp_yaml) + self.finish_pose = FinishPose(wp_yaml) + self.waypoints_filepath = Path(filepath) + self.plot_waypoints() + self.master.title(Path(filepath).name + " - " + self.master.title()) + self.file_menu.entryconfigure("Save", state=tk.NORMAL) + self.file_menu.entryconfigure("Save As", state=tk.NORMAL) + self.popup_menu.entryconfigure("Add waypoint here", state=tk.NORMAL) + return + + + """ + +++++ File -> Save +++++ + """ + def menu_save(self, event=None): + self.save_waypoints(str(self.waypoints_filepath)) + self.message("Saved changes!") + return + + + """ + +++++ File -> Save As +++++ + """ + def menu_saveas(self, event=None): + new_filepath = tkinter.filedialog.asksaveasfilename( + parent=self.master, + title="Save As", + initialdir=str(Path('..','..','waypoint_nav','param')), + filetypes=[("YAML", ".yaml")], + defaultextension=".yaml" + ) + if len(new_filepath) == 0: return # cancel + self.save_waypoints(new_filepath) + current_title = self.master.title() + old_filename = self.waypoints_filepath.name + self.waypoints_filepath = Path(new_filepath) + self.master.title(current_title.replace(old_filename, self.waypoints_filepath.name)) + self.message("Save As" + "\"" + str(new_filepath) + "\"") + return + + + """ + +++++ File -> Exit +++++ + """ + def menu_exit(self, event=None): + self.master.destroy() + + + """ + +++++ 現在のウェイポイント情報を指定のファイルに書き込む +++++ + """ + def save_waypoints(self, path): + with open(path, 'w') as f: + f.write(get_waypoint_yaml(self.waypoints, self.finish_pose)) + return + + + + """ + ################################# + 原点とウェイポイントの表示 + ################################# + """ + """ + +++++ 地図上の原点に円を描画 +++++ + """ + def plot_origin(self): + x, y = self.mymap.transform(self.mymap.img_origin[0], self.mymap.img_origin[1]) + r = self.point_rad # 円の半径(ピクセル) + x0 = x - r + y0 = y - r + x1 = x + r + 1 + y1 = y + r + 1 + if self.canvas.find_withtag("origin"): + self.canvas.moveto("origin", x0, y0) + else: + self.canvas.create_oval(x0, y0, x1, y1, tags="origin", fill='cyan', outline='blue') + return + + + """ + +++++ 地図上にウェイポイントとフィニッシュポーズを描画 +++++ + """ + def plot_waypoints(self, id=None): + if not self.waypoints: return + # 引数にidが指定された場合、そのポイントのみを再描画して終了 + if id: + wp = self.waypoints.get_waypoint(id) + cx, cy = self.real2canvas(float(wp["x"]), float(wp["y"])) + x0 = cx - self.point_rad + y0 = cy - self.point_rad + self.canvas.moveto(id, round(x0), round(y0)) + return + + if len(self.waypoints.get_id_list()) == 0: + # 初めて描画する場合 + for n, wp in enumerate(self.waypoints.get_waypoint()): + id = self.create_waypoint(wp) + self.waypoints.set_id(num=n+1, id=id) + else: + # 既に描画されている場合 + for id in self.waypoints.get_id_list(): + wp = self.waypoints.get_waypoint(id) + cx, cy = self.real2canvas(float(wp["x"]), float(wp["y"])) + x0 = cx - self.point_rad + y0 = cy - self.point_rad + self.canvas.moveto(id, round(x0), round(y0)) + # Finish poseを描画 + cx, cy = self.real2canvas(self.finish_pose.x, self.finish_pose.y) + x0 = cx + y0 = cy + x1 = x0 + math.cos(self.finish_pose.yaw) * self.point_rad * 3 + y1 = y0 - math.sin(self.finish_pose.yaw) * self.point_rad * 3 + if self.finish_pose.id is not None: + # movetoだと上手くいかないので、毎回削除、再描画 + self.canvas.delete(self.finish_pose.id) + self.finish_pose.id = self.canvas.create_line(x0, y0, x1, y1, tags="finish_pose", + width=10, arrow=tk.LAST, arrowshape=(12,15,9), fill="#AAF" + ) + return + + + """ + +++++ キャンバスに新たなウェイポイントを描画する +++++ + """ + def create_waypoint(self, waypoint: dict): + cx, cy = self.real2canvas(float(waypoint["x"]), float(waypoint["y"])) + x0 = round(cx - self.point_rad) + y0 = round(cy - self.point_rad) + x1 = round(cx + self.point_rad + 1) + y1 = round(cy + self.point_rad + 1) + id = self.canvas.create_oval(x0, y0, x1, y1, fill='#FDD', outline='red', activefill='red') + self.canvas.tag_bind(id, "", lambda event, wp_id=id: self.waypoint_clicked(event, wp_id)) + self.canvas.tag_bind(id, "", lambda event, wp_id=id: self.waypoint_enter(event, wp_id)) + self.canvas.tag_bind(id, "", self.waypoint_leave) + self.canvas.tag_bind(id, "", self.waypoint_click_move) + return id + + + """ + +++++ ウェイポイントが左クリックされたときのコールバック +++++ + """ + def waypoint_clicked(self, event, wp_id): + if wp_id != self.editing_waypoint_id: # 編集中のウェイポイントを切り替え + self.canvas.itemconfig(self.editing_waypoint_id, fill='#FDD') + self.editing_waypoint_id = wp_id + self.canvas.itemconfig(wp_id, fill='red') + self.disp_waypoint_info(wp_id) + self.message("Show selected waypoint information") + return + + + """ + +++++ ウェイポイントを左クリックしながら動かしたときのコールバック +++++ + """ + def waypoint_click_move(self, event): + if not self.moving_waypoint: return + if self.old_click_point is None: + self.old_click_point = [event.x, event.y] + return + delta_x = event.x-self.old_click_point[0] + delta_y = event.y-self.old_click_point[1] + self.canvas.move(self.editing_waypoint_id, delta_x, delta_y) + box = self.canvas.bbox(self.editing_waypoint_id) + px = (box[2] + box[0]) / 2 # ウィンドウ上の座標 + py = (box[3] + box[1]) / 2 + img_x, img_y = self.mymap.inv_transform(px, py) + # マップ画像上の座標を、実際の座標に変換 + x, y = self.mymap.image2real(img_x, img_y) + # 編集中のウェイポイント情報を更新 + self.waypoints.set_waypoint_val(self.editing_waypoint_id, "x", x) + self.waypoints.set_waypoint_val(self.editing_waypoint_id, "y", y) + # 表示中のウェイポイント情報を更新 + txt_box = self.wp_info_win.grid_slaves(column=1, row=0)[0] + txt_box.delete(0, tk.END) + txt_box.insert(tk.END, x) + txt_box = self.wp_info_win.grid_slaves(column=1, row=1)[0] + txt_box.delete(0, tk.END) + txt_box.insert(tk.END, y) + self.old_click_point = [event.x, event.y] + return + + + """ + +++++ ウェイポイントを示す円にカーソルが入ったときと出たときのコールバック +++++ + """ + def waypoint_enter(self, event, wp_id): + wp_num = self.waypoints.get_num(wp_id) + self.waypoint_num["text"] = " Waypoint No. {} " .format(str(wp_num)) + + def waypoint_leave(self, event): + self.waypoint_num["text"] = " Waypoint No. ----- " + + + + """ + ###################################### + 別窓でのウェイポイントの情報表示 + ###################################### + """ + """ + +++++ ウェイポイントが左クリックされたとき、別窓で情報を表示する関数 +++++ + """ + def disp_waypoint_info(self, id): + point = self.waypoints.get_waypoint(id=id) + if (self.wp_info_win is None) or (not self.wp_info_win.winfo_exists()): + # ウィンドウが表示されてない場合、初期化 + self.wp_info_win = tk.Toplevel() + self.wp_info_win.lower() + self.wp_info_win.protocol("WM_DELETE_WINDOW", self.close_wp_info) + # ウェイポイントファイルのキーを取得し、ラベルとテキストボックスを配置 + for i, key in enumerate(point.keys()): + key_label = tk.Label(self.wp_info_win, text=key+":", width=6, font=("Consolas",15), anchor=tk.E) + key_label.grid(column=0, row=i, padx=2, pady=5) + txt_box = tk.Entry(self.wp_info_win, width=20, font=("Consolas", 15)) + txt_box.insert(tk.END, str(point[key]).lower()) + txt_box.grid(column=1, row=i, padx=2, pady=2, ipady=3, sticky=tk.EW) + # Apply, DnD(Drag & Drop), remove ボタン + canv = tk.Canvas(self.wp_info_win) + canv.grid(column=0, columnspan=2, row=self.wp_info_win.grid_size()[1], sticky=tk.EW) + apply_btn = tk.Button(canv, text="Apply", width=5, height=1, bg="#FDD", + command=self.apply_btn_callback) + apply_btn.pack(side=tk.RIGHT, anchor=tk.SE, padx=5, pady=5) + dnd_btn = tk.Button(canv, text="DnD", width=5, height=1, bg="#EEE") + dnd_btn["command"] = lambda obj=dnd_btn: self.dnd_btn_callback(dnd_btn) + dnd_btn.pack(side=tk.RIGHT, anchor=tk.SE, padx=5, pady=5) + remove_btn = tk.Button(canv, text="Remove", width=7, height=1, bg="#F00", + command=self.remove_btn_callback) + remove_btn.pack(side=tk.LEFT, anchor=tk.SE, padx=5, pady=5) + # 位置とサイズを設定 + self.wp_info_win.update() + w = self.wp_info_win.winfo_width() + h = self.wp_info_win.winfo_height() + x = self.master.winfo_x() + self.canv_w - w + y = self.master.winfo_y() + self.canv_h - h + geometry = "{}x{}+{}+{}".format(w, h, x, y) + self.wp_info_win.geometry(geometry) + self.wp_info_win.lift() + self.wp_info_win.attributes('-topmost', True) # サブウィンドウを最前面で固定 + else: + # 既にウィンドウが表示されている場合、テキストボックスの中身を変える + for i, key in enumerate(point): + txt_box = self.wp_info_win.grid_slaves(column=1, row=i)[0] + txt_box.delete(0, tk.END) + txt_box.insert(tk.END, str(point[key]).lower()) + self.wp_info_win.title("Waypoint " + str(self.waypoints.get_num(id))) # タイトルを設定 + return + + + """ + +++++ Applyボタンを押したときのコールバック +++++ + """ + def apply_btn_callback(self): + point = self.waypoints.get_waypoint(id=self.editing_waypoint_id) + for i, key in enumerate(point.keys()): + txt_box = self.wp_info_win.grid_slaves(column=1, row=i)[0] + self.waypoints.set_waypoint_val(self.editing_waypoint_id, key, txt_box.get()) + self.plot_waypoints(id=self.editing_waypoint_id) + self.message("Apply changes of waypoint parameters") + return + + + """ + +++++ ドラッグ&ドロップボタン(DnD)を押したときのコールバック +++++ + """ + def dnd_btn_callback(self, obj=None): + if obj is None: return + btn = obj + # 押された状態とそうでない状態を切り替える + if btn["relief"] == tk.RAISED: + btn["relief"] = tk.SUNKEN + btn["bg"] = "#AAA" + self.moving_waypoint = True + self.message("Drag & Drop to move waypoint") + elif btn["relief"] == tk.SUNKEN: + btn["relief"] = tk.RAISED + btn["bg"] = "#EEE" + self.moving_waypoint = False + self.message("Show selected waypoint information") + return + + + """ + +++++ removeボタンを押したときのコールバック +++++ + """ + def remove_btn_callback(self): + self.waypoints.remove(self.editing_waypoint_id) + self.canvas.delete(self.editing_waypoint_id) # ウェイポイントを示す円を削除 + self.close_wp_info() + self.message("Removed waypoint") + return + + + """ + +++++ ウェイポイント情報を表示するサブウィンドウを閉じたときのコールバック +++++ + """ + def close_wp_info(self): + self.canvas.itemconfig(self.editing_waypoint_id, fill='#FDD') + self.editing_waypoint_id = None + self.wp_info_win.destroy() + return + + + + """ + ########################### + ウェイポイントの追加 + ########################### + """ + """ + +++++ 右クリックしてポップアップメニューのadd waypoint hereをクリックしたときのコールバック関数 +++++ + """ + def add_waypoint_here(self): + if (self.wp_info_win is not None) and (self.wp_info_win.winfo_exists()): + self.close_wp_info() + img_xy = self.right_click_coord + if self.mymap.pil_img.getpixel((img_xy[0], img_xy[1]))[0] == 0: + self.message("There is obstacles") + return + # 何番目のウェイポイントの次に追加するか入力させる + add_wp_win = tk.Toplevel() + add_wp_win.title("Add waypoint") + add_wp_win.protocol("WM_DELETE_WINDOW") + add_wp_win.attributes('-topmost', True) # サブウィンドウを最前面で固定 + msg = tk.Label(add_wp_win, text="Add waypoint after no. ", font=("Consolas",15), anchor=tk.E) + msg.grid(column=0, row=0, padx=10, pady=10, sticky=tk.EW) + txt_box = tk.Entry(add_wp_win, width=4, font=("Consolas",15)) + txt_box.grid(column=1, row=0, pady=10, sticky=tk.W) + # Add ボタン + add_btn = tk.Button(add_wp_win, text="Add", width=5, height=1, + command=lambda num_box=txt_box, win=add_wp_win: self.add_btn_callback(num_box, win) + ) + add_btn.grid(column=0, columnspan=2, row=1, padx=10, pady=10) + add_wp_win.update() + w = add_wp_win.winfo_width() + 10 + h = add_wp_win.winfo_height() + x = int((self.canv_w - w) / 2) + y = int((self.canv_h - h) / 2) + geometry = "{}x{}+{}+{}".format(w, h, x, y) + add_wp_win.geometry(geometry) + self.message("Add waypoint") + return + + + """ + +++++ add waypoint hereをクリックして開いた別窓のAddボタンのコールバック +++++ + """ + def add_btn_callback(self, num_box: tk.Entry, win: tk.Toplevel): + prev_num = num_box.get() + if (prev_num == ""): + self.message("Please enter number") + return + win.destroy() + prev_num = int(prev_num) + img_xy = self.right_click_coord + # ウェイポイント座標を計算 + x, y = self.mymap.image2real(img_xy[0], img_xy[1]) + # ウェイポイントを追加 + point = {} + for key in self.waypoints.point_keys: + if (key=="x"): point[key] = x + elif (key=="y"): point[key] = y + elif (key=="z"): point[key] = 0.0 + else: point[key] = "" + id = self.create_waypoint(point) + self.waypoints.insert(prev_num+1, point, id=id) + self.plot_waypoints(id=id) + self.editing_waypoint_id = id + self.canvas.itemconfig(id, fill='red') + self.disp_waypoint_info(id) + return + + + + """ + ############################### + イベントコールバック関数 + ############################### + """ + """ + +++++ キャンバス内でマウスを動かしたとき +++++ + """ + def mouse_move(self, event): + if not self.mymap: return + img_x, img_y = self.mymap.inv_transform(event.x, event.y) + if (img_x < 0) or (img_y < 0) or (img_x > self.mymap.width()) or (img_y > self.mymap.height()): + self.mouse_position["text"] = " Out of map " + return + x, y = self.mymap.image2real(img_x, img_y) + self.mouse_position["text"] = " ( x, y ) = ( {}, {} ) ".format(x, y) + return + + + """ + +++++ マウスホイールを回転したとき(タッチパッドをドラッグしたとき) +++++ + """ + def mouse_wheel(self, event): + if not self.mymap: return + if event.delta > 0: + # 上に回転(タッチパッドなら下にドラッグ)=> 拡大 + self.mymap.scale_at(event.x, event.y, 1.1) + else: + # 下に回転(タッチパッドなら上にドラッグ)=> 縮小 + self.mymap.scale_at(event.x, event.y, 0.9) + self.draw_image() + self.plot_origin() + self.plot_waypoints() + return + + + """ + +++++ 左クリックされたとき +++++ + """ + def left_click(self, event): + self.popup_menu.unpost() # 右クリックで出るポップアップメニューを非表示 + return + + + """ + +++++ マウスを左クリックしながらドラッグしたとき +++++ + """ + def left_click_move(self, event): + if not self.mymap: return + if self.moving_waypoint: return + if self.old_click_point is None: + self.old_click_point = [event.x, event.y] + return + # カーソルの移動量を計算 + delta_x = event.x - self.old_click_point[0] + delta_y = event.y - self.old_click_point[1] + # ウェイポイント移動モードでないとき、地図を平行移動 + self.mymap.translate(delta_x, delta_y) + self.draw_image() + # origin, waypoints finish_pose を平行移動 + self.canvas.move("origin", delta_x, delta_y) + if self.waypoints: + for id in self.waypoints.get_id_list(): + self.canvas.move(id, delta_x, delta_y) + self.canvas.move("finish_pose", delta_x, delta_y) + self.old_click_point = [event.x, event.y] + return + + + """ + +++++ マウスの左クリックを離したとき +++++ + """ + def left_click_release(self, event): + self.old_click_point = None + return + + + """ + +++++ 右クリックしたとき +++++ + """ + def right_click(self, event): + if not self.mymap: return + # クリックした座標の近くにあるオブジェクトを取得 + clicked_obj = self.canvas.find_enclosed(event.x-20, event.y-20, event.x+20, event.y+20) + if clicked_obj: # 何かオブジェクトがクリックされていた場合 + return + # クリックされた座標 => 元画像の座標 の変換 + img_x, img_y = self.mymap.inv_transform(event.x, event.y) + # 変換後の元画像の座標がサイズから外れている場合(地図画像の外をクリックしている) + if (img_x < 0) or (img_y < 0) or (img_x > self.mymap.width()) or (img_y > self.mymap.height()): + return + self.popup_menu.post(event.x_root, event.y_root) # メニューをポップアップ + self.right_click_coord = [img_x, img_y] # クリックされた元画像上の座標を変数に格納 + return + + + """ + +++++ Ctrl押しながら左クリックしたとき +++++ + """ + def ctrl_left_click(self, event): + if not self.mymap: return + self.mymap.scale_at(event.x, event.y, 1.2) + self.draw_image() + self.plot_origin() + self.plot_waypoints() + self.message("Zoom In") + return + + + """ + +++++ Ctrl押しながら右クリックしたとき +++++ + """ + def ctrl_right_click(self, event): + if not self.mymap: return + self.mymap.scale_at(event.x, event.y, 0.8) + self.draw_image() + self.plot_origin() + self.plot_waypoints() + self.message("Zoom Out") + return + + + """ + +++++ ウィンドウサイズが変更されたとき、情報を更新する +++++ + """ + def window_resize_callback(self, event): + cw = self.canvas.winfo_width() + ch = self.canvas.winfo_height() + if (self.canv_w != cw) or (self.canv_h != ch): + self.canv_w = cw + self.canv_h = ch + self.draw_image() + return + + + + """ + ############################################## + 地図画像の表示、メッセージ表示、座標変換 + ############################################## + """ + """ + +++++ 元画像をaffne変換して描画 +++++ + """ + def draw_image(self): + if not self.mymap: return + if not self.canvas.find_withtag("map_image"): # 初めて画像を描画するとき + self.canvas.create_image(0, 0, anchor='nw', tags="map_image", + image=self.mymap.get_draw_image((self.canv_w, self.canv_h)) + ) + else: + # 既に描画された画像を差し替える + self.canvas.itemconfig("map_image", image=self.mymap.get_draw_image((self.canv_w, self.canv_h))) + return + + + """ + +++++ 画面上部にメッセージを表示する +++++ + """ + def message(self, msg): + if not isinstance(msg, str): + msg = str(msg) + self.msg_label["text"] = str(msg) + + + """ + +++++ 実際の座標をキャンバス上の座標に変換 +++++ + """ + def real2canvas(self, x, y): + img_x, img_y = self.mymap.real2image(x,y) + real_x, real_y = self.mymap.transform(img_x, img_y) + return real_x, real_y + + + + + +if __name__ == "__main__": + root = tk.Tk() # 大元になるウィンドウ + w, h = root.winfo_screenwidth()-10, root.winfo_screenheight()-100 + root.geometry("%dx%d+0+0" % (w, h)) + app = Application(master=root) # tk.Frameを継承したApplicationクラスのインスタンス + app.mainloop() diff --git a/src/waypoint_navigation/waypoint_nav/CMakeLists.txt b/src/waypoint_navigation/waypoint_nav/CMakeLists.txt new file mode 100644 index 0000000..b4c1003 --- /dev/null +++ b/src/waypoint_navigation/waypoint_nav/CMakeLists.txt @@ -0,0 +1,61 @@ +cmake_minimum_required(VERSION 3.0.2) +project(waypoint_nav) + +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED + move_base_msgs + geometry_msgs + move_base + roscpp + actionlib_msgs + actionlib + tf + std_srvs + dynamic_reconfigure + base_local_planner + dwa_local_planner + std_msgs +) + + + +find_package(PkgConfig) +pkg_search_module(yaml-cpp REQUIRED yaml-cpp) +pkg_search_module(waypoint_saver REQUIRED waypoint_saver) + +if(NOT ${yaml-cpp_VERSION} VERSION_LESS "0.5") +add_definitions(-DNEW_YAMLCPP) +endif() + +catkin_package( + INCLUDE_DIRS include + LIBRARIES ${PROJECT_NAME} + DEPENDS waypoint_saver +) + +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${yaml-cpp_INCLUDE_DIRS} + ${waypoint_saver_INCLUDE_DIRS} + ../waypoint_saver/include +) + +add_executable(waypoint_nav src/waypoint_nav.cpp) + +target_link_libraries(waypoint_nav + ${catkin_LIBRARIES} + ${yaml-cpp_LIBRARIES} +) + +add_executable(velocity_controller src/velocity_controller.cpp) + +target_link_libraries(velocity_controller + ${catkin_LIBRARIES} +) + diff --git a/src/waypoint_navigation/waypoint_nav/include/waypoint_nav.h b/src/waypoint_navigation/waypoint_nav/include/waypoint_nav.h new file mode 100644 index 0000000..de4896e --- /dev/null +++ b/src/waypoint_navigation/waypoint_nav/include/waypoint_nav.h @@ -0,0 +1,34 @@ +// #include +// #include // include Waypoint class +// #include + + +// class WaypointArray : public geometry_msgs::PoseArray { +// /* +// std_msgs/Header header +// geometry_msgs/Pose[] poses +// */ +// public: +// std::vector waypoint_list; + + +// void add_waypoint(double x, double y, double z, float vel, float rad) +// { +// Waypoint point; +// point.set_x(x); +// point.set_y(y); +// point.set_z(z); +// point.set_vel(vel); +// point.set_rad(rad); +// waypoint_list.push_back(point); +// } + + +// geometry_msgs::PoseArray get_posearray_msg() +// { +// geometry_msgs::PoseArray posearray; +// posearray.header = header; +// posearray.poses = poses; +// return posearray; +// } +// }; \ No newline at end of file diff --git a/src/waypoint_navigation/waypoint_nav/launch/waypoint_nav.launch b/src/waypoint_navigation/waypoint_nav/launch/waypoint_nav.launch new file mode 100644 index 0000000..eaa8101 --- /dev/null +++ b/src/waypoint_navigation/waypoint_nav/launch/waypoint_nav.launch @@ -0,0 +1,22 @@ + + + + + + + + + + +
+ + + + + + + diff --git a/src/waypoint_navigation/waypoint_nav/maps/map.pgm b/src/waypoint_navigation/waypoint_nav/maps/map.pgm new file mode 100644 index 0000000..10700a1 --- /dev/null +++ b/src/waypoint_navigation/waypoint_nav/maps/map.pgm Binary files differ diff --git a/src/waypoint_navigation/waypoint_nav/maps/map.yaml b/src/waypoint_navigation/waypoint_nav/maps/map.yaml new file mode 100644 index 0000000..8cf0bd4 --- /dev/null +++ b/src/waypoint_navigation/waypoint_nav/maps/map.yaml @@ -0,0 +1,7 @@ +image: ./map.pgm +resolution: 0.050000 +origin: [-10.000000, -10.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/waypoint_navigation/waypoint_nav/maps/map_gakunai.pgm b/src/waypoint_navigation/waypoint_nav/maps/map_gakunai.pgm new file mode 100644 index 0000000..8a70604 --- /dev/null +++ b/src/waypoint_navigation/waypoint_nav/maps/map_gakunai.pgm Binary files differ diff --git a/src/waypoint_navigation/waypoint_nav/maps/map_gakunai.yaml b/src/waypoint_navigation/waypoint_nav/maps/map_gakunai.yaml new file mode 100644 index 0000000..27872d5 --- /dev/null +++ b/src/waypoint_navigation/waypoint_nav/maps/map_gakunai.yaml @@ -0,0 +1,7 @@ +image: map_gakunai.pgm +resolution: 0.050000 +origin: [-100.000000, -100.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/waypoint_navigation/waypoint_nav/package.xml b/src/waypoint_navigation/waypoint_nav/package.xml new file mode 100644 index 0000000..b993d36 --- /dev/null +++ b/src/waypoint_navigation/waypoint_nav/package.xml @@ -0,0 +1,56 @@ + + + waypoint_nav + 0.0.0 + The waypoint_nav package + + + + + ubuntu + + + + + + TODO + + + catkin + + move_base + yaml-cpp + move_base_msgs + geometry_msgs + roscpp + actionlib_msgs + actionlib + tf + std_srvs + dynamic_reconfigure + base_local_planner + dwa_local_planner + waypoint_saver + std_msgs + + move_base + yaml-cpp + move_base_msgs + geometry_msgs + roscpp + actionlib_msgs + actionlib + tf + dynamic_reconfigure + base_local_planner + dwa_local_planner + waypoint_saver + std_msgs + + + + + + + + diff --git a/src/waypoint_navigation/waypoint_nav/rviz_cfg/nav.rviz b/src/waypoint_navigation/waypoint_nav/rviz_cfg/nav.rviz new file mode 100644 index 0000000..e0e7674 --- /dev/null +++ b/src/waypoint_navigation/waypoint_nav/rviz_cfg/nav.rviz @@ -0,0 +1,368 @@ +Panels: + - Class: rviz/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: ~ + Splitter Ratio: 0.5 + Tree Height: 636 + - 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: "" + - Class: orne_rviz_plugins/StateTriggerPanel + Name: StateTriggerPanel +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: /map + Unreliable: false + Use Timestamp: false + 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 + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + hokuyo_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + imu_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + left_caster_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + left_wheel: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + right_caster_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + right_wheel: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + velodyne_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 0; 255; 0 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 170; 0; 0 + Min Color: 0; 85; 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 5 + Size (m): 0.10000000149011612 + Style: Points + Topic: /scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.30000001192092896 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: Particles + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Arrow (Flat) + Topic: /particlecloud + Unreliable: false + Value: true + - Alpha: 1 + Class: rviz/Polygon + Color: 25; 255; 0 + Enabled: true + Name: Footprint + Queue Size: 10 + Topic: /move_base/global_costmap/obstacle_layer_footprint/footprint_stamped + Unreliable: false + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 25; 255; 0 + Enabled: true + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.30000001192092896 + Line Style: Lines + Line Width: 0.029999999329447746 + Name: Global Plan + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Queue Size: 10 + Radius: 0.029999999329447746 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: /move_base/NavfnROS/plan + Unreliable: false + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 255; 255; 0 + Enabled: true + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.30000001192092896 + Line Style: Billboards + Line Width: 0.10000000149011612 + Name: Local Plan + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Queue Size: 10 + Radius: 0.029999999329447746 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: /move_base/TrajectoryPlannerROS/local_plan + Unreliable: false + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: costmap + Draw Behind: true + Enabled: true + Name: GlobalCostmap + Topic: /move_base/global_costmap/costmap + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: costmap + Draw Behind: false + Enabled: true + Name: LocalCostmap + Topic: /move_base/local_costmap/costmap + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.30000001192092896 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 0; 0; 127 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: Waypoints + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Arrow (Flat) + Topic: /waypoints + Unreliable: false + Value: true + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Class: rviz/Pose + Color: 0; 0; 127 + Enabled: false + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Name: Pose + Queue Size: 10 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Shape: Arrow + Topic: /move_base_simple/goal + Unreliable: false + Value: false + - Alpha: 1 + Class: rviz/PointStamped + Color: 204; 41; 204 + Enabled: false + History Length: 10 + Name: PointStamped + Queue Size: 10 + Radius: 0.20000000298023224 + Topic: /target_point + Unreliable: false + Value: false + - Alpha: 1 + Class: rviz/PointStamped + Color: 239; 41; 41 + Enabled: false + History Length: 1 + Name: PointStamped + Queue Size: 10 + Radius: 0.4000000059604645 + Topic: /filtered_target_point + Unreliable: false + Value: false + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: map + Frame Rate: 10 + 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/ThirdPersonFollower + Distance: 35.39775466918945 + 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.3276565670967102 + Y: -0.7599051594734192 + Z: 0 + Focal Shape Fixed Size: false + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 1.339796543121338 + Target Frame: base_link + Yaw: 3.1153953075408936 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 897 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd00000004000000000000019300000326fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005d00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003e000002b9000000cb00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000002200530074006100740065005400720069006700670065007200500061006e0065006c01000002fd000000670000004100ffffff000000010000010f000002b3fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003e000002b3000000a500fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005e00000003bfc0100000002fb0000000800540069006d00650000000000000005e00000039300fffffffb0000000800540069006d006501000000000000045000000000000000000000035c0000032600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + StateTriggerPanel: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1269 + X: 564 + Y: -20 diff --git a/src/waypoint_navigation/waypoint_nav/src/velocity_controller.cpp b/src/waypoint_navigation/waypoint_nav/src/velocity_controller.cpp new file mode 100644 index 0000000..d064beb --- /dev/null +++ b/src/waypoint_navigation/waypoint_nav/src/velocity_controller.cpp @@ -0,0 +1,81 @@ +#include +#include +#include +#include +#include + +#include + + +class VelocityController { +public: + VelocityController() : + move_base_action_("move_base", true), + standard_vel_(1.0), + current_max_vel_(1.0), + min_vel_(0.0) + { + while((move_base_action_.waitForServer(ros::Duration(1.0)) == false) && (ros::ok() == true)) { + ROS_INFO("Waiting..."); + } + + ros::NodeHandle nh; + max_vel_sub_ = nh.subscribe("/max_vel", 1, &VelocityController::maxVelCallback, this); + cmd_vel_sub_ = nh.subscribe("/cmd_vel_in", 10, &VelocityController::cmdVelCallback, this); + cmd_vel_pub_ = nh.advertise("/cmd_vel_out", 10); + + std::string planner = "base_local_planner/TrajectoryPlannerROS"; + std::string param_max = "/move_base/TrajectoryPlannerROS/max_vel_x"; + std::string param_min = "/move_base/TrajectoryPlannerROS/min_vel_x"; + nh.param("/move_base/base_local_planner", planner, planner); + if (planner == "dwa_local_planner/DWAPlannerROS") { + param_max = "/move_base/DWAPlannerROS/max_vel_trans"; + param_min = "/move_base/DWAPlannerROS/min_vel_trans"; + } + nh.param(param_max, standard_vel_, standard_vel_); + nh.param(param_min, min_vel_, min_vel_); + ROS_INFO_STREAM("Standard max vel: " << standard_vel_); + } + + + + void maxVelCallback(const std_msgs::Float32 &msg) + { + current_max_vel_ = standard_vel_ * msg.data; + current_max_vel_ = std::max(current_max_vel_, min_vel_); + ROS_INFO_STREAM("Set max vel: " << current_max_vel_); + } + + + + void cmdVelCallback(const geometry_msgs::Twist &msg) + { + pub_msg_.linear.x = std::min(float(msg.linear.x), current_max_vel_); + pub_msg_.angular = msg.angular; + cmd_vel_pub_.publish(pub_msg_); + } + + + +private: + actionlib::SimpleActionClient move_base_action_; + ros::Subscriber max_vel_sub_; + ros::Subscriber cmd_vel_sub_; + ros::Publisher cmd_vel_pub_; + float standard_vel_, current_max_vel_, min_vel_; + geometry_msgs::Twist pub_msg_; +}; + + + + + + + +int main(int argc, char *argv[]) { + ros::init(argc, argv, "velocity_controller"); + VelocityController vc; + + ros::spin(); + return 0; +} \ No newline at end of file diff --git a/src/waypoint_navigation/waypoint_nav/src/waypoint_nav.cpp b/src/waypoint_navigation/waypoint_nav/src/waypoint_nav.cpp new file mode 100644 index 0000000..d251054 --- /dev/null +++ b/src/waypoint_navigation/waypoint_nav/src/waypoint_nav.cpp @@ -0,0 +1,471 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +// #include +// #include +// #include + +#include +#include // include Waypoint class + +#include +#include +#include +#include +#include + +#ifdef NEW_YAMLCPP +template +void operator >> (const YAML::Node& node, T& i) +{ + i = node.as(); +} +#endif + + +class SwitchRunningStatus : public std::exception { +public: + SwitchRunningStatus() : std::exception() { } +}; + + + +class WaypointsNavigation{ +public: + /* + ++++++++++ Constructer ++++++++++ + */ + WaypointsNavigation() : + has_activate_(false), + move_base_action_("move_base", true), + rate_(10), + last_moved_time_(0), + dist_err_(1.0) + { + while((move_base_action_.waitForServer(ros::Duration(1.0)) == false) && (ros::ok() == true)) + { + ROS_INFO("Waiting..."); + } + ros::NodeHandle private_nh("~"); + private_nh.param("robot_frame", robot_frame_, std::string("base_link")); + private_nh.param("world_frame", world_frame_, std::string("map")); + + double max_update_rate; + private_nh.param("max_update_rate", max_update_rate, 10.0); + rate_ = ros::Rate(max_update_rate); + std::string filename = ""; + private_nh.param("filename", filename, filename); + if (filename != "") { + ROS_INFO_STREAM("Read waypoints data from " << filename); + if (!readFile(filename)) { + ROS_ERROR("Failed loading waypoints file"); + } else { + finish_pose_ = waypoints_.poses.end()-1; + computeWpOrientation(); + } + current_waypoint_ = waypoints_.poses.begin(); + wp_num_.data = 1; + } else { + ROS_ERROR("waypoints file doesn't have name"); + } + + ros::NodeHandle nh; + start_server_ = nh.advertiseService("start_wp_nav", &WaypointsNavigation::startNavigationCallback, this); + stop_server_ = nh.advertiseService("stop_wp_nav", &WaypointsNavigation::stopNavigationCallback, this); + resume_server_ = nh.advertiseService("resume_nav", &WaypointsNavigation::resumeNavigationCallback, this); + cmd_vel_sub_ = nh.subscribe("cmd_vel", 1, &WaypointsNavigation::cmdVelCallback, this); + wp_pub_ = nh.advertise("waypoints", 10); + max_vel_pub_ = nh.advertise("max_vel", 5); + wp_num_pub_ = nh.advertise("waypoint_number", 5); + clear_costmaps_srv_ = nh.serviceClient("/move_base/clear_costmaps"); + } + + + + /* + ++++++++++ Read waypoints file ++++++++++ + */ + bool readFile(const std::string &filename) + { + waypoints_.poses.clear(); + try { + std::ifstream ifs(filename.c_str(), std::ifstream::in); + if (ifs.good() == false) return false; + + YAML::Node node; + #ifdef NEW_YAMLCPP + node = YAML::Load(ifs); + #else + YAML::Parser parser(ifs); + parser.GetNextDocument(node); + #endif + + // Read waypoints from yaml file + #ifdef NEW_YAMLCPP + const YAML::Node &wp_node_tmp = node["waypoints"]; + const YAML::Node *wp_node = wp_node_tmp ? &wp_node_tmp : NULL; + #else + const YAML::Node *wp_node = node.FindValue("waypoints"); + #endif + geometry_msgs::Pose pose; + Waypoint point; + if (wp_node != NULL) { + for(int i=0; i < wp_node->size(); i++) { + (*wp_node)[i]["point"]["x"] >> pose.position.x; + (*wp_node)[i]["point"]["y"] >> pose.position.y; + (*wp_node)[i]["point"]["z"] >> pose.position.z; + waypoints_.poses.push_back(pose); + point.x = pose.position.x; + point.y = pose.position.y; + point.z = pose.position.z; + (*wp_node)[i]["point"]["vel"] >> point.vel; + (*wp_node)[i]["point"]["rad"] >> point.rad; + (*wp_node)[i]["point"]["stop"] >> point.stop; + waypoint_list_.push_back(point); + } + } else { + return false; + } + + // Read finish_pose + #ifdef NEW_YAMLCPP + const YAML::Node &fp_node_tmp = node["finish_pose"]; + const YAML::Node *fp_node = fp_node_tmp ? &fp_node_tmp : NULL; + #else + const YAML::Node *fp_node = node.FindValue("finish_pose"); + #endif + if (fp_node != NULL) { + (*fp_node)["pose"]["position"]["x"] >> pose.position.x; + (*fp_node)["pose"]["position"]["y"] >> pose.position.y; + (*fp_node)["pose"]["position"]["z"] >> pose.position.z; + (*fp_node)["pose"]["orientation"]["x"] >> pose.orientation.x; + (*fp_node)["pose"]["orientation"]["y"] >> pose.orientation.y; + (*fp_node)["pose"]["orientation"]["z"] >> pose.orientation.z; + (*fp_node)["pose"]["orientation"]["w"] >> pose.orientation.w; + waypoints_.poses.push_back(pose); + point.x = pose.position.x; + point.y = pose.position.y; + point.z = pose.position.z; + waypoint_list_.push_back(point); + } else { + return false; + } + + } catch(YAML::ParserException &e) { + return false; + + } catch(YAML::RepresentationException &e) { + return false; + } + + return true; + } + + + + /* + ++++++++++ Compute target orientation for each waypoint ++++++++++ + */ + void computeWpOrientation() + { + for(std::vector::iterator it = waypoints_.poses.begin(); it != finish_pose_; it++) { + double goal_direction = atan2((it+1)->position.y - (it)->position.y, + (it+1)->position.x - (it)->position.x); + (it)->orientation = tf::createQuaternionMsgFromYaw(goal_direction); + } + waypoints_.header.frame_id = world_frame_; + } + + + + /* + ++++++++++ Callback function for "StartWaypointsNavigation" button on rviz ++++++++++ + */ + bool startNavigationCallback(std_srvs::Trigger::Request &request, std_srvs::Trigger::Response &response) + { + if ((has_activate_) || (current_waypoint_ != waypoints_.poses.begin())) { + ROS_WARN("Waypoint navigation is already started"); + response.success = false; + return false; + } + std_srvs::Empty empty; + while(!clear_costmaps_srv_.call(empty)) { + ROS_WARN("Resend clear costmap service"); + sleep(); + } + current_waypoint_ = waypoints_.poses.begin(); + wp_num_.data = 1; + has_activate_ = true; + response.success = true; + return true; + } + + + + /* + ++++++++++ Callback function for "ResumeWaypointsNavigation" button on rviz ++++++++++ + */ + bool resumeNavigationCallback(std_srvs::Trigger::Request &request, std_srvs::Trigger::Response &response) + { + if (has_activate_) { + ROS_WARN("Navigation is already active"); + response.success = false; + } else { + ROS_INFO("Navigation has resumed"); + has_activate_ = true; + response.success = true; + } + return true; + } + + + + /* + ++++++++++ Callback function for service of "stop_wp_nav" ++++++++++ + */ + bool stopNavigationCallback(std_srvs::Trigger::Request &request, std_srvs::Trigger::Response &response) + { + if (has_activate_) { + ROS_INFO("Waypoint navigation has been stopped"); + has_activate_ = false; + response.success = true; + } else { + ROS_WARN("Waypoint navigation is already stopped"); + response.success = false; + } + return true; + } + + + + /* + ++++++++++ Callback function for cmd_vel topic ++++++++++ + */ + void cmdVelCallback(const geometry_msgs::Twist &msg) + { + if (has_activate_ && + msg.linear.x > -0.001 && msg.linear.x < 0.001 && + msg.linear.y > -0.001 && msg.linear.y < 0.001 && + msg.linear.z > -0.001 && msg.linear.z < 0.001 && + msg.angular.x > -0.001 && msg.angular.x < 0.001 && + msg.angular.y > -0.001 && msg.angular.y < 0.001 && + msg.angular.z > -0.001 && msg.angular.z < 0.001) + { + // ROS_INFO("command velocity all zero"); + } else { + last_moved_time_ = ros::Time::now().toSec(); + } + } + + + + /* + ++++++++++ Check if robot reached the goal sent to move_base ++++++++++ + */ + bool navigationFinished() + { + return move_base_action_.getState() == actionlib::SimpleClientGoalState::SUCCEEDED; + } + + + + /* + ++++++++++ Check if robot reached current waypoint ++++++++++ + */ + bool onNavigationPoint(const geometry_msgs::Point &dest, double dist_err = 0.8) + { + if (waypoint_list_[wp_num_.data-1].stop) { + return navigationFinished(); + } + tf::StampedTransform robot_gl = getRobotPosGL(); + const double wx = dest.x; + const double wy = dest.y; + const double rx = robot_gl.getOrigin().x(); + const double ry = robot_gl.getOrigin().y(); + const double dist = std::sqrt(std::pow(wx - rx, 2) + std::pow(wy - ry, 2)); + return dist < dist_err; + } + + + + /* + ++++++++++ Get gloabl position of robot ++++++++++ + */ + tf::StampedTransform getRobotPosGL() + { + tf::StampedTransform robot_gl; + try { + tf_listener_.lookupTransform(world_frame_, robot_frame_, ros::Time(0.0), robot_gl); + } catch(tf::TransformException &e) { + ROS_WARN_STREAM("tf::TransformException: " << e.what()); + } + return robot_gl; + } + + + + /* + ++++++++++ Sleep function used in main loop function ++++++++++ + */ + void sleep() + { + rate_.sleep(); + ros::spinOnce(); + publishPoseArray(); + } + + + + /* + ++++++++++ Publish waypoints to be displayed as arrows on rviz ++++++++++ + */ + void publishPoseArray() + { + waypoints_.header.stamp = ros::Time::now(); + wp_pub_.publish(waypoints_); + } + + + + /* + ++++++++++ Send goal to move_base ++++++++++ + */ + void startNavigationGL(const geometry_msgs::Pose &dest) + { + setMaxVel(); + move_base_msgs::MoveBaseGoal move_base_goal; + move_base_goal.target_pose.header.stamp = ros::Time::now(); + move_base_goal.target_pose.header.frame_id = world_frame_; + move_base_goal.target_pose.pose.position = dest.position; + move_base_goal.target_pose.pose.orientation = dest.orientation; + move_base_action_.sendGoal(move_base_goal); + } + + + + /* + ++++++++++ Publish ratio to maximum speed ++++++++++ + */ + void setMaxVel() + { + float max_vel_rate = waypoint_list_[wp_num_.data-1].vel; + max_vel_msg_.data = max_vel_rate; + max_vel_pub_.publish(max_vel_msg_); + } + + + + /* + ++++++++++ Main loop function ++++++++++ + */ + void run() + { + while(ros::ok()) { + // has_activate_ is false, nothing to do + if (!has_activate_) { + sleep(); + continue; + } + // go to fianal goal and finish process + if (current_waypoint_ == finish_pose_) { + ROS_INFO_STREAM("Go to final goal"); + startNavigationGL(*current_waypoint_); + while(!navigationFinished() && ros::ok()) sleep(); + ROS_INFO("Final goal reached!!"); + has_activate_ = false; + continue; + } + // go to current waypoint + ROS_INFO_STREAM("Go to waypoint " << wp_num_.data); + ROS_INFO_STREAM("x: " << waypoint_list_[wp_num_.data-1].x << ", y: " << waypoint_list_[wp_num_.data-1].y); + startNavigationGL(*current_waypoint_); + int resend_goal = 0; + double start_nav_time = ros::Time::now().toSec(); + dist_err_ = waypoint_list_[wp_num_.data-1].rad; + try { + // loop until reach waypoint + while(!onNavigationPoint(current_waypoint_->position, dist_err_)) { + if (!has_activate_) { + throw SwitchRunningStatus(); + } + double time = ros::Time::now().toSec(); + if (time - start_nav_time > 10.0 && time - last_moved_time_ > 10.0) { + ROS_WARN("Resend the navigation goal."); + std_srvs::Empty empty; + clear_costmaps_srv_.call(empty); + startNavigationGL(*current_waypoint_); + resend_goal++; + if (resend_goal == 3) { + ROS_WARN("Skip waypoint."); + current_waypoint_++; + wp_num_.data++; + startNavigationGL(*current_waypoint_); + } + start_nav_time = time; + } + wp_num_pub_.publish(wp_num_); + sleep(); + } + // if current waypoint is stop point + if (waypoint_list_[wp_num_.data-1].stop) { + has_activate_ = false; + move_base_action_.cancelAllGoals(); + ROS_INFO("Waiting for navigation to resume..."); + } + // update current waypoint + current_waypoint_++; + wp_num_.data++; + + } catch(const SwitchRunningStatus &e) { + ROS_INFO_STREAM("Running status switched"); + } + sleep(); + } + } + + + + +private: + actionlib::SimpleActionClient move_base_action_; + geometry_msgs::PoseArray waypoints_; + visualization_msgs::MarkerArray marker_; + std::vector waypoint_list_; + std::vector::iterator current_waypoint_; + std::vector::iterator finish_pose_; + bool has_activate_; + std::string robot_frame_, world_frame_; + tf::TransformListener tf_listener_; + ros::Rate rate_; + ros::ServiceServer start_server_, stop_server_, resume_server_; + ros::Subscriber cmd_vel_sub_; + ros::Publisher wp_pub_, max_vel_pub_, wp_num_pub_; + ros::ServiceClient clear_costmaps_srv_; + double last_moved_time_, dist_err_; + std_msgs::UInt16 wp_num_; + std_msgs::Float32 max_vel_msg_; +}; + + + + + + +int main(int argc, char *argv[]) { + ros::init(argc, argv, ROS_PACKAGE_NAME); + WaypointsNavigation w_nav; + w_nav.run(); + + return 0; +} diff --git a/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints.yaml b/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints.yaml new file mode 100644 index 0000000..92f70d6 --- /dev/null +++ b/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints.yaml @@ -0,0 +1,10 @@ +waypoints: +- point: {x: -0.45, y: -0.499032, z: 0.0, vel: 1.0, rad: 0.3, stop: false} +- point: {x: 0.50, y: -0.576395, z: 0.0, vel: 0.5, rad: 0.1, stop: true} +- point: {x: 0.50, y: 0.80, z: 0.0, vel: 1.0, rad: 0.3, stop: false} +- point: {x: 0.515219, y: 1.8, z: 0.0, vel: 0.3, rad: 0.1, stop: true} +finish_pose: + header: {seq: 0.0, stamp: 1620367430.3803937, frame_id: base_link} + pose: + position: {x: -0.550981, y: 1.8, z: 0.0} + orientation: {x: 0.0, y: 0.0, z: 0.99749, w: 0.07074} \ No newline at end of file diff --git a/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints_gakunai.yaml b/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints_gakunai.yaml new file mode 100644 index 0000000..1b42abe --- /dev/null +++ b/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints_gakunai.yaml @@ -0,0 +1,27 @@ +waypoints: +- point: {x: 15.549, y: 1.99887, z: 0} +- point: {x: 27.7033, y: 0.740999, z: 0} +- point: {x: 44.367489, y: -3.73285, z: 0.0} +- point: {x: 53.4473, y: -1.98026, z: 0} +- point: {x: 53.5381, y: 13.9875, z: 0} +- point: {x: 53.0202, y: 25.7033, z: 0} +- point: {x: 52.624, y: 40.8326, z: 0} +- point: {x: 52.4651, y: 56.1678, z: 0} +- point: {x: 47.4651, y: 55.9678, z: 0} +- point: {x: 41.1833, y: 55.7508, z: 0} +- point: {x: 30.9773, y: 56.3972, z: 0} +- point: {x: 19.605, y: 55.9349, z: 0} +- point: {x: 9.74244, y: 57.775, z: 0} +- point: {x: 9.04664, y: 53.1814, z: 0} +- point: {x: 12.2474, y: 45.1187, z: 0} +- point: {x: 17.5568, y: 32.2592, z: 0} +- point: {x: 19.6331, y: 27.0299, z: 0} +- point: {x: 23.7635, y: 17.3945, z: 0} +- point: {x: 27.6797, y: 6.92171, z: 0} +- point: {x: 29.8247, y: 1.30448, z: 0} +- point: {x: 12.7818, y: 1.13019, z: 0} +finish_pose: + header: {seq: 0, stamp: 1623386648.025251, frame_id: base_link} + pose: + position: {x: -0.8863756, y: 0.5020624, z: 0} + orientation: {x: 0, y: 0, z: 0.999797, w: -0.0201511} \ No newline at end of file diff --git a/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints_gakunai_edit.yaml b/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints_gakunai_edit.yaml new file mode 100644 index 0000000..5d13f3a --- /dev/null +++ b/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints_gakunai_edit.yaml @@ -0,0 +1,27 @@ +waypoints: +- point: {x: 15.549, y: 1.99887, z: 0} +- point: {x: 27.7033, y: 0.740999, z: 0} +- point: {x: 44.5033, y: -3.88193, z: 0} +- point: {x: 53.4473, y: -1.98026, z: 0} +- point: {x: 53.5381, y: 13.9875, z: 0} +- point: {x: 53.0202, y: 25.7033, z: 0} +- point: {x: 52.624, y: 40.8326, z: 0} +- point: {x: 52.4651, y: 56.1678, z: 0} +- point: {x: 47.4651, y: 55.9678, z: 0} +- point: {x: 41.1833, y: 55.7508, z: 0} +- point: {x: 30.9773, y: 56.3972, z: 0} +- point: {x: 19.605, y: 55.9349, z: 0} +- point: {x: 9.74244, y: 57.775, z: 0} +- point: {x: 9.04664, y: 53.1814, z: 0} +- point: {x: 12.2474, y: 45.1187, z: 0} +- point: {x: 17.5568, y: 32.2592, z: 0} +- point: {x: 19.6331, y: 27.0299, z: 0} +- point: {x: 23.7635, y: 17.3945, z: 0} +- point: {x: 27.6797, y: 6.92171, z: 0} +- point: {x: 29.8247, y: 1.30448, z: 0} +- point: {x: 12.7818, y: 1.13019, z: 0} +finish_pose: + header: {seq: 0, stamp: 1623386648.025251, frame_id: base_link} + pose: + position: {x: -0.8863756, y: 0.5020624, z: 0} + orientation: {x: 0, y: 0, z: 0.999797, w: -0.0201511} \ No newline at end of file diff --git a/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints_test.yaml b/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints_test.yaml new file mode 100644 index 0000000..713cc07 --- /dev/null +++ b/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints_test.yaml @@ -0,0 +1,13 @@ +waypoints: +- point: {x: -1.01321, y: -0.528956, z: -0.000870705, vel: 1, rad: 0.8, stop: 0} +- point: {x: -0.0284393, y: -0.471859, z: 0.00520468, vel: 1, rad: 0.8, stop: 0} +- point: {x: 0.981428, y: -0.5452, z: 0.00261879, vel: 1, rad: 0.8, stop: 0} +- point: {x: 1.90456, y: -0.536331, z: 0.00246334, vel: 1, rad: 0.8, stop: 0} +- point: {x: 1.95224, y: 0.538929, z: 0.00476408, vel: 1, rad: 0.8, stop: 0} +- point: {x: 0.603558, y: 0.551442, z: 0.00079298, vel: 1, rad: 0.8, stop: 0} +- point: {x: 0.539775, y: 1.787, z: 0.00275993, vel: 1, rad: 0.8, stop: 0} +finish_pose: + header: {seq: 0, stamp: 244.465000000, frame_id: map} + pose: + position: {x: -0.488029, y: 1.82672, z: 0} + orientation: {x: 0, y: 0, z: 0.999992, w: 0.00399584} diff --git a/src/waypoint_navigation/waypoint_saver/CMakeLists.txt b/src/waypoint_navigation/waypoint_saver/CMakeLists.txt new file mode 100644 index 0000000..4134cad --- /dev/null +++ b/src/waypoint_navigation/waypoint_saver/CMakeLists.txt @@ -0,0 +1,89 @@ +cmake_minimum_required(VERSION 3.0.2) +project(waypoint_saver) + + + +find_package(catkin REQUIRED + geometry_msgs + visualization_msgs + roscpp + tf +) + + +catkin_package( + INCLUDE_DIRS include + LIBRARIES ${PROJECT_NAME} +) + + + +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${yaml-cpp_INCLUDE_DIRS} +) + + + + +add_executable(waypoint_saver src/waypoint_saver.cpp) + +target_link_libraries(waypoint_saver + ${catkin_LIBRARIES} +) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# catkin_install_python(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html +# install(TARGETS ${PROJECT_NAME}_node +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark libraries for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html +# install(TARGETS ${PROJECT_NAME} +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_waypoint_saver.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/src/waypoint_navigation/waypoint_saver/include/waypoint_saver.h b/src/waypoint_navigation/waypoint_saver/include/waypoint_saver.h new file mode 100644 index 0000000..9cf23da --- /dev/null +++ b/src/waypoint_navigation/waypoint_saver/include/waypoint_saver.h @@ -0,0 +1,36 @@ +#include +#include + +class Waypoint { +public: + double x, y, z; + float vel; + float rad; + bool stop; + + Waypoint() : + x(0.0), + y(0.0), + z(0.0), + vel(1.0), + rad(0.8), + stop(false) + { + } + + + std::string getYAMLstr() + { + std::stringstream ss; + ss << "{"; + ss << "x: " << x << ", " ; + ss << "y: " << y << ", " ; + ss << "z: " << z << ", " ; + ss << "vel: " << vel << ", " ; + ss << "rad: " << rad << ", " ; + ss << "stop: " << (stop ? "true" : "false") << "}" ; + return ss.str(); + // {x: *, y: *, z: *, vel: *, rad: *, stop: *} + } + +}; \ No newline at end of file diff --git a/src/waypoint_navigation/waypoint_saver/launch/waypoint_saver.launch b/src/waypoint_navigation/waypoint_saver/launch/waypoint_saver.launch new file mode 100644 index 0000000..9873494 --- /dev/null +++ b/src/waypoint_navigation/waypoint_saver/launch/waypoint_saver.launch @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/waypoint_navigation/waypoint_saver/package.xml b/src/waypoint_navigation/waypoint_saver/package.xml new file mode 100644 index 0000000..1ce6999 --- /dev/null +++ b/src/waypoint_navigation/waypoint_saver/package.xml @@ -0,0 +1,38 @@ + + + waypoint_saver + 0.0.0 + The waypoint_saver package + + + + + ubuntu + + + + + + TODO + + + catkin + + + geometry_msgs + visualization_msgs + roscpp + tf + + geometry_msgs + visualization_msgs + roscpp + tf + + + + + + + + diff --git a/src/waypoint_navigation/waypoint_saver/rviz_cfg/record_waypoints.rviz b/src/waypoint_navigation/waypoint_saver/rviz_cfg/record_waypoints.rviz new file mode 100644 index 0000000..659846c --- /dev/null +++ b/src/waypoint_navigation/waypoint_saver/rviz_cfg/record_waypoints.rviz @@ -0,0 +1,240 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: ~ + Splitter Ratio: 0.5 + Tree Height: 418 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: LaserScan +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: /map + Unreliable: false + Use Timestamp: false + 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 + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_scan: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + caster_back_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + imu_link: + Alpha: 1 + Show Axes: false + Show Trail: false + wheel_left_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wheel_right_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Points + Topic: /scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /waypoints + Name: Waypoints + Namespaces: + {} + Queue Size: 100 + Value: true + - Alpha: 1 + Class: rviz/PointStamped + Color: 204; 41; 204 + Enabled: true + History Length: 1 + Name: PointStamped + Queue Size: 10 + Radius: 0.20000000298023224 + Topic: /clicked_point + Unreliable: false + Value: true + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Class: rviz/Pose + Color: 255; 25; 0 + Enabled: true + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Name: Pose + Queue Size: 10 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Shape: Arrow + Topic: /move_base_simple/goal + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: map + Frame Rate: 10 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 9.116127014160156 + 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.43540072441101074 + Y: -0.04363036900758743 + Z: 0.47935307025909424 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 1.179796576499939 + Target Frame: + Yaw: 3.1354191303253174 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 716 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd0000000400000000000001560000022dfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005d00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003e0000022d000000cb00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000252fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000252000000a500fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b00000026c00fffffffb0000000800540069006d00650100000000000004500000000000000000000003540000022d00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 195 + Y: 59 diff --git a/src/waypoint_navigation/waypoint_saver/src/waypoint_saver.cpp b/src/waypoint_navigation/waypoint_saver/src/waypoint_saver.cpp new file mode 100644 index 0000000..61b6e02 --- /dev/null +++ b/src/waypoint_navigation/waypoint_saver/src/waypoint_saver.cpp @@ -0,0 +1,229 @@ +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include + +#include // include Waypoint class + + + +class WaypointsSaver{ +public: + WaypointsSaver() : + filename_("waypoints.yaml"), + default_rad_(0.8) + { + waypoints_viz_sub_ = nh_.subscribe("waypoints_viz", 1, &WaypointsSaver::waypointsVizCallback, this); + waypoints_joy_sub_ = nh_.subscribe("waypoints_joy", 1, &WaypointsSaver::waypointsJoyCallback, this); + finish_pose_sub_ = nh_.subscribe("finish_pose", 1, &WaypointsSaver::finishPoseCallback, this); + markers_pub_ = nh_.advertise("waypoints", 10); + + ros::NodeHandle private_nh("~"); + private_nh.param("filename", filename_, filename_); + private_nh.param("save_joy_button", save_joy_button_, 0); + private_nh.param("robot_frame", robot_frame_, std::string("base_link")); + private_nh.param("world_frame", world_frame_, std::string("map")); + private_nh.param("default_rad", default_rad_, default_rad_); + } + + + + /* + ++++++++++ Save waypoint by joy stick button ++++++++++ + */ + void waypointsJoyCallback(const sensor_msgs::Joy &msg) + { + static ros::Time saved_time(0.0); + if (msg.buttons[save_joy_button_] == 1 && (ros::Time::now() - saved_time).toSec() > 3.0) { + pushbackWaypoint(); + saved_time = ros::Time::now(); + } + publishMarkerArray(); + } + + + + /* + ++++++++++ Save waypoint by "Publish Point" on rviz ++++++++++ + */ + void waypointsVizCallback(const geometry_msgs::PointStamped &msg) + { + Waypoint point; + point.x = msg.point.x; + point.y = msg.point.y; + point.z = msg.point.z; + point.rad = default_rad_; + waypoints_.push_back(point); + addWaypointMarker(point); + publishMarkerArray(); + } + + + + /* + ++++++++++ Save finish pose by "2D Nav Goal" on rviz ++++++++++ + */ + void finishPoseCallback(const geometry_msgs::PoseStamped &msg) + { + finish_pose_ = msg; + save(); + waypoints_.clear(); + } + + + + /* + ++++++++++ Get robot's pose and add waypoint ++++++++++ + */ + void pushbackWaypoint() + { + tf::StampedTransform robot_gl; + try { + tf_listener_.lookupTransform(world_frame_, robot_frame_, ros::Time(0.0), robot_gl); + Waypoint point; + point.x = robot_gl.getOrigin().x(); + point.y = robot_gl.getOrigin().y(); + point.z = robot_gl.getOrigin().z(); + point.rad = default_rad_; + waypoints_.push_back(point); + addWaypointMarker(point); + } + catch(tf::TransformException &e) { + ROS_WARN_STREAM("tf::TransformException: " << e.what()); + } + } + + + + /* + ++++++++++ Add marker to display on rviz ++++++++++ + */ + void addWaypointMarker(Waypoint point) + { + double scale = 0.2; + int number = waypoints_.size(); + std::stringstream name; + name << "Waypoint " << number; + + visualization_msgs::Marker marker; + marker.header.frame_id = world_frame_; + marker.header.stamp = ros::Time::now(); + marker.ns = name.str(); + marker.id = number; + marker.type = visualization_msgs::Marker::SPHERE; + marker.action = visualization_msgs::Marker::ADD; + marker.pose.position.x = point.x; + marker.pose.position.y = point.y; + marker.pose.position.z = scale/2; + marker.scale.x = scale; + marker.scale.y = scale; + marker.scale.z = scale; + marker.color.r=0.8f; + marker.color.g=0.2f; + marker.color.b=0.2f; + marker.color.a = 1.0f; + + markers_.push_back(marker); + } + + + + /* + ++++++++++ Publish markerArray to display waypoints on rviz ++++++++++ + */ + void publishMarkerArray() + { + visualization_msgs::MarkerArray marker_array; + marker_array.markers = markers_; + markers_pub_.publish(marker_array); + } + + + + /* + ++++++++++ Save waypoints as yaml file ++++++++++ + */ + void save() + { + std::ofstream ofs(filename_.c_str(), std::ios::out); + /* + waypoints: + - point: {x: *, y: *, z: *, ...} + */ + ofs << "waypoints:" << std::endl; + for(int i=0; i < waypoints_.size(); i++) { + ofs << "- point: " << waypoints_[i].getYAMLstr() << std::endl; + } + /* + finish_pose: + header: {seq: *, stamp: *, frame_id: *} + pose: + positioin: {x: *, y: *, z: *} + orientation: {x: *, y: *, z: *, w: *} + */ + ofs << "finish_pose:" << std::endl; + ofs << " header: {" ; + ofs << "seq: " << finish_pose_.header.seq << ", " ; + ofs << "stamp: " << finish_pose_.header.stamp << ", " ; + ofs << "frame_id: " << finish_pose_.header.frame_id << "}" << std::endl; + ofs << " pose: " << std::endl; + ofs << " position: {" ; + ofs << "x: " << finish_pose_.pose.position.x << ", " ; + ofs << "y: " << finish_pose_.pose.position.y << ", " ; + ofs << "z: " << finish_pose_.pose.position.z << "}" << std::endl; + ofs << " orientation: {" ; + ofs << "x: " << finish_pose_.pose.orientation.x << ", " ; + ofs << "y: " << finish_pose_.pose.orientation.y << ", " ; + ofs << "z: " << finish_pose_.pose.orientation.z << ", " ; + ofs << "w: " << finish_pose_.pose.orientation.w << "}" << std::endl; + + ofs.close(); + ROS_INFO_STREAM("write success"); + } + + + + void run() + { + ros::spin(); + } + + + +private: + ros::Subscriber waypoints_viz_sub_; + ros::Subscriber waypoints_joy_sub_; + ros::Subscriber finish_pose_sub_; + ros::Publisher markers_pub_; + std::vector waypoints_; + std::vector markers_; + geometry_msgs::PoseStamped finish_pose_; + tf::TransformListener tf_listener_; + int save_joy_button_; + ros::NodeHandle nh_; + std::string filename_; + std::string world_frame_; + std::string robot_frame_; + float default_rad_; +}; + + + + + +int main(int argc, char *argv[]) +{ + ros::init(argc, argv, "waypoints_saver"); + WaypointsSaver saver; + saver.run(); + + return 0; +} diff --git a/src/zlac8015d_ros/LICENSE b/src/zlac8015d_ros/LICENSE new file mode 100644 index 0000000..f288702 --- /dev/null +++ b/src/zlac8015d_ros/LICENSE @@ -0,0 +1,674 @@ + GNU GENERAL PUBLIC LICENSE + Version 3, 29 June 2007 + + Copyright (C) 2007 Free Software Foundation, Inc. + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + + Preamble + + The GNU General Public License is a free, copyleft license for +software and other kinds of works. + + The licenses for most software and other practical works are designed +to take away your freedom to share and change the works. By contrast, +the GNU General Public License is intended to guarantee your freedom to +share and change all versions of a program--to make sure it remains free +software for all its users. We, the Free Software Foundation, use the +GNU General Public License for most of our software; it applies also to +any other work released this way by its authors. You can apply it to +your programs, too. + + When we speak of free software, we are referring to freedom, not +price. Our General Public Licenses are designed to make sure that you +have the freedom to distribute copies of free software (and charge for +them if you wish), that you receive source code or can get it if you +want it, that you can change the software or use pieces of it in new +free programs, and that you know you can do these things. + + To protect your rights, we need to prevent others from denying you +these rights or asking you to surrender the rights. Therefore, you have +certain responsibilities if you distribute copies of the software, or if +you modify it: responsibilities to respect the freedom of others. + + For example, if you distribute copies of such a program, whether +gratis or for a fee, you must pass on to the recipients the same +freedoms that you received. You must make sure that they, too, receive +or can get the source code. And you must show them these terms so they +know their rights. + + Developers that use the GNU GPL protect your rights with two steps: +(1) assert copyright on the software, and (2) offer you this License +giving you legal permission to copy, distribute and/or modify it. + + For the developers' and authors' protection, the GPL clearly explains +that there is no warranty for this free software. For both users' and +authors' sake, the GPL requires that modified versions be marked as +changed, so that their problems will not be attributed erroneously to +authors of previous versions. + + Some devices are designed to deny users access to install or run +modified versions of the software inside them, although the manufacturer +can do so. This is fundamentally incompatible with the aim of +protecting users' freedom to change the software. The systematic +pattern of such abuse occurs in the area of products for individuals to +use, which is precisely where it is most unacceptable. Therefore, we +have designed this version of the GPL to prohibit the practice for those +products. If such problems arise substantially in other domains, we +stand ready to extend this provision to those domains in future versions +of the GPL, as needed to protect the freedom of users. + + Finally, every program is threatened constantly by software patents. +States should not allow patents to restrict development and use of +software on general-purpose computers, but in those that do, we wish to +avoid the special danger that patents applied to a free program could +make it effectively proprietary. To prevent this, the GPL assures that +patents cannot be used to render the program non-free. + + The precise terms and conditions for copying, distribution and +modification follow. + + TERMS AND CONDITIONS + + 0. Definitions. + + "This License" refers to version 3 of the GNU General Public License. + + "Copyright" also means copyright-like laws that apply to other kinds of +works, such as semiconductor masks. + + "The Program" refers to any copyrightable work licensed under this +License. Each licensee is addressed as "you". "Licensees" and +"recipients" may be individuals or organizations. + + To "modify" a work means to copy from or adapt all or part of the work +in a fashion requiring copyright permission, other than the making of an +exact copy. The resulting work is called a "modified version" of the +earlier work or a work "based on" the earlier work. + + A "covered work" means either the unmodified Program or a work based +on the Program. + + To "propagate" a work means to do anything with it that, without +permission, would make you directly or secondarily liable for +infringement under applicable copyright law, except executing it on a +computer or modifying a private copy. Propagation includes copying, +distribution (with or without modification), making available to the +public, and in some countries other activities as well. + + To "convey" a work means any kind of propagation that enables other +parties to make or receive copies. Mere interaction with a user through +a computer network, with no transfer of a copy, is not conveying. + + An interactive user interface displays "Appropriate Legal Notices" +to the extent that it includes a convenient and prominently visible +feature that (1) displays an appropriate copyright notice, and (2) +tells the user that there is no warranty for the work (except to the +extent that warranties are provided), that licensees may convey the +work under this License, and how to view a copy of this License. If +the interface presents a list of user commands or options, such as a +menu, a prominent item in the list meets this criterion. + + 1. Source Code. + + The "source code" for a work means the preferred form of the work +for making modifications to it. "Object code" means any non-source +form of a work. + + A "Standard Interface" means an interface that either is an official +standard defined by a recognized standards body, or, in the case of +interfaces specified for a particular programming language, one that +is widely used among developers working in that language. + + The "System Libraries" of an executable work include anything, other +than the work as a whole, that (a) is included in the normal form of +packaging a Major Component, but which is not part of that Major +Component, and (b) serves only to enable use of the work with that +Major Component, or to implement a Standard Interface for which an +implementation is available to the public in source code form. A +"Major Component", in this context, means a major essential component +(kernel, window system, and so on) of the specific operating system +(if any) on which the executable work runs, or a compiler used to +produce the work, or an object code interpreter used to run it. + + The "Corresponding Source" for a work in object code form means all +the source code needed to generate, install, and (for an executable +work) run the object code and to modify the work, including scripts to +control those activities. However, it does not include the work's +System Libraries, or general-purpose tools or generally available free +programs which are used unmodified in performing those activities but +which are not part of the work. For example, Corresponding Source +includes interface definition files associated with source files for +the work, and the source code for shared libraries and dynamically +linked subprograms that the work is specifically designed to require, +such as by intimate data communication or control flow between those +subprograms and other parts of the work. + + The Corresponding Source need not include anything that users +can regenerate automatically from other parts of the Corresponding +Source. + + The Corresponding Source for a work in source code form is that +same work. + + 2. Basic Permissions. + + All rights granted under this License are granted for the term of +copyright on the Program, and are irrevocable provided the stated +conditions are met. This License explicitly affirms your unlimited +permission to run the unmodified Program. The output from running a +covered work is covered by this License only if the output, given its +content, constitutes a covered work. This License acknowledges your +rights of fair use or other equivalent, as provided by copyright law. + + You may make, run and propagate covered works that you do not +convey, without conditions so long as your license otherwise remains +in force. You may convey covered works to others for the sole purpose +of having them make modifications exclusively for you, or provide you +with facilities for running those works, provided that you comply with +the terms of this License in conveying all material for which you do +not control copyright. Those thus making or running the covered works +for you must do so exclusively on your behalf, under your direction +and control, on terms that prohibit them from making any copies of +your copyrighted material outside their relationship with you. + + Conveying under any other circumstances is permitted solely under +the conditions stated below. Sublicensing is not allowed; section 10 +makes it unnecessary. + + 3. Protecting Users' Legal Rights From Anti-Circumvention Law. + + No covered work shall be deemed part of an effective technological +measure under any applicable law fulfilling obligations under article +11 of the WIPO copyright treaty adopted on 20 December 1996, or +similar laws prohibiting or restricting circumvention of such +measures. + + When you convey a covered work, you waive any legal power to forbid +circumvention of technological measures to the extent such circumvention +is effected by exercising rights under this License with respect to +the covered work, and you disclaim any intention to limit operation or +modification of the work as a means of enforcing, against the work's +users, your or third parties' legal rights to forbid circumvention of +technological measures. + + 4. Conveying Verbatim Copies. + + You may convey verbatim copies of the Program's source code as you +receive it, in any medium, provided that you conspicuously and +appropriately publish on each copy an appropriate copyright notice; +keep intact all notices stating that this License and any +non-permissive terms added in accord with section 7 apply to the code; +keep intact all notices of the absence of any warranty; and give all +recipients a copy of this License along with the Program. + + You may charge any price or no price for each copy that you convey, +and you may offer support or warranty protection for a fee. + + 5. Conveying Modified Source Versions. + + You may convey a work based on the Program, or the modifications to +produce it from the Program, in the form of source code under the +terms of section 4, provided that you also meet all of these conditions: + + a) The work must carry prominent notices stating that you modified + it, and giving a relevant date. + + b) The work must carry prominent notices stating that it is + released under this License and any conditions added under section + 7. This requirement modifies the requirement in section 4 to + "keep intact all notices". + + c) You must license the entire work, as a whole, under this + License to anyone who comes into possession of a copy. This + License will therefore apply, along with any applicable section 7 + additional terms, to the whole of the work, and all its parts, + regardless of how they are packaged. This License gives no + permission to license the work in any other way, but it does not + invalidate such permission if you have separately received it. + + d) If the work has interactive user interfaces, each must display + Appropriate Legal Notices; however, if the Program has interactive + interfaces that do not display Appropriate Legal Notices, your + work need not make them do so. + + A compilation of a covered work with other separate and independent +works, which are not by their nature extensions of the covered work, +and which are not combined with it such as to form a larger program, +in or on a volume of a storage or distribution medium, is called an +"aggregate" if the compilation and its resulting copyright are not +used to limit the access or legal rights of the compilation's users +beyond what the individual works permit. Inclusion of a covered work +in an aggregate does not cause this License to apply to the other +parts of the aggregate. + + 6. Conveying Non-Source Forms. + + You may convey a covered work in object code form under the terms +of sections 4 and 5, provided that you also convey the +machine-readable Corresponding Source under the terms of this License, +in one of these ways: + + a) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by the + Corresponding Source fixed on a durable physical medium + customarily used for software interchange. + + b) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by a + written offer, valid for at least three years and valid for as + long as you offer spare parts or customer support for that product + model, to give anyone who possesses the object code either (1) a + copy of the Corresponding Source for all the software in the + product that is covered by this License, on a durable physical + medium customarily used for software interchange, for a price no + more than your reasonable cost of physically performing this + conveying of source, or (2) access to copy the + Corresponding Source from a network server at no charge. + + c) Convey individual copies of the object code with a copy of the + written offer to provide the Corresponding Source. This + alternative is allowed only occasionally and noncommercially, and + only if you received the object code with such an offer, in accord + with subsection 6b. + + d) Convey the object code by offering access from a designated + place (gratis or for a charge), and offer equivalent access to the + Corresponding Source in the same way through the same place at no + further charge. You need not require recipients to copy the + Corresponding Source along with the object code. If the place to + copy the object code is a network server, the Corresponding Source + may be on a different server (operated by you or a third party) + that supports equivalent copying facilities, provided you maintain + clear directions next to the object code saying where to find the + Corresponding Source. Regardless of what server hosts the + Corresponding Source, you remain obligated to ensure that it is + available for as long as needed to satisfy these requirements. + + e) Convey the object code using peer-to-peer transmission, provided + you inform other peers where the object code and Corresponding + Source of the work are being offered to the general public at no + charge under subsection 6d. + + A separable portion of the object code, whose source code is excluded +from the Corresponding Source as a System Library, need not be +included in conveying the object code work. + + A "User Product" is either (1) a "consumer product", which means any +tangible personal property which is normally used for personal, family, +or household purposes, or (2) anything designed or sold for incorporation +into a dwelling. In determining whether a product is a consumer product, +doubtful cases shall be resolved in favor of coverage. For a particular +product received by a particular user, "normally used" refers to a +typical or common use of that class of product, regardless of the status +of the particular user or of the way in which the particular user +actually uses, or expects or is expected to use, the product. A product +is a consumer product regardless of whether the product has substantial +commercial, industrial or non-consumer uses, unless such uses represent +the only significant mode of use of the product. + + "Installation Information" for a User Product means any methods, +procedures, authorization keys, or other information required to install +and execute modified versions of a covered work in that User Product from +a modified version of its Corresponding Source. The information must +suffice to ensure that the continued functioning of the modified object +code is in no case prevented or interfered with solely because +modification has been made. + + If you convey an object code work under this section in, or with, or +specifically for use in, a User Product, and the conveying occurs as +part of a transaction in which the right of possession and use of the +User Product is transferred to the recipient in perpetuity or for a +fixed term (regardless of how the transaction is characterized), the +Corresponding Source conveyed under this section must be accompanied +by the Installation Information. But this requirement does not apply +if neither you nor any third party retains the ability to install +modified object code on the User Product (for example, the work has +been installed in ROM). + + The requirement to provide Installation Information does not include a +requirement to continue to provide support service, warranty, or updates +for a work that has been modified or installed by the recipient, or for +the User Product in which it has been modified or installed. Access to a +network may be denied when the modification itself materially and +adversely affects the operation of the network or violates the rules and +protocols for communication across the network. + + Corresponding Source conveyed, and Installation Information provided, +in accord with this section must be in a format that is publicly +documented (and with an implementation available to the public in +source code form), and must require no special password or key for +unpacking, reading or copying. + + 7. Additional Terms. + + "Additional permissions" are terms that supplement the terms of this +License by making exceptions from one or more of its conditions. +Additional permissions that are applicable to the entire Program shall +be treated as though they were included in this License, to the extent +that they are valid under applicable law. If additional permissions +apply only to part of the Program, that part may be used separately +under those permissions, but the entire Program remains governed by +this License without regard to the additional permissions. + + When you convey a copy of a covered work, you may at your option +remove any additional permissions from that copy, or from any part of +it. (Additional permissions may be written to require their own +removal in certain cases when you modify the work.) You may place +additional permissions on material, added by you to a covered work, +for which you have or can give appropriate copyright permission. + + Notwithstanding any other provision of this License, for material you +add to a covered work, you may (if authorized by the copyright holders of +that material) supplement the terms of this License with terms: + + a) Disclaiming warranty or limiting liability differently from the + terms of sections 15 and 16 of this License; or + + b) Requiring preservation of specified reasonable legal notices or + author attributions in that material or in the Appropriate Legal + Notices displayed by works containing it; or + + c) Prohibiting misrepresentation of the origin of that material, or + requiring that modified versions of such material be marked in + reasonable ways as different from the original version; or + + d) Limiting the use for publicity purposes of names of licensors or + authors of the material; or + + e) Declining to grant rights under trademark law for use of some + trade names, trademarks, or service marks; or + + f) Requiring indemnification of licensors and authors of that + material by anyone who conveys the material (or modified versions of + it) with contractual assumptions of liability to the recipient, for + any liability that these contractual assumptions directly impose on + those licensors and authors. + + All other non-permissive additional terms are considered "further +restrictions" within the meaning of section 10. If the Program as you +received it, or any part of it, contains a notice stating that it is +governed by this License along with a term that is a further +restriction, you may remove that term. If a license document contains +a further restriction but permits relicensing or conveying under this +License, you may add to a covered work material governed by the terms +of that license document, provided that the further restriction does +not survive such relicensing or conveying. + + If you add terms to a covered work in accord with this section, you +must place, in the relevant source files, a statement of the +additional terms that apply to those files, or a notice indicating +where to find the applicable terms. + + Additional terms, permissive or non-permissive, may be stated in the +form of a separately written license, or stated as exceptions; +the above requirements apply either way. + + 8. Termination. + + You may not propagate or modify a covered work except as expressly +provided under this License. Any attempt otherwise to propagate or +modify it is void, and will automatically terminate your rights under +this License (including any patent licenses granted under the third +paragraph of section 11). + + However, if you cease all violation of this License, then your +license from a particular copyright holder is reinstated (a) +provisionally, unless and until the copyright holder explicitly and +finally terminates your license, and (b) permanently, if the copyright +holder fails to notify you of the violation by some reasonable means +prior to 60 days after the cessation. + + Moreover, your license from a particular copyright holder is +reinstated permanently if the copyright holder notifies you of the +violation by some reasonable means, this is the first time you have +received notice of violation of this License (for any work) from that +copyright holder, and you cure the violation prior to 30 days after +your receipt of the notice. + + Termination of your rights under this section does not terminate the +licenses of parties who have received copies or rights from you under +this License. If your rights have been terminated and not permanently +reinstated, you do not qualify to receive new licenses for the same +material under section 10. + + 9. Acceptance Not Required for Having Copies. + + You are not required to accept this License in order to receive or +run a copy of the Program. Ancillary propagation of a covered work +occurring solely as a consequence of using peer-to-peer transmission +to receive a copy likewise does not require acceptance. However, +nothing other than this License grants you permission to propagate or +modify any covered work. These actions infringe copyright if you do +not accept this License. Therefore, by modifying or propagating a +covered work, you indicate your acceptance of this License to do so. + + 10. Automatic Licensing of Downstream Recipients. + + Each time you convey a covered work, the recipient automatically +receives a license from the original licensors, to run, modify and +propagate that work, subject to this License. You are not responsible +for enforcing compliance by third parties with this License. + + An "entity transaction" is a transaction transferring control of an +organization, or substantially all assets of one, or subdividing an +organization, or merging organizations. If propagation of a covered +work results from an entity transaction, each party to that +transaction who receives a copy of the work also receives whatever +licenses to the work the party's predecessor in interest had or could +give under the previous paragraph, plus a right to possession of the +Corresponding Source of the work from the predecessor in interest, if +the predecessor has it or can get it with reasonable efforts. + + You may not impose any further restrictions on the exercise of the +rights granted or affirmed under this License. For example, you may +not impose a license fee, royalty, or other charge for exercise of +rights granted under this License, and you may not initiate litigation +(including a cross-claim or counterclaim in a lawsuit) alleging that +any patent claim is infringed by making, using, selling, offering for +sale, or importing the Program or any portion of it. + + 11. Patents. + + A "contributor" is a copyright holder who authorizes use under this +License of the Program or a work on which the Program is based. The +work thus licensed is called the contributor's "contributor version". + + A contributor's "essential patent claims" are all patent claims +owned or controlled by the contributor, whether already acquired or +hereafter acquired, that would be infringed by some manner, permitted +by this License, of making, using, or selling its contributor version, +but do not include claims that would be infringed only as a +consequence of further modification of the contributor version. For +purposes of this definition, "control" includes the right to grant +patent sublicenses in a manner consistent with the requirements of +this License. + + Each contributor grants you a non-exclusive, worldwide, royalty-free +patent license under the contributor's essential patent claims, to +make, use, sell, offer for sale, import and otherwise run, modify and +propagate the contents of its contributor version. + + In the following three paragraphs, a "patent license" is any express +agreement or commitment, however denominated, not to enforce a patent +(such as an express permission to practice a patent or covenant not to +sue for patent infringement). To "grant" such a patent license to a +party means to make such an agreement or commitment not to enforce a +patent against the party. + + If you convey a covered work, knowingly relying on a patent license, +and the Corresponding Source of the work is not available for anyone +to copy, free of charge and under the terms of this License, through a +publicly available network server or other readily accessible means, +then you must either (1) cause the Corresponding Source to be so +available, or (2) arrange to deprive yourself of the benefit of the +patent license for this particular work, or (3) arrange, in a manner +consistent with the requirements of this License, to extend the patent +license to downstream recipients. "Knowingly relying" means you have +actual knowledge that, but for the patent license, your conveying the +covered work in a country, or your recipient's use of the covered work +in a country, would infringe one or more identifiable patents in that +country that you have reason to believe are valid. + + If, pursuant to or in connection with a single transaction or +arrangement, you convey, or propagate by procuring conveyance of, a +covered work, and grant a patent license to some of the parties +receiving the covered work authorizing them to use, propagate, modify +or convey a specific copy of the covered work, then the patent license +you grant is automatically extended to all recipients of the covered +work and works based on it. + + A patent license is "discriminatory" if it does not include within +the scope of its coverage, prohibits the exercise of, or is +conditioned on the non-exercise of one or more of the rights that are +specifically granted under this License. You may not convey a covered +work if you are a party to an arrangement with a third party that is +in the business of distributing software, under which you make payment +to the third party based on the extent of your activity of conveying +the work, and under which the third party grants, to any of the +parties who would receive the covered work from you, a discriminatory +patent license (a) in connection with copies of the covered work +conveyed by you (or copies made from those copies), or (b) primarily +for and in connection with specific products or compilations that +contain the covered work, unless you entered into that arrangement, +or that patent license was granted, prior to 28 March 2007. + + Nothing in this License shall be construed as excluding or limiting +any implied license or other defenses to infringement that may +otherwise be available to you under applicable patent law. + + 12. No Surrender of Others' Freedom. + + If conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot convey a +covered work so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you may +not convey it at all. For example, if you agree to terms that obligate you +to collect a royalty for further conveying from those to whom you convey +the Program, the only way you could satisfy both those terms and this +License would be to refrain entirely from conveying the Program. + + 13. Use with the GNU Affero General Public License. + + Notwithstanding any other provision of this License, you have +permission to link or combine any covered work with a work licensed +under version 3 of the GNU Affero General Public License into a single +combined work, and to convey the resulting work. The terms of this +License will continue to apply to the part which is the covered work, +but the special requirements of the GNU Affero General Public License, +section 13, concerning interaction through a network will apply to the +combination as such. + + 14. Revised Versions of this License. + + The Free Software Foundation may publish revised and/or new versions of +the GNU General Public License from time to time. Such new versions will +be similar in spirit to the present version, but may differ in detail to +address new problems or concerns. + + Each version is given a distinguishing version number. If the +Program specifies that a certain numbered version of the GNU General +Public License "or any later version" applies to it, you have the +option of following the terms and conditions either of that numbered +version or of any later version published by the Free Software +Foundation. If the Program does not specify a version number of the +GNU General Public License, you may choose any version ever published +by the Free Software Foundation. + + If the Program specifies that a proxy can decide which future +versions of the GNU General Public License can be used, that proxy's +public statement of acceptance of a version permanently authorizes you +to choose that version for the Program. + + Later license versions may give you additional or different +permissions. However, no additional obligations are imposed on any +author or copyright holder as a result of your choosing to follow a +later version. + + 15. Disclaimer of Warranty. + + THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY +APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT +HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY +OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, +THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM +IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF +ALL NECESSARY SERVICING, REPAIR OR CORRECTION. + + 16. Limitation of Liability. + + IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING +WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS +THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY +GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE +USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF +DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD +PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), +EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF +SUCH DAMAGES. + + 17. Interpretation of Sections 15 and 16. + + If the disclaimer of warranty and limitation of liability provided +above cannot be given local legal effect according to their terms, +reviewing courts shall apply local law that most closely approximates +an absolute waiver of all civil liability in connection with the +Program, unless a warranty or assumption of liability accompanies a +copy of the Program in return for a fee. + + END OF TERMS AND CONDITIONS + + How to Apply These Terms to Your New Programs + + If you develop a new program, and you want it to be of the greatest +possible use to the public, the best way to achieve this is to make it +free software which everyone can redistribute and change under these terms. + + To do so, attach the following notices to the program. It is safest +to attach them to the start of each source file to most effectively +state the exclusion of warranty; and each file should have at least +the "copyright" line and a pointer to where the full notice is found. + + + Copyright (C) + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + +Also add information on how to contact you by electronic and paper mail. + + If the program does terminal interaction, make it output a short +notice like this when it starts in an interactive mode: + + Copyright (C) + This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. + This is free software, and you are welcome to redistribute it + under certain conditions; type `show c' for details. + +The hypothetical commands `show w' and `show c' should show the appropriate +parts of the General Public License. Of course, your program's commands +might be different; for a GUI interface, you would use an "about box". + + You should also get your employer (if you work as a programmer) or school, +if any, to sign a "copyright disclaimer" for the program, if necessary. +For more information on this, and how to apply and follow the GNU GPL, see +. + + The GNU General Public License does not permit incorporating your program +into proprietary programs. If your program is a subroutine library, you +may consider it more useful to permit linking proprietary applications with +the library. If this is what you want to do, use the GNU Lesser General +Public License instead of this License. But first, please read +. diff --git a/src/zlac8015d_ros/README.md b/src/zlac8015d_ros/README.md index bf8aa92..d38891e 100644 --- a/src/zlac8015d_ros/README.md +++ b/src/zlac8015d_ros/README.md @@ -37,10 +37,10 @@ - `max_left_rpm`: Maximum rpm of left tire. Default is `150`. - `max_right_rpm`: Maximum rpm of right tire. Default is `150`. - `deadband_rpm`: Width of rpm to be regarded as 0. If `3`, then -3 to 3 is considered rpm 0. Default is `3`. -- `TF_header_flame`: Header flame of TF. Default is `odom`. -- `TF_child_flame`: Child flame of TF. Default is `base_link`. -- `odom_header_flame`: Header flame of odom. Default is `odom`. -- `odom_child_flame`: Child flame of odom. Default is `base_link`. +- `TF_header_frame`: Header frame of TF. Default is `odom`. +- `TF_child_frame`: Child frame of TF. Default is `base_link`. +- `odom_header_frame`: Header frame of odom. Default is `odom`. +- `odom_child_frame`: Child frame of odom. Default is `base_link`. ### Topics This node publishes the following topics. diff --git a/src/zlac8015d_ros/emergency_stop/emergency_stop.ino b/src/zlac8015d_ros/emergency_stop/emergency_stop.ino new file mode 100644 index 0000000..e8ad546 --- /dev/null +++ b/src/zlac8015d_ros/emergency_stop/emergency_stop.ino @@ -0,0 +1,109 @@ +/* +Copyright (C) 2022 Alpaca-zip + +This program is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. + +This program is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with this program. If not, see . + +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +For the emergency stop to work correctly, you will need to: + +1, Edit ModbusMaster.h + +2, Line 252: static const uint16_t ku16MBResponseTimeout = 2000; => static const uint16_t ku16MBResponseTimeout = 100; +*/ + +#include +#define MAX485_DE 3 +#define MAX485_RE_NEG 2 + +ModbusMaster node; // instantiate ModbusMaster object + +// set pin numbers: +const int estop_buttonPin = 7; // the number of the estop button pin +const int reset_buttonPin = 8; // the number of the reset button pin +const int ledPin = 13; // the number of the LED pin +int estop_buttonState = 0; // variable for reading the estop button status +int reset_buttonState = 0; // variable for reading the reset button status +bool estop_flag; // flag for emer_stop() +bool reset_flag; // flag for reset() + +void preTransmission(){ + digitalWrite(MAX485_RE_NEG, 1); + digitalWrite(MAX485_DE, 1); +} + +void postTransmission(){ + digitalWrite(MAX485_RE_NEG, 0); + digitalWrite(MAX485_DE, 0); +} + +void emer_stop(){ + uint8_t estop_response; + while(estop_flag){ + estop_response = node.writeSingleRegister(0x200E, 0x05); // 0x05: emergency stop + if(estop_response == 0){ + digitalWrite(ledPin, HIGH); // turn LED on + estop_flag = false; + reset_flag = true; + } + } +} + +void reset(){ + uint8_t reset_response; + while(reset_flag){ + reset_response = node.writeSingleRegister(0x200E, 0x06); // 0x06: clear fault + if(reset_response == 0) continue; + reset_response = node.writeSingleRegister(0x200E, 0x07); // 0x07: stop + if(reset_response == 0) continue; + reset_response = node.writeSingleRegister(0x200E, 0x08); // 0x08: enable + if(reset_response == 0){ + digitalWrite(ledPin, LOW); // turn LED off + estop_flag = true; + reset_flag = false; + } + } +} + +void setup(){ + pinMode(ledPin, OUTPUT); // initialize the LED pin as an output: + pinMode(estop_buttonPin, INPUT_PULLUP); // initialize the estop button pin as an input + pinMode(reset_buttonPin, INPUT_PULLUP); // initialize the reset button pin as an input + pinMode(MAX485_RE_NEG, OUTPUT); // initialize the MAX485_RE_NEG pin as an output + pinMode(MAX485_DE, OUTPUT); // initialize the MAX485_DE pin as an output + + // Init in receive mode + digitalWrite(MAX485_RE_NEG, 0); + digitalWrite(MAX485_DE, 0); + + Serial.begin(115200); // modbus communication runs at 115200 baud + node.begin(1, Serial); // modbus slave ID 1 + // callbacks allow us to configure the RS485 transceiver correctly + node.preTransmission(preTransmission); + node.postTransmission(postTransmission); + + estop_flag = true; // initialize the flag as a TRUE + reset_flag = false; // initialize the flag as a FALSE +} + +void loop(){ + estop_buttonState = digitalRead(estop_buttonPin); // read the state of the estop_buttonPin value + reset_buttonState = digitalRead(reset_buttonPin); // read the state of the reset_buttonPin value + + if(estop_buttonState == LOW){ // estop button is pressed + emer_stop(); + }else if(reset_buttonState == LOW){ // reset button is pressed + reset(); + } +} diff --git a/src/zlac8015d_ros/emergency_stop/module_PCB/emergency_stop.fzz b/src/zlac8015d_ros/emergency_stop/module_PCB/emergency_stop.fzz new file mode 100644 index 0000000..b2e7678 --- /dev/null +++ b/src/zlac8015d_ros/emergency_stop/module_PCB/emergency_stop.fzz Binary files differ diff --git a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_contour.gm1 b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_contour.gm1 new file mode 100644 index 0000000..367d0be --- /dev/null +++ b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_contour.gm1 @@ -0,0 +1,26 @@ +G04 MADE WITH FRITZING* +G04 WWW.FRITZING.ORG* +G04 DOUBLE SIDED* +G04 HOLES PLATED* +G04 CONTOUR ON CENTER OF CONTOUR VECTOR* +%ASAXBY*% +%FSLAX23Y23*% +%MOIN*% +%OFA0B0*% +%SFA1.0B1.0*% +%ADD10R,2.602410X1.799010*% +%ADD11C,0.008000*% +%ADD10C,0.008*% +%LNCONTOUR*% +G90* +G70* +G54D10* +G54D11* +X4Y1795D02* +X2598Y1795D01* +X2598Y4D01* +X4Y4D01* +X4Y1795D01* +D02* +G04 End of contour* +M02* \ No newline at end of file diff --git a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_copperBottom.gbl b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_copperBottom.gbl new file mode 100644 index 0000000..ef253af --- /dev/null +++ b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_copperBottom.gbl @@ -0,0 +1,4775 @@ +G04 MADE WITH FRITZING* +G04 WWW.FRITZING.ORG* +G04 DOUBLE SIDED* +G04 HOLES PLATED* +G04 CONTOUR ON CENTER OF CONTOUR VECTOR* +%ASAXBY*% +%FSLAX23Y23*% +%MOIN*% +%OFA0B0*% +%SFA1.0B1.0*% +%ADD10C,0.075000*% +%ADD11C,0.070000*% +%ADD12C,0.078000*% +%ADD13R,0.069972X0.070000*% +%ADD14C,0.024000*% +%LNCOPPER0*% +G90* +G70* +G54D10* +X1491Y1416D03* +X423Y1693D03* +X683Y974D03* +X1003Y1128D03* +G54D11* +X1699Y1599D03* +X1699Y1499D03* +X1699Y1399D03* +X1699Y1299D03* +X1699Y1199D03* +X1699Y1099D03* +X1699Y999D03* +X1699Y899D03* +X1699Y799D03* +X1699Y699D03* +X1699Y599D03* +X1699Y499D03* +X1699Y399D03* +X1699Y299D03* +X1699Y199D03* +X2299Y1599D03* +X2299Y1499D03* +X2299Y1399D03* +X2299Y1299D03* +X2299Y1199D03* +X2299Y1099D03* +X2299Y999D03* +X2299Y899D03* +X2299Y799D03* +X2299Y699D03* +X2299Y599D03* +X2299Y499D03* +X2299Y399D03* +X2299Y299D03* +X2299Y199D03* +G54D12* +X1199Y1699D03* +X1299Y1699D03* +X1399Y1699D03* +X1499Y1699D03* +X1199Y99D03* +X1299Y99D03* +X1399Y99D03* +X1499Y99D03* +X399Y1099D03* +X499Y1099D03* +X599Y1099D03* +X699Y1099D03* +X799Y1099D03* +X899Y1099D03* +X299Y1699D03* +X299Y1599D03* +X999Y1699D03* +X999Y1599D03* +G54D13* +X1699Y1599D03* +G54D14* +X1397Y1199D02* +X1681Y1199D01* +D02* +X1399Y1680D02* +X1397Y1199D01* +D02* +X1299Y1100D02* +X1299Y1680D01* +D02* +X1681Y1099D02* +X1299Y1100D01* +D02* +X1500Y1500D02* +X1681Y1499D01* +D02* +X1499Y1680D02* +X1500Y1500D01* +D02* +X1799Y1600D02* +X1717Y1599D01* +D02* +X1799Y100D02* +X1799Y1600D01* +D02* +X1198Y1198D02* +X198Y1198D01* +D02* +X198Y1198D02* +X198Y399D01* +D02* +X198Y399D02* +X1600Y399D01* +D02* +X1600Y399D02* +X1600Y100D01* +D02* +X1600Y100D02* +X1799Y100D01* +D02* +X1199Y1680D02* +X1198Y1198D01* +D02* +X599Y598D02* +X1681Y599D01* +D02* +X599Y1080D02* +X599Y598D01* +D02* +X800Y697D02* +X1681Y699D01* +D02* +X799Y1080D02* +X800Y697D01* +G36* +X1338Y1671D02* +X1338Y1669D01* +X1336Y1669D01* +X1336Y1665D01* +X1334Y1665D01* +X1334Y1663D01* +X1330Y1663D01* +X1330Y1661D01* +X1328Y1661D01* +X1328Y1659D01* +X1326Y1659D01* +X1326Y1657D01* +X1322Y1657D01* +X1322Y1477D01* +X1320Y1477D01* +X1320Y1123D01* +X1424Y1123D01* +X1424Y1121D01* +X1660Y1121D01* +X1660Y1123D01* +X1662Y1123D01* +X1662Y1125D01* +X1664Y1125D01* +X1664Y1127D01* +X1666Y1127D01* +X1666Y1131D01* +X1668Y1131D01* +X1668Y1133D01* +X1672Y1133D01* +X1672Y1135D01* +X1674Y1135D01* +X1674Y1137D01* +X1678Y1137D01* +X1678Y1139D01* +X1680Y1139D01* +X1680Y1159D01* +X1678Y1159D01* +X1678Y1161D01* +X1674Y1161D01* +X1674Y1163D01* +X1672Y1163D01* +X1672Y1165D01* +X1668Y1165D01* +X1668Y1167D01* +X1666Y1167D01* +X1666Y1171D01* +X1664Y1171D01* +X1664Y1173D01* +X1662Y1173D01* +X1662Y1175D01* +X1660Y1175D01* +X1660Y1177D01* +X1392Y1177D01* +X1392Y1179D01* +X1386Y1179D01* +X1386Y1181D01* +X1384Y1181D01* +X1384Y1183D01* +X1382Y1183D01* +X1382Y1185D01* +X1380Y1185D01* +X1380Y1187D01* +X1378Y1187D01* +X1378Y1191D01* +X1376Y1191D01* +X1376Y1633D01* +X1378Y1633D01* +X1378Y1655D01* +X1376Y1655D01* +X1376Y1657D01* +X1372Y1657D01* +X1372Y1659D01* +X1370Y1659D01* +X1370Y1661D01* +X1368Y1661D01* +X1368Y1663D01* +X1366Y1663D01* +X1366Y1665D01* +X1364Y1665D01* +X1364Y1667D01* +X1362Y1667D01* +X1362Y1669D01* +X1360Y1669D01* +X1360Y1671D01* +X1338Y1671D01* +G37* +D02* +G36* +X1438Y1671D02* +X1438Y1669D01* +X1436Y1669D01* +X1436Y1665D01* +X1434Y1665D01* +X1434Y1663D01* +X1430Y1663D01* +X1430Y1661D01* +X1428Y1661D01* +X1428Y1659D01* +X1426Y1659D01* +X1426Y1657D01* +X1422Y1657D01* +X1422Y1629D01* +X1420Y1629D01* +X1420Y1221D01* +X1660Y1221D01* +X1660Y1223D01* +X1662Y1223D01* +X1662Y1225D01* +X1664Y1225D01* +X1664Y1227D01* +X1666Y1227D01* +X1666Y1231D01* +X1668Y1231D01* +X1668Y1233D01* +X1672Y1233D01* +X1672Y1235D01* +X1674Y1235D01* +X1674Y1237D01* +X1678Y1237D01* +X1678Y1239D01* +X1680Y1239D01* +X1680Y1259D01* +X1678Y1259D01* +X1678Y1261D01* +X1674Y1261D01* +X1674Y1263D01* +X1672Y1263D01* +X1672Y1265D01* +X1668Y1265D01* +X1668Y1267D01* +X1666Y1267D01* +X1666Y1271D01* +X1664Y1271D01* +X1664Y1273D01* +X1662Y1273D01* +X1662Y1275D01* +X1660Y1275D01* +X1660Y1279D01* +X1658Y1279D01* +X1658Y1285D01* +X1656Y1285D01* +X1656Y1291D01* +X1654Y1291D01* +X1654Y1307D01* +X1656Y1307D01* +X1656Y1313D01* +X1658Y1313D01* +X1658Y1319D01* +X1660Y1319D01* +X1660Y1323D01* +X1662Y1323D01* +X1662Y1325D01* +X1664Y1325D01* +X1664Y1327D01* +X1666Y1327D01* +X1666Y1331D01* +X1668Y1331D01* +X1668Y1333D01* +X1672Y1333D01* +X1672Y1335D01* +X1674Y1335D01* +X1674Y1337D01* +X1678Y1337D01* +X1678Y1339D01* +X1680Y1339D01* +X1680Y1359D01* +X1678Y1359D01* +X1678Y1361D01* +X1674Y1361D01* +X1674Y1363D01* +X1672Y1363D01* +X1672Y1365D01* +X1668Y1365D01* +X1668Y1367D01* +X1666Y1367D01* +X1666Y1371D01* +X1664Y1371D01* +X1664Y1373D01* +X1662Y1373D01* +X1662Y1375D01* +X1660Y1375D01* +X1660Y1379D01* +X1658Y1379D01* +X1658Y1385D01* +X1656Y1385D01* +X1656Y1391D01* +X1654Y1391D01* +X1654Y1407D01* +X1656Y1407D01* +X1656Y1413D01* +X1658Y1413D01* +X1658Y1419D01* +X1660Y1419D01* +X1660Y1423D01* +X1662Y1423D01* +X1662Y1425D01* +X1664Y1425D01* +X1664Y1427D01* +X1666Y1427D01* +X1666Y1431D01* +X1668Y1431D01* +X1668Y1433D01* +X1672Y1433D01* +X1672Y1435D01* +X1674Y1435D01* +X1674Y1437D01* +X1678Y1437D01* +X1678Y1439D01* +X1680Y1439D01* +X1680Y1459D01* +X1678Y1459D01* +X1678Y1461D01* +X1674Y1461D01* +X1674Y1463D01* +X1672Y1463D01* +X1672Y1465D01* +X1668Y1465D01* +X1668Y1467D01* +X1666Y1467D01* +X1666Y1471D01* +X1664Y1471D01* +X1664Y1473D01* +X1662Y1473D01* +X1662Y1475D01* +X1660Y1475D01* +X1660Y1477D01* +X1498Y1477D01* +X1498Y1479D01* +X1490Y1479D01* +X1490Y1481D01* +X1488Y1481D01* +X1488Y1483D01* +X1484Y1483D01* +X1484Y1487D01* +X1482Y1487D01* +X1482Y1489D01* +X1480Y1489D01* +X1480Y1493D01* +X1478Y1493D01* +X1478Y1655D01* +X1476Y1655D01* +X1476Y1657D01* +X1472Y1657D01* +X1472Y1659D01* +X1470Y1659D01* +X1470Y1661D01* +X1468Y1661D01* +X1468Y1663D01* +X1466Y1663D01* +X1466Y1665D01* +X1464Y1665D01* +X1464Y1667D01* +X1462Y1667D01* +X1462Y1669D01* +X1460Y1669D01* +X1460Y1671D01* +X1438Y1671D01* +G37* +D02* +G36* +X132Y1759D02* +X132Y1739D01* +X136Y1739D01* +X136Y1737D01* +X138Y1737D01* +X138Y1735D01* +X140Y1735D01* +X140Y1731D01* +X142Y1731D01* +X142Y1729D01* +X144Y1729D01* +X144Y1725D01* +X146Y1725D01* +X146Y1721D01* +X148Y1721D01* +X148Y1717D01* +X150Y1717D01* +X150Y1711D01* +X152Y1711D01* +X152Y1687D01* +X150Y1687D01* +X150Y1681D01* +X148Y1681D01* +X148Y1677D01* +X146Y1677D01* +X146Y1673D01* +X144Y1673D01* +X144Y1669D01* +X142Y1669D01* +X142Y1667D01* +X140Y1667D01* +X140Y1663D01* +X138Y1663D01* +X138Y1661D01* +X136Y1661D01* +X136Y1659D01* +X132Y1659D01* +X132Y1657D01* +X130Y1657D01* +X130Y1655D01* +X128Y1655D01* +X128Y1653D01* +X124Y1653D01* +X124Y1651D01* +X120Y1651D01* +X120Y1649D01* +X114Y1649D01* +X114Y1647D01* +X104Y1647D01* +X104Y1645D01* +X272Y1645D01* +X272Y1659D01* +X270Y1659D01* +X270Y1661D01* +X268Y1661D01* +X268Y1663D01* +X266Y1663D01* +X266Y1665D01* +X264Y1665D01* +X264Y1667D01* +X262Y1667D01* +X262Y1669D01* +X260Y1669D01* +X260Y1671D01* +X258Y1671D01* +X258Y1675D01* +X256Y1675D01* +X256Y1679D01* +X254Y1679D01* +X254Y1683D01* +X252Y1683D01* +X252Y1691D01* +X250Y1691D01* +X250Y1707D01* +X252Y1707D01* +X252Y1715D01* +X254Y1715D01* +X254Y1719D01* +X256Y1719D01* +X256Y1723D01* +X258Y1723D01* +X258Y1727D01* +X260Y1727D01* +X260Y1729D01* +X262Y1729D01* +X262Y1731D01* +X264Y1731D01* +X264Y1733D01* +X266Y1733D01* +X266Y1735D01* +X268Y1735D01* +X268Y1737D01* +X270Y1737D01* +X270Y1739D01* +X272Y1739D01* +X272Y1759D01* +X132Y1759D01* +G37* +D02* +G36* +X326Y1759D02* +X326Y1739D01* +X328Y1739D01* +X328Y1737D01* +X332Y1737D01* +X332Y1735D01* +X334Y1735D01* +X334Y1733D01* +X336Y1733D01* +X336Y1729D01* +X338Y1729D01* +X338Y1727D01* +X340Y1727D01* +X340Y1725D01* +X342Y1725D01* +X342Y1721D01* +X344Y1721D01* +X344Y1717D01* +X346Y1717D01* +X346Y1709D01* +X348Y1709D01* +X348Y1689D01* +X346Y1689D01* +X346Y1681D01* +X344Y1681D01* +X344Y1677D01* +X342Y1677D01* +X342Y1673D01* +X340Y1673D01* +X340Y1671D01* +X338Y1671D01* +X338Y1669D01* +X336Y1669D01* +X336Y1665D01* +X334Y1665D01* +X334Y1663D01* +X330Y1663D01* +X330Y1661D01* +X328Y1661D01* +X328Y1659D01* +X326Y1659D01* +X326Y1639D01* +X328Y1639D01* +X328Y1637D01* +X332Y1637D01* +X332Y1635D01* +X334Y1635D01* +X334Y1633D01* +X336Y1633D01* +X336Y1629D01* +X338Y1629D01* +X338Y1627D01* +X340Y1627D01* +X340Y1625D01* +X342Y1625D01* +X342Y1621D01* +X344Y1621D01* +X344Y1617D01* +X346Y1617D01* +X346Y1609D01* +X348Y1609D01* +X348Y1589D01* +X346Y1589D01* +X346Y1581D01* +X344Y1581D01* +X344Y1577D01* +X342Y1577D01* +X342Y1573D01* +X340Y1573D01* +X340Y1571D01* +X338Y1571D01* +X338Y1569D01* +X336Y1569D01* +X336Y1565D01* +X334Y1565D01* +X334Y1563D01* +X330Y1563D01* +X330Y1561D01* +X328Y1561D01* +X328Y1559D01* +X326Y1559D01* +X326Y1557D01* +X322Y1557D01* +X322Y1555D01* +X318Y1555D01* +X318Y1553D01* +X312Y1553D01* +X312Y1551D01* +X986Y1551D01* +X986Y1553D01* +X980Y1553D01* +X980Y1555D01* +X976Y1555D01* +X976Y1557D01* +X972Y1557D01* +X972Y1559D01* +X970Y1559D01* +X970Y1561D01* +X968Y1561D01* +X968Y1563D01* +X966Y1563D01* +X966Y1565D01* +X964Y1565D01* +X964Y1567D01* +X962Y1567D01* +X962Y1569D01* +X960Y1569D01* +X960Y1571D01* +X958Y1571D01* +X958Y1575D01* +X956Y1575D01* +X956Y1579D01* +X954Y1579D01* +X954Y1583D01* +X952Y1583D01* +X952Y1591D01* +X950Y1591D01* +X950Y1607D01* +X952Y1607D01* +X952Y1615D01* +X954Y1615D01* +X954Y1619D01* +X956Y1619D01* +X956Y1623D01* +X958Y1623D01* +X958Y1627D01* +X960Y1627D01* +X960Y1629D01* +X962Y1629D01* +X962Y1631D01* +X964Y1631D01* +X964Y1633D01* +X966Y1633D01* +X966Y1635D01* +X968Y1635D01* +X968Y1637D01* +X970Y1637D01* +X970Y1639D01* +X972Y1639D01* +X972Y1659D01* +X970Y1659D01* +X970Y1661D01* +X968Y1661D01* +X968Y1663D01* +X966Y1663D01* +X966Y1665D01* +X964Y1665D01* +X964Y1667D01* +X962Y1667D01* +X962Y1669D01* +X960Y1669D01* +X960Y1671D01* +X958Y1671D01* +X958Y1675D01* +X956Y1675D01* +X956Y1679D01* +X954Y1679D01* +X954Y1683D01* +X952Y1683D01* +X952Y1691D01* +X950Y1691D01* +X950Y1707D01* +X952Y1707D01* +X952Y1715D01* +X954Y1715D01* +X954Y1719D01* +X956Y1719D01* +X956Y1723D01* +X958Y1723D01* +X958Y1727D01* +X960Y1727D01* +X960Y1729D01* +X962Y1729D01* +X962Y1731D01* +X964Y1731D01* +X964Y1733D01* +X966Y1733D01* +X966Y1735D01* +X968Y1735D01* +X968Y1737D01* +X970Y1737D01* +X970Y1739D01* +X972Y1739D01* +X972Y1759D01* +X326Y1759D01* +G37* +D02* +G36* +X1026Y1759D02* +X1026Y1739D01* +X1028Y1739D01* +X1028Y1737D01* +X1032Y1737D01* +X1032Y1735D01* +X1034Y1735D01* +X1034Y1733D01* +X1036Y1733D01* +X1036Y1729D01* +X1038Y1729D01* +X1038Y1727D01* +X1040Y1727D01* +X1040Y1725D01* +X1042Y1725D01* +X1042Y1721D01* +X1044Y1721D01* +X1044Y1717D01* +X1046Y1717D01* +X1046Y1709D01* +X1048Y1709D01* +X1048Y1689D01* +X1046Y1689D01* +X1046Y1681D01* +X1044Y1681D01* +X1044Y1677D01* +X1042Y1677D01* +X1042Y1673D01* +X1040Y1673D01* +X1040Y1671D01* +X1038Y1671D01* +X1038Y1669D01* +X1036Y1669D01* +X1036Y1665D01* +X1034Y1665D01* +X1034Y1663D01* +X1030Y1663D01* +X1030Y1661D01* +X1028Y1661D01* +X1028Y1659D01* +X1026Y1659D01* +X1026Y1639D01* +X1028Y1639D01* +X1028Y1637D01* +X1032Y1637D01* +X1032Y1635D01* +X1034Y1635D01* +X1034Y1633D01* +X1036Y1633D01* +X1036Y1629D01* +X1038Y1629D01* +X1038Y1627D01* +X1040Y1627D01* +X1040Y1625D01* +X1042Y1625D01* +X1042Y1621D01* +X1044Y1621D01* +X1044Y1617D01* +X1046Y1617D01* +X1046Y1609D01* +X1048Y1609D01* +X1048Y1589D01* +X1046Y1589D01* +X1046Y1581D01* +X1044Y1581D01* +X1044Y1577D01* +X1042Y1577D01* +X1042Y1573D01* +X1040Y1573D01* +X1040Y1571D01* +X1038Y1571D01* +X1038Y1569D01* +X1036Y1569D01* +X1036Y1565D01* +X1034Y1565D01* +X1034Y1563D01* +X1030Y1563D01* +X1030Y1561D01* +X1028Y1561D01* +X1028Y1559D01* +X1026Y1559D01* +X1026Y1557D01* +X1022Y1557D01* +X1022Y1555D01* +X1018Y1555D01* +X1018Y1553D01* +X1012Y1553D01* +X1012Y1551D01* +X1178Y1551D01* +X1178Y1655D01* +X1176Y1655D01* +X1176Y1657D01* +X1172Y1657D01* +X1172Y1659D01* +X1170Y1659D01* +X1170Y1661D01* +X1168Y1661D01* +X1168Y1663D01* +X1166Y1663D01* +X1166Y1665D01* +X1164Y1665D01* +X1164Y1667D01* +X1162Y1667D01* +X1162Y1669D01* +X1160Y1669D01* +X1160Y1671D01* +X1158Y1671D01* +X1158Y1675D01* +X1156Y1675D01* +X1156Y1679D01* +X1154Y1679D01* +X1154Y1683D01* +X1152Y1683D01* +X1152Y1691D01* +X1150Y1691D01* +X1150Y1707D01* +X1152Y1707D01* +X1152Y1715D01* +X1154Y1715D01* +X1154Y1719D01* +X1156Y1719D01* +X1156Y1723D01* +X1158Y1723D01* +X1158Y1727D01* +X1160Y1727D01* +X1160Y1729D01* +X1162Y1729D01* +X1162Y1731D01* +X1164Y1731D01* +X1164Y1733D01* +X1166Y1733D01* +X1166Y1735D01* +X1168Y1735D01* +X1168Y1737D01* +X1170Y1737D01* +X1170Y1739D01* +X1172Y1739D01* +X1172Y1759D01* +X1026Y1759D01* +G37* +D02* +G36* +X1526Y1759D02* +X1526Y1739D01* +X1528Y1739D01* +X1528Y1737D01* +X1532Y1737D01* +X1532Y1735D01* +X1534Y1735D01* +X1534Y1733D01* +X1536Y1733D01* +X1536Y1729D01* +X1538Y1729D01* +X1538Y1727D01* +X1540Y1727D01* +X1540Y1725D01* +X1542Y1725D01* +X1542Y1721D01* +X1544Y1721D01* +X1544Y1717D01* +X1546Y1717D01* +X1546Y1709D01* +X1548Y1709D01* +X1548Y1689D01* +X1546Y1689D01* +X1546Y1681D01* +X1544Y1681D01* +X1544Y1677D01* +X1542Y1677D01* +X1542Y1673D01* +X1540Y1673D01* +X1540Y1671D01* +X1538Y1671D01* +X1538Y1669D01* +X1536Y1669D01* +X1536Y1665D01* +X1534Y1665D01* +X1534Y1663D01* +X1530Y1663D01* +X1530Y1661D01* +X1528Y1661D01* +X1528Y1659D01* +X1526Y1659D01* +X1526Y1657D01* +X1522Y1657D01* +X1522Y1645D01* +X1744Y1645D01* +X1744Y1621D01* +X1808Y1621D01* +X1808Y1619D01* +X1812Y1619D01* +X1812Y1617D01* +X1814Y1617D01* +X1814Y1615D01* +X1816Y1615D01* +X1816Y1613D01* +X1818Y1613D01* +X1818Y1609D01* +X1820Y1609D01* +X1820Y155D01* +X2288Y155D01* +X2288Y157D01* +X2282Y157D01* +X2282Y159D01* +X2278Y159D01* +X2278Y161D01* +X2274Y161D01* +X2274Y163D01* +X2272Y163D01* +X2272Y165D01* +X2268Y165D01* +X2268Y167D01* +X2266Y167D01* +X2266Y171D01* +X2264Y171D01* +X2264Y173D01* +X2262Y173D01* +X2262Y175D01* +X2260Y175D01* +X2260Y179D01* +X2258Y179D01* +X2258Y185D01* +X2256Y185D01* +X2256Y191D01* +X2254Y191D01* +X2254Y207D01* +X2256Y207D01* +X2256Y213D01* +X2258Y213D01* +X2258Y219D01* +X2260Y219D01* +X2260Y223D01* +X2262Y223D01* +X2262Y225D01* +X2264Y225D01* +X2264Y227D01* +X2266Y227D01* +X2266Y231D01* +X2268Y231D01* +X2268Y233D01* +X2272Y233D01* +X2272Y235D01* +X2274Y235D01* +X2274Y237D01* +X2278Y237D01* +X2278Y239D01* +X2280Y239D01* +X2280Y259D01* +X2278Y259D01* +X2278Y261D01* +X2274Y261D01* +X2274Y263D01* +X2272Y263D01* +X2272Y265D01* +X2268Y265D01* +X2268Y267D01* +X2266Y267D01* +X2266Y271D01* +X2264Y271D01* +X2264Y273D01* +X2262Y273D01* +X2262Y275D01* +X2260Y275D01* +X2260Y279D01* +X2258Y279D01* +X2258Y285D01* +X2256Y285D01* +X2256Y291D01* +X2254Y291D01* +X2254Y307D01* +X2256Y307D01* +X2256Y313D01* +X2258Y313D01* +X2258Y319D01* +X2260Y319D01* +X2260Y323D01* +X2262Y323D01* +X2262Y325D01* +X2264Y325D01* +X2264Y327D01* +X2266Y327D01* +X2266Y331D01* +X2268Y331D01* +X2268Y333D01* +X2272Y333D01* +X2272Y335D01* +X2274Y335D01* +X2274Y337D01* +X2278Y337D01* +X2278Y339D01* +X2280Y339D01* +X2280Y359D01* +X2278Y359D01* +X2278Y361D01* +X2274Y361D01* +X2274Y363D01* +X2272Y363D01* +X2272Y365D01* +X2268Y365D01* +X2268Y367D01* +X2266Y367D01* +X2266Y371D01* +X2264Y371D01* +X2264Y373D01* +X2262Y373D01* +X2262Y375D01* +X2260Y375D01* +X2260Y379D01* +X2258Y379D01* +X2258Y385D01* +X2256Y385D01* +X2256Y391D01* +X2254Y391D01* +X2254Y407D01* +X2256Y407D01* +X2256Y413D01* +X2258Y413D01* +X2258Y419D01* +X2260Y419D01* +X2260Y423D01* +X2262Y423D01* +X2262Y425D01* +X2264Y425D01* +X2264Y427D01* +X2266Y427D01* +X2266Y431D01* +X2268Y431D01* +X2268Y433D01* +X2272Y433D01* +X2272Y435D01* +X2274Y435D01* +X2274Y437D01* +X2278Y437D01* +X2278Y439D01* +X2280Y439D01* +X2280Y459D01* +X2278Y459D01* +X2278Y461D01* +X2274Y461D01* +X2274Y463D01* +X2272Y463D01* +X2272Y465D01* +X2268Y465D01* +X2268Y467D01* +X2266Y467D01* +X2266Y471D01* +X2264Y471D01* +X2264Y473D01* +X2262Y473D01* +X2262Y475D01* +X2260Y475D01* +X2260Y479D01* +X2258Y479D01* +X2258Y485D01* +X2256Y485D01* +X2256Y491D01* +X2254Y491D01* +X2254Y507D01* +X2256Y507D01* +X2256Y513D01* +X2258Y513D01* +X2258Y519D01* +X2260Y519D01* +X2260Y523D01* +X2262Y523D01* +X2262Y525D01* +X2264Y525D01* +X2264Y527D01* +X2266Y527D01* +X2266Y531D01* +X2268Y531D01* +X2268Y533D01* +X2272Y533D01* +X2272Y535D01* +X2274Y535D01* +X2274Y537D01* +X2278Y537D01* +X2278Y539D01* +X2280Y539D01* +X2280Y559D01* +X2278Y559D01* +X2278Y561D01* +X2274Y561D01* +X2274Y563D01* +X2272Y563D01* +X2272Y565D01* +X2268Y565D01* +X2268Y567D01* +X2266Y567D01* +X2266Y571D01* +X2264Y571D01* +X2264Y573D01* +X2262Y573D01* +X2262Y575D01* +X2260Y575D01* +X2260Y579D01* +X2258Y579D01* +X2258Y585D01* +X2256Y585D01* +X2256Y591D01* +X2254Y591D01* +X2254Y607D01* +X2256Y607D01* +X2256Y613D01* +X2258Y613D01* +X2258Y619D01* +X2260Y619D01* +X2260Y623D01* +X2262Y623D01* +X2262Y625D01* +X2264Y625D01* +X2264Y627D01* +X2266Y627D01* +X2266Y631D01* +X2268Y631D01* +X2268Y633D01* +X2272Y633D01* +X2272Y635D01* +X2274Y635D01* +X2274Y637D01* +X2278Y637D01* +X2278Y639D01* +X2280Y639D01* +X2280Y659D01* +X2278Y659D01* +X2278Y661D01* +X2274Y661D01* +X2274Y663D01* +X2272Y663D01* +X2272Y665D01* +X2268Y665D01* +X2268Y667D01* +X2266Y667D01* +X2266Y671D01* +X2264Y671D01* +X2264Y673D01* +X2262Y673D01* +X2262Y675D01* +X2260Y675D01* +X2260Y679D01* +X2258Y679D01* +X2258Y685D01* +X2256Y685D01* +X2256Y691D01* +X2254Y691D01* +X2254Y707D01* +X2256Y707D01* +X2256Y713D01* +X2258Y713D01* +X2258Y719D01* +X2260Y719D01* +X2260Y723D01* +X2262Y723D01* +X2262Y725D01* +X2264Y725D01* +X2264Y727D01* +X2266Y727D01* +X2266Y731D01* +X2268Y731D01* +X2268Y733D01* +X2272Y733D01* +X2272Y735D01* +X2274Y735D01* +X2274Y737D01* +X2278Y737D01* +X2278Y739D01* +X2280Y739D01* +X2280Y759D01* +X2278Y759D01* +X2278Y761D01* +X2274Y761D01* +X2274Y763D01* +X2272Y763D01* +X2272Y765D01* +X2268Y765D01* +X2268Y767D01* +X2266Y767D01* +X2266Y771D01* +X2264Y771D01* +X2264Y773D01* +X2262Y773D01* +X2262Y775D01* +X2260Y775D01* +X2260Y779D01* +X2258Y779D01* +X2258Y785D01* +X2256Y785D01* +X2256Y791D01* +X2254Y791D01* +X2254Y807D01* +X2256Y807D01* +X2256Y813D01* +X2258Y813D01* +X2258Y819D01* +X2260Y819D01* +X2260Y823D01* +X2262Y823D01* +X2262Y825D01* +X2264Y825D01* +X2264Y827D01* +X2266Y827D01* +X2266Y831D01* +X2268Y831D01* +X2268Y833D01* +X2272Y833D01* +X2272Y835D01* +X2274Y835D01* +X2274Y837D01* +X2278Y837D01* +X2278Y839D01* +X2280Y839D01* +X2280Y859D01* +X2278Y859D01* +X2278Y861D01* +X2274Y861D01* +X2274Y863D01* +X2272Y863D01* +X2272Y865D01* +X2268Y865D01* +X2268Y867D01* +X2266Y867D01* +X2266Y871D01* +X2264Y871D01* +X2264Y873D01* +X2262Y873D01* +X2262Y875D01* +X2260Y875D01* +X2260Y879D01* +X2258Y879D01* +X2258Y885D01* +X2256Y885D01* +X2256Y891D01* +X2254Y891D01* +X2254Y907D01* +X2256Y907D01* +X2256Y913D01* +X2258Y913D01* +X2258Y919D01* +X2260Y919D01* +X2260Y923D01* +X2262Y923D01* +X2262Y925D01* +X2264Y925D01* +X2264Y927D01* +X2266Y927D01* +X2266Y931D01* +X2268Y931D01* +X2268Y933D01* +X2272Y933D01* +X2272Y935D01* +X2274Y935D01* +X2274Y937D01* +X2278Y937D01* +X2278Y939D01* +X2280Y939D01* +X2280Y959D01* +X2278Y959D01* +X2278Y961D01* +X2274Y961D01* +X2274Y963D01* +X2272Y963D01* +X2272Y965D01* +X2268Y965D01* +X2268Y967D01* +X2266Y967D01* +X2266Y971D01* +X2264Y971D01* +X2264Y973D01* +X2262Y973D01* +X2262Y975D01* +X2260Y975D01* +X2260Y979D01* +X2258Y979D01* +X2258Y985D01* +X2256Y985D01* +X2256Y991D01* +X2254Y991D01* +X2254Y1007D01* +X2256Y1007D01* +X2256Y1013D01* +X2258Y1013D01* +X2258Y1019D01* +X2260Y1019D01* +X2260Y1023D01* +X2262Y1023D01* +X2262Y1025D01* +X2264Y1025D01* +X2264Y1027D01* +X2266Y1027D01* +X2266Y1031D01* +X2268Y1031D01* +X2268Y1033D01* +X2272Y1033D01* +X2272Y1035D01* +X2274Y1035D01* +X2274Y1037D01* +X2278Y1037D01* +X2278Y1039D01* +X2280Y1039D01* +X2280Y1059D01* +X2278Y1059D01* +X2278Y1061D01* +X2274Y1061D01* +X2274Y1063D01* +X2272Y1063D01* +X2272Y1065D01* +X2268Y1065D01* +X2268Y1067D01* +X2266Y1067D01* +X2266Y1071D01* +X2264Y1071D01* +X2264Y1073D01* +X2262Y1073D01* +X2262Y1075D01* +X2260Y1075D01* +X2260Y1079D01* +X2258Y1079D01* +X2258Y1085D01* +X2256Y1085D01* +X2256Y1091D01* +X2254Y1091D01* +X2254Y1107D01* +X2256Y1107D01* +X2256Y1113D01* +X2258Y1113D01* +X2258Y1119D01* +X2260Y1119D01* +X2260Y1123D01* +X2262Y1123D01* +X2262Y1125D01* +X2264Y1125D01* +X2264Y1127D01* +X2266Y1127D01* +X2266Y1131D01* +X2268Y1131D01* +X2268Y1133D01* +X2272Y1133D01* +X2272Y1135D01* +X2274Y1135D01* +X2274Y1137D01* +X2278Y1137D01* +X2278Y1139D01* +X2280Y1139D01* +X2280Y1159D01* +X2278Y1159D01* +X2278Y1161D01* +X2274Y1161D01* +X2274Y1163D01* +X2272Y1163D01* +X2272Y1165D01* +X2268Y1165D01* +X2268Y1167D01* +X2266Y1167D01* +X2266Y1171D01* +X2264Y1171D01* +X2264Y1173D01* +X2262Y1173D01* +X2262Y1175D01* +X2260Y1175D01* +X2260Y1179D01* +X2258Y1179D01* +X2258Y1185D01* +X2256Y1185D01* +X2256Y1191D01* +X2254Y1191D01* +X2254Y1207D01* +X2256Y1207D01* +X2256Y1213D01* +X2258Y1213D01* +X2258Y1219D01* +X2260Y1219D01* +X2260Y1223D01* +X2262Y1223D01* +X2262Y1225D01* +X2264Y1225D01* +X2264Y1227D01* +X2266Y1227D01* +X2266Y1231D01* +X2268Y1231D01* +X2268Y1233D01* +X2272Y1233D01* +X2272Y1235D01* +X2274Y1235D01* +X2274Y1237D01* +X2278Y1237D01* +X2278Y1239D01* +X2280Y1239D01* +X2280Y1259D01* +X2278Y1259D01* +X2278Y1261D01* +X2274Y1261D01* +X2274Y1263D01* +X2272Y1263D01* +X2272Y1265D01* +X2268Y1265D01* +X2268Y1267D01* +X2266Y1267D01* +X2266Y1271D01* +X2264Y1271D01* +X2264Y1273D01* +X2262Y1273D01* +X2262Y1275D01* +X2260Y1275D01* +X2260Y1279D01* +X2258Y1279D01* +X2258Y1285D01* +X2256Y1285D01* +X2256Y1291D01* +X2254Y1291D01* +X2254Y1307D01* +X2256Y1307D01* +X2256Y1313D01* +X2258Y1313D01* +X2258Y1319D01* +X2260Y1319D01* +X2260Y1323D01* +X2262Y1323D01* +X2262Y1325D01* +X2264Y1325D01* +X2264Y1327D01* +X2266Y1327D01* +X2266Y1331D01* +X2268Y1331D01* +X2268Y1333D01* +X2272Y1333D01* +X2272Y1335D01* +X2274Y1335D01* +X2274Y1337D01* +X2278Y1337D01* +X2278Y1339D01* +X2280Y1339D01* +X2280Y1359D01* +X2278Y1359D01* +X2278Y1361D01* +X2274Y1361D01* +X2274Y1363D01* +X2272Y1363D01* +X2272Y1365D01* +X2268Y1365D01* +X2268Y1367D01* +X2266Y1367D01* +X2266Y1371D01* +X2264Y1371D01* +X2264Y1373D01* +X2262Y1373D01* +X2262Y1375D01* +X2260Y1375D01* +X2260Y1379D01* +X2258Y1379D01* +X2258Y1385D01* +X2256Y1385D01* +X2256Y1391D01* +X2254Y1391D01* +X2254Y1407D01* +X2256Y1407D01* +X2256Y1413D01* +X2258Y1413D01* +X2258Y1419D01* +X2260Y1419D01* +X2260Y1423D01* +X2262Y1423D01* +X2262Y1425D01* +X2264Y1425D01* +X2264Y1427D01* +X2266Y1427D01* +X2266Y1431D01* +X2268Y1431D01* +X2268Y1433D01* +X2272Y1433D01* +X2272Y1435D01* +X2274Y1435D01* +X2274Y1437D01* +X2278Y1437D01* +X2278Y1439D01* +X2280Y1439D01* +X2280Y1459D01* +X2278Y1459D01* +X2278Y1461D01* +X2274Y1461D01* +X2274Y1463D01* +X2272Y1463D01* +X2272Y1465D01* +X2268Y1465D01* +X2268Y1467D01* +X2266Y1467D01* +X2266Y1471D01* +X2264Y1471D01* +X2264Y1473D01* +X2262Y1473D01* +X2262Y1475D01* +X2260Y1475D01* +X2260Y1479D01* +X2258Y1479D01* +X2258Y1485D01* +X2256Y1485D01* +X2256Y1491D01* +X2254Y1491D01* +X2254Y1507D01* +X2256Y1507D01* +X2256Y1513D01* +X2258Y1513D01* +X2258Y1519D01* +X2260Y1519D01* +X2260Y1523D01* +X2262Y1523D01* +X2262Y1525D01* +X2264Y1525D01* +X2264Y1527D01* +X2266Y1527D01* +X2266Y1531D01* +X2268Y1531D01* +X2268Y1533D01* +X2272Y1533D01* +X2272Y1535D01* +X2274Y1535D01* +X2274Y1537D01* +X2278Y1537D01* +X2278Y1539D01* +X2280Y1539D01* +X2280Y1559D01* +X2278Y1559D01* +X2278Y1561D01* +X2274Y1561D01* +X2274Y1563D01* +X2272Y1563D01* +X2272Y1565D01* +X2268Y1565D01* +X2268Y1567D01* +X2266Y1567D01* +X2266Y1571D01* +X2264Y1571D01* +X2264Y1573D01* +X2262Y1573D01* +X2262Y1575D01* +X2260Y1575D01* +X2260Y1579D01* +X2258Y1579D01* +X2258Y1585D01* +X2256Y1585D01* +X2256Y1591D01* +X2254Y1591D01* +X2254Y1607D01* +X2256Y1607D01* +X2256Y1613D01* +X2258Y1613D01* +X2258Y1619D01* +X2260Y1619D01* +X2260Y1623D01* +X2262Y1623D01* +X2262Y1625D01* +X2264Y1625D01* +X2264Y1627D01* +X2266Y1627D01* +X2266Y1631D01* +X2268Y1631D01* +X2268Y1633D01* +X2272Y1633D01* +X2272Y1635D01* +X2274Y1635D01* +X2274Y1637D01* +X2278Y1637D01* +X2278Y1639D01* +X2280Y1639D01* +X2280Y1641D01* +X2286Y1641D01* +X2286Y1643D01* +X2298Y1643D01* +X2298Y1645D01* +X2494Y1645D01* +X2494Y1647D01* +X2484Y1647D01* +X2484Y1649D01* +X2478Y1649D01* +X2478Y1651D01* +X2476Y1651D01* +X2476Y1653D01* +X2472Y1653D01* +X2472Y1655D01* +X2468Y1655D01* +X2468Y1657D01* +X2466Y1657D01* +X2466Y1659D01* +X2464Y1659D01* +X2464Y1661D01* +X2462Y1661D01* +X2462Y1663D01* +X2460Y1663D01* +X2460Y1665D01* +X2458Y1665D01* +X2458Y1667D01* +X2456Y1667D01* +X2456Y1669D01* +X2454Y1669D01* +X2454Y1673D01* +X2452Y1673D01* +X2452Y1677D01* +X2450Y1677D01* +X2450Y1681D01* +X2448Y1681D01* +X2448Y1689D01* +X2446Y1689D01* +X2446Y1709D01* +X2448Y1709D01* +X2448Y1717D01* +X2450Y1717D01* +X2450Y1721D01* +X2452Y1721D01* +X2452Y1725D01* +X2454Y1725D01* +X2454Y1729D01* +X2456Y1729D01* +X2456Y1731D01* +X2458Y1731D01* +X2458Y1733D01* +X2460Y1733D01* +X2460Y1737D01* +X2464Y1737D01* +X2464Y1739D01* +X2466Y1739D01* +X2466Y1759D01* +X1526Y1759D01* +G37* +D02* +G36* +X2542Y1669D02* +X2542Y1667D01* +X2540Y1667D01* +X2540Y1663D01* +X2538Y1663D01* +X2538Y1661D01* +X2536Y1661D01* +X2536Y1659D01* +X2532Y1659D01* +X2532Y1657D01* +X2530Y1657D01* +X2530Y1655D01* +X2528Y1655D01* +X2528Y1653D01* +X2524Y1653D01* +X2524Y1651D01* +X2520Y1651D01* +X2520Y1649D01* +X2514Y1649D01* +X2514Y1647D01* +X2504Y1647D01* +X2504Y1645D01* +X2562Y1645D01* +X2562Y1669D01* +X2542Y1669D01* +G37* +D02* +G36* +X40Y1665D02* +X40Y1645D01* +X94Y1645D01* +X94Y1647D01* +X84Y1647D01* +X84Y1649D01* +X78Y1649D01* +X78Y1651D01* +X76Y1651D01* +X76Y1653D01* +X72Y1653D01* +X72Y1655D01* +X68Y1655D01* +X68Y1657D01* +X66Y1657D01* +X66Y1659D01* +X64Y1659D01* +X64Y1661D01* +X62Y1661D01* +X62Y1663D01* +X60Y1663D01* +X60Y1665D01* +X40Y1665D01* +G37* +D02* +G36* +X40Y1645D02* +X40Y1643D01* +X272Y1643D01* +X272Y1645D01* +X40Y1645D01* +G37* +D02* +G36* +X40Y1645D02* +X40Y1643D01* +X272Y1643D01* +X272Y1645D01* +X40Y1645D01* +G37* +D02* +G36* +X1522Y1645D02* +X1522Y1521D01* +X1660Y1521D01* +X1660Y1523D01* +X1662Y1523D01* +X1662Y1525D01* +X1664Y1525D01* +X1664Y1527D01* +X1666Y1527D01* +X1666Y1531D01* +X1668Y1531D01* +X1668Y1533D01* +X1672Y1533D01* +X1672Y1535D01* +X1674Y1535D01* +X1674Y1555D01* +X1654Y1555D01* +X1654Y1643D01* +X1656Y1643D01* +X1656Y1645D01* +X1522Y1645D01* +G37* +D02* +G36* +X2300Y1645D02* +X2300Y1643D01* +X2562Y1643D01* +X2562Y1645D01* +X2300Y1645D01* +G37* +D02* +G36* +X2300Y1645D02* +X2300Y1643D01* +X2562Y1643D01* +X2562Y1645D01* +X2300Y1645D01* +G37* +D02* +G36* +X40Y1643D02* +X40Y1551D01* +X286Y1551D01* +X286Y1553D01* +X280Y1553D01* +X280Y1555D01* +X276Y1555D01* +X276Y1557D01* +X272Y1557D01* +X272Y1559D01* +X270Y1559D01* +X270Y1561D01* +X268Y1561D01* +X268Y1563D01* +X266Y1563D01* +X266Y1565D01* +X264Y1565D01* +X264Y1567D01* +X262Y1567D01* +X262Y1569D01* +X260Y1569D01* +X260Y1571D01* +X258Y1571D01* +X258Y1575D01* +X256Y1575D01* +X256Y1579D01* +X254Y1579D01* +X254Y1583D01* +X252Y1583D01* +X252Y1591D01* +X250Y1591D01* +X250Y1607D01* +X252Y1607D01* +X252Y1615D01* +X254Y1615D01* +X254Y1619D01* +X256Y1619D01* +X256Y1623D01* +X258Y1623D01* +X258Y1627D01* +X260Y1627D01* +X260Y1629D01* +X262Y1629D01* +X262Y1631D01* +X264Y1631D01* +X264Y1633D01* +X266Y1633D01* +X266Y1635D01* +X268Y1635D01* +X268Y1637D01* +X270Y1637D01* +X270Y1639D01* +X272Y1639D01* +X272Y1643D01* +X40Y1643D01* +G37* +D02* +G36* +X2312Y1643D02* +X2312Y1641D01* +X2318Y1641D01* +X2318Y1639D01* +X2322Y1639D01* +X2322Y1637D01* +X2324Y1637D01* +X2324Y1635D01* +X2328Y1635D01* +X2328Y1633D01* +X2330Y1633D01* +X2330Y1631D01* +X2332Y1631D01* +X2332Y1629D01* +X2334Y1629D01* +X2334Y1627D01* +X2336Y1627D01* +X2336Y1623D01* +X2338Y1623D01* +X2338Y1619D01* +X2340Y1619D01* +X2340Y1615D01* +X2342Y1615D01* +X2342Y1609D01* +X2344Y1609D01* +X2344Y1589D01* +X2342Y1589D01* +X2342Y1583D01* +X2340Y1583D01* +X2340Y1579D01* +X2338Y1579D01* +X2338Y1575D01* +X2336Y1575D01* +X2336Y1573D01* +X2334Y1573D01* +X2334Y1569D01* +X2332Y1569D01* +X2332Y1567D01* +X2330Y1567D01* +X2330Y1565D01* +X2328Y1565D01* +X2328Y1563D01* +X2324Y1563D01* +X2324Y1561D01* +X2322Y1561D01* +X2322Y1559D01* +X2318Y1559D01* +X2318Y1539D01* +X2322Y1539D01* +X2322Y1537D01* +X2324Y1537D01* +X2324Y1535D01* +X2328Y1535D01* +X2328Y1533D01* +X2330Y1533D01* +X2330Y1531D01* +X2332Y1531D01* +X2332Y1529D01* +X2334Y1529D01* +X2334Y1527D01* +X2336Y1527D01* +X2336Y1523D01* +X2338Y1523D01* +X2338Y1519D01* +X2340Y1519D01* +X2340Y1515D01* +X2342Y1515D01* +X2342Y1509D01* +X2344Y1509D01* +X2344Y1489D01* +X2342Y1489D01* +X2342Y1483D01* +X2340Y1483D01* +X2340Y1479D01* +X2338Y1479D01* +X2338Y1475D01* +X2336Y1475D01* +X2336Y1473D01* +X2334Y1473D01* +X2334Y1469D01* +X2332Y1469D01* +X2332Y1467D01* +X2330Y1467D01* +X2330Y1465D01* +X2328Y1465D01* +X2328Y1463D01* +X2324Y1463D01* +X2324Y1461D01* +X2322Y1461D01* +X2322Y1459D01* +X2318Y1459D01* +X2318Y1439D01* +X2322Y1439D01* +X2322Y1437D01* +X2324Y1437D01* +X2324Y1435D01* +X2328Y1435D01* +X2328Y1433D01* +X2330Y1433D01* +X2330Y1431D01* +X2332Y1431D01* +X2332Y1429D01* +X2334Y1429D01* +X2334Y1427D01* +X2336Y1427D01* +X2336Y1423D01* +X2338Y1423D01* +X2338Y1419D01* +X2340Y1419D01* +X2340Y1415D01* +X2342Y1415D01* +X2342Y1409D01* +X2344Y1409D01* +X2344Y1389D01* +X2342Y1389D01* +X2342Y1383D01* +X2340Y1383D01* +X2340Y1379D01* +X2338Y1379D01* +X2338Y1375D01* +X2336Y1375D01* +X2336Y1373D01* +X2334Y1373D01* +X2334Y1369D01* +X2332Y1369D01* +X2332Y1367D01* +X2330Y1367D01* +X2330Y1365D01* +X2328Y1365D01* +X2328Y1363D01* +X2324Y1363D01* +X2324Y1361D01* +X2322Y1361D01* +X2322Y1359D01* +X2318Y1359D01* +X2318Y1339D01* +X2322Y1339D01* +X2322Y1337D01* +X2324Y1337D01* +X2324Y1335D01* +X2328Y1335D01* +X2328Y1333D01* +X2330Y1333D01* +X2330Y1331D01* +X2332Y1331D01* +X2332Y1329D01* +X2334Y1329D01* +X2334Y1327D01* +X2336Y1327D01* +X2336Y1323D01* +X2338Y1323D01* +X2338Y1319D01* +X2340Y1319D01* +X2340Y1315D01* +X2342Y1315D01* +X2342Y1309D01* +X2344Y1309D01* +X2344Y1289D01* +X2342Y1289D01* +X2342Y1283D01* +X2340Y1283D01* +X2340Y1279D01* +X2338Y1279D01* +X2338Y1275D01* +X2336Y1275D01* +X2336Y1273D01* +X2334Y1273D01* +X2334Y1269D01* +X2332Y1269D01* +X2332Y1267D01* +X2330Y1267D01* +X2330Y1265D01* +X2328Y1265D01* +X2328Y1263D01* +X2324Y1263D01* +X2324Y1261D01* +X2322Y1261D01* +X2322Y1259D01* +X2318Y1259D01* +X2318Y1239D01* +X2322Y1239D01* +X2322Y1237D01* +X2324Y1237D01* +X2324Y1235D01* +X2328Y1235D01* +X2328Y1233D01* +X2330Y1233D01* +X2330Y1231D01* +X2332Y1231D01* +X2332Y1229D01* +X2334Y1229D01* +X2334Y1227D01* +X2336Y1227D01* +X2336Y1223D01* +X2338Y1223D01* +X2338Y1219D01* +X2340Y1219D01* +X2340Y1215D01* +X2342Y1215D01* +X2342Y1209D01* +X2344Y1209D01* +X2344Y1189D01* +X2342Y1189D01* +X2342Y1183D01* +X2340Y1183D01* +X2340Y1179D01* +X2338Y1179D01* +X2338Y1175D01* +X2336Y1175D01* +X2336Y1173D01* +X2334Y1173D01* +X2334Y1169D01* +X2332Y1169D01* +X2332Y1167D01* +X2330Y1167D01* +X2330Y1165D01* +X2328Y1165D01* +X2328Y1163D01* +X2324Y1163D01* +X2324Y1161D01* +X2322Y1161D01* +X2322Y1159D01* +X2318Y1159D01* +X2318Y1139D01* +X2322Y1139D01* +X2322Y1137D01* +X2324Y1137D01* +X2324Y1135D01* +X2328Y1135D01* +X2328Y1133D01* +X2330Y1133D01* +X2330Y1131D01* +X2332Y1131D01* +X2332Y1129D01* +X2334Y1129D01* +X2334Y1127D01* +X2336Y1127D01* +X2336Y1123D01* +X2338Y1123D01* +X2338Y1119D01* +X2340Y1119D01* +X2340Y1115D01* +X2342Y1115D01* +X2342Y1109D01* +X2344Y1109D01* +X2344Y1089D01* +X2342Y1089D01* +X2342Y1083D01* +X2340Y1083D01* +X2340Y1079D01* +X2338Y1079D01* +X2338Y1075D01* +X2336Y1075D01* +X2336Y1073D01* +X2334Y1073D01* +X2334Y1069D01* +X2332Y1069D01* +X2332Y1067D01* +X2330Y1067D01* +X2330Y1065D01* +X2328Y1065D01* +X2328Y1063D01* +X2324Y1063D01* +X2324Y1061D01* +X2322Y1061D01* +X2322Y1059D01* +X2318Y1059D01* +X2318Y1039D01* +X2322Y1039D01* +X2322Y1037D01* +X2324Y1037D01* +X2324Y1035D01* +X2328Y1035D01* +X2328Y1033D01* +X2330Y1033D01* +X2330Y1031D01* +X2332Y1031D01* +X2332Y1029D01* +X2334Y1029D01* +X2334Y1027D01* +X2336Y1027D01* +X2336Y1023D01* +X2338Y1023D01* +X2338Y1019D01* +X2340Y1019D01* +X2340Y1015D01* +X2342Y1015D01* +X2342Y1009D01* +X2344Y1009D01* +X2344Y989D01* +X2342Y989D01* +X2342Y983D01* +X2340Y983D01* +X2340Y979D01* +X2338Y979D01* +X2338Y975D01* +X2336Y975D01* +X2336Y973D01* +X2334Y973D01* +X2334Y969D01* +X2332Y969D01* +X2332Y967D01* +X2330Y967D01* +X2330Y965D01* +X2328Y965D01* +X2328Y963D01* +X2324Y963D01* +X2324Y961D01* +X2322Y961D01* +X2322Y959D01* +X2318Y959D01* +X2318Y939D01* +X2322Y939D01* +X2322Y937D01* +X2324Y937D01* +X2324Y935D01* +X2328Y935D01* +X2328Y933D01* +X2330Y933D01* +X2330Y931D01* +X2332Y931D01* +X2332Y929D01* +X2334Y929D01* +X2334Y927D01* +X2336Y927D01* +X2336Y923D01* +X2338Y923D01* +X2338Y919D01* +X2340Y919D01* +X2340Y915D01* +X2342Y915D01* +X2342Y909D01* +X2344Y909D01* +X2344Y889D01* +X2342Y889D01* +X2342Y883D01* +X2340Y883D01* +X2340Y879D01* +X2338Y879D01* +X2338Y875D01* +X2336Y875D01* +X2336Y873D01* +X2334Y873D01* +X2334Y869D01* +X2332Y869D01* +X2332Y867D01* +X2330Y867D01* +X2330Y865D01* +X2328Y865D01* +X2328Y863D01* +X2324Y863D01* +X2324Y861D01* +X2322Y861D01* +X2322Y859D01* +X2318Y859D01* +X2318Y839D01* +X2322Y839D01* +X2322Y837D01* +X2324Y837D01* +X2324Y835D01* +X2328Y835D01* +X2328Y833D01* +X2330Y833D01* +X2330Y831D01* +X2332Y831D01* +X2332Y829D01* +X2334Y829D01* +X2334Y827D01* +X2336Y827D01* +X2336Y823D01* +X2338Y823D01* +X2338Y819D01* +X2340Y819D01* +X2340Y815D01* +X2342Y815D01* +X2342Y809D01* +X2344Y809D01* +X2344Y789D01* +X2342Y789D01* +X2342Y783D01* +X2340Y783D01* +X2340Y779D01* +X2338Y779D01* +X2338Y775D01* +X2336Y775D01* +X2336Y773D01* +X2334Y773D01* +X2334Y769D01* +X2332Y769D01* +X2332Y767D01* +X2330Y767D01* +X2330Y765D01* +X2328Y765D01* +X2328Y763D01* +X2324Y763D01* +X2324Y761D01* +X2322Y761D01* +X2322Y759D01* +X2318Y759D01* +X2318Y739D01* +X2322Y739D01* +X2322Y737D01* +X2324Y737D01* +X2324Y735D01* +X2328Y735D01* +X2328Y733D01* +X2330Y733D01* +X2330Y731D01* +X2332Y731D01* +X2332Y729D01* +X2334Y729D01* +X2334Y727D01* +X2336Y727D01* +X2336Y723D01* +X2338Y723D01* +X2338Y719D01* +X2340Y719D01* +X2340Y715D01* +X2342Y715D01* +X2342Y709D01* +X2344Y709D01* +X2344Y689D01* +X2342Y689D01* +X2342Y683D01* +X2340Y683D01* +X2340Y679D01* +X2338Y679D01* +X2338Y675D01* +X2336Y675D01* +X2336Y673D01* +X2334Y673D01* +X2334Y669D01* +X2332Y669D01* +X2332Y667D01* +X2330Y667D01* +X2330Y665D01* +X2328Y665D01* +X2328Y663D01* +X2324Y663D01* +X2324Y661D01* +X2322Y661D01* +X2322Y659D01* +X2318Y659D01* +X2318Y639D01* +X2322Y639D01* +X2322Y637D01* +X2324Y637D01* +X2324Y635D01* +X2328Y635D01* +X2328Y633D01* +X2330Y633D01* +X2330Y631D01* +X2332Y631D01* +X2332Y629D01* +X2334Y629D01* +X2334Y627D01* +X2336Y627D01* +X2336Y623D01* +X2338Y623D01* +X2338Y619D01* +X2340Y619D01* +X2340Y615D01* +X2342Y615D01* +X2342Y609D01* +X2344Y609D01* +X2344Y589D01* +X2342Y589D01* +X2342Y583D01* +X2340Y583D01* +X2340Y579D01* +X2338Y579D01* +X2338Y575D01* +X2336Y575D01* +X2336Y573D01* +X2334Y573D01* +X2334Y569D01* +X2332Y569D01* +X2332Y567D01* +X2330Y567D01* +X2330Y565D01* +X2328Y565D01* +X2328Y563D01* +X2324Y563D01* +X2324Y561D01* +X2322Y561D01* +X2322Y559D01* +X2318Y559D01* +X2318Y539D01* +X2322Y539D01* +X2322Y537D01* +X2324Y537D01* +X2324Y535D01* +X2328Y535D01* +X2328Y533D01* +X2330Y533D01* +X2330Y531D01* +X2332Y531D01* +X2332Y529D01* +X2334Y529D01* +X2334Y527D01* +X2336Y527D01* +X2336Y523D01* +X2338Y523D01* +X2338Y519D01* +X2340Y519D01* +X2340Y515D01* +X2342Y515D01* +X2342Y509D01* +X2344Y509D01* +X2344Y489D01* +X2342Y489D01* +X2342Y483D01* +X2340Y483D01* +X2340Y479D01* +X2338Y479D01* +X2338Y475D01* +X2336Y475D01* +X2336Y473D01* +X2334Y473D01* +X2334Y469D01* +X2332Y469D01* +X2332Y467D01* +X2330Y467D01* +X2330Y465D01* +X2328Y465D01* +X2328Y463D01* +X2324Y463D01* +X2324Y461D01* +X2322Y461D01* +X2322Y459D01* +X2318Y459D01* +X2318Y439D01* +X2322Y439D01* +X2322Y437D01* +X2324Y437D01* +X2324Y435D01* +X2328Y435D01* +X2328Y433D01* +X2330Y433D01* +X2330Y431D01* +X2332Y431D01* +X2332Y429D01* +X2334Y429D01* +X2334Y427D01* +X2336Y427D01* +X2336Y423D01* +X2338Y423D01* +X2338Y419D01* +X2340Y419D01* +X2340Y415D01* +X2342Y415D01* +X2342Y409D01* +X2344Y409D01* +X2344Y389D01* +X2342Y389D01* +X2342Y383D01* +X2340Y383D01* +X2340Y379D01* +X2338Y379D01* +X2338Y375D01* +X2336Y375D01* +X2336Y373D01* +X2334Y373D01* +X2334Y369D01* +X2332Y369D01* +X2332Y367D01* +X2330Y367D01* +X2330Y365D01* +X2328Y365D01* +X2328Y363D01* +X2324Y363D01* +X2324Y361D01* +X2322Y361D01* +X2322Y359D01* +X2318Y359D01* +X2318Y339D01* +X2322Y339D01* +X2322Y337D01* +X2324Y337D01* +X2324Y335D01* +X2328Y335D01* +X2328Y333D01* +X2330Y333D01* +X2330Y331D01* +X2332Y331D01* +X2332Y329D01* +X2334Y329D01* +X2334Y327D01* +X2336Y327D01* +X2336Y323D01* +X2338Y323D01* +X2338Y319D01* +X2340Y319D01* +X2340Y315D01* +X2342Y315D01* +X2342Y309D01* +X2344Y309D01* +X2344Y289D01* +X2342Y289D01* +X2342Y283D01* +X2340Y283D01* +X2340Y279D01* +X2338Y279D01* +X2338Y275D01* +X2336Y275D01* +X2336Y273D01* +X2334Y273D01* +X2334Y269D01* +X2332Y269D01* +X2332Y267D01* +X2330Y267D01* +X2330Y265D01* +X2328Y265D01* +X2328Y263D01* +X2324Y263D01* +X2324Y261D01* +X2322Y261D01* +X2322Y259D01* +X2318Y259D01* +X2318Y239D01* +X2322Y239D01* +X2322Y237D01* +X2324Y237D01* +X2324Y235D01* +X2328Y235D01* +X2328Y233D01* +X2330Y233D01* +X2330Y231D01* +X2332Y231D01* +X2332Y229D01* +X2334Y229D01* +X2334Y227D01* +X2336Y227D01* +X2336Y223D01* +X2338Y223D01* +X2338Y219D01* +X2340Y219D01* +X2340Y215D01* +X2342Y215D01* +X2342Y209D01* +X2344Y209D01* +X2344Y189D01* +X2342Y189D01* +X2342Y183D01* +X2340Y183D01* +X2340Y179D01* +X2338Y179D01* +X2338Y175D01* +X2336Y175D01* +X2336Y173D01* +X2334Y173D01* +X2334Y169D01* +X2332Y169D01* +X2332Y167D01* +X2330Y167D01* +X2330Y165D01* +X2328Y165D01* +X2328Y163D01* +X2324Y163D01* +X2324Y161D01* +X2322Y161D01* +X2322Y159D01* +X2318Y159D01* +X2318Y157D01* +X2312Y157D01* +X2312Y155D01* +X2562Y155D01* +X2562Y1643D01* +X2312Y1643D01* +G37* +D02* +G36* +X40Y1551D02* +X40Y1549D01* +X1178Y1549D01* +X1178Y1551D01* +X40Y1551D01* +G37* +D02* +G36* +X40Y1551D02* +X40Y1549D01* +X1178Y1549D01* +X1178Y1551D01* +X40Y1551D01* +G37* +D02* +G36* +X40Y1551D02* +X40Y1549D01* +X1178Y1549D01* +X1178Y1551D01* +X40Y1551D01* +G37* +D02* +G36* +X40Y1549D02* +X40Y153D01* +X104Y153D01* +X104Y151D01* +X114Y151D01* +X114Y149D01* +X1500Y149D01* +X1500Y147D01* +X1512Y147D01* +X1512Y145D01* +X1518Y145D01* +X1518Y143D01* +X1522Y143D01* +X1522Y141D01* +X1526Y141D01* +X1526Y139D01* +X1528Y139D01* +X1528Y137D01* +X1532Y137D01* +X1532Y135D01* +X1534Y135D01* +X1534Y133D01* +X1536Y133D01* +X1536Y129D01* +X1538Y129D01* +X1538Y127D01* +X1540Y127D01* +X1540Y125D01* +X1542Y125D01* +X1542Y121D01* +X1544Y121D01* +X1544Y117D01* +X1546Y117D01* +X1546Y109D01* +X1548Y109D01* +X1548Y89D01* +X1546Y89D01* +X1546Y81D01* +X1544Y81D01* +X1544Y77D01* +X1596Y77D01* +X1596Y79D01* +X1590Y79D01* +X1590Y81D01* +X1588Y81D01* +X1588Y83D01* +X1584Y83D01* +X1584Y87D01* +X1582Y87D01* +X1582Y89D01* +X1580Y89D01* +X1580Y93D01* +X1578Y93D01* +X1578Y377D01* +X192Y377D01* +X192Y379D01* +X188Y379D01* +X188Y381D01* +X184Y381D01* +X184Y383D01* +X182Y383D01* +X182Y385D01* +X180Y385D01* +X180Y389D01* +X178Y389D01* +X178Y393D01* +X176Y393D01* +X176Y1203D01* +X178Y1203D01* +X178Y1209D01* +X180Y1209D01* +X180Y1211D01* +X182Y1211D01* +X182Y1213D01* +X184Y1213D01* +X184Y1215D01* +X186Y1215D01* +X186Y1217D01* +X190Y1217D01* +X190Y1219D01* +X198Y1219D01* +X198Y1221D01* +X1176Y1221D01* +X1176Y1537D01* +X1178Y1537D01* +X1178Y1549D01* +X40Y1549D01* +G37* +D02* +G36* +X1820Y155D02* +X1820Y153D01* +X2562Y153D01* +X2562Y155D01* +X1820Y155D01* +G37* +D02* +G36* +X1820Y155D02* +X1820Y153D01* +X2562Y153D01* +X2562Y155D01* +X1820Y155D01* +G37* +D02* +G36* +X40Y153D02* +X40Y133D01* +X60Y133D01* +X60Y137D01* +X64Y137D01* +X64Y139D01* +X66Y139D01* +X66Y141D01* +X68Y141D01* +X68Y143D01* +X72Y143D01* +X72Y145D01* +X74Y145D01* +X74Y147D01* +X78Y147D01* +X78Y149D01* +X84Y149D01* +X84Y151D01* +X94Y151D01* +X94Y153D01* +X40Y153D01* +G37* +D02* +G36* +X1820Y153D02* +X1820Y91D01* +X1818Y91D01* +X1818Y87D01* +X1816Y87D01* +X1816Y85D01* +X1814Y85D01* +X1814Y83D01* +X1812Y83D01* +X1812Y81D01* +X1808Y81D01* +X1808Y79D01* +X1802Y79D01* +X1802Y77D01* +X2450Y77D01* +X2450Y81D01* +X2448Y81D01* +X2448Y89D01* +X2446Y89D01* +X2446Y109D01* +X2448Y109D01* +X2448Y117D01* +X2450Y117D01* +X2450Y121D01* +X2452Y121D01* +X2452Y125D01* +X2454Y125D01* +X2454Y129D01* +X2456Y129D01* +X2456Y131D01* +X2458Y131D01* +X2458Y133D01* +X2460Y133D01* +X2460Y137D01* +X2464Y137D01* +X2464Y139D01* +X2466Y139D01* +X2466Y141D01* +X2468Y141D01* +X2468Y143D01* +X2472Y143D01* +X2472Y145D01* +X2474Y145D01* +X2474Y147D01* +X2478Y147D01* +X2478Y149D01* +X2484Y149D01* +X2484Y151D01* +X2494Y151D01* +X2494Y153D01* +X1820Y153D01* +G37* +D02* +G36* +X2504Y153D02* +X2504Y151D01* +X2514Y151D01* +X2514Y149D01* +X2520Y149D01* +X2520Y147D01* +X2524Y147D01* +X2524Y145D01* +X2528Y145D01* +X2528Y143D01* +X2530Y143D01* +X2530Y141D01* +X2532Y141D01* +X2532Y139D01* +X2536Y139D01* +X2536Y137D01* +X2538Y137D01* +X2538Y135D01* +X2540Y135D01* +X2540Y131D01* +X2542Y131D01* +X2542Y129D01* +X2562Y129D01* +X2562Y153D01* +X2504Y153D01* +G37* +D02* +G36* +X120Y149D02* +X120Y147D01* +X124Y147D01* +X124Y145D01* +X128Y145D01* +X128Y143D01* +X130Y143D01* +X130Y141D01* +X132Y141D01* +X132Y139D01* +X136Y139D01* +X136Y137D01* +X138Y137D01* +X138Y135D01* +X140Y135D01* +X140Y131D01* +X142Y131D01* +X142Y129D01* +X144Y129D01* +X144Y125D01* +X146Y125D01* +X146Y123D01* +X148Y123D01* +X148Y117D01* +X150Y117D01* +X150Y111D01* +X152Y111D01* +X152Y87D01* +X150Y87D01* +X150Y81D01* +X148Y81D01* +X148Y77D01* +X146Y77D01* +X146Y73D01* +X144Y73D01* +X144Y69D01* +X142Y69D01* +X142Y67D01* +X140Y67D01* +X140Y63D01* +X138Y63D01* +X138Y61D01* +X136Y61D01* +X136Y41D01* +X1170Y41D01* +X1170Y61D01* +X1168Y61D01* +X1168Y63D01* +X1166Y63D01* +X1166Y65D01* +X1164Y65D01* +X1164Y67D01* +X1162Y67D01* +X1162Y69D01* +X1160Y69D01* +X1160Y71D01* +X1158Y71D01* +X1158Y75D01* +X1156Y75D01* +X1156Y79D01* +X1154Y79D01* +X1154Y83D01* +X1152Y83D01* +X1152Y91D01* +X1150Y91D01* +X1150Y107D01* +X1152Y107D01* +X1152Y115D01* +X1154Y115D01* +X1154Y119D01* +X1156Y119D01* +X1156Y123D01* +X1158Y123D01* +X1158Y127D01* +X1160Y127D01* +X1160Y129D01* +X1162Y129D01* +X1162Y131D01* +X1164Y131D01* +X1164Y133D01* +X1166Y133D01* +X1166Y135D01* +X1168Y135D01* +X1168Y137D01* +X1170Y137D01* +X1170Y139D01* +X1172Y139D01* +X1172Y141D01* +X1176Y141D01* +X1176Y143D01* +X1180Y143D01* +X1180Y145D01* +X1186Y145D01* +X1186Y147D01* +X1198Y147D01* +X1198Y149D01* +X120Y149D01* +G37* +D02* +G36* +X1200Y149D02* +X1200Y147D01* +X1212Y147D01* +X1212Y145D01* +X1218Y145D01* +X1218Y143D01* +X1222Y143D01* +X1222Y141D01* +X1226Y141D01* +X1226Y139D01* +X1228Y139D01* +X1228Y137D01* +X1232Y137D01* +X1232Y135D01* +X1234Y135D01* +X1234Y133D01* +X1236Y133D01* +X1236Y129D01* +X1238Y129D01* +X1238Y127D01* +X1260Y127D01* +X1260Y129D01* +X1262Y129D01* +X1262Y131D01* +X1264Y131D01* +X1264Y133D01* +X1266Y133D01* +X1266Y135D01* +X1268Y135D01* +X1268Y137D01* +X1270Y137D01* +X1270Y139D01* +X1272Y139D01* +X1272Y141D01* +X1276Y141D01* +X1276Y143D01* +X1280Y143D01* +X1280Y145D01* +X1286Y145D01* +X1286Y147D01* +X1298Y147D01* +X1298Y149D01* +X1200Y149D01* +G37* +D02* +G36* +X1300Y149D02* +X1300Y147D01* +X1312Y147D01* +X1312Y145D01* +X1318Y145D01* +X1318Y143D01* +X1322Y143D01* +X1322Y141D01* +X1326Y141D01* +X1326Y139D01* +X1328Y139D01* +X1328Y137D01* +X1332Y137D01* +X1332Y135D01* +X1334Y135D01* +X1334Y133D01* +X1336Y133D01* +X1336Y129D01* +X1338Y129D01* +X1338Y127D01* +X1360Y127D01* +X1360Y129D01* +X1362Y129D01* +X1362Y131D01* +X1364Y131D01* +X1364Y133D01* +X1366Y133D01* +X1366Y135D01* +X1368Y135D01* +X1368Y137D01* +X1370Y137D01* +X1370Y139D01* +X1372Y139D01* +X1372Y141D01* +X1376Y141D01* +X1376Y143D01* +X1380Y143D01* +X1380Y145D01* +X1386Y145D01* +X1386Y147D01* +X1398Y147D01* +X1398Y149D01* +X1300Y149D01* +G37* +D02* +G36* +X1400Y149D02* +X1400Y147D01* +X1412Y147D01* +X1412Y145D01* +X1418Y145D01* +X1418Y143D01* +X1422Y143D01* +X1422Y141D01* +X1426Y141D01* +X1426Y139D01* +X1428Y139D01* +X1428Y137D01* +X1432Y137D01* +X1432Y135D01* +X1434Y135D01* +X1434Y133D01* +X1436Y133D01* +X1436Y129D01* +X1438Y129D01* +X1438Y127D01* +X1460Y127D01* +X1460Y129D01* +X1462Y129D01* +X1462Y131D01* +X1464Y131D01* +X1464Y133D01* +X1466Y133D01* +X1466Y135D01* +X1468Y135D01* +X1468Y137D01* +X1470Y137D01* +X1470Y139D01* +X1472Y139D01* +X1472Y141D01* +X1476Y141D01* +X1476Y143D01* +X1480Y143D01* +X1480Y145D01* +X1486Y145D01* +X1486Y147D01* +X1498Y147D01* +X1498Y149D01* +X1400Y149D01* +G37* +D02* +G36* +X1542Y77D02* +X1542Y75D01* +X2452Y75D01* +X2452Y77D01* +X1542Y77D01* +G37* +D02* +G36* +X1542Y77D02* +X1542Y75D01* +X2452Y75D01* +X2452Y77D01* +X1542Y77D01* +G37* +D02* +G36* +X1542Y75D02* +X1542Y73D01* +X1540Y73D01* +X1540Y71D01* +X1538Y71D01* +X1538Y69D01* +X1536Y69D01* +X1536Y65D01* +X1534Y65D01* +X1534Y63D01* +X1530Y63D01* +X1530Y61D01* +X1528Y61D01* +X1528Y41D01* +X2464Y41D01* +X2464Y61D01* +X2462Y61D01* +X2462Y63D01* +X2460Y63D01* +X2460Y65D01* +X2458Y65D01* +X2458Y67D01* +X2456Y67D01* +X2456Y69D01* +X2454Y69D01* +X2454Y73D01* +X2452Y73D01* +X2452Y75D01* +X1542Y75D01* +G37* +D02* +G36* +X638Y1071D02* +X638Y1069D01* +X636Y1069D01* +X636Y1065D01* +X634Y1065D01* +X634Y1063D01* +X630Y1063D01* +X630Y1061D01* +X628Y1061D01* +X628Y1059D01* +X626Y1059D01* +X626Y1057D01* +X622Y1057D01* +X622Y1051D01* +X686Y1051D01* +X686Y1053D01* +X680Y1053D01* +X680Y1055D01* +X676Y1055D01* +X676Y1057D01* +X672Y1057D01* +X672Y1059D01* +X670Y1059D01* +X670Y1061D01* +X668Y1061D01* +X668Y1063D01* +X666Y1063D01* +X666Y1065D01* +X664Y1065D01* +X664Y1067D01* +X662Y1067D01* +X662Y1069D01* +X660Y1069D01* +X660Y1071D01* +X638Y1071D01* +G37* +D02* +G36* +X738Y1071D02* +X738Y1069D01* +X736Y1069D01* +X736Y1065D01* +X734Y1065D01* +X734Y1063D01* +X730Y1063D01* +X730Y1061D01* +X728Y1061D01* +X728Y1059D01* +X726Y1059D01* +X726Y1057D01* +X722Y1057D01* +X722Y1055D01* +X718Y1055D01* +X718Y1053D01* +X712Y1053D01* +X712Y1051D01* +X778Y1051D01* +X778Y1055D01* +X776Y1055D01* +X776Y1057D01* +X772Y1057D01* +X772Y1059D01* +X770Y1059D01* +X770Y1061D01* +X768Y1061D01* +X768Y1063D01* +X766Y1063D01* +X766Y1065D01* +X764Y1065D01* +X764Y1067D01* +X762Y1067D01* +X762Y1069D01* +X760Y1069D01* +X760Y1071D01* +X738Y1071D01* +G37* +D02* +G36* +X622Y1051D02* +X622Y1049D01* +X778Y1049D01* +X778Y1051D01* +X622Y1051D01* +G37* +D02* +G36* +X622Y1051D02* +X622Y1049D01* +X778Y1049D01* +X778Y1051D01* +X622Y1051D01* +G37* +D02* +G36* +X622Y1049D02* +X622Y853D01* +X620Y853D01* +X620Y675D01* +X794Y675D01* +X794Y677D01* +X790Y677D01* +X790Y679D01* +X786Y679D01* +X786Y681D01* +X784Y681D01* +X784Y683D01* +X782Y683D01* +X782Y687D01* +X780Y687D01* +X780Y693D01* +X778Y693D01* +X778Y1049D01* +X622Y1049D01* +G37* +D02* +G36* +X1212Y677D02* +X1212Y675D01* +X1660Y675D01* +X1660Y677D01* +X1212Y677D01* +G37* +D02* +G36* +X620Y675D02* +X620Y673D01* +X1662Y673D01* +X1662Y675D01* +X620Y675D01* +G37* +D02* +G36* +X620Y675D02* +X620Y673D01* +X1662Y673D01* +X1662Y675D01* +X620Y675D01* +G37* +D02* +G36* +X620Y673D02* +X620Y621D01* +X1660Y621D01* +X1660Y623D01* +X1662Y623D01* +X1662Y625D01* +X1664Y625D01* +X1664Y627D01* +X1666Y627D01* +X1666Y631D01* +X1668Y631D01* +X1668Y633D01* +X1672Y633D01* +X1672Y635D01* +X1674Y635D01* +X1674Y637D01* +X1678Y637D01* +X1678Y639D01* +X1680Y639D01* +X1680Y659D01* +X1678Y659D01* +X1678Y661D01* +X1674Y661D01* +X1674Y663D01* +X1672Y663D01* +X1672Y665D01* +X1668Y665D01* +X1668Y667D01* +X1666Y667D01* +X1666Y671D01* +X1664Y671D01* +X1664Y673D01* +X620Y673D01* +G37* +D02* +G36* +X1238Y1671D02* +X1238Y1669D01* +X1236Y1669D01* +X1236Y1665D01* +X1234Y1665D01* +X1234Y1663D01* +X1230Y1663D01* +X1230Y1661D01* +X1228Y1661D01* +X1228Y1659D01* +X1226Y1659D01* +X1226Y1657D01* +X1222Y1657D01* +X1222Y1531D01* +X1220Y1531D01* +X1220Y1191D01* +X1218Y1191D01* +X1218Y1187D01* +X1216Y1187D01* +X1216Y1183D01* +X1214Y1183D01* +X1214Y1181D01* +X1210Y1181D01* +X1210Y1179D01* +X1208Y1179D01* +X1208Y1177D01* +X220Y1177D01* +X220Y1149D01* +X900Y1149D01* +X900Y1147D01* +X912Y1147D01* +X912Y1145D01* +X918Y1145D01* +X918Y1143D01* +X922Y1143D01* +X922Y1141D01* +X926Y1141D01* +X926Y1139D01* +X928Y1139D01* +X928Y1137D01* +X932Y1137D01* +X932Y1135D01* +X934Y1135D01* +X934Y1133D01* +X936Y1133D01* +X936Y1129D01* +X938Y1129D01* +X938Y1127D01* +X940Y1127D01* +X940Y1125D01* +X942Y1125D01* +X942Y1121D01* +X944Y1121D01* +X944Y1117D01* +X946Y1117D01* +X946Y1109D01* +X948Y1109D01* +X948Y1089D01* +X946Y1089D01* +X946Y1081D01* +X944Y1081D01* +X944Y1077D01* +X942Y1077D01* +X942Y1073D01* +X940Y1073D01* +X940Y1071D01* +X938Y1071D01* +X938Y1069D01* +X936Y1069D01* +X936Y1065D01* +X934Y1065D01* +X934Y1063D01* +X930Y1063D01* +X930Y1061D01* +X928Y1061D01* +X928Y1059D01* +X926Y1059D01* +X926Y1057D01* +X922Y1057D01* +X922Y1055D01* +X918Y1055D01* +X918Y1053D01* +X912Y1053D01* +X912Y1051D01* +X1680Y1051D01* +X1680Y1059D01* +X1678Y1059D01* +X1678Y1061D01* +X1674Y1061D01* +X1674Y1063D01* +X1672Y1063D01* +X1672Y1065D01* +X1668Y1065D01* +X1668Y1067D01* +X1666Y1067D01* +X1666Y1071D01* +X1664Y1071D01* +X1664Y1073D01* +X1662Y1073D01* +X1662Y1075D01* +X1660Y1075D01* +X1660Y1077D01* +X1418Y1077D01* +X1418Y1079D01* +X1290Y1079D01* +X1290Y1081D01* +X1286Y1081D01* +X1286Y1083D01* +X1284Y1083D01* +X1284Y1085D01* +X1282Y1085D01* +X1282Y1087D01* +X1280Y1087D01* +X1280Y1091D01* +X1278Y1091D01* +X1278Y1097D01* +X1276Y1097D01* +X1276Y1485D01* +X1278Y1485D01* +X1278Y1655D01* +X1276Y1655D01* +X1276Y1657D01* +X1272Y1657D01* +X1272Y1659D01* +X1270Y1659D01* +X1270Y1661D01* +X1268Y1661D01* +X1268Y1663D01* +X1266Y1663D01* +X1266Y1665D01* +X1264Y1665D01* +X1264Y1667D01* +X1262Y1667D01* +X1262Y1669D01* +X1260Y1669D01* +X1260Y1671D01* +X1238Y1671D01* +G37* +D02* +G36* +X1744Y1577D02* +X1744Y1555D01* +X1724Y1555D01* +X1724Y1535D01* +X1728Y1535D01* +X1728Y1533D01* +X1730Y1533D01* +X1730Y1531D01* +X1732Y1531D01* +X1732Y1529D01* +X1734Y1529D01* +X1734Y1527D01* +X1736Y1527D01* +X1736Y1523D01* +X1738Y1523D01* +X1738Y1519D01* +X1740Y1519D01* +X1740Y1515D01* +X1742Y1515D01* +X1742Y1509D01* +X1744Y1509D01* +X1744Y1489D01* +X1742Y1489D01* +X1742Y1483D01* +X1740Y1483D01* +X1740Y1479D01* +X1738Y1479D01* +X1738Y1475D01* +X1736Y1475D01* +X1736Y1473D01* +X1734Y1473D01* +X1734Y1469D01* +X1732Y1469D01* +X1732Y1467D01* +X1730Y1467D01* +X1730Y1465D01* +X1728Y1465D01* +X1728Y1463D01* +X1724Y1463D01* +X1724Y1461D01* +X1722Y1461D01* +X1722Y1459D01* +X1718Y1459D01* +X1718Y1439D01* +X1722Y1439D01* +X1722Y1437D01* +X1724Y1437D01* +X1724Y1435D01* +X1728Y1435D01* +X1728Y1433D01* +X1730Y1433D01* +X1730Y1431D01* +X1732Y1431D01* +X1732Y1429D01* +X1734Y1429D01* +X1734Y1427D01* +X1736Y1427D01* +X1736Y1423D01* +X1738Y1423D01* +X1738Y1419D01* +X1740Y1419D01* +X1740Y1415D01* +X1742Y1415D01* +X1742Y1409D01* +X1744Y1409D01* +X1744Y1389D01* +X1742Y1389D01* +X1742Y1383D01* +X1740Y1383D01* +X1740Y1379D01* +X1738Y1379D01* +X1738Y1375D01* +X1736Y1375D01* +X1736Y1373D01* +X1734Y1373D01* +X1734Y1369D01* +X1732Y1369D01* +X1732Y1367D01* +X1730Y1367D01* +X1730Y1365D01* +X1728Y1365D01* +X1728Y1363D01* +X1724Y1363D01* +X1724Y1361D01* +X1722Y1361D01* +X1722Y1359D01* +X1718Y1359D01* +X1718Y1339D01* +X1722Y1339D01* +X1722Y1337D01* +X1724Y1337D01* +X1724Y1335D01* +X1728Y1335D01* +X1728Y1333D01* +X1730Y1333D01* +X1730Y1331D01* +X1732Y1331D01* +X1732Y1329D01* +X1734Y1329D01* +X1734Y1327D01* +X1736Y1327D01* +X1736Y1323D01* +X1738Y1323D01* +X1738Y1319D01* +X1740Y1319D01* +X1740Y1315D01* +X1742Y1315D01* +X1742Y1309D01* +X1744Y1309D01* +X1744Y1289D01* +X1742Y1289D01* +X1742Y1283D01* +X1740Y1283D01* +X1740Y1279D01* +X1738Y1279D01* +X1738Y1275D01* +X1736Y1275D01* +X1736Y1273D01* +X1734Y1273D01* +X1734Y1269D01* +X1732Y1269D01* +X1732Y1267D01* +X1730Y1267D01* +X1730Y1265D01* +X1728Y1265D01* +X1728Y1263D01* +X1724Y1263D01* +X1724Y1261D01* +X1722Y1261D01* +X1722Y1259D01* +X1718Y1259D01* +X1718Y1239D01* +X1722Y1239D01* +X1722Y1237D01* +X1724Y1237D01* +X1724Y1235D01* +X1728Y1235D01* +X1728Y1233D01* +X1730Y1233D01* +X1730Y1231D01* +X1732Y1231D01* +X1732Y1229D01* +X1734Y1229D01* +X1734Y1227D01* +X1736Y1227D01* +X1736Y1223D01* +X1738Y1223D01* +X1738Y1219D01* +X1740Y1219D01* +X1740Y1215D01* +X1742Y1215D01* +X1742Y1209D01* +X1744Y1209D01* +X1744Y1189D01* +X1742Y1189D01* +X1742Y1183D01* +X1740Y1183D01* +X1740Y1179D01* +X1738Y1179D01* +X1738Y1175D01* +X1736Y1175D01* +X1736Y1173D01* +X1734Y1173D01* +X1734Y1169D01* +X1732Y1169D01* +X1732Y1167D01* +X1730Y1167D01* +X1730Y1165D01* +X1728Y1165D01* +X1728Y1163D01* +X1724Y1163D01* +X1724Y1161D01* +X1722Y1161D01* +X1722Y1159D01* +X1718Y1159D01* +X1718Y1139D01* +X1722Y1139D01* +X1722Y1137D01* +X1724Y1137D01* +X1724Y1135D01* +X1728Y1135D01* +X1728Y1133D01* +X1730Y1133D01* +X1730Y1131D01* +X1732Y1131D01* +X1732Y1129D01* +X1734Y1129D01* +X1734Y1127D01* +X1736Y1127D01* +X1736Y1123D01* +X1738Y1123D01* +X1738Y1119D01* +X1740Y1119D01* +X1740Y1115D01* +X1742Y1115D01* +X1742Y1109D01* +X1744Y1109D01* +X1744Y1089D01* +X1742Y1089D01* +X1742Y1083D01* +X1740Y1083D01* +X1740Y1079D01* +X1738Y1079D01* +X1738Y1075D01* +X1736Y1075D01* +X1736Y1073D01* +X1734Y1073D01* +X1734Y1069D01* +X1732Y1069D01* +X1732Y1067D01* +X1730Y1067D01* +X1730Y1065D01* +X1728Y1065D01* +X1728Y1063D01* +X1724Y1063D01* +X1724Y1061D01* +X1722Y1061D01* +X1722Y1059D01* +X1718Y1059D01* +X1718Y1039D01* +X1722Y1039D01* +X1722Y1037D01* +X1724Y1037D01* +X1724Y1035D01* +X1728Y1035D01* +X1728Y1033D01* +X1730Y1033D01* +X1730Y1031D01* +X1732Y1031D01* +X1732Y1029D01* +X1734Y1029D01* +X1734Y1027D01* +X1736Y1027D01* +X1736Y1023D01* +X1738Y1023D01* +X1738Y1019D01* +X1740Y1019D01* +X1740Y1015D01* +X1742Y1015D01* +X1742Y1009D01* +X1744Y1009D01* +X1744Y989D01* +X1742Y989D01* +X1742Y983D01* +X1740Y983D01* +X1740Y979D01* +X1738Y979D01* +X1738Y975D01* +X1736Y975D01* +X1736Y973D01* +X1734Y973D01* +X1734Y969D01* +X1732Y969D01* +X1732Y967D01* +X1730Y967D01* +X1730Y965D01* +X1728Y965D01* +X1728Y963D01* +X1724Y963D01* +X1724Y961D01* +X1722Y961D01* +X1722Y959D01* +X1718Y959D01* +X1718Y939D01* +X1722Y939D01* +X1722Y937D01* +X1724Y937D01* +X1724Y935D01* +X1728Y935D01* +X1728Y933D01* +X1730Y933D01* +X1730Y931D01* +X1732Y931D01* +X1732Y929D01* +X1734Y929D01* +X1734Y927D01* +X1736Y927D01* +X1736Y923D01* +X1738Y923D01* +X1738Y919D01* +X1740Y919D01* +X1740Y915D01* +X1742Y915D01* +X1742Y909D01* +X1744Y909D01* +X1744Y889D01* +X1742Y889D01* +X1742Y883D01* +X1740Y883D01* +X1740Y879D01* +X1738Y879D01* +X1738Y875D01* +X1736Y875D01* +X1736Y873D01* +X1734Y873D01* +X1734Y869D01* +X1732Y869D01* +X1732Y867D01* +X1730Y867D01* +X1730Y865D01* +X1728Y865D01* +X1728Y863D01* +X1724Y863D01* +X1724Y861D01* +X1722Y861D01* +X1722Y859D01* +X1718Y859D01* +X1718Y839D01* +X1722Y839D01* +X1722Y837D01* +X1724Y837D01* +X1724Y835D01* +X1728Y835D01* +X1728Y833D01* +X1730Y833D01* +X1730Y831D01* +X1732Y831D01* +X1732Y829D01* +X1734Y829D01* +X1734Y827D01* +X1736Y827D01* +X1736Y823D01* +X1738Y823D01* +X1738Y819D01* +X1740Y819D01* +X1740Y815D01* +X1742Y815D01* +X1742Y809D01* +X1744Y809D01* +X1744Y789D01* +X1742Y789D01* +X1742Y783D01* +X1740Y783D01* +X1740Y779D01* +X1738Y779D01* +X1738Y775D01* +X1736Y775D01* +X1736Y773D01* +X1734Y773D01* +X1734Y769D01* +X1732Y769D01* +X1732Y767D01* +X1730Y767D01* +X1730Y765D01* +X1728Y765D01* +X1728Y763D01* +X1724Y763D01* +X1724Y761D01* +X1722Y761D01* +X1722Y759D01* +X1718Y759D01* +X1718Y739D01* +X1722Y739D01* +X1722Y737D01* +X1724Y737D01* +X1724Y735D01* +X1728Y735D01* +X1728Y733D01* +X1730Y733D01* +X1730Y731D01* +X1732Y731D01* +X1732Y729D01* +X1734Y729D01* +X1734Y727D01* +X1736Y727D01* +X1736Y723D01* +X1738Y723D01* +X1738Y719D01* +X1740Y719D01* +X1740Y715D01* +X1742Y715D01* +X1742Y709D01* +X1744Y709D01* +X1744Y689D01* +X1742Y689D01* +X1742Y683D01* +X1740Y683D01* +X1740Y679D01* +X1738Y679D01* +X1738Y675D01* +X1736Y675D01* +X1736Y673D01* +X1734Y673D01* +X1734Y669D01* +X1732Y669D01* +X1732Y667D01* +X1730Y667D01* +X1730Y665D01* +X1728Y665D01* +X1728Y663D01* +X1724Y663D01* +X1724Y661D01* +X1722Y661D01* +X1722Y659D01* +X1718Y659D01* +X1718Y639D01* +X1722Y639D01* +X1722Y637D01* +X1724Y637D01* +X1724Y635D01* +X1728Y635D01* +X1728Y633D01* +X1730Y633D01* +X1730Y631D01* +X1732Y631D01* +X1732Y629D01* +X1734Y629D01* +X1734Y627D01* +X1736Y627D01* +X1736Y623D01* +X1738Y623D01* +X1738Y619D01* +X1740Y619D01* +X1740Y615D01* +X1742Y615D01* +X1742Y609D01* +X1744Y609D01* +X1744Y589D01* +X1742Y589D01* +X1742Y583D01* +X1740Y583D01* +X1740Y579D01* +X1738Y579D01* +X1738Y575D01* +X1736Y575D01* +X1736Y573D01* +X1734Y573D01* +X1734Y569D01* +X1732Y569D01* +X1732Y567D01* +X1730Y567D01* +X1730Y565D01* +X1728Y565D01* +X1728Y563D01* +X1724Y563D01* +X1724Y561D01* +X1722Y561D01* +X1722Y559D01* +X1718Y559D01* +X1718Y539D01* +X1722Y539D01* +X1722Y537D01* +X1724Y537D01* +X1724Y535D01* +X1728Y535D01* +X1728Y533D01* +X1730Y533D01* +X1730Y531D01* +X1732Y531D01* +X1732Y529D01* +X1734Y529D01* +X1734Y527D01* +X1736Y527D01* +X1736Y523D01* +X1738Y523D01* +X1738Y519D01* +X1740Y519D01* +X1740Y515D01* +X1742Y515D01* +X1742Y509D01* +X1744Y509D01* +X1744Y489D01* +X1742Y489D01* +X1742Y483D01* +X1740Y483D01* +X1740Y479D01* +X1738Y479D01* +X1738Y475D01* +X1736Y475D01* +X1736Y473D01* +X1734Y473D01* +X1734Y469D01* +X1732Y469D01* +X1732Y467D01* +X1730Y467D01* +X1730Y465D01* +X1728Y465D01* +X1728Y463D01* +X1724Y463D01* +X1724Y461D01* +X1722Y461D01* +X1722Y459D01* +X1718Y459D01* +X1718Y439D01* +X1722Y439D01* +X1722Y437D01* +X1724Y437D01* +X1724Y435D01* +X1728Y435D01* +X1728Y433D01* +X1730Y433D01* +X1730Y431D01* +X1732Y431D01* +X1732Y429D01* +X1734Y429D01* +X1734Y427D01* +X1736Y427D01* +X1736Y423D01* +X1738Y423D01* +X1738Y419D01* +X1740Y419D01* +X1740Y415D01* +X1742Y415D01* +X1742Y409D01* +X1744Y409D01* +X1744Y389D01* +X1742Y389D01* +X1742Y383D01* +X1740Y383D01* +X1740Y379D01* +X1738Y379D01* +X1738Y375D01* +X1736Y375D01* +X1736Y373D01* +X1734Y373D01* +X1734Y369D01* +X1732Y369D01* +X1732Y367D01* +X1730Y367D01* +X1730Y365D01* +X1728Y365D01* +X1728Y363D01* +X1724Y363D01* +X1724Y361D01* +X1722Y361D01* +X1722Y359D01* +X1718Y359D01* +X1718Y339D01* +X1722Y339D01* +X1722Y337D01* +X1724Y337D01* +X1724Y335D01* +X1728Y335D01* +X1728Y333D01* +X1730Y333D01* +X1730Y331D01* +X1732Y331D01* +X1732Y329D01* +X1734Y329D01* +X1734Y327D01* +X1736Y327D01* +X1736Y323D01* +X1738Y323D01* +X1738Y319D01* +X1740Y319D01* +X1740Y315D01* +X1742Y315D01* +X1742Y309D01* +X1744Y309D01* +X1744Y289D01* +X1742Y289D01* +X1742Y283D01* +X1740Y283D01* +X1740Y279D01* +X1738Y279D01* +X1738Y275D01* +X1736Y275D01* +X1736Y273D01* +X1734Y273D01* +X1734Y269D01* +X1732Y269D01* +X1732Y267D01* +X1730Y267D01* +X1730Y265D01* +X1728Y265D01* +X1728Y263D01* +X1724Y263D01* +X1724Y261D01* +X1722Y261D01* +X1722Y259D01* +X1718Y259D01* +X1718Y239D01* +X1722Y239D01* +X1722Y237D01* +X1724Y237D01* +X1724Y235D01* +X1728Y235D01* +X1728Y233D01* +X1730Y233D01* +X1730Y231D01* +X1732Y231D01* +X1732Y229D01* +X1734Y229D01* +X1734Y227D01* +X1736Y227D01* +X1736Y223D01* +X1738Y223D01* +X1738Y219D01* +X1740Y219D01* +X1740Y215D01* +X1742Y215D01* +X1742Y209D01* +X1744Y209D01* +X1744Y189D01* +X1742Y189D01* +X1742Y183D01* +X1740Y183D01* +X1740Y179D01* +X1738Y179D01* +X1738Y175D01* +X1736Y175D01* +X1736Y173D01* +X1734Y173D01* +X1734Y169D01* +X1732Y169D01* +X1732Y167D01* +X1730Y167D01* +X1730Y165D01* +X1728Y165D01* +X1728Y163D01* +X1724Y163D01* +X1724Y161D01* +X1722Y161D01* +X1722Y159D01* +X1718Y159D01* +X1718Y157D01* +X1712Y157D01* +X1712Y155D01* +X1776Y155D01* +X1776Y1577D01* +X1744Y1577D01* +G37* +D02* +G36* +X220Y1149D02* +X220Y1051D01* +X386Y1051D01* +X386Y1053D01* +X380Y1053D01* +X380Y1055D01* +X376Y1055D01* +X376Y1057D01* +X372Y1057D01* +X372Y1059D01* +X370Y1059D01* +X370Y1061D01* +X368Y1061D01* +X368Y1063D01* +X366Y1063D01* +X366Y1065D01* +X364Y1065D01* +X364Y1067D01* +X362Y1067D01* +X362Y1069D01* +X360Y1069D01* +X360Y1071D01* +X358Y1071D01* +X358Y1075D01* +X356Y1075D01* +X356Y1079D01* +X354Y1079D01* +X354Y1083D01* +X352Y1083D01* +X352Y1091D01* +X350Y1091D01* +X350Y1107D01* +X352Y1107D01* +X352Y1115D01* +X354Y1115D01* +X354Y1119D01* +X356Y1119D01* +X356Y1123D01* +X358Y1123D01* +X358Y1127D01* +X360Y1127D01* +X360Y1129D01* +X362Y1129D01* +X362Y1131D01* +X364Y1131D01* +X364Y1133D01* +X366Y1133D01* +X366Y1135D01* +X368Y1135D01* +X368Y1137D01* +X370Y1137D01* +X370Y1139D01* +X372Y1139D01* +X372Y1141D01* +X376Y1141D01* +X376Y1143D01* +X380Y1143D01* +X380Y1145D01* +X386Y1145D01* +X386Y1147D01* +X398Y1147D01* +X398Y1149D01* +X220Y1149D01* +G37* +D02* +G36* +X400Y1149D02* +X400Y1147D01* +X412Y1147D01* +X412Y1145D01* +X418Y1145D01* +X418Y1143D01* +X422Y1143D01* +X422Y1141D01* +X426Y1141D01* +X426Y1139D01* +X428Y1139D01* +X428Y1137D01* +X432Y1137D01* +X432Y1135D01* +X434Y1135D01* +X434Y1133D01* +X436Y1133D01* +X436Y1129D01* +X438Y1129D01* +X438Y1127D01* +X460Y1127D01* +X460Y1129D01* +X462Y1129D01* +X462Y1131D01* +X464Y1131D01* +X464Y1133D01* +X466Y1133D01* +X466Y1135D01* +X468Y1135D01* +X468Y1137D01* +X470Y1137D01* +X470Y1139D01* +X472Y1139D01* +X472Y1141D01* +X476Y1141D01* +X476Y1143D01* +X480Y1143D01* +X480Y1145D01* +X486Y1145D01* +X486Y1147D01* +X498Y1147D01* +X498Y1149D01* +X400Y1149D01* +G37* +D02* +G36* +X500Y1149D02* +X500Y1147D01* +X512Y1147D01* +X512Y1145D01* +X518Y1145D01* +X518Y1143D01* +X522Y1143D01* +X522Y1141D01* +X526Y1141D01* +X526Y1139D01* +X528Y1139D01* +X528Y1137D01* +X532Y1137D01* +X532Y1135D01* +X534Y1135D01* +X534Y1133D01* +X536Y1133D01* +X536Y1129D01* +X538Y1129D01* +X538Y1127D01* +X560Y1127D01* +X560Y1129D01* +X562Y1129D01* +X562Y1131D01* +X564Y1131D01* +X564Y1133D01* +X566Y1133D01* +X566Y1135D01* +X568Y1135D01* +X568Y1137D01* +X570Y1137D01* +X570Y1139D01* +X572Y1139D01* +X572Y1141D01* +X576Y1141D01* +X576Y1143D01* +X580Y1143D01* +X580Y1145D01* +X586Y1145D01* +X586Y1147D01* +X598Y1147D01* +X598Y1149D01* +X500Y1149D01* +G37* +D02* +G36* +X600Y1149D02* +X600Y1147D01* +X612Y1147D01* +X612Y1145D01* +X618Y1145D01* +X618Y1143D01* +X622Y1143D01* +X622Y1141D01* +X626Y1141D01* +X626Y1139D01* +X628Y1139D01* +X628Y1137D01* +X632Y1137D01* +X632Y1135D01* +X634Y1135D01* +X634Y1133D01* +X636Y1133D01* +X636Y1129D01* +X638Y1129D01* +X638Y1127D01* +X660Y1127D01* +X660Y1129D01* +X662Y1129D01* +X662Y1131D01* +X664Y1131D01* +X664Y1133D01* +X666Y1133D01* +X666Y1135D01* +X668Y1135D01* +X668Y1137D01* +X670Y1137D01* +X670Y1139D01* +X672Y1139D01* +X672Y1141D01* +X676Y1141D01* +X676Y1143D01* +X680Y1143D01* +X680Y1145D01* +X686Y1145D01* +X686Y1147D01* +X698Y1147D01* +X698Y1149D01* +X600Y1149D01* +G37* +D02* +G36* +X700Y1149D02* +X700Y1147D01* +X712Y1147D01* +X712Y1145D01* +X718Y1145D01* +X718Y1143D01* +X722Y1143D01* +X722Y1141D01* +X726Y1141D01* +X726Y1139D01* +X728Y1139D01* +X728Y1137D01* +X732Y1137D01* +X732Y1135D01* +X734Y1135D01* +X734Y1133D01* +X736Y1133D01* +X736Y1129D01* +X738Y1129D01* +X738Y1127D01* +X760Y1127D01* +X760Y1129D01* +X762Y1129D01* +X762Y1131D01* +X764Y1131D01* +X764Y1133D01* +X766Y1133D01* +X766Y1135D01* +X768Y1135D01* +X768Y1137D01* +X770Y1137D01* +X770Y1139D01* +X772Y1139D01* +X772Y1141D01* +X776Y1141D01* +X776Y1143D01* +X780Y1143D01* +X780Y1145D01* +X786Y1145D01* +X786Y1147D01* +X798Y1147D01* +X798Y1149D01* +X700Y1149D01* +G37* +D02* +G36* +X800Y1149D02* +X800Y1147D01* +X812Y1147D01* +X812Y1145D01* +X818Y1145D01* +X818Y1143D01* +X822Y1143D01* +X822Y1141D01* +X826Y1141D01* +X826Y1139D01* +X828Y1139D01* +X828Y1137D01* +X832Y1137D01* +X832Y1135D01* +X834Y1135D01* +X834Y1133D01* +X836Y1133D01* +X836Y1129D01* +X838Y1129D01* +X838Y1127D01* +X860Y1127D01* +X860Y1129D01* +X862Y1129D01* +X862Y1131D01* +X864Y1131D01* +X864Y1133D01* +X866Y1133D01* +X866Y1135D01* +X868Y1135D01* +X868Y1137D01* +X870Y1137D01* +X870Y1139D01* +X872Y1139D01* +X872Y1141D01* +X876Y1141D01* +X876Y1143D01* +X880Y1143D01* +X880Y1145D01* +X886Y1145D01* +X886Y1147D01* +X898Y1147D01* +X898Y1149D01* +X800Y1149D01* +G37* +D02* +G36* +X438Y1071D02* +X438Y1069D01* +X436Y1069D01* +X436Y1065D01* +X434Y1065D01* +X434Y1063D01* +X430Y1063D01* +X430Y1061D01* +X428Y1061D01* +X428Y1059D01* +X426Y1059D01* +X426Y1057D01* +X422Y1057D01* +X422Y1055D01* +X418Y1055D01* +X418Y1053D01* +X412Y1053D01* +X412Y1051D01* +X486Y1051D01* +X486Y1053D01* +X480Y1053D01* +X480Y1055D01* +X476Y1055D01* +X476Y1057D01* +X472Y1057D01* +X472Y1059D01* +X470Y1059D01* +X470Y1061D01* +X468Y1061D01* +X468Y1063D01* +X466Y1063D01* +X466Y1065D01* +X464Y1065D01* +X464Y1067D01* +X462Y1067D01* +X462Y1069D01* +X460Y1069D01* +X460Y1071D01* +X438Y1071D01* +G37* +D02* +G36* +X538Y1071D02* +X538Y1069D01* +X536Y1069D01* +X536Y1065D01* +X534Y1065D01* +X534Y1063D01* +X530Y1063D01* +X530Y1061D01* +X528Y1061D01* +X528Y1059D01* +X526Y1059D01* +X526Y1057D01* +X522Y1057D01* +X522Y1055D01* +X518Y1055D01* +X518Y1053D01* +X512Y1053D01* +X512Y1051D01* +X578Y1051D01* +X578Y1055D01* +X576Y1055D01* +X576Y1057D01* +X572Y1057D01* +X572Y1059D01* +X570Y1059D01* +X570Y1061D01* +X568Y1061D01* +X568Y1063D01* +X566Y1063D01* +X566Y1065D01* +X564Y1065D01* +X564Y1067D01* +X562Y1067D01* +X562Y1069D01* +X560Y1069D01* +X560Y1071D01* +X538Y1071D01* +G37* +D02* +G36* +X838Y1071D02* +X838Y1069D01* +X836Y1069D01* +X836Y1065D01* +X834Y1065D01* +X834Y1063D01* +X830Y1063D01* +X830Y1061D01* +X828Y1061D01* +X828Y1059D01* +X826Y1059D01* +X826Y1057D01* +X822Y1057D01* +X822Y1051D01* +X886Y1051D01* +X886Y1053D01* +X880Y1053D01* +X880Y1055D01* +X876Y1055D01* +X876Y1057D01* +X872Y1057D01* +X872Y1059D01* +X870Y1059D01* +X870Y1061D01* +X868Y1061D01* +X868Y1063D01* +X866Y1063D01* +X866Y1065D01* +X864Y1065D01* +X864Y1067D01* +X862Y1067D01* +X862Y1069D01* +X860Y1069D01* +X860Y1071D01* +X838Y1071D01* +G37* +D02* +G36* +X220Y1051D02* +X220Y1049D01* +X578Y1049D01* +X578Y1051D01* +X220Y1051D01* +G37* +D02* +G36* +X220Y1051D02* +X220Y1049D01* +X578Y1049D01* +X578Y1051D01* +X220Y1051D01* +G37* +D02* +G36* +X220Y1051D02* +X220Y1049D01* +X578Y1049D01* +X578Y1051D01* +X220Y1051D01* +G37* +D02* +G36* +X822Y1051D02* +X822Y1049D01* +X1680Y1049D01* +X1680Y1051D01* +X822Y1051D01* +G37* +D02* +G36* +X822Y1051D02* +X822Y1049D01* +X1680Y1049D01* +X1680Y1051D01* +X822Y1051D01* +G37* +D02* +G36* +X220Y1049D02* +X220Y421D01* +X1606Y421D01* +X1606Y419D01* +X1610Y419D01* +X1610Y417D01* +X1614Y417D01* +X1614Y415D01* +X1616Y415D01* +X1616Y413D01* +X1618Y413D01* +X1618Y411D01* +X1620Y411D01* +X1620Y405D01* +X1622Y405D01* +X1622Y155D01* +X1688Y155D01* +X1688Y157D01* +X1682Y157D01* +X1682Y159D01* +X1678Y159D01* +X1678Y161D01* +X1674Y161D01* +X1674Y163D01* +X1672Y163D01* +X1672Y165D01* +X1668Y165D01* +X1668Y167D01* +X1666Y167D01* +X1666Y171D01* +X1664Y171D01* +X1664Y173D01* +X1662Y173D01* +X1662Y175D01* +X1660Y175D01* +X1660Y179D01* +X1658Y179D01* +X1658Y185D01* +X1656Y185D01* +X1656Y191D01* +X1654Y191D01* +X1654Y207D01* +X1656Y207D01* +X1656Y213D01* +X1658Y213D01* +X1658Y219D01* +X1660Y219D01* +X1660Y223D01* +X1662Y223D01* +X1662Y225D01* +X1664Y225D01* +X1664Y227D01* +X1666Y227D01* +X1666Y231D01* +X1668Y231D01* +X1668Y233D01* +X1672Y233D01* +X1672Y235D01* +X1674Y235D01* +X1674Y237D01* +X1678Y237D01* +X1678Y239D01* +X1680Y239D01* +X1680Y259D01* +X1678Y259D01* +X1678Y261D01* +X1674Y261D01* +X1674Y263D01* +X1672Y263D01* +X1672Y265D01* +X1668Y265D01* +X1668Y267D01* +X1666Y267D01* +X1666Y271D01* +X1664Y271D01* +X1664Y273D01* +X1662Y273D01* +X1662Y275D01* +X1660Y275D01* +X1660Y279D01* +X1658Y279D01* +X1658Y285D01* +X1656Y285D01* +X1656Y291D01* +X1654Y291D01* +X1654Y307D01* +X1656Y307D01* +X1656Y313D01* +X1658Y313D01* +X1658Y319D01* +X1660Y319D01* +X1660Y323D01* +X1662Y323D01* +X1662Y325D01* +X1664Y325D01* +X1664Y327D01* +X1666Y327D01* +X1666Y331D01* +X1668Y331D01* +X1668Y333D01* +X1672Y333D01* +X1672Y335D01* +X1674Y335D01* +X1674Y337D01* +X1678Y337D01* +X1678Y339D01* +X1680Y339D01* +X1680Y359D01* +X1678Y359D01* +X1678Y361D01* +X1674Y361D01* +X1674Y363D01* +X1672Y363D01* +X1672Y365D01* +X1668Y365D01* +X1668Y367D01* +X1666Y367D01* +X1666Y371D01* +X1664Y371D01* +X1664Y373D01* +X1662Y373D01* +X1662Y375D01* +X1660Y375D01* +X1660Y379D01* +X1658Y379D01* +X1658Y385D01* +X1656Y385D01* +X1656Y391D01* +X1654Y391D01* +X1654Y407D01* +X1656Y407D01* +X1656Y413D01* +X1658Y413D01* +X1658Y419D01* +X1660Y419D01* +X1660Y423D01* +X1662Y423D01* +X1662Y425D01* +X1664Y425D01* +X1664Y427D01* +X1666Y427D01* +X1666Y431D01* +X1668Y431D01* +X1668Y433D01* +X1672Y433D01* +X1672Y435D01* +X1674Y435D01* +X1674Y437D01* +X1678Y437D01* +X1678Y439D01* +X1680Y439D01* +X1680Y459D01* +X1678Y459D01* +X1678Y461D01* +X1674Y461D01* +X1674Y463D01* +X1672Y463D01* +X1672Y465D01* +X1668Y465D01* +X1668Y467D01* +X1666Y467D01* +X1666Y471D01* +X1664Y471D01* +X1664Y473D01* +X1662Y473D01* +X1662Y475D01* +X1660Y475D01* +X1660Y479D01* +X1658Y479D01* +X1658Y485D01* +X1656Y485D01* +X1656Y491D01* +X1654Y491D01* +X1654Y507D01* +X1656Y507D01* +X1656Y513D01* +X1658Y513D01* +X1658Y519D01* +X1660Y519D01* +X1660Y523D01* +X1662Y523D01* +X1662Y525D01* +X1664Y525D01* +X1664Y527D01* +X1666Y527D01* +X1666Y531D01* +X1668Y531D01* +X1668Y533D01* +X1672Y533D01* +X1672Y535D01* +X1674Y535D01* +X1674Y537D01* +X1678Y537D01* +X1678Y539D01* +X1680Y539D01* +X1680Y559D01* +X1678Y559D01* +X1678Y561D01* +X1674Y561D01* +X1674Y563D01* +X1672Y563D01* +X1672Y565D01* +X1668Y565D01* +X1668Y567D01* +X1666Y567D01* +X1666Y571D01* +X1664Y571D01* +X1664Y573D01* +X1662Y573D01* +X1662Y575D01* +X1660Y575D01* +X1660Y577D01* +X590Y577D01* +X590Y579D01* +X586Y579D01* +X586Y581D01* +X584Y581D01* +X584Y583D01* +X582Y583D01* +X582Y585D01* +X580Y585D01* +X580Y589D01* +X578Y589D01* +X578Y595D01* +X576Y595D01* +X576Y861D01* +X578Y861D01* +X578Y1049D01* +X220Y1049D01* +G37* +D02* +G36* +X822Y1049D02* +X822Y719D01* +X1206Y719D01* +X1206Y721D01* +X1660Y721D01* +X1660Y723D01* +X1662Y723D01* +X1662Y725D01* +X1664Y725D01* +X1664Y727D01* +X1666Y727D01* +X1666Y731D01* +X1668Y731D01* +X1668Y733D01* +X1672Y733D01* +X1672Y735D01* +X1674Y735D01* +X1674Y737D01* +X1678Y737D01* +X1678Y739D01* +X1680Y739D01* +X1680Y759D01* +X1678Y759D01* +X1678Y761D01* +X1674Y761D01* +X1674Y763D01* +X1672Y763D01* +X1672Y765D01* +X1668Y765D01* +X1668Y767D01* +X1666Y767D01* +X1666Y771D01* +X1664Y771D01* +X1664Y773D01* +X1662Y773D01* +X1662Y775D01* +X1660Y775D01* +X1660Y779D01* +X1658Y779D01* +X1658Y785D01* +X1656Y785D01* +X1656Y791D01* +X1654Y791D01* +X1654Y807D01* +X1656Y807D01* +X1656Y813D01* +X1658Y813D01* +X1658Y819D01* +X1660Y819D01* +X1660Y823D01* +X1662Y823D01* +X1662Y825D01* +X1664Y825D01* +X1664Y827D01* +X1666Y827D01* +X1666Y831D01* +X1668Y831D01* +X1668Y833D01* +X1672Y833D01* +X1672Y835D01* +X1674Y835D01* +X1674Y837D01* +X1678Y837D01* +X1678Y839D01* +X1680Y839D01* +X1680Y859D01* +X1678Y859D01* +X1678Y861D01* +X1674Y861D01* +X1674Y863D01* +X1672Y863D01* +X1672Y865D01* +X1668Y865D01* +X1668Y867D01* +X1666Y867D01* +X1666Y871D01* +X1664Y871D01* +X1664Y873D01* +X1662Y873D01* +X1662Y875D01* +X1660Y875D01* +X1660Y879D01* +X1658Y879D01* +X1658Y885D01* +X1656Y885D01* +X1656Y891D01* +X1654Y891D01* +X1654Y907D01* +X1656Y907D01* +X1656Y913D01* +X1658Y913D01* +X1658Y919D01* +X1660Y919D01* +X1660Y923D01* +X1662Y923D01* +X1662Y925D01* +X1664Y925D01* +X1664Y927D01* +X1666Y927D01* +X1666Y931D01* +X1668Y931D01* +X1668Y933D01* +X1672Y933D01* +X1672Y935D01* +X1674Y935D01* +X1674Y937D01* +X1678Y937D01* +X1678Y939D01* +X1680Y939D01* +X1680Y959D01* +X1678Y959D01* +X1678Y961D01* +X1674Y961D01* +X1674Y963D01* +X1672Y963D01* +X1672Y965D01* +X1668Y965D01* +X1668Y967D01* +X1666Y967D01* +X1666Y971D01* +X1664Y971D01* +X1664Y973D01* +X1662Y973D01* +X1662Y975D01* +X1660Y975D01* +X1660Y979D01* +X1658Y979D01* +X1658Y985D01* +X1656Y985D01* +X1656Y991D01* +X1654Y991D01* +X1654Y1007D01* +X1656Y1007D01* +X1656Y1013D01* +X1658Y1013D01* +X1658Y1019D01* +X1660Y1019D01* +X1660Y1023D01* +X1662Y1023D01* +X1662Y1025D01* +X1664Y1025D01* +X1664Y1027D01* +X1666Y1027D01* +X1666Y1031D01* +X1668Y1031D01* +X1668Y1033D01* +X1672Y1033D01* +X1672Y1035D01* +X1674Y1035D01* +X1674Y1037D01* +X1678Y1037D01* +X1678Y1039D01* +X1680Y1039D01* +X1680Y1049D01* +X822Y1049D01* +G37* +D02* +G36* +X1622Y155D02* +X1622Y153D01* +X1776Y153D01* +X1776Y155D01* +X1622Y155D01* +G37* +D02* +G36* +X1622Y155D02* +X1622Y153D01* +X1776Y153D01* +X1776Y155D01* +X1622Y155D01* +G37* +D02* +G36* +X1622Y153D02* +X1622Y121D01* +X1776Y121D01* +X1776Y153D01* +X1622Y153D01* +G37* +D02* +G04 End of Copper0* +M02* \ No newline at end of file diff --git a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_copperTop.gtl b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_copperTop.gtl new file mode 100644 index 0000000..f36c772 --- /dev/null +++ b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_copperTop.gtl @@ -0,0 +1,4718 @@ +G04 MADE WITH FRITZING* +G04 WWW.FRITZING.ORG* +G04 DOUBLE SIDED* +G04 HOLES PLATED* +G04 CONTOUR ON CENTER OF CONTOUR VECTOR* +%ASAXBY*% +%FSLAX23Y23*% +%MOIN*% +%OFA0B0*% +%SFA1.0B1.0*% +%ADD10C,0.075000*% +%ADD11C,0.070000*% +%ADD12C,0.078000*% +%ADD13R,0.069972X0.070000*% +%ADD14C,0.024000*% +%LNCOPPER1*% +G90* +G70* +G54D10* +X1794Y1593D03* +X423Y1693D03* +G54D11* +X1699Y1599D03* +X1699Y1499D03* +X1699Y1399D03* +X1699Y1299D03* +X1699Y1199D03* +X1699Y1099D03* +X1699Y999D03* +X1699Y899D03* +X1699Y799D03* +X1699Y699D03* +X1699Y599D03* +X1699Y499D03* +X1699Y399D03* +X1699Y299D03* +X1699Y199D03* +X2299Y1599D03* +X2299Y1499D03* +X2299Y1399D03* +X2299Y1299D03* +X2299Y1199D03* +X2299Y1099D03* +X2299Y999D03* +X2299Y899D03* +X2299Y799D03* +X2299Y699D03* +X2299Y599D03* +X2299Y499D03* +X2299Y399D03* +X2299Y299D03* +X2299Y199D03* +G54D12* +X1199Y1699D03* +X1299Y1699D03* +X1399Y1699D03* +X1499Y1699D03* +X1199Y99D03* +X1299Y99D03* +X1399Y99D03* +X1499Y99D03* +X399Y1099D03* +X499Y1099D03* +X599Y1099D03* +X699Y1099D03* +X799Y1099D03* +X899Y1099D03* +X299Y1699D03* +X299Y1599D03* +X999Y1699D03* +X999Y1599D03* +G54D13* +X1699Y1599D03* +G54D14* +X500Y100D02* +X499Y1080D01* +D02* +X1180Y99D02* +X500Y100D01* +D02* +X2200Y1500D02* +X2200Y1697D01* +D02* +X2200Y1697D02* +X1599Y1697D01* +D02* +X1599Y199D02* +X1200Y199D01* +D02* +X1200Y199D02* +X1199Y118D01* +D02* +X1599Y1697D02* +X1599Y199D01* +D02* +X2281Y1499D02* +X2200Y1500D01* +D02* +X2200Y1298D02* +X2281Y1299D01* +D02* +X2200Y100D02* +X2200Y1298D01* +D02* +X1518Y99D02* +X2200Y100D01* +G36* +X1622Y1675D02* +X1622Y1645D01* +X1744Y1645D01* +X1744Y1555D01* +X1724Y1555D01* +X1724Y1535D01* +X1728Y1535D01* +X1728Y1533D01* +X1730Y1533D01* +X1730Y1531D01* +X1732Y1531D01* +X1732Y1529D01* +X1734Y1529D01* +X1734Y1527D01* +X1736Y1527D01* +X1736Y1523D01* +X1738Y1523D01* +X1738Y1519D01* +X1740Y1519D01* +X1740Y1515D01* +X1742Y1515D01* +X1742Y1509D01* +X1744Y1509D01* +X1744Y1489D01* +X1742Y1489D01* +X1742Y1483D01* +X1740Y1483D01* +X1740Y1479D01* +X1738Y1479D01* +X1738Y1475D01* +X1736Y1475D01* +X1736Y1473D01* +X1734Y1473D01* +X1734Y1469D01* +X1732Y1469D01* +X1732Y1467D01* +X1730Y1467D01* +X1730Y1465D01* +X1728Y1465D01* +X1728Y1463D01* +X1724Y1463D01* +X1724Y1461D01* +X1722Y1461D01* +X1722Y1459D01* +X1718Y1459D01* +X1718Y1439D01* +X1722Y1439D01* +X1722Y1437D01* +X1724Y1437D01* +X1724Y1435D01* +X1728Y1435D01* +X1728Y1433D01* +X1730Y1433D01* +X1730Y1431D01* +X1732Y1431D01* +X1732Y1429D01* +X1734Y1429D01* +X1734Y1427D01* +X1736Y1427D01* +X1736Y1423D01* +X1738Y1423D01* +X1738Y1419D01* +X1740Y1419D01* +X1740Y1415D01* +X1742Y1415D01* +X1742Y1409D01* +X1744Y1409D01* +X1744Y1389D01* +X1742Y1389D01* +X1742Y1383D01* +X1740Y1383D01* +X1740Y1379D01* +X1738Y1379D01* +X1738Y1375D01* +X1736Y1375D01* +X1736Y1373D01* +X1734Y1373D01* +X1734Y1369D01* +X1732Y1369D01* +X1732Y1367D01* +X1730Y1367D01* +X1730Y1365D01* +X1728Y1365D01* +X1728Y1363D01* +X1724Y1363D01* +X1724Y1361D01* +X1722Y1361D01* +X1722Y1359D01* +X1718Y1359D01* +X1718Y1339D01* +X1722Y1339D01* +X1722Y1337D01* +X1724Y1337D01* +X1724Y1335D01* +X1728Y1335D01* +X1728Y1333D01* +X1730Y1333D01* +X1730Y1331D01* +X1732Y1331D01* +X1732Y1329D01* +X1734Y1329D01* +X1734Y1327D01* +X1736Y1327D01* +X1736Y1323D01* +X1738Y1323D01* +X1738Y1319D01* +X1740Y1319D01* +X1740Y1315D01* +X1742Y1315D01* +X1742Y1309D01* +X1744Y1309D01* +X1744Y1289D01* +X1742Y1289D01* +X1742Y1283D01* +X1740Y1283D01* +X1740Y1279D01* +X1738Y1279D01* +X1738Y1275D01* +X1736Y1275D01* +X1736Y1273D01* +X1734Y1273D01* +X1734Y1269D01* +X1732Y1269D01* +X1732Y1267D01* +X1730Y1267D01* +X1730Y1265D01* +X1728Y1265D01* +X1728Y1263D01* +X1724Y1263D01* +X1724Y1261D01* +X1722Y1261D01* +X1722Y1259D01* +X1718Y1259D01* +X1718Y1239D01* +X1722Y1239D01* +X1722Y1237D01* +X1724Y1237D01* +X1724Y1235D01* +X1728Y1235D01* +X1728Y1233D01* +X1730Y1233D01* +X1730Y1231D01* +X1732Y1231D01* +X1732Y1229D01* +X1734Y1229D01* +X1734Y1227D01* +X1736Y1227D01* +X1736Y1223D01* +X1738Y1223D01* +X1738Y1219D01* +X1740Y1219D01* +X1740Y1215D01* +X1742Y1215D01* +X1742Y1209D01* +X1744Y1209D01* +X1744Y1189D01* +X1742Y1189D01* +X1742Y1183D01* +X1740Y1183D01* +X1740Y1179D01* +X1738Y1179D01* +X1738Y1175D01* +X1736Y1175D01* +X1736Y1173D01* +X1734Y1173D01* +X1734Y1169D01* +X1732Y1169D01* +X1732Y1167D01* +X1730Y1167D01* +X1730Y1165D01* +X1728Y1165D01* +X1728Y1163D01* +X1724Y1163D01* +X1724Y1161D01* +X1722Y1161D01* +X1722Y1159D01* +X1718Y1159D01* +X1718Y1139D01* +X1722Y1139D01* +X1722Y1137D01* +X1724Y1137D01* +X1724Y1135D01* +X1728Y1135D01* +X1728Y1133D01* +X1730Y1133D01* +X1730Y1131D01* +X1732Y1131D01* +X1732Y1129D01* +X1734Y1129D01* +X1734Y1127D01* +X1736Y1127D01* +X1736Y1123D01* +X1738Y1123D01* +X1738Y1119D01* +X1740Y1119D01* +X1740Y1115D01* +X1742Y1115D01* +X1742Y1109D01* +X1744Y1109D01* +X1744Y1089D01* +X1742Y1089D01* +X1742Y1083D01* +X1740Y1083D01* +X1740Y1079D01* +X1738Y1079D01* +X1738Y1075D01* +X1736Y1075D01* +X1736Y1073D01* +X1734Y1073D01* +X1734Y1069D01* +X1732Y1069D01* +X1732Y1067D01* +X1730Y1067D01* +X1730Y1065D01* +X1728Y1065D01* +X1728Y1063D01* +X1724Y1063D01* +X1724Y1061D01* +X1722Y1061D01* +X1722Y1059D01* +X1718Y1059D01* +X1718Y1039D01* +X1722Y1039D01* +X1722Y1037D01* +X1724Y1037D01* +X1724Y1035D01* +X1728Y1035D01* +X1728Y1033D01* +X1730Y1033D01* +X1730Y1031D01* +X1732Y1031D01* +X1732Y1029D01* +X1734Y1029D01* +X1734Y1027D01* +X1736Y1027D01* +X1736Y1023D01* +X1738Y1023D01* +X1738Y1019D01* +X1740Y1019D01* +X1740Y1015D01* +X1742Y1015D01* +X1742Y1009D01* +X1744Y1009D01* +X1744Y989D01* +X1742Y989D01* +X1742Y983D01* +X1740Y983D01* +X1740Y979D01* +X1738Y979D01* +X1738Y975D01* +X1736Y975D01* +X1736Y973D01* +X1734Y973D01* +X1734Y969D01* +X1732Y969D01* +X1732Y967D01* +X1730Y967D01* +X1730Y965D01* +X1728Y965D01* +X1728Y963D01* +X1724Y963D01* +X1724Y961D01* +X1722Y961D01* +X1722Y959D01* +X1718Y959D01* +X1718Y939D01* +X1722Y939D01* +X1722Y937D01* +X1724Y937D01* +X1724Y935D01* +X1728Y935D01* +X1728Y933D01* +X1730Y933D01* +X1730Y931D01* +X1732Y931D01* +X1732Y929D01* +X1734Y929D01* +X1734Y927D01* +X1736Y927D01* +X1736Y923D01* +X1738Y923D01* +X1738Y919D01* +X1740Y919D01* +X1740Y915D01* +X1742Y915D01* +X1742Y909D01* +X1744Y909D01* +X1744Y889D01* +X1742Y889D01* +X1742Y883D01* +X1740Y883D01* +X1740Y879D01* +X1738Y879D01* +X1738Y875D01* +X1736Y875D01* +X1736Y873D01* +X1734Y873D01* +X1734Y869D01* +X1732Y869D01* +X1732Y867D01* +X1730Y867D01* +X1730Y865D01* +X1728Y865D01* +X1728Y863D01* +X1724Y863D01* +X1724Y861D01* +X1722Y861D01* +X1722Y859D01* +X1718Y859D01* +X1718Y839D01* +X1722Y839D01* +X1722Y837D01* +X1724Y837D01* +X1724Y835D01* +X1728Y835D01* +X1728Y833D01* +X1730Y833D01* +X1730Y831D01* +X1732Y831D01* +X1732Y829D01* +X1734Y829D01* +X1734Y827D01* +X1736Y827D01* +X1736Y823D01* +X1738Y823D01* +X1738Y819D01* +X1740Y819D01* +X1740Y815D01* +X1742Y815D01* +X1742Y809D01* +X1744Y809D01* +X1744Y789D01* +X1742Y789D01* +X1742Y783D01* +X1740Y783D01* +X1740Y779D01* +X1738Y779D01* +X1738Y775D01* +X1736Y775D01* +X1736Y773D01* +X1734Y773D01* +X1734Y769D01* +X1732Y769D01* +X1732Y767D01* +X1730Y767D01* +X1730Y765D01* +X1728Y765D01* +X1728Y763D01* +X1724Y763D01* +X1724Y761D01* +X1722Y761D01* +X1722Y759D01* +X1718Y759D01* +X1718Y739D01* +X1722Y739D01* +X1722Y737D01* +X1724Y737D01* +X1724Y735D01* +X1728Y735D01* +X1728Y733D01* +X1730Y733D01* +X1730Y731D01* +X1732Y731D01* +X1732Y729D01* +X1734Y729D01* +X1734Y727D01* +X1736Y727D01* +X1736Y723D01* +X1738Y723D01* +X1738Y719D01* +X1740Y719D01* +X1740Y715D01* +X1742Y715D01* +X1742Y709D01* +X1744Y709D01* +X1744Y689D01* +X1742Y689D01* +X1742Y683D01* +X1740Y683D01* +X1740Y679D01* +X1738Y679D01* +X1738Y675D01* +X1736Y675D01* +X1736Y673D01* +X1734Y673D01* +X1734Y669D01* +X1732Y669D01* +X1732Y667D01* +X1730Y667D01* +X1730Y665D01* +X1728Y665D01* +X1728Y663D01* +X1724Y663D01* +X1724Y661D01* +X1722Y661D01* +X1722Y659D01* +X1718Y659D01* +X1718Y639D01* +X1722Y639D01* +X1722Y637D01* +X1724Y637D01* +X1724Y635D01* +X1728Y635D01* +X1728Y633D01* +X1730Y633D01* +X1730Y631D01* +X1732Y631D01* +X1732Y629D01* +X1734Y629D01* +X1734Y627D01* +X1736Y627D01* +X1736Y623D01* +X1738Y623D01* +X1738Y619D01* +X1740Y619D01* +X1740Y615D01* +X1742Y615D01* +X1742Y609D01* +X1744Y609D01* +X1744Y589D01* +X1742Y589D01* +X1742Y583D01* +X1740Y583D01* +X1740Y579D01* +X1738Y579D01* +X1738Y575D01* +X1736Y575D01* +X1736Y573D01* +X1734Y573D01* +X1734Y569D01* +X1732Y569D01* +X1732Y567D01* +X1730Y567D01* +X1730Y565D01* +X1728Y565D01* +X1728Y563D01* +X1724Y563D01* +X1724Y561D01* +X1722Y561D01* +X1722Y559D01* +X1718Y559D01* +X1718Y539D01* +X1722Y539D01* +X1722Y537D01* +X1724Y537D01* +X1724Y535D01* +X1728Y535D01* +X1728Y533D01* +X1730Y533D01* +X1730Y531D01* +X1732Y531D01* +X1732Y529D01* +X1734Y529D01* +X1734Y527D01* +X1736Y527D01* +X1736Y523D01* +X1738Y523D01* +X1738Y519D01* +X1740Y519D01* +X1740Y515D01* +X1742Y515D01* +X1742Y509D01* +X1744Y509D01* +X1744Y489D01* +X1742Y489D01* +X1742Y483D01* +X1740Y483D01* +X1740Y479D01* +X1738Y479D01* +X1738Y475D01* +X1736Y475D01* +X1736Y473D01* +X1734Y473D01* +X1734Y469D01* +X1732Y469D01* +X1732Y467D01* +X1730Y467D01* +X1730Y465D01* +X1728Y465D01* +X1728Y463D01* +X1724Y463D01* +X1724Y461D01* +X1722Y461D01* +X1722Y459D01* +X1718Y459D01* +X1718Y439D01* +X1722Y439D01* +X1722Y437D01* +X1724Y437D01* +X1724Y435D01* +X1728Y435D01* +X1728Y433D01* +X1730Y433D01* +X1730Y431D01* +X1732Y431D01* +X1732Y429D01* +X1734Y429D01* +X1734Y427D01* +X1736Y427D01* +X1736Y423D01* +X1738Y423D01* +X1738Y419D01* +X1740Y419D01* +X1740Y415D01* +X1742Y415D01* +X1742Y409D01* +X1744Y409D01* +X1744Y389D01* +X1742Y389D01* +X1742Y383D01* +X1740Y383D01* +X1740Y379D01* +X1738Y379D01* +X1738Y375D01* +X1736Y375D01* +X1736Y373D01* +X1734Y373D01* +X1734Y369D01* +X1732Y369D01* +X1732Y367D01* +X1730Y367D01* +X1730Y365D01* +X1728Y365D01* +X1728Y363D01* +X1724Y363D01* +X1724Y361D01* +X1722Y361D01* +X1722Y359D01* +X1718Y359D01* +X1718Y339D01* +X1722Y339D01* +X1722Y337D01* +X1724Y337D01* +X1724Y335D01* +X1728Y335D01* +X1728Y333D01* +X1730Y333D01* +X1730Y331D01* +X1732Y331D01* +X1732Y329D01* +X1734Y329D01* +X1734Y327D01* +X1736Y327D01* +X1736Y323D01* +X1738Y323D01* +X1738Y319D01* +X1740Y319D01* +X1740Y315D01* +X1742Y315D01* +X1742Y309D01* +X1744Y309D01* +X1744Y289D01* +X1742Y289D01* +X1742Y283D01* +X1740Y283D01* +X1740Y279D01* +X1738Y279D01* +X1738Y275D01* +X1736Y275D01* +X1736Y273D01* +X1734Y273D01* +X1734Y269D01* +X1732Y269D01* +X1732Y267D01* +X1730Y267D01* +X1730Y265D01* +X1728Y265D01* +X1728Y263D01* +X1724Y263D01* +X1724Y261D01* +X1722Y261D01* +X1722Y259D01* +X1718Y259D01* +X1718Y239D01* +X1722Y239D01* +X1722Y237D01* +X1724Y237D01* +X1724Y235D01* +X1728Y235D01* +X1728Y233D01* +X1730Y233D01* +X1730Y231D01* +X1732Y231D01* +X1732Y229D01* +X1734Y229D01* +X1734Y227D01* +X1736Y227D01* +X1736Y223D01* +X1738Y223D01* +X1738Y219D01* +X1740Y219D01* +X1740Y215D01* +X1742Y215D01* +X1742Y209D01* +X1744Y209D01* +X1744Y189D01* +X1742Y189D01* +X1742Y183D01* +X1740Y183D01* +X1740Y179D01* +X1738Y179D01* +X1738Y175D01* +X1736Y175D01* +X1736Y173D01* +X1734Y173D01* +X1734Y169D01* +X1732Y169D01* +X1732Y167D01* +X1730Y167D01* +X1730Y165D01* +X1728Y165D01* +X1728Y163D01* +X1724Y163D01* +X1724Y161D01* +X1722Y161D01* +X1722Y159D01* +X1718Y159D01* +X1718Y157D01* +X1712Y157D01* +X1712Y155D01* +X2178Y155D01* +X2178Y1305D01* +X2180Y1305D01* +X2180Y1309D01* +X2182Y1309D01* +X2182Y1311D01* +X2184Y1311D01* +X2184Y1315D01* +X2188Y1315D01* +X2188Y1317D01* +X2190Y1317D01* +X2190Y1319D01* +X2198Y1319D01* +X2198Y1321D01* +X2260Y1321D01* +X2260Y1323D01* +X2262Y1323D01* +X2262Y1325D01* +X2264Y1325D01* +X2264Y1327D01* +X2266Y1327D01* +X2266Y1331D01* +X2268Y1331D01* +X2268Y1333D01* +X2272Y1333D01* +X2272Y1335D01* +X2274Y1335D01* +X2274Y1337D01* +X2278Y1337D01* +X2278Y1339D01* +X2280Y1339D01* +X2280Y1359D01* +X2278Y1359D01* +X2278Y1361D01* +X2274Y1361D01* +X2274Y1363D01* +X2272Y1363D01* +X2272Y1365D01* +X2268Y1365D01* +X2268Y1367D01* +X2266Y1367D01* +X2266Y1371D01* +X2264Y1371D01* +X2264Y1373D01* +X2262Y1373D01* +X2262Y1375D01* +X2260Y1375D01* +X2260Y1379D01* +X2258Y1379D01* +X2258Y1385D01* +X2256Y1385D01* +X2256Y1391D01* +X2254Y1391D01* +X2254Y1407D01* +X2256Y1407D01* +X2256Y1413D01* +X2258Y1413D01* +X2258Y1419D01* +X2260Y1419D01* +X2260Y1423D01* +X2262Y1423D01* +X2262Y1425D01* +X2264Y1425D01* +X2264Y1427D01* +X2266Y1427D01* +X2266Y1431D01* +X2268Y1431D01* +X2268Y1433D01* +X2272Y1433D01* +X2272Y1435D01* +X2274Y1435D01* +X2274Y1437D01* +X2278Y1437D01* +X2278Y1439D01* +X2280Y1439D01* +X2280Y1459D01* +X2278Y1459D01* +X2278Y1461D01* +X2274Y1461D01* +X2274Y1463D01* +X2272Y1463D01* +X2272Y1465D01* +X2268Y1465D01* +X2268Y1467D01* +X2266Y1467D01* +X2266Y1471D01* +X2264Y1471D01* +X2264Y1473D01* +X2262Y1473D01* +X2262Y1475D01* +X2260Y1475D01* +X2260Y1477D01* +X2198Y1477D01* +X2198Y1479D01* +X2190Y1479D01* +X2190Y1481D01* +X2188Y1481D01* +X2188Y1483D01* +X2184Y1483D01* +X2184Y1485D01* +X2182Y1485D01* +X2182Y1489D01* +X2180Y1489D01* +X2180Y1493D01* +X2178Y1493D01* +X2178Y1675D01* +X1622Y1675D01* +G37* +D02* +G36* +X1622Y1645D02* +X1622Y199D01* +X1620Y199D01* +X1620Y189D01* +X1618Y189D01* +X1618Y187D01* +X1616Y187D01* +X1616Y183D01* +X1612Y183D01* +X1612Y181D01* +X1610Y181D01* +X1610Y179D01* +X1606Y179D01* +X1606Y177D01* +X1222Y177D01* +X1222Y155D01* +X1688Y155D01* +X1688Y157D01* +X1682Y157D01* +X1682Y159D01* +X1678Y159D01* +X1678Y161D01* +X1674Y161D01* +X1674Y163D01* +X1672Y163D01* +X1672Y165D01* +X1668Y165D01* +X1668Y167D01* +X1666Y167D01* +X1666Y171D01* +X1664Y171D01* +X1664Y173D01* +X1662Y173D01* +X1662Y175D01* +X1660Y175D01* +X1660Y179D01* +X1658Y179D01* +X1658Y185D01* +X1656Y185D01* +X1656Y191D01* +X1654Y191D01* +X1654Y207D01* +X1656Y207D01* +X1656Y213D01* +X1658Y213D01* +X1658Y219D01* +X1660Y219D01* +X1660Y223D01* +X1662Y223D01* +X1662Y225D01* +X1664Y225D01* +X1664Y227D01* +X1666Y227D01* +X1666Y231D01* +X1668Y231D01* +X1668Y233D01* +X1672Y233D01* +X1672Y235D01* +X1674Y235D01* +X1674Y237D01* +X1678Y237D01* +X1678Y239D01* +X1680Y239D01* +X1680Y259D01* +X1678Y259D01* +X1678Y261D01* +X1674Y261D01* +X1674Y263D01* +X1672Y263D01* +X1672Y265D01* +X1668Y265D01* +X1668Y267D01* +X1666Y267D01* +X1666Y271D01* +X1664Y271D01* +X1664Y273D01* +X1662Y273D01* +X1662Y275D01* +X1660Y275D01* +X1660Y279D01* +X1658Y279D01* +X1658Y285D01* +X1656Y285D01* +X1656Y291D01* +X1654Y291D01* +X1654Y307D01* +X1656Y307D01* +X1656Y313D01* +X1658Y313D01* +X1658Y319D01* +X1660Y319D01* +X1660Y323D01* +X1662Y323D01* +X1662Y325D01* +X1664Y325D01* +X1664Y327D01* +X1666Y327D01* +X1666Y331D01* +X1668Y331D01* +X1668Y333D01* +X1672Y333D01* +X1672Y335D01* +X1674Y335D01* +X1674Y337D01* +X1678Y337D01* +X1678Y339D01* +X1680Y339D01* +X1680Y359D01* +X1678Y359D01* +X1678Y361D01* +X1674Y361D01* +X1674Y363D01* +X1672Y363D01* +X1672Y365D01* +X1668Y365D01* +X1668Y367D01* +X1666Y367D01* +X1666Y371D01* +X1664Y371D01* +X1664Y373D01* +X1662Y373D01* +X1662Y375D01* +X1660Y375D01* +X1660Y379D01* +X1658Y379D01* +X1658Y385D01* +X1656Y385D01* +X1656Y391D01* +X1654Y391D01* +X1654Y407D01* +X1656Y407D01* +X1656Y413D01* +X1658Y413D01* +X1658Y419D01* +X1660Y419D01* +X1660Y423D01* +X1662Y423D01* +X1662Y425D01* +X1664Y425D01* +X1664Y427D01* +X1666Y427D01* +X1666Y431D01* +X1668Y431D01* +X1668Y433D01* +X1672Y433D01* +X1672Y435D01* +X1674Y435D01* +X1674Y437D01* +X1678Y437D01* +X1678Y439D01* +X1680Y439D01* +X1680Y459D01* +X1678Y459D01* +X1678Y461D01* +X1674Y461D01* +X1674Y463D01* +X1672Y463D01* +X1672Y465D01* +X1668Y465D01* +X1668Y467D01* +X1666Y467D01* +X1666Y471D01* +X1664Y471D01* +X1664Y473D01* +X1662Y473D01* +X1662Y475D01* +X1660Y475D01* +X1660Y479D01* +X1658Y479D01* +X1658Y485D01* +X1656Y485D01* +X1656Y491D01* +X1654Y491D01* +X1654Y507D01* +X1656Y507D01* +X1656Y513D01* +X1658Y513D01* +X1658Y519D01* +X1660Y519D01* +X1660Y523D01* +X1662Y523D01* +X1662Y525D01* +X1664Y525D01* +X1664Y527D01* +X1666Y527D01* +X1666Y531D01* +X1668Y531D01* +X1668Y533D01* +X1672Y533D01* +X1672Y535D01* +X1674Y535D01* +X1674Y537D01* +X1678Y537D01* +X1678Y539D01* +X1680Y539D01* +X1680Y559D01* +X1678Y559D01* +X1678Y561D01* +X1674Y561D01* +X1674Y563D01* +X1672Y563D01* +X1672Y565D01* +X1668Y565D01* +X1668Y567D01* +X1666Y567D01* +X1666Y571D01* +X1664Y571D01* +X1664Y573D01* +X1662Y573D01* +X1662Y575D01* +X1660Y575D01* +X1660Y579D01* +X1658Y579D01* +X1658Y585D01* +X1656Y585D01* +X1656Y591D01* +X1654Y591D01* +X1654Y607D01* +X1656Y607D01* +X1656Y613D01* +X1658Y613D01* +X1658Y619D01* +X1660Y619D01* +X1660Y623D01* +X1662Y623D01* +X1662Y625D01* +X1664Y625D01* +X1664Y627D01* +X1666Y627D01* +X1666Y631D01* +X1668Y631D01* +X1668Y633D01* +X1672Y633D01* +X1672Y635D01* +X1674Y635D01* +X1674Y637D01* +X1678Y637D01* +X1678Y639D01* +X1680Y639D01* +X1680Y659D01* +X1678Y659D01* +X1678Y661D01* +X1674Y661D01* +X1674Y663D01* +X1672Y663D01* +X1672Y665D01* +X1668Y665D01* +X1668Y667D01* +X1666Y667D01* +X1666Y671D01* +X1664Y671D01* +X1664Y673D01* +X1662Y673D01* +X1662Y675D01* +X1660Y675D01* +X1660Y679D01* +X1658Y679D01* +X1658Y685D01* +X1656Y685D01* +X1656Y691D01* +X1654Y691D01* +X1654Y707D01* +X1656Y707D01* +X1656Y713D01* +X1658Y713D01* +X1658Y719D01* +X1660Y719D01* +X1660Y723D01* +X1662Y723D01* +X1662Y725D01* +X1664Y725D01* +X1664Y727D01* +X1666Y727D01* +X1666Y731D01* +X1668Y731D01* +X1668Y733D01* +X1672Y733D01* +X1672Y735D01* +X1674Y735D01* +X1674Y737D01* +X1678Y737D01* +X1678Y739D01* +X1680Y739D01* +X1680Y759D01* +X1678Y759D01* +X1678Y761D01* +X1674Y761D01* +X1674Y763D01* +X1672Y763D01* +X1672Y765D01* +X1668Y765D01* +X1668Y767D01* +X1666Y767D01* +X1666Y771D01* +X1664Y771D01* +X1664Y773D01* +X1662Y773D01* +X1662Y775D01* +X1660Y775D01* +X1660Y779D01* +X1658Y779D01* +X1658Y785D01* +X1656Y785D01* +X1656Y791D01* +X1654Y791D01* +X1654Y807D01* +X1656Y807D01* +X1656Y813D01* +X1658Y813D01* +X1658Y819D01* +X1660Y819D01* +X1660Y823D01* +X1662Y823D01* +X1662Y825D01* +X1664Y825D01* +X1664Y827D01* +X1666Y827D01* +X1666Y831D01* +X1668Y831D01* +X1668Y833D01* +X1672Y833D01* +X1672Y835D01* +X1674Y835D01* +X1674Y837D01* +X1678Y837D01* +X1678Y839D01* +X1680Y839D01* +X1680Y859D01* +X1678Y859D01* +X1678Y861D01* +X1674Y861D01* +X1674Y863D01* +X1672Y863D01* +X1672Y865D01* +X1668Y865D01* +X1668Y867D01* +X1666Y867D01* +X1666Y871D01* +X1664Y871D01* +X1664Y873D01* +X1662Y873D01* +X1662Y875D01* +X1660Y875D01* +X1660Y879D01* +X1658Y879D01* +X1658Y885D01* +X1656Y885D01* +X1656Y891D01* +X1654Y891D01* +X1654Y907D01* +X1656Y907D01* +X1656Y913D01* +X1658Y913D01* +X1658Y919D01* +X1660Y919D01* +X1660Y923D01* +X1662Y923D01* +X1662Y925D01* +X1664Y925D01* +X1664Y927D01* +X1666Y927D01* +X1666Y931D01* +X1668Y931D01* +X1668Y933D01* +X1672Y933D01* +X1672Y935D01* +X1674Y935D01* +X1674Y937D01* +X1678Y937D01* +X1678Y939D01* +X1680Y939D01* +X1680Y959D01* +X1678Y959D01* +X1678Y961D01* +X1674Y961D01* +X1674Y963D01* +X1672Y963D01* +X1672Y965D01* +X1668Y965D01* +X1668Y967D01* +X1666Y967D01* +X1666Y971D01* +X1664Y971D01* +X1664Y973D01* +X1662Y973D01* +X1662Y975D01* +X1660Y975D01* +X1660Y979D01* +X1658Y979D01* +X1658Y985D01* +X1656Y985D01* +X1656Y991D01* +X1654Y991D01* +X1654Y1007D01* +X1656Y1007D01* +X1656Y1013D01* +X1658Y1013D01* +X1658Y1019D01* +X1660Y1019D01* +X1660Y1023D01* +X1662Y1023D01* +X1662Y1025D01* +X1664Y1025D01* +X1664Y1027D01* +X1666Y1027D01* +X1666Y1031D01* +X1668Y1031D01* +X1668Y1033D01* +X1672Y1033D01* +X1672Y1035D01* +X1674Y1035D01* +X1674Y1037D01* +X1678Y1037D01* +X1678Y1039D01* +X1680Y1039D01* +X1680Y1059D01* +X1678Y1059D01* +X1678Y1061D01* +X1674Y1061D01* +X1674Y1063D01* +X1672Y1063D01* +X1672Y1065D01* +X1668Y1065D01* +X1668Y1067D01* +X1666Y1067D01* +X1666Y1071D01* +X1664Y1071D01* +X1664Y1073D01* +X1662Y1073D01* +X1662Y1075D01* +X1660Y1075D01* +X1660Y1079D01* +X1658Y1079D01* +X1658Y1085D01* +X1656Y1085D01* +X1656Y1091D01* +X1654Y1091D01* +X1654Y1107D01* +X1656Y1107D01* +X1656Y1113D01* +X1658Y1113D01* +X1658Y1119D01* +X1660Y1119D01* +X1660Y1123D01* +X1662Y1123D01* +X1662Y1125D01* +X1664Y1125D01* +X1664Y1127D01* +X1666Y1127D01* +X1666Y1131D01* +X1668Y1131D01* +X1668Y1133D01* +X1672Y1133D01* +X1672Y1135D01* +X1674Y1135D01* +X1674Y1137D01* +X1678Y1137D01* +X1678Y1139D01* +X1680Y1139D01* +X1680Y1159D01* +X1678Y1159D01* +X1678Y1161D01* +X1674Y1161D01* +X1674Y1163D01* +X1672Y1163D01* +X1672Y1165D01* +X1668Y1165D01* +X1668Y1167D01* +X1666Y1167D01* +X1666Y1171D01* +X1664Y1171D01* +X1664Y1173D01* +X1662Y1173D01* +X1662Y1175D01* +X1660Y1175D01* +X1660Y1179D01* +X1658Y1179D01* +X1658Y1185D01* +X1656Y1185D01* +X1656Y1191D01* +X1654Y1191D01* +X1654Y1207D01* +X1656Y1207D01* +X1656Y1213D01* +X1658Y1213D01* +X1658Y1219D01* +X1660Y1219D01* +X1660Y1223D01* +X1662Y1223D01* +X1662Y1225D01* +X1664Y1225D01* +X1664Y1227D01* +X1666Y1227D01* +X1666Y1231D01* +X1668Y1231D01* +X1668Y1233D01* +X1672Y1233D01* +X1672Y1235D01* +X1674Y1235D01* +X1674Y1237D01* +X1678Y1237D01* +X1678Y1239D01* +X1680Y1239D01* +X1680Y1259D01* +X1678Y1259D01* +X1678Y1261D01* +X1674Y1261D01* +X1674Y1263D01* +X1672Y1263D01* +X1672Y1265D01* +X1668Y1265D01* +X1668Y1267D01* +X1666Y1267D01* +X1666Y1271D01* +X1664Y1271D01* +X1664Y1273D01* +X1662Y1273D01* +X1662Y1275D01* +X1660Y1275D01* +X1660Y1279D01* +X1658Y1279D01* +X1658Y1285D01* +X1656Y1285D01* +X1656Y1291D01* +X1654Y1291D01* +X1654Y1307D01* +X1656Y1307D01* +X1656Y1313D01* +X1658Y1313D01* +X1658Y1319D01* +X1660Y1319D01* +X1660Y1323D01* +X1662Y1323D01* +X1662Y1325D01* +X1664Y1325D01* +X1664Y1327D01* +X1666Y1327D01* +X1666Y1331D01* +X1668Y1331D01* +X1668Y1333D01* +X1672Y1333D01* +X1672Y1335D01* +X1674Y1335D01* +X1674Y1337D01* +X1678Y1337D01* +X1678Y1339D01* +X1680Y1339D01* +X1680Y1359D01* +X1678Y1359D01* +X1678Y1361D01* +X1674Y1361D01* +X1674Y1363D01* +X1672Y1363D01* +X1672Y1365D01* +X1668Y1365D01* +X1668Y1367D01* +X1666Y1367D01* +X1666Y1371D01* +X1664Y1371D01* +X1664Y1373D01* +X1662Y1373D01* +X1662Y1375D01* +X1660Y1375D01* +X1660Y1379D01* +X1658Y1379D01* +X1658Y1385D01* +X1656Y1385D01* +X1656Y1391D01* +X1654Y1391D01* +X1654Y1407D01* +X1656Y1407D01* +X1656Y1413D01* +X1658Y1413D01* +X1658Y1419D01* +X1660Y1419D01* +X1660Y1423D01* +X1662Y1423D01* +X1662Y1425D01* +X1664Y1425D01* +X1664Y1427D01* +X1666Y1427D01* +X1666Y1431D01* +X1668Y1431D01* +X1668Y1433D01* +X1672Y1433D01* +X1672Y1435D01* +X1674Y1435D01* +X1674Y1437D01* +X1678Y1437D01* +X1678Y1439D01* +X1680Y1439D01* +X1680Y1459D01* +X1678Y1459D01* +X1678Y1461D01* +X1674Y1461D01* +X1674Y1463D01* +X1672Y1463D01* +X1672Y1465D01* +X1668Y1465D01* +X1668Y1467D01* +X1666Y1467D01* +X1666Y1471D01* +X1664Y1471D01* +X1664Y1473D01* +X1662Y1473D01* +X1662Y1475D01* +X1660Y1475D01* +X1660Y1479D01* +X1658Y1479D01* +X1658Y1485D01* +X1656Y1485D01* +X1656Y1491D01* +X1654Y1491D01* +X1654Y1507D01* +X1656Y1507D01* +X1656Y1513D01* +X1658Y1513D01* +X1658Y1519D01* +X1660Y1519D01* +X1660Y1523D01* +X1662Y1523D01* +X1662Y1525D01* +X1664Y1525D01* +X1664Y1527D01* +X1666Y1527D01* +X1666Y1531D01* +X1668Y1531D01* +X1668Y1533D01* +X1672Y1533D01* +X1672Y1535D01* +X1674Y1535D01* +X1674Y1555D01* +X1654Y1555D01* +X1654Y1643D01* +X1656Y1643D01* +X1656Y1645D01* +X1622Y1645D01* +G37* +D02* +G36* +X1222Y155D02* +X1222Y153D01* +X2178Y153D01* +X2178Y155D01* +X1222Y155D01* +G37* +D02* +G36* +X1222Y155D02* +X1222Y153D01* +X2178Y153D01* +X2178Y155D01* +X1222Y155D01* +G37* +D02* +G36* +X1222Y153D02* +X1222Y149D01* +X1500Y149D01* +X1500Y147D01* +X1512Y147D01* +X1512Y145D01* +X1518Y145D01* +X1518Y143D01* +X1522Y143D01* +X1522Y141D01* +X1526Y141D01* +X1526Y139D01* +X1528Y139D01* +X1528Y137D01* +X1532Y137D01* +X1532Y135D01* +X1534Y135D01* +X1534Y133D01* +X1536Y133D01* +X1536Y129D01* +X1538Y129D01* +X1538Y127D01* +X1540Y127D01* +X1540Y125D01* +X1542Y125D01* +X1542Y121D01* +X2130Y121D01* +X2130Y123D01* +X2178Y123D01* +X2178Y153D01* +X1222Y153D01* +G37* +D02* +G36* +X1222Y149D02* +X1222Y141D01* +X1226Y141D01* +X1226Y139D01* +X1228Y139D01* +X1228Y137D01* +X1232Y137D01* +X1232Y135D01* +X1234Y135D01* +X1234Y133D01* +X1236Y133D01* +X1236Y129D01* +X1238Y129D01* +X1238Y127D01* +X1260Y127D01* +X1260Y129D01* +X1262Y129D01* +X1262Y131D01* +X1264Y131D01* +X1264Y133D01* +X1266Y133D01* +X1266Y135D01* +X1268Y135D01* +X1268Y137D01* +X1270Y137D01* +X1270Y139D01* +X1272Y139D01* +X1272Y141D01* +X1276Y141D01* +X1276Y143D01* +X1280Y143D01* +X1280Y145D01* +X1286Y145D01* +X1286Y147D01* +X1298Y147D01* +X1298Y149D01* +X1222Y149D01* +G37* +D02* +G36* +X1300Y149D02* +X1300Y147D01* +X1312Y147D01* +X1312Y145D01* +X1318Y145D01* +X1318Y143D01* +X1322Y143D01* +X1322Y141D01* +X1326Y141D01* +X1326Y139D01* +X1328Y139D01* +X1328Y137D01* +X1332Y137D01* +X1332Y135D01* +X1334Y135D01* +X1334Y133D01* +X1336Y133D01* +X1336Y129D01* +X1338Y129D01* +X1338Y127D01* +X1360Y127D01* +X1360Y129D01* +X1362Y129D01* +X1362Y131D01* +X1364Y131D01* +X1364Y133D01* +X1366Y133D01* +X1366Y135D01* +X1368Y135D01* +X1368Y137D01* +X1370Y137D01* +X1370Y139D01* +X1372Y139D01* +X1372Y141D01* +X1376Y141D01* +X1376Y143D01* +X1380Y143D01* +X1380Y145D01* +X1386Y145D01* +X1386Y147D01* +X1398Y147D01* +X1398Y149D01* +X1300Y149D01* +G37* +D02* +G36* +X1400Y149D02* +X1400Y147D01* +X1412Y147D01* +X1412Y145D01* +X1418Y145D01* +X1418Y143D01* +X1422Y143D01* +X1422Y141D01* +X1426Y141D01* +X1426Y139D01* +X1428Y139D01* +X1428Y137D01* +X1432Y137D01* +X1432Y135D01* +X1434Y135D01* +X1434Y133D01* +X1436Y133D01* +X1436Y129D01* +X1438Y129D01* +X1438Y127D01* +X1460Y127D01* +X1460Y129D01* +X1462Y129D01* +X1462Y131D01* +X1464Y131D01* +X1464Y133D01* +X1466Y133D01* +X1466Y135D01* +X1468Y135D01* +X1468Y137D01* +X1470Y137D01* +X1470Y139D01* +X1472Y139D01* +X1472Y141D01* +X1476Y141D01* +X1476Y143D01* +X1480Y143D01* +X1480Y145D01* +X1486Y145D01* +X1486Y147D01* +X1498Y147D01* +X1498Y149D01* +X1400Y149D01* +G37* +D02* +G36* +X132Y1759D02* +X132Y1739D01* +X136Y1739D01* +X136Y1737D01* +X138Y1737D01* +X138Y1735D01* +X140Y1735D01* +X140Y1731D01* +X142Y1731D01* +X142Y1729D01* +X144Y1729D01* +X144Y1725D01* +X146Y1725D01* +X146Y1721D01* +X148Y1721D01* +X148Y1717D01* +X150Y1717D01* +X150Y1711D01* +X152Y1711D01* +X152Y1687D01* +X150Y1687D01* +X150Y1681D01* +X148Y1681D01* +X148Y1677D01* +X146Y1677D01* +X146Y1673D01* +X144Y1673D01* +X144Y1669D01* +X142Y1669D01* +X142Y1667D01* +X140Y1667D01* +X140Y1663D01* +X138Y1663D01* +X138Y1661D01* +X136Y1661D01* +X136Y1659D01* +X132Y1659D01* +X132Y1657D01* +X130Y1657D01* +X130Y1655D01* +X128Y1655D01* +X128Y1653D01* +X124Y1653D01* +X124Y1651D01* +X120Y1651D01* +X120Y1649D01* +X114Y1649D01* +X114Y1647D01* +X104Y1647D01* +X104Y1645D01* +X272Y1645D01* +X272Y1659D01* +X270Y1659D01* +X270Y1661D01* +X268Y1661D01* +X268Y1663D01* +X266Y1663D01* +X266Y1665D01* +X264Y1665D01* +X264Y1667D01* +X262Y1667D01* +X262Y1669D01* +X260Y1669D01* +X260Y1671D01* +X258Y1671D01* +X258Y1675D01* +X256Y1675D01* +X256Y1679D01* +X254Y1679D01* +X254Y1683D01* +X252Y1683D01* +X252Y1691D01* +X250Y1691D01* +X250Y1707D01* +X252Y1707D01* +X252Y1715D01* +X254Y1715D01* +X254Y1719D01* +X256Y1719D01* +X256Y1723D01* +X258Y1723D01* +X258Y1727D01* +X260Y1727D01* +X260Y1729D01* +X262Y1729D01* +X262Y1731D01* +X264Y1731D01* +X264Y1733D01* +X266Y1733D01* +X266Y1735D01* +X268Y1735D01* +X268Y1737D01* +X270Y1737D01* +X270Y1739D01* +X272Y1739D01* +X272Y1759D01* +X132Y1759D01* +G37* +D02* +G36* +X326Y1759D02* +X326Y1739D01* +X328Y1739D01* +X328Y1737D01* +X332Y1737D01* +X332Y1735D01* +X334Y1735D01* +X334Y1733D01* +X336Y1733D01* +X336Y1729D01* +X338Y1729D01* +X338Y1727D01* +X340Y1727D01* +X340Y1725D01* +X342Y1725D01* +X342Y1721D01* +X344Y1721D01* +X344Y1717D01* +X346Y1717D01* +X346Y1709D01* +X348Y1709D01* +X348Y1689D01* +X346Y1689D01* +X346Y1681D01* +X344Y1681D01* +X344Y1677D01* +X342Y1677D01* +X342Y1673D01* +X340Y1673D01* +X340Y1671D01* +X338Y1671D01* +X338Y1669D01* +X336Y1669D01* +X336Y1665D01* +X334Y1665D01* +X334Y1663D01* +X330Y1663D01* +X330Y1661D01* +X328Y1661D01* +X328Y1659D01* +X326Y1659D01* +X326Y1639D01* +X328Y1639D01* +X328Y1637D01* +X332Y1637D01* +X332Y1635D01* +X334Y1635D01* +X334Y1633D01* +X336Y1633D01* +X336Y1629D01* +X338Y1629D01* +X338Y1627D01* +X340Y1627D01* +X340Y1625D01* +X342Y1625D01* +X342Y1621D01* +X344Y1621D01* +X344Y1617D01* +X346Y1617D01* +X346Y1609D01* +X348Y1609D01* +X348Y1589D01* +X346Y1589D01* +X346Y1581D01* +X344Y1581D01* +X344Y1577D01* +X342Y1577D01* +X342Y1573D01* +X340Y1573D01* +X340Y1571D01* +X338Y1571D01* +X338Y1569D01* +X336Y1569D01* +X336Y1565D01* +X334Y1565D01* +X334Y1563D01* +X330Y1563D01* +X330Y1561D01* +X328Y1561D01* +X328Y1559D01* +X326Y1559D01* +X326Y1557D01* +X322Y1557D01* +X322Y1555D01* +X318Y1555D01* +X318Y1553D01* +X312Y1553D01* +X312Y1551D01* +X986Y1551D01* +X986Y1553D01* +X980Y1553D01* +X980Y1555D01* +X976Y1555D01* +X976Y1557D01* +X972Y1557D01* +X972Y1559D01* +X970Y1559D01* +X970Y1561D01* +X968Y1561D01* +X968Y1563D01* +X966Y1563D01* +X966Y1565D01* +X964Y1565D01* +X964Y1567D01* +X962Y1567D01* +X962Y1569D01* +X960Y1569D01* +X960Y1571D01* +X958Y1571D01* +X958Y1575D01* +X956Y1575D01* +X956Y1579D01* +X954Y1579D01* +X954Y1583D01* +X952Y1583D01* +X952Y1591D01* +X950Y1591D01* +X950Y1607D01* +X952Y1607D01* +X952Y1615D01* +X954Y1615D01* +X954Y1619D01* +X956Y1619D01* +X956Y1623D01* +X958Y1623D01* +X958Y1627D01* +X960Y1627D01* +X960Y1629D01* +X962Y1629D01* +X962Y1631D01* +X964Y1631D01* +X964Y1633D01* +X966Y1633D01* +X966Y1635D01* +X968Y1635D01* +X968Y1637D01* +X970Y1637D01* +X970Y1639D01* +X972Y1639D01* +X972Y1659D01* +X970Y1659D01* +X970Y1661D01* +X968Y1661D01* +X968Y1663D01* +X966Y1663D01* +X966Y1665D01* +X964Y1665D01* +X964Y1667D01* +X962Y1667D01* +X962Y1669D01* +X960Y1669D01* +X960Y1671D01* +X958Y1671D01* +X958Y1675D01* +X956Y1675D01* +X956Y1679D01* +X954Y1679D01* +X954Y1683D01* +X952Y1683D01* +X952Y1691D01* +X950Y1691D01* +X950Y1707D01* +X952Y1707D01* +X952Y1715D01* +X954Y1715D01* +X954Y1719D01* +X956Y1719D01* +X956Y1723D01* +X958Y1723D01* +X958Y1727D01* +X960Y1727D01* +X960Y1729D01* +X962Y1729D01* +X962Y1731D01* +X964Y1731D01* +X964Y1733D01* +X966Y1733D01* +X966Y1735D01* +X968Y1735D01* +X968Y1737D01* +X970Y1737D01* +X970Y1739D01* +X972Y1739D01* +X972Y1759D01* +X326Y1759D01* +G37* +D02* +G36* +X1026Y1759D02* +X1026Y1739D01* +X1028Y1739D01* +X1028Y1737D01* +X1032Y1737D01* +X1032Y1735D01* +X1034Y1735D01* +X1034Y1733D01* +X1036Y1733D01* +X1036Y1729D01* +X1038Y1729D01* +X1038Y1727D01* +X1040Y1727D01* +X1040Y1725D01* +X1042Y1725D01* +X1042Y1721D01* +X1044Y1721D01* +X1044Y1717D01* +X1046Y1717D01* +X1046Y1709D01* +X1048Y1709D01* +X1048Y1689D01* +X1046Y1689D01* +X1046Y1681D01* +X1044Y1681D01* +X1044Y1677D01* +X1042Y1677D01* +X1042Y1673D01* +X1040Y1673D01* +X1040Y1671D01* +X1038Y1671D01* +X1038Y1669D01* +X1036Y1669D01* +X1036Y1665D01* +X1034Y1665D01* +X1034Y1663D01* +X1030Y1663D01* +X1030Y1661D01* +X1028Y1661D01* +X1028Y1659D01* +X1026Y1659D01* +X1026Y1651D01* +X1186Y1651D01* +X1186Y1653D01* +X1180Y1653D01* +X1180Y1655D01* +X1176Y1655D01* +X1176Y1657D01* +X1172Y1657D01* +X1172Y1659D01* +X1170Y1659D01* +X1170Y1661D01* +X1168Y1661D01* +X1168Y1663D01* +X1166Y1663D01* +X1166Y1665D01* +X1164Y1665D01* +X1164Y1667D01* +X1162Y1667D01* +X1162Y1669D01* +X1160Y1669D01* +X1160Y1671D01* +X1158Y1671D01* +X1158Y1675D01* +X1156Y1675D01* +X1156Y1679D01* +X1154Y1679D01* +X1154Y1683D01* +X1152Y1683D01* +X1152Y1691D01* +X1150Y1691D01* +X1150Y1707D01* +X1152Y1707D01* +X1152Y1715D01* +X1154Y1715D01* +X1154Y1719D01* +X1156Y1719D01* +X1156Y1723D01* +X1158Y1723D01* +X1158Y1727D01* +X1160Y1727D01* +X1160Y1729D01* +X1162Y1729D01* +X1162Y1731D01* +X1164Y1731D01* +X1164Y1733D01* +X1166Y1733D01* +X1166Y1735D01* +X1168Y1735D01* +X1168Y1737D01* +X1170Y1737D01* +X1170Y1739D01* +X1172Y1739D01* +X1172Y1759D01* +X1026Y1759D01* +G37* +D02* +G36* +X1526Y1759D02* +X1526Y1739D01* +X1528Y1739D01* +X1528Y1737D01* +X1532Y1737D01* +X1532Y1735D01* +X1534Y1735D01* +X1534Y1733D01* +X1536Y1733D01* +X1536Y1729D01* +X1538Y1729D01* +X1538Y1727D01* +X1540Y1727D01* +X1540Y1725D01* +X1542Y1725D01* +X1542Y1721D01* +X1544Y1721D01* +X1544Y1719D01* +X2208Y1719D01* +X2208Y1717D01* +X2212Y1717D01* +X2212Y1715D01* +X2214Y1715D01* +X2214Y1713D01* +X2216Y1713D01* +X2216Y1711D01* +X2218Y1711D01* +X2218Y1709D01* +X2220Y1709D01* +X2220Y1703D01* +X2222Y1703D01* +X2222Y1521D01* +X2260Y1521D01* +X2260Y1523D01* +X2262Y1523D01* +X2262Y1525D01* +X2264Y1525D01* +X2264Y1527D01* +X2266Y1527D01* +X2266Y1531D01* +X2268Y1531D01* +X2268Y1533D01* +X2272Y1533D01* +X2272Y1535D01* +X2274Y1535D01* +X2274Y1537D01* +X2278Y1537D01* +X2278Y1539D01* +X2280Y1539D01* +X2280Y1559D01* +X2278Y1559D01* +X2278Y1561D01* +X2274Y1561D01* +X2274Y1563D01* +X2272Y1563D01* +X2272Y1565D01* +X2268Y1565D01* +X2268Y1567D01* +X2266Y1567D01* +X2266Y1571D01* +X2264Y1571D01* +X2264Y1573D01* +X2262Y1573D01* +X2262Y1575D01* +X2260Y1575D01* +X2260Y1579D01* +X2258Y1579D01* +X2258Y1585D01* +X2256Y1585D01* +X2256Y1591D01* +X2254Y1591D01* +X2254Y1607D01* +X2256Y1607D01* +X2256Y1613D01* +X2258Y1613D01* +X2258Y1619D01* +X2260Y1619D01* +X2260Y1623D01* +X2262Y1623D01* +X2262Y1625D01* +X2264Y1625D01* +X2264Y1627D01* +X2266Y1627D01* +X2266Y1631D01* +X2268Y1631D01* +X2268Y1633D01* +X2272Y1633D01* +X2272Y1635D01* +X2274Y1635D01* +X2274Y1637D01* +X2278Y1637D01* +X2278Y1639D01* +X2280Y1639D01* +X2280Y1641D01* +X2286Y1641D01* +X2286Y1643D01* +X2298Y1643D01* +X2298Y1645D01* +X2494Y1645D01* +X2494Y1647D01* +X2484Y1647D01* +X2484Y1649D01* +X2478Y1649D01* +X2478Y1651D01* +X2476Y1651D01* +X2476Y1653D01* +X2472Y1653D01* +X2472Y1655D01* +X2468Y1655D01* +X2468Y1657D01* +X2466Y1657D01* +X2466Y1659D01* +X2464Y1659D01* +X2464Y1661D01* +X2462Y1661D01* +X2462Y1663D01* +X2460Y1663D01* +X2460Y1665D01* +X2458Y1665D01* +X2458Y1667D01* +X2456Y1667D01* +X2456Y1669D01* +X2454Y1669D01* +X2454Y1673D01* +X2452Y1673D01* +X2452Y1677D01* +X2450Y1677D01* +X2450Y1681D01* +X2448Y1681D01* +X2448Y1689D01* +X2446Y1689D01* +X2446Y1709D01* +X2448Y1709D01* +X2448Y1717D01* +X2450Y1717D01* +X2450Y1721D01* +X2452Y1721D01* +X2452Y1725D01* +X2454Y1725D01* +X2454Y1729D01* +X2456Y1729D01* +X2456Y1731D01* +X2458Y1731D01* +X2458Y1733D01* +X2460Y1733D01* +X2460Y1737D01* +X2464Y1737D01* +X2464Y1739D01* +X2466Y1739D01* +X2466Y1759D01* +X1526Y1759D01* +G37* +D02* +G36* +X1544Y1719D02* +X1544Y1717D01* +X1546Y1717D01* +X1546Y1709D01* +X1548Y1709D01* +X1548Y1689D01* +X1546Y1689D01* +X1546Y1681D01* +X1544Y1681D01* +X1544Y1677D01* +X1542Y1677D01* +X1542Y1673D01* +X1540Y1673D01* +X1540Y1671D01* +X1538Y1671D01* +X1538Y1669D01* +X1536Y1669D01* +X1536Y1665D01* +X1534Y1665D01* +X1534Y1663D01* +X1530Y1663D01* +X1530Y1661D01* +X1528Y1661D01* +X1528Y1659D01* +X1526Y1659D01* +X1526Y1657D01* +X1522Y1657D01* +X1522Y1655D01* +X1518Y1655D01* +X1518Y1653D01* +X1512Y1653D01* +X1512Y1651D01* +X1578Y1651D01* +X1578Y1707D01* +X1580Y1707D01* +X1580Y1709D01* +X1582Y1709D01* +X1582Y1713D01* +X1584Y1713D01* +X1584Y1715D01* +X1588Y1715D01* +X1588Y1717D01* +X1592Y1717D01* +X1592Y1719D01* +X1544Y1719D01* +G37* +D02* +G36* +X1238Y1671D02* +X1238Y1669D01* +X1236Y1669D01* +X1236Y1665D01* +X1234Y1665D01* +X1234Y1663D01* +X1230Y1663D01* +X1230Y1661D01* +X1228Y1661D01* +X1228Y1659D01* +X1226Y1659D01* +X1226Y1657D01* +X1222Y1657D01* +X1222Y1655D01* +X1218Y1655D01* +X1218Y1653D01* +X1212Y1653D01* +X1212Y1651D01* +X1286Y1651D01* +X1286Y1653D01* +X1280Y1653D01* +X1280Y1655D01* +X1276Y1655D01* +X1276Y1657D01* +X1272Y1657D01* +X1272Y1659D01* +X1270Y1659D01* +X1270Y1661D01* +X1268Y1661D01* +X1268Y1663D01* +X1266Y1663D01* +X1266Y1665D01* +X1264Y1665D01* +X1264Y1667D01* +X1262Y1667D01* +X1262Y1669D01* +X1260Y1669D01* +X1260Y1671D01* +X1238Y1671D01* +G37* +D02* +G36* +X1338Y1671D02* +X1338Y1669D01* +X1336Y1669D01* +X1336Y1665D01* +X1334Y1665D01* +X1334Y1663D01* +X1330Y1663D01* +X1330Y1661D01* +X1328Y1661D01* +X1328Y1659D01* +X1326Y1659D01* +X1326Y1657D01* +X1322Y1657D01* +X1322Y1655D01* +X1318Y1655D01* +X1318Y1653D01* +X1312Y1653D01* +X1312Y1651D01* +X1386Y1651D01* +X1386Y1653D01* +X1380Y1653D01* +X1380Y1655D01* +X1376Y1655D01* +X1376Y1657D01* +X1372Y1657D01* +X1372Y1659D01* +X1370Y1659D01* +X1370Y1661D01* +X1368Y1661D01* +X1368Y1663D01* +X1366Y1663D01* +X1366Y1665D01* +X1364Y1665D01* +X1364Y1667D01* +X1362Y1667D01* +X1362Y1669D01* +X1360Y1669D01* +X1360Y1671D01* +X1338Y1671D01* +G37* +D02* +G36* +X1438Y1671D02* +X1438Y1669D01* +X1436Y1669D01* +X1436Y1665D01* +X1434Y1665D01* +X1434Y1663D01* +X1430Y1663D01* +X1430Y1661D01* +X1428Y1661D01* +X1428Y1659D01* +X1426Y1659D01* +X1426Y1657D01* +X1422Y1657D01* +X1422Y1655D01* +X1418Y1655D01* +X1418Y1653D01* +X1412Y1653D01* +X1412Y1651D01* +X1486Y1651D01* +X1486Y1653D01* +X1480Y1653D01* +X1480Y1655D01* +X1476Y1655D01* +X1476Y1657D01* +X1472Y1657D01* +X1472Y1659D01* +X1470Y1659D01* +X1470Y1661D01* +X1468Y1661D01* +X1468Y1663D01* +X1466Y1663D01* +X1466Y1665D01* +X1464Y1665D01* +X1464Y1667D01* +X1462Y1667D01* +X1462Y1669D01* +X1460Y1669D01* +X1460Y1671D01* +X1438Y1671D01* +G37* +D02* +G36* +X2542Y1669D02* +X2542Y1667D01* +X2540Y1667D01* +X2540Y1663D01* +X2538Y1663D01* +X2538Y1661D01* +X2536Y1661D01* +X2536Y1659D01* +X2532Y1659D01* +X2532Y1657D01* +X2530Y1657D01* +X2530Y1655D01* +X2528Y1655D01* +X2528Y1653D01* +X2524Y1653D01* +X2524Y1651D01* +X2520Y1651D01* +X2520Y1649D01* +X2514Y1649D01* +X2514Y1647D01* +X2504Y1647D01* +X2504Y1645D01* +X2562Y1645D01* +X2562Y1669D01* +X2542Y1669D01* +G37* +D02* +G36* +X40Y1665D02* +X40Y1645D01* +X94Y1645D01* +X94Y1647D01* +X84Y1647D01* +X84Y1649D01* +X78Y1649D01* +X78Y1651D01* +X76Y1651D01* +X76Y1653D01* +X72Y1653D01* +X72Y1655D01* +X68Y1655D01* +X68Y1657D01* +X66Y1657D01* +X66Y1659D01* +X64Y1659D01* +X64Y1661D01* +X62Y1661D01* +X62Y1663D01* +X60Y1663D01* +X60Y1665D01* +X40Y1665D01* +G37* +D02* +G36* +X1026Y1651D02* +X1026Y1649D01* +X1578Y1649D01* +X1578Y1651D01* +X1026Y1651D01* +G37* +D02* +G36* +X1026Y1651D02* +X1026Y1649D01* +X1578Y1649D01* +X1578Y1651D01* +X1026Y1651D01* +G37* +D02* +G36* +X1026Y1651D02* +X1026Y1649D01* +X1578Y1649D01* +X1578Y1651D01* +X1026Y1651D01* +G37* +D02* +G36* +X1026Y1651D02* +X1026Y1649D01* +X1578Y1649D01* +X1578Y1651D01* +X1026Y1651D01* +G37* +D02* +G36* +X1026Y1651D02* +X1026Y1649D01* +X1578Y1649D01* +X1578Y1651D01* +X1026Y1651D01* +G37* +D02* +G36* +X1026Y1649D02* +X1026Y1639D01* +X1028Y1639D01* +X1028Y1637D01* +X1032Y1637D01* +X1032Y1635D01* +X1034Y1635D01* +X1034Y1633D01* +X1036Y1633D01* +X1036Y1629D01* +X1038Y1629D01* +X1038Y1627D01* +X1040Y1627D01* +X1040Y1625D01* +X1042Y1625D01* +X1042Y1621D01* +X1044Y1621D01* +X1044Y1617D01* +X1046Y1617D01* +X1046Y1609D01* +X1048Y1609D01* +X1048Y1589D01* +X1046Y1589D01* +X1046Y1581D01* +X1044Y1581D01* +X1044Y1577D01* +X1042Y1577D01* +X1042Y1573D01* +X1040Y1573D01* +X1040Y1571D01* +X1038Y1571D01* +X1038Y1569D01* +X1036Y1569D01* +X1036Y1565D01* +X1034Y1565D01* +X1034Y1563D01* +X1030Y1563D01* +X1030Y1561D01* +X1028Y1561D01* +X1028Y1559D01* +X1026Y1559D01* +X1026Y1557D01* +X1022Y1557D01* +X1022Y1555D01* +X1018Y1555D01* +X1018Y1553D01* +X1012Y1553D01* +X1012Y1551D01* +X1578Y1551D01* +X1578Y1649D01* +X1026Y1649D01* +G37* +D02* +G36* +X40Y1645D02* +X40Y1643D01* +X272Y1643D01* +X272Y1645D01* +X40Y1645D01* +G37* +D02* +G36* +X40Y1645D02* +X40Y1643D01* +X272Y1643D01* +X272Y1645D01* +X40Y1645D01* +G37* +D02* +G36* +X2300Y1645D02* +X2300Y1643D01* +X2562Y1643D01* +X2562Y1645D01* +X2300Y1645D01* +G37* +D02* +G36* +X2300Y1645D02* +X2300Y1643D01* +X2562Y1643D01* +X2562Y1645D01* +X2300Y1645D01* +G37* +D02* +G36* +X40Y1643D02* +X40Y1551D01* +X286Y1551D01* +X286Y1553D01* +X280Y1553D01* +X280Y1555D01* +X276Y1555D01* +X276Y1557D01* +X272Y1557D01* +X272Y1559D01* +X270Y1559D01* +X270Y1561D01* +X268Y1561D01* +X268Y1563D01* +X266Y1563D01* +X266Y1565D01* +X264Y1565D01* +X264Y1567D01* +X262Y1567D01* +X262Y1569D01* +X260Y1569D01* +X260Y1571D01* +X258Y1571D01* +X258Y1575D01* +X256Y1575D01* +X256Y1579D01* +X254Y1579D01* +X254Y1583D01* +X252Y1583D01* +X252Y1591D01* +X250Y1591D01* +X250Y1607D01* +X252Y1607D01* +X252Y1615D01* +X254Y1615D01* +X254Y1619D01* +X256Y1619D01* +X256Y1623D01* +X258Y1623D01* +X258Y1627D01* +X260Y1627D01* +X260Y1629D01* +X262Y1629D01* +X262Y1631D01* +X264Y1631D01* +X264Y1633D01* +X266Y1633D01* +X266Y1635D01* +X268Y1635D01* +X268Y1637D01* +X270Y1637D01* +X270Y1639D01* +X272Y1639D01* +X272Y1643D01* +X40Y1643D01* +G37* +D02* +G36* +X2312Y1643D02* +X2312Y1641D01* +X2318Y1641D01* +X2318Y1639D01* +X2322Y1639D01* +X2322Y1637D01* +X2324Y1637D01* +X2324Y1635D01* +X2328Y1635D01* +X2328Y1633D01* +X2330Y1633D01* +X2330Y1631D01* +X2332Y1631D01* +X2332Y1629D01* +X2334Y1629D01* +X2334Y1627D01* +X2336Y1627D01* +X2336Y1623D01* +X2338Y1623D01* +X2338Y1619D01* +X2340Y1619D01* +X2340Y1615D01* +X2342Y1615D01* +X2342Y1609D01* +X2344Y1609D01* +X2344Y1589D01* +X2342Y1589D01* +X2342Y1583D01* +X2340Y1583D01* +X2340Y1579D01* +X2338Y1579D01* +X2338Y1575D01* +X2336Y1575D01* +X2336Y1573D01* +X2334Y1573D01* +X2334Y1569D01* +X2332Y1569D01* +X2332Y1567D01* +X2330Y1567D01* +X2330Y1565D01* +X2328Y1565D01* +X2328Y1563D01* +X2324Y1563D01* +X2324Y1561D01* +X2322Y1561D01* +X2322Y1559D01* +X2318Y1559D01* +X2318Y1539D01* +X2322Y1539D01* +X2322Y1537D01* +X2324Y1537D01* +X2324Y1535D01* +X2328Y1535D01* +X2328Y1533D01* +X2330Y1533D01* +X2330Y1531D01* +X2332Y1531D01* +X2332Y1529D01* +X2334Y1529D01* +X2334Y1527D01* +X2336Y1527D01* +X2336Y1523D01* +X2338Y1523D01* +X2338Y1519D01* +X2340Y1519D01* +X2340Y1515D01* +X2342Y1515D01* +X2342Y1509D01* +X2344Y1509D01* +X2344Y1489D01* +X2342Y1489D01* +X2342Y1483D01* +X2340Y1483D01* +X2340Y1479D01* +X2338Y1479D01* +X2338Y1475D01* +X2336Y1475D01* +X2336Y1473D01* +X2334Y1473D01* +X2334Y1469D01* +X2332Y1469D01* +X2332Y1467D01* +X2330Y1467D01* +X2330Y1465D01* +X2328Y1465D01* +X2328Y1463D01* +X2324Y1463D01* +X2324Y1461D01* +X2322Y1461D01* +X2322Y1459D01* +X2318Y1459D01* +X2318Y1439D01* +X2322Y1439D01* +X2322Y1437D01* +X2324Y1437D01* +X2324Y1435D01* +X2328Y1435D01* +X2328Y1433D01* +X2330Y1433D01* +X2330Y1431D01* +X2332Y1431D01* +X2332Y1429D01* +X2334Y1429D01* +X2334Y1427D01* +X2336Y1427D01* +X2336Y1423D01* +X2338Y1423D01* +X2338Y1419D01* +X2340Y1419D01* +X2340Y1415D01* +X2342Y1415D01* +X2342Y1409D01* +X2344Y1409D01* +X2344Y1389D01* +X2342Y1389D01* +X2342Y1383D01* +X2340Y1383D01* +X2340Y1379D01* +X2338Y1379D01* +X2338Y1375D01* +X2336Y1375D01* +X2336Y1373D01* +X2334Y1373D01* +X2334Y1369D01* +X2332Y1369D01* +X2332Y1367D01* +X2330Y1367D01* +X2330Y1365D01* +X2328Y1365D01* +X2328Y1363D01* +X2324Y1363D01* +X2324Y1361D01* +X2322Y1361D01* +X2322Y1359D01* +X2318Y1359D01* +X2318Y1339D01* +X2322Y1339D01* +X2322Y1337D01* +X2324Y1337D01* +X2324Y1335D01* +X2328Y1335D01* +X2328Y1333D01* +X2330Y1333D01* +X2330Y1331D01* +X2332Y1331D01* +X2332Y1329D01* +X2334Y1329D01* +X2334Y1327D01* +X2336Y1327D01* +X2336Y1323D01* +X2338Y1323D01* +X2338Y1319D01* +X2340Y1319D01* +X2340Y1315D01* +X2342Y1315D01* +X2342Y1309D01* +X2344Y1309D01* +X2344Y1289D01* +X2342Y1289D01* +X2342Y1283D01* +X2340Y1283D01* +X2340Y1279D01* +X2338Y1279D01* +X2338Y1275D01* +X2336Y1275D01* +X2336Y1273D01* +X2334Y1273D01* +X2334Y1269D01* +X2332Y1269D01* +X2332Y1267D01* +X2330Y1267D01* +X2330Y1265D01* +X2328Y1265D01* +X2328Y1263D01* +X2324Y1263D01* +X2324Y1261D01* +X2322Y1261D01* +X2322Y1259D01* +X2318Y1259D01* +X2318Y1239D01* +X2322Y1239D01* +X2322Y1237D01* +X2324Y1237D01* +X2324Y1235D01* +X2328Y1235D01* +X2328Y1233D01* +X2330Y1233D01* +X2330Y1231D01* +X2332Y1231D01* +X2332Y1229D01* +X2334Y1229D01* +X2334Y1227D01* +X2336Y1227D01* +X2336Y1223D01* +X2338Y1223D01* +X2338Y1219D01* +X2340Y1219D01* +X2340Y1215D01* +X2342Y1215D01* +X2342Y1209D01* +X2344Y1209D01* +X2344Y1189D01* +X2342Y1189D01* +X2342Y1183D01* +X2340Y1183D01* +X2340Y1179D01* +X2338Y1179D01* +X2338Y1175D01* +X2336Y1175D01* +X2336Y1173D01* +X2334Y1173D01* +X2334Y1169D01* +X2332Y1169D01* +X2332Y1167D01* +X2330Y1167D01* +X2330Y1165D01* +X2328Y1165D01* +X2328Y1163D01* +X2324Y1163D01* +X2324Y1161D01* +X2322Y1161D01* +X2322Y1159D01* +X2318Y1159D01* +X2318Y1139D01* +X2322Y1139D01* +X2322Y1137D01* +X2324Y1137D01* +X2324Y1135D01* +X2328Y1135D01* +X2328Y1133D01* +X2330Y1133D01* +X2330Y1131D01* +X2332Y1131D01* +X2332Y1129D01* +X2334Y1129D01* +X2334Y1127D01* +X2336Y1127D01* +X2336Y1123D01* +X2338Y1123D01* +X2338Y1119D01* +X2340Y1119D01* +X2340Y1115D01* +X2342Y1115D01* +X2342Y1109D01* +X2344Y1109D01* +X2344Y1089D01* +X2342Y1089D01* +X2342Y1083D01* +X2340Y1083D01* +X2340Y1079D01* +X2338Y1079D01* +X2338Y1075D01* +X2336Y1075D01* +X2336Y1073D01* +X2334Y1073D01* +X2334Y1069D01* +X2332Y1069D01* +X2332Y1067D01* +X2330Y1067D01* +X2330Y1065D01* +X2328Y1065D01* +X2328Y1063D01* +X2324Y1063D01* +X2324Y1061D01* +X2322Y1061D01* +X2322Y1059D01* +X2318Y1059D01* +X2318Y1039D01* +X2322Y1039D01* +X2322Y1037D01* +X2324Y1037D01* +X2324Y1035D01* +X2328Y1035D01* +X2328Y1033D01* +X2330Y1033D01* +X2330Y1031D01* +X2332Y1031D01* +X2332Y1029D01* +X2334Y1029D01* +X2334Y1027D01* +X2336Y1027D01* +X2336Y1023D01* +X2338Y1023D01* +X2338Y1019D01* +X2340Y1019D01* +X2340Y1015D01* +X2342Y1015D01* +X2342Y1009D01* +X2344Y1009D01* +X2344Y989D01* +X2342Y989D01* +X2342Y983D01* +X2340Y983D01* +X2340Y979D01* +X2338Y979D01* +X2338Y975D01* +X2336Y975D01* +X2336Y973D01* +X2334Y973D01* +X2334Y969D01* +X2332Y969D01* +X2332Y967D01* +X2330Y967D01* +X2330Y965D01* +X2328Y965D01* +X2328Y963D01* +X2324Y963D01* +X2324Y961D01* +X2322Y961D01* +X2322Y959D01* +X2318Y959D01* +X2318Y939D01* +X2322Y939D01* +X2322Y937D01* +X2324Y937D01* +X2324Y935D01* +X2328Y935D01* +X2328Y933D01* +X2330Y933D01* +X2330Y931D01* +X2332Y931D01* +X2332Y929D01* +X2334Y929D01* +X2334Y927D01* +X2336Y927D01* +X2336Y923D01* +X2338Y923D01* +X2338Y919D01* +X2340Y919D01* +X2340Y915D01* +X2342Y915D01* +X2342Y909D01* +X2344Y909D01* +X2344Y889D01* +X2342Y889D01* +X2342Y883D01* +X2340Y883D01* +X2340Y879D01* +X2338Y879D01* +X2338Y875D01* +X2336Y875D01* +X2336Y873D01* +X2334Y873D01* +X2334Y869D01* +X2332Y869D01* +X2332Y867D01* +X2330Y867D01* +X2330Y865D01* +X2328Y865D01* +X2328Y863D01* +X2324Y863D01* +X2324Y861D01* +X2322Y861D01* +X2322Y859D01* +X2318Y859D01* +X2318Y839D01* +X2322Y839D01* +X2322Y837D01* +X2324Y837D01* +X2324Y835D01* +X2328Y835D01* +X2328Y833D01* +X2330Y833D01* +X2330Y831D01* +X2332Y831D01* +X2332Y829D01* +X2334Y829D01* +X2334Y827D01* +X2336Y827D01* +X2336Y823D01* +X2338Y823D01* +X2338Y819D01* +X2340Y819D01* +X2340Y815D01* +X2342Y815D01* +X2342Y809D01* +X2344Y809D01* +X2344Y789D01* +X2342Y789D01* +X2342Y783D01* +X2340Y783D01* +X2340Y779D01* +X2338Y779D01* +X2338Y775D01* +X2336Y775D01* +X2336Y773D01* +X2334Y773D01* +X2334Y769D01* +X2332Y769D01* +X2332Y767D01* +X2330Y767D01* +X2330Y765D01* +X2328Y765D01* +X2328Y763D01* +X2324Y763D01* +X2324Y761D01* +X2322Y761D01* +X2322Y759D01* +X2318Y759D01* +X2318Y739D01* +X2322Y739D01* +X2322Y737D01* +X2324Y737D01* +X2324Y735D01* +X2328Y735D01* +X2328Y733D01* +X2330Y733D01* +X2330Y731D01* +X2332Y731D01* +X2332Y729D01* +X2334Y729D01* +X2334Y727D01* +X2336Y727D01* +X2336Y723D01* +X2338Y723D01* +X2338Y719D01* +X2340Y719D01* +X2340Y715D01* +X2342Y715D01* +X2342Y709D01* +X2344Y709D01* +X2344Y689D01* +X2342Y689D01* +X2342Y683D01* +X2340Y683D01* +X2340Y679D01* +X2338Y679D01* +X2338Y675D01* +X2336Y675D01* +X2336Y673D01* +X2334Y673D01* +X2334Y669D01* +X2332Y669D01* +X2332Y667D01* +X2330Y667D01* +X2330Y665D01* +X2328Y665D01* +X2328Y663D01* +X2324Y663D01* +X2324Y661D01* +X2322Y661D01* +X2322Y659D01* +X2318Y659D01* +X2318Y639D01* +X2322Y639D01* +X2322Y637D01* +X2324Y637D01* +X2324Y635D01* +X2328Y635D01* +X2328Y633D01* +X2330Y633D01* +X2330Y631D01* +X2332Y631D01* +X2332Y629D01* +X2334Y629D01* +X2334Y627D01* +X2336Y627D01* +X2336Y623D01* +X2338Y623D01* +X2338Y619D01* +X2340Y619D01* +X2340Y615D01* +X2342Y615D01* +X2342Y609D01* +X2344Y609D01* +X2344Y589D01* +X2342Y589D01* +X2342Y583D01* +X2340Y583D01* +X2340Y579D01* +X2338Y579D01* +X2338Y575D01* +X2336Y575D01* +X2336Y573D01* +X2334Y573D01* +X2334Y569D01* +X2332Y569D01* +X2332Y567D01* +X2330Y567D01* +X2330Y565D01* +X2328Y565D01* +X2328Y563D01* +X2324Y563D01* +X2324Y561D01* +X2322Y561D01* +X2322Y559D01* +X2318Y559D01* +X2318Y539D01* +X2322Y539D01* +X2322Y537D01* +X2324Y537D01* +X2324Y535D01* +X2328Y535D01* +X2328Y533D01* +X2330Y533D01* +X2330Y531D01* +X2332Y531D01* +X2332Y529D01* +X2334Y529D01* +X2334Y527D01* +X2336Y527D01* +X2336Y523D01* +X2338Y523D01* +X2338Y519D01* +X2340Y519D01* +X2340Y515D01* +X2342Y515D01* +X2342Y509D01* +X2344Y509D01* +X2344Y489D01* +X2342Y489D01* +X2342Y483D01* +X2340Y483D01* +X2340Y479D01* +X2338Y479D01* +X2338Y475D01* +X2336Y475D01* +X2336Y473D01* +X2334Y473D01* +X2334Y469D01* +X2332Y469D01* +X2332Y467D01* +X2330Y467D01* +X2330Y465D01* +X2328Y465D01* +X2328Y463D01* +X2324Y463D01* +X2324Y461D01* +X2322Y461D01* +X2322Y459D01* +X2318Y459D01* +X2318Y439D01* +X2322Y439D01* +X2322Y437D01* +X2324Y437D01* +X2324Y435D01* +X2328Y435D01* +X2328Y433D01* +X2330Y433D01* +X2330Y431D01* +X2332Y431D01* +X2332Y429D01* +X2334Y429D01* +X2334Y427D01* +X2336Y427D01* +X2336Y423D01* +X2338Y423D01* +X2338Y419D01* +X2340Y419D01* +X2340Y415D01* +X2342Y415D01* +X2342Y409D01* +X2344Y409D01* +X2344Y389D01* +X2342Y389D01* +X2342Y383D01* +X2340Y383D01* +X2340Y379D01* +X2338Y379D01* +X2338Y375D01* +X2336Y375D01* +X2336Y373D01* +X2334Y373D01* +X2334Y369D01* +X2332Y369D01* +X2332Y367D01* +X2330Y367D01* +X2330Y365D01* +X2328Y365D01* +X2328Y363D01* +X2324Y363D01* +X2324Y361D01* +X2322Y361D01* +X2322Y359D01* +X2318Y359D01* +X2318Y339D01* +X2322Y339D01* +X2322Y337D01* +X2324Y337D01* +X2324Y335D01* +X2328Y335D01* +X2328Y333D01* +X2330Y333D01* +X2330Y331D01* +X2332Y331D01* +X2332Y329D01* +X2334Y329D01* +X2334Y327D01* +X2336Y327D01* +X2336Y323D01* +X2338Y323D01* +X2338Y319D01* +X2340Y319D01* +X2340Y315D01* +X2342Y315D01* +X2342Y309D01* +X2344Y309D01* +X2344Y289D01* +X2342Y289D01* +X2342Y283D01* +X2340Y283D01* +X2340Y279D01* +X2338Y279D01* +X2338Y275D01* +X2336Y275D01* +X2336Y273D01* +X2334Y273D01* +X2334Y269D01* +X2332Y269D01* +X2332Y267D01* +X2330Y267D01* +X2330Y265D01* +X2328Y265D01* +X2328Y263D01* +X2324Y263D01* +X2324Y261D01* +X2322Y261D01* +X2322Y259D01* +X2318Y259D01* +X2318Y239D01* +X2322Y239D01* +X2322Y237D01* +X2324Y237D01* +X2324Y235D01* +X2328Y235D01* +X2328Y233D01* +X2330Y233D01* +X2330Y231D01* +X2332Y231D01* +X2332Y229D01* +X2334Y229D01* +X2334Y227D01* +X2336Y227D01* +X2336Y223D01* +X2338Y223D01* +X2338Y219D01* +X2340Y219D01* +X2340Y215D01* +X2342Y215D01* +X2342Y209D01* +X2344Y209D01* +X2344Y189D01* +X2342Y189D01* +X2342Y183D01* +X2340Y183D01* +X2340Y179D01* +X2338Y179D01* +X2338Y175D01* +X2336Y175D01* +X2336Y173D01* +X2334Y173D01* +X2334Y169D01* +X2332Y169D01* +X2332Y167D01* +X2330Y167D01* +X2330Y165D01* +X2328Y165D01* +X2328Y163D01* +X2324Y163D01* +X2324Y161D01* +X2322Y161D01* +X2322Y159D01* +X2318Y159D01* +X2318Y157D01* +X2312Y157D01* +X2312Y155D01* +X2562Y155D01* +X2562Y1643D01* +X2312Y1643D01* +G37* +D02* +G36* +X40Y1551D02* +X40Y1549D01* +X1578Y1549D01* +X1578Y1551D01* +X40Y1551D01* +G37* +D02* +G36* +X40Y1551D02* +X40Y1549D01* +X1578Y1549D01* +X1578Y1551D01* +X40Y1551D01* +G37* +D02* +G36* +X40Y1551D02* +X40Y1549D01* +X1578Y1549D01* +X1578Y1551D01* +X40Y1551D01* +G37* +D02* +G36* +X40Y1549D02* +X40Y1149D01* +X900Y1149D01* +X900Y1147D01* +X912Y1147D01* +X912Y1145D01* +X918Y1145D01* +X918Y1143D01* +X922Y1143D01* +X922Y1141D01* +X926Y1141D01* +X926Y1139D01* +X928Y1139D01* +X928Y1137D01* +X932Y1137D01* +X932Y1135D01* +X934Y1135D01* +X934Y1133D01* +X936Y1133D01* +X936Y1129D01* +X938Y1129D01* +X938Y1127D01* +X940Y1127D01* +X940Y1125D01* +X942Y1125D01* +X942Y1121D01* +X944Y1121D01* +X944Y1117D01* +X946Y1117D01* +X946Y1109D01* +X948Y1109D01* +X948Y1089D01* +X946Y1089D01* +X946Y1081D01* +X944Y1081D01* +X944Y1077D01* +X942Y1077D01* +X942Y1073D01* +X940Y1073D01* +X940Y1071D01* +X938Y1071D01* +X938Y1069D01* +X936Y1069D01* +X936Y1065D01* +X934Y1065D01* +X934Y1063D01* +X930Y1063D01* +X930Y1061D01* +X928Y1061D01* +X928Y1059D01* +X926Y1059D01* +X926Y1057D01* +X922Y1057D01* +X922Y1055D01* +X918Y1055D01* +X918Y1053D01* +X912Y1053D01* +X912Y1051D01* +X1578Y1051D01* +X1578Y1549D01* +X40Y1549D01* +G37* +D02* +G36* +X2222Y1277D02* +X2222Y155D01* +X2288Y155D01* +X2288Y157D01* +X2282Y157D01* +X2282Y159D01* +X2278Y159D01* +X2278Y161D01* +X2274Y161D01* +X2274Y163D01* +X2272Y163D01* +X2272Y165D01* +X2268Y165D01* +X2268Y167D01* +X2266Y167D01* +X2266Y171D01* +X2264Y171D01* +X2264Y173D01* +X2262Y173D01* +X2262Y175D01* +X2260Y175D01* +X2260Y179D01* +X2258Y179D01* +X2258Y185D01* +X2256Y185D01* +X2256Y191D01* +X2254Y191D01* +X2254Y207D01* +X2256Y207D01* +X2256Y213D01* +X2258Y213D01* +X2258Y219D01* +X2260Y219D01* +X2260Y223D01* +X2262Y223D01* +X2262Y225D01* +X2264Y225D01* +X2264Y227D01* +X2266Y227D01* +X2266Y231D01* +X2268Y231D01* +X2268Y233D01* +X2272Y233D01* +X2272Y235D01* +X2274Y235D01* +X2274Y237D01* +X2278Y237D01* +X2278Y239D01* +X2280Y239D01* +X2280Y259D01* +X2278Y259D01* +X2278Y261D01* +X2274Y261D01* +X2274Y263D01* +X2272Y263D01* +X2272Y265D01* +X2268Y265D01* +X2268Y267D01* +X2266Y267D01* +X2266Y271D01* +X2264Y271D01* +X2264Y273D01* +X2262Y273D01* +X2262Y275D01* +X2260Y275D01* +X2260Y279D01* +X2258Y279D01* +X2258Y285D01* +X2256Y285D01* +X2256Y291D01* +X2254Y291D01* +X2254Y307D01* +X2256Y307D01* +X2256Y313D01* +X2258Y313D01* +X2258Y319D01* +X2260Y319D01* +X2260Y323D01* +X2262Y323D01* +X2262Y325D01* +X2264Y325D01* +X2264Y327D01* +X2266Y327D01* +X2266Y331D01* +X2268Y331D01* +X2268Y333D01* +X2272Y333D01* +X2272Y335D01* +X2274Y335D01* +X2274Y337D01* +X2278Y337D01* +X2278Y339D01* +X2280Y339D01* +X2280Y359D01* +X2278Y359D01* +X2278Y361D01* +X2274Y361D01* +X2274Y363D01* +X2272Y363D01* +X2272Y365D01* +X2268Y365D01* +X2268Y367D01* +X2266Y367D01* +X2266Y371D01* +X2264Y371D01* +X2264Y373D01* +X2262Y373D01* +X2262Y375D01* +X2260Y375D01* +X2260Y379D01* +X2258Y379D01* +X2258Y385D01* +X2256Y385D01* +X2256Y391D01* +X2254Y391D01* +X2254Y407D01* +X2256Y407D01* +X2256Y413D01* +X2258Y413D01* +X2258Y419D01* +X2260Y419D01* +X2260Y423D01* +X2262Y423D01* +X2262Y425D01* +X2264Y425D01* +X2264Y427D01* +X2266Y427D01* +X2266Y431D01* +X2268Y431D01* +X2268Y433D01* +X2272Y433D01* +X2272Y435D01* +X2274Y435D01* +X2274Y437D01* +X2278Y437D01* +X2278Y439D01* +X2280Y439D01* +X2280Y459D01* +X2278Y459D01* +X2278Y461D01* +X2274Y461D01* +X2274Y463D01* +X2272Y463D01* +X2272Y465D01* +X2268Y465D01* +X2268Y467D01* +X2266Y467D01* +X2266Y471D01* +X2264Y471D01* +X2264Y473D01* +X2262Y473D01* +X2262Y475D01* +X2260Y475D01* +X2260Y479D01* +X2258Y479D01* +X2258Y485D01* +X2256Y485D01* +X2256Y491D01* +X2254Y491D01* +X2254Y507D01* +X2256Y507D01* +X2256Y513D01* +X2258Y513D01* +X2258Y519D01* +X2260Y519D01* +X2260Y523D01* +X2262Y523D01* +X2262Y525D01* +X2264Y525D01* +X2264Y527D01* +X2266Y527D01* +X2266Y531D01* +X2268Y531D01* +X2268Y533D01* +X2272Y533D01* +X2272Y535D01* +X2274Y535D01* +X2274Y537D01* +X2278Y537D01* +X2278Y539D01* +X2280Y539D01* +X2280Y559D01* +X2278Y559D01* +X2278Y561D01* +X2274Y561D01* +X2274Y563D01* +X2272Y563D01* +X2272Y565D01* +X2268Y565D01* +X2268Y567D01* +X2266Y567D01* +X2266Y571D01* +X2264Y571D01* +X2264Y573D01* +X2262Y573D01* +X2262Y575D01* +X2260Y575D01* +X2260Y579D01* +X2258Y579D01* +X2258Y585D01* +X2256Y585D01* +X2256Y591D01* +X2254Y591D01* +X2254Y607D01* +X2256Y607D01* +X2256Y613D01* +X2258Y613D01* +X2258Y619D01* +X2260Y619D01* +X2260Y623D01* +X2262Y623D01* +X2262Y625D01* +X2264Y625D01* +X2264Y627D01* +X2266Y627D01* +X2266Y631D01* +X2268Y631D01* +X2268Y633D01* +X2272Y633D01* +X2272Y635D01* +X2274Y635D01* +X2274Y637D01* +X2278Y637D01* +X2278Y639D01* +X2280Y639D01* +X2280Y659D01* +X2278Y659D01* +X2278Y661D01* +X2274Y661D01* +X2274Y663D01* +X2272Y663D01* +X2272Y665D01* +X2268Y665D01* +X2268Y667D01* +X2266Y667D01* +X2266Y671D01* +X2264Y671D01* +X2264Y673D01* +X2262Y673D01* +X2262Y675D01* +X2260Y675D01* +X2260Y679D01* +X2258Y679D01* +X2258Y685D01* +X2256Y685D01* +X2256Y691D01* +X2254Y691D01* +X2254Y707D01* +X2256Y707D01* +X2256Y713D01* +X2258Y713D01* +X2258Y719D01* +X2260Y719D01* +X2260Y723D01* +X2262Y723D01* +X2262Y725D01* +X2264Y725D01* +X2264Y727D01* +X2266Y727D01* +X2266Y731D01* +X2268Y731D01* +X2268Y733D01* +X2272Y733D01* +X2272Y735D01* +X2274Y735D01* +X2274Y737D01* +X2278Y737D01* +X2278Y739D01* +X2280Y739D01* +X2280Y759D01* +X2278Y759D01* +X2278Y761D01* +X2274Y761D01* +X2274Y763D01* +X2272Y763D01* +X2272Y765D01* +X2268Y765D01* +X2268Y767D01* +X2266Y767D01* +X2266Y771D01* +X2264Y771D01* +X2264Y773D01* +X2262Y773D01* +X2262Y775D01* +X2260Y775D01* +X2260Y779D01* +X2258Y779D01* +X2258Y785D01* +X2256Y785D01* +X2256Y791D01* +X2254Y791D01* +X2254Y807D01* +X2256Y807D01* +X2256Y813D01* +X2258Y813D01* +X2258Y819D01* +X2260Y819D01* +X2260Y823D01* +X2262Y823D01* +X2262Y825D01* +X2264Y825D01* +X2264Y827D01* +X2266Y827D01* +X2266Y831D01* +X2268Y831D01* +X2268Y833D01* +X2272Y833D01* +X2272Y835D01* +X2274Y835D01* +X2274Y837D01* +X2278Y837D01* +X2278Y839D01* +X2280Y839D01* +X2280Y859D01* +X2278Y859D01* +X2278Y861D01* +X2274Y861D01* +X2274Y863D01* +X2272Y863D01* +X2272Y865D01* +X2268Y865D01* +X2268Y867D01* +X2266Y867D01* +X2266Y871D01* +X2264Y871D01* +X2264Y873D01* +X2262Y873D01* +X2262Y875D01* +X2260Y875D01* +X2260Y879D01* +X2258Y879D01* +X2258Y885D01* +X2256Y885D01* +X2256Y891D01* +X2254Y891D01* +X2254Y907D01* +X2256Y907D01* +X2256Y913D01* +X2258Y913D01* +X2258Y919D01* +X2260Y919D01* +X2260Y923D01* +X2262Y923D01* +X2262Y925D01* +X2264Y925D01* +X2264Y927D01* +X2266Y927D01* +X2266Y931D01* +X2268Y931D01* +X2268Y933D01* +X2272Y933D01* +X2272Y935D01* +X2274Y935D01* +X2274Y937D01* +X2278Y937D01* +X2278Y939D01* +X2280Y939D01* +X2280Y959D01* +X2278Y959D01* +X2278Y961D01* +X2274Y961D01* +X2274Y963D01* +X2272Y963D01* +X2272Y965D01* +X2268Y965D01* +X2268Y967D01* +X2266Y967D01* +X2266Y971D01* +X2264Y971D01* +X2264Y973D01* +X2262Y973D01* +X2262Y975D01* +X2260Y975D01* +X2260Y979D01* +X2258Y979D01* +X2258Y985D01* +X2256Y985D01* +X2256Y991D01* +X2254Y991D01* +X2254Y1007D01* +X2256Y1007D01* +X2256Y1013D01* +X2258Y1013D01* +X2258Y1019D01* +X2260Y1019D01* +X2260Y1023D01* +X2262Y1023D01* +X2262Y1025D01* +X2264Y1025D01* +X2264Y1027D01* +X2266Y1027D01* +X2266Y1031D01* +X2268Y1031D01* +X2268Y1033D01* +X2272Y1033D01* +X2272Y1035D01* +X2274Y1035D01* +X2274Y1037D01* +X2278Y1037D01* +X2278Y1039D01* +X2280Y1039D01* +X2280Y1059D01* +X2278Y1059D01* +X2278Y1061D01* +X2274Y1061D01* +X2274Y1063D01* +X2272Y1063D01* +X2272Y1065D01* +X2268Y1065D01* +X2268Y1067D01* +X2266Y1067D01* +X2266Y1071D01* +X2264Y1071D01* +X2264Y1073D01* +X2262Y1073D01* +X2262Y1075D01* +X2260Y1075D01* +X2260Y1079D01* +X2258Y1079D01* +X2258Y1085D01* +X2256Y1085D01* +X2256Y1091D01* +X2254Y1091D01* +X2254Y1107D01* +X2256Y1107D01* +X2256Y1113D01* +X2258Y1113D01* +X2258Y1119D01* +X2260Y1119D01* +X2260Y1123D01* +X2262Y1123D01* +X2262Y1125D01* +X2264Y1125D01* +X2264Y1127D01* +X2266Y1127D01* +X2266Y1131D01* +X2268Y1131D01* +X2268Y1133D01* +X2272Y1133D01* +X2272Y1135D01* +X2274Y1135D01* +X2274Y1137D01* +X2278Y1137D01* +X2278Y1139D01* +X2280Y1139D01* +X2280Y1159D01* +X2278Y1159D01* +X2278Y1161D01* +X2274Y1161D01* +X2274Y1163D01* +X2272Y1163D01* +X2272Y1165D01* +X2268Y1165D01* +X2268Y1167D01* +X2266Y1167D01* +X2266Y1171D01* +X2264Y1171D01* +X2264Y1173D01* +X2262Y1173D01* +X2262Y1175D01* +X2260Y1175D01* +X2260Y1179D01* +X2258Y1179D01* +X2258Y1185D01* +X2256Y1185D01* +X2256Y1191D01* +X2254Y1191D01* +X2254Y1207D01* +X2256Y1207D01* +X2256Y1213D01* +X2258Y1213D01* +X2258Y1219D01* +X2260Y1219D01* +X2260Y1223D01* +X2262Y1223D01* +X2262Y1225D01* +X2264Y1225D01* +X2264Y1227D01* +X2266Y1227D01* +X2266Y1231D01* +X2268Y1231D01* +X2268Y1233D01* +X2272Y1233D01* +X2272Y1235D01* +X2274Y1235D01* +X2274Y1237D01* +X2278Y1237D01* +X2278Y1239D01* +X2280Y1239D01* +X2280Y1259D01* +X2278Y1259D01* +X2278Y1261D01* +X2274Y1261D01* +X2274Y1263D01* +X2272Y1263D01* +X2272Y1265D01* +X2268Y1265D01* +X2268Y1267D01* +X2266Y1267D01* +X2266Y1271D01* +X2264Y1271D01* +X2264Y1273D01* +X2262Y1273D01* +X2262Y1275D01* +X2260Y1275D01* +X2260Y1277D01* +X2222Y1277D01* +G37* +D02* +G36* +X40Y1149D02* +X40Y1051D01* +X386Y1051D01* +X386Y1053D01* +X380Y1053D01* +X380Y1055D01* +X376Y1055D01* +X376Y1057D01* +X372Y1057D01* +X372Y1059D01* +X370Y1059D01* +X370Y1061D01* +X368Y1061D01* +X368Y1063D01* +X366Y1063D01* +X366Y1065D01* +X364Y1065D01* +X364Y1067D01* +X362Y1067D01* +X362Y1069D01* +X360Y1069D01* +X360Y1071D01* +X358Y1071D01* +X358Y1075D01* +X356Y1075D01* +X356Y1079D01* +X354Y1079D01* +X354Y1083D01* +X352Y1083D01* +X352Y1091D01* +X350Y1091D01* +X350Y1107D01* +X352Y1107D01* +X352Y1115D01* +X354Y1115D01* +X354Y1119D01* +X356Y1119D01* +X356Y1123D01* +X358Y1123D01* +X358Y1127D01* +X360Y1127D01* +X360Y1129D01* +X362Y1129D01* +X362Y1131D01* +X364Y1131D01* +X364Y1133D01* +X366Y1133D01* +X366Y1135D01* +X368Y1135D01* +X368Y1137D01* +X370Y1137D01* +X370Y1139D01* +X372Y1139D01* +X372Y1141D01* +X376Y1141D01* +X376Y1143D01* +X380Y1143D01* +X380Y1145D01* +X386Y1145D01* +X386Y1147D01* +X398Y1147D01* +X398Y1149D01* +X40Y1149D01* +G37* +D02* +G36* +X400Y1149D02* +X400Y1147D01* +X412Y1147D01* +X412Y1145D01* +X418Y1145D01* +X418Y1143D01* +X422Y1143D01* +X422Y1141D01* +X426Y1141D01* +X426Y1139D01* +X428Y1139D01* +X428Y1137D01* +X432Y1137D01* +X432Y1135D01* +X434Y1135D01* +X434Y1133D01* +X436Y1133D01* +X436Y1129D01* +X438Y1129D01* +X438Y1127D01* +X460Y1127D01* +X460Y1129D01* +X462Y1129D01* +X462Y1131D01* +X464Y1131D01* +X464Y1133D01* +X466Y1133D01* +X466Y1135D01* +X468Y1135D01* +X468Y1137D01* +X470Y1137D01* +X470Y1139D01* +X472Y1139D01* +X472Y1141D01* +X476Y1141D01* +X476Y1143D01* +X480Y1143D01* +X480Y1145D01* +X486Y1145D01* +X486Y1147D01* +X498Y1147D01* +X498Y1149D01* +X400Y1149D01* +G37* +D02* +G36* +X500Y1149D02* +X500Y1147D01* +X512Y1147D01* +X512Y1145D01* +X518Y1145D01* +X518Y1143D01* +X522Y1143D01* +X522Y1141D01* +X526Y1141D01* +X526Y1139D01* +X528Y1139D01* +X528Y1137D01* +X532Y1137D01* +X532Y1135D01* +X534Y1135D01* +X534Y1133D01* +X536Y1133D01* +X536Y1129D01* +X538Y1129D01* +X538Y1127D01* +X560Y1127D01* +X560Y1129D01* +X562Y1129D01* +X562Y1131D01* +X564Y1131D01* +X564Y1133D01* +X566Y1133D01* +X566Y1135D01* +X568Y1135D01* +X568Y1137D01* +X570Y1137D01* +X570Y1139D01* +X572Y1139D01* +X572Y1141D01* +X576Y1141D01* +X576Y1143D01* +X580Y1143D01* +X580Y1145D01* +X586Y1145D01* +X586Y1147D01* +X598Y1147D01* +X598Y1149D01* +X500Y1149D01* +G37* +D02* +G36* +X600Y1149D02* +X600Y1147D01* +X612Y1147D01* +X612Y1145D01* +X618Y1145D01* +X618Y1143D01* +X622Y1143D01* +X622Y1141D01* +X626Y1141D01* +X626Y1139D01* +X628Y1139D01* +X628Y1137D01* +X632Y1137D01* +X632Y1135D01* +X634Y1135D01* +X634Y1133D01* +X636Y1133D01* +X636Y1129D01* +X638Y1129D01* +X638Y1127D01* +X660Y1127D01* +X660Y1129D01* +X662Y1129D01* +X662Y1131D01* +X664Y1131D01* +X664Y1133D01* +X666Y1133D01* +X666Y1135D01* +X668Y1135D01* +X668Y1137D01* +X670Y1137D01* +X670Y1139D01* +X672Y1139D01* +X672Y1141D01* +X676Y1141D01* +X676Y1143D01* +X680Y1143D01* +X680Y1145D01* +X686Y1145D01* +X686Y1147D01* +X698Y1147D01* +X698Y1149D01* +X600Y1149D01* +G37* +D02* +G36* +X700Y1149D02* +X700Y1147D01* +X712Y1147D01* +X712Y1145D01* +X718Y1145D01* +X718Y1143D01* +X722Y1143D01* +X722Y1141D01* +X726Y1141D01* +X726Y1139D01* +X728Y1139D01* +X728Y1137D01* +X732Y1137D01* +X732Y1135D01* +X734Y1135D01* +X734Y1133D01* +X736Y1133D01* +X736Y1129D01* +X738Y1129D01* +X738Y1127D01* +X760Y1127D01* +X760Y1129D01* +X762Y1129D01* +X762Y1131D01* +X764Y1131D01* +X764Y1133D01* +X766Y1133D01* +X766Y1135D01* +X768Y1135D01* +X768Y1137D01* +X770Y1137D01* +X770Y1139D01* +X772Y1139D01* +X772Y1141D01* +X776Y1141D01* +X776Y1143D01* +X780Y1143D01* +X780Y1145D01* +X786Y1145D01* +X786Y1147D01* +X798Y1147D01* +X798Y1149D01* +X700Y1149D01* +G37* +D02* +G36* +X800Y1149D02* +X800Y1147D01* +X812Y1147D01* +X812Y1145D01* +X818Y1145D01* +X818Y1143D01* +X822Y1143D01* +X822Y1141D01* +X826Y1141D01* +X826Y1139D01* +X828Y1139D01* +X828Y1137D01* +X832Y1137D01* +X832Y1135D01* +X834Y1135D01* +X834Y1133D01* +X836Y1133D01* +X836Y1129D01* +X838Y1129D01* +X838Y1127D01* +X860Y1127D01* +X860Y1129D01* +X862Y1129D01* +X862Y1131D01* +X864Y1131D01* +X864Y1133D01* +X866Y1133D01* +X866Y1135D01* +X868Y1135D01* +X868Y1137D01* +X870Y1137D01* +X870Y1139D01* +X872Y1139D01* +X872Y1141D01* +X876Y1141D01* +X876Y1143D01* +X880Y1143D01* +X880Y1145D01* +X886Y1145D01* +X886Y1147D01* +X898Y1147D01* +X898Y1149D01* +X800Y1149D01* +G37* +D02* +G36* +X438Y1071D02* +X438Y1069D01* +X436Y1069D01* +X436Y1065D01* +X434Y1065D01* +X434Y1063D01* +X430Y1063D01* +X430Y1061D01* +X428Y1061D01* +X428Y1059D01* +X426Y1059D01* +X426Y1057D01* +X422Y1057D01* +X422Y1055D01* +X418Y1055D01* +X418Y1053D01* +X412Y1053D01* +X412Y1051D01* +X478Y1051D01* +X478Y1055D01* +X476Y1055D01* +X476Y1057D01* +X472Y1057D01* +X472Y1059D01* +X470Y1059D01* +X470Y1061D01* +X468Y1061D01* +X468Y1063D01* +X466Y1063D01* +X466Y1065D01* +X464Y1065D01* +X464Y1067D01* +X462Y1067D01* +X462Y1069D01* +X460Y1069D01* +X460Y1071D01* +X438Y1071D01* +G37* +D02* +G36* +X538Y1071D02* +X538Y1069D01* +X536Y1069D01* +X536Y1065D01* +X534Y1065D01* +X534Y1063D01* +X530Y1063D01* +X530Y1061D01* +X528Y1061D01* +X528Y1059D01* +X526Y1059D01* +X526Y1057D01* +X522Y1057D01* +X522Y1051D01* +X586Y1051D01* +X586Y1053D01* +X580Y1053D01* +X580Y1055D01* +X576Y1055D01* +X576Y1057D01* +X572Y1057D01* +X572Y1059D01* +X570Y1059D01* +X570Y1061D01* +X568Y1061D01* +X568Y1063D01* +X566Y1063D01* +X566Y1065D01* +X564Y1065D01* +X564Y1067D01* +X562Y1067D01* +X562Y1069D01* +X560Y1069D01* +X560Y1071D01* +X538Y1071D01* +G37* +D02* +G36* +X638Y1071D02* +X638Y1069D01* +X636Y1069D01* +X636Y1065D01* +X634Y1065D01* +X634Y1063D01* +X630Y1063D01* +X630Y1061D01* +X628Y1061D01* +X628Y1059D01* +X626Y1059D01* +X626Y1057D01* +X622Y1057D01* +X622Y1055D01* +X618Y1055D01* +X618Y1053D01* +X612Y1053D01* +X612Y1051D01* +X686Y1051D01* +X686Y1053D01* +X680Y1053D01* +X680Y1055D01* +X676Y1055D01* +X676Y1057D01* +X672Y1057D01* +X672Y1059D01* +X670Y1059D01* +X670Y1061D01* +X668Y1061D01* +X668Y1063D01* +X666Y1063D01* +X666Y1065D01* +X664Y1065D01* +X664Y1067D01* +X662Y1067D01* +X662Y1069D01* +X660Y1069D01* +X660Y1071D01* +X638Y1071D01* +G37* +D02* +G36* +X738Y1071D02* +X738Y1069D01* +X736Y1069D01* +X736Y1065D01* +X734Y1065D01* +X734Y1063D01* +X730Y1063D01* +X730Y1061D01* +X728Y1061D01* +X728Y1059D01* +X726Y1059D01* +X726Y1057D01* +X722Y1057D01* +X722Y1055D01* +X718Y1055D01* +X718Y1053D01* +X712Y1053D01* +X712Y1051D01* +X786Y1051D01* +X786Y1053D01* +X780Y1053D01* +X780Y1055D01* +X776Y1055D01* +X776Y1057D01* +X772Y1057D01* +X772Y1059D01* +X770Y1059D01* +X770Y1061D01* +X768Y1061D01* +X768Y1063D01* +X766Y1063D01* +X766Y1065D01* +X764Y1065D01* +X764Y1067D01* +X762Y1067D01* +X762Y1069D01* +X760Y1069D01* +X760Y1071D01* +X738Y1071D01* +G37* +D02* +G36* +X838Y1071D02* +X838Y1069D01* +X836Y1069D01* +X836Y1065D01* +X834Y1065D01* +X834Y1063D01* +X830Y1063D01* +X830Y1061D01* +X828Y1061D01* +X828Y1059D01* +X826Y1059D01* +X826Y1057D01* +X822Y1057D01* +X822Y1055D01* +X818Y1055D01* +X818Y1053D01* +X812Y1053D01* +X812Y1051D01* +X886Y1051D01* +X886Y1053D01* +X880Y1053D01* +X880Y1055D01* +X876Y1055D01* +X876Y1057D01* +X872Y1057D01* +X872Y1059D01* +X870Y1059D01* +X870Y1061D01* +X868Y1061D01* +X868Y1063D01* +X866Y1063D01* +X866Y1065D01* +X864Y1065D01* +X864Y1067D01* +X862Y1067D01* +X862Y1069D01* +X860Y1069D01* +X860Y1071D01* +X838Y1071D01* +G37* +D02* +G36* +X40Y1051D02* +X40Y1049D01* +X478Y1049D01* +X478Y1051D01* +X40Y1051D01* +G37* +D02* +G36* +X40Y1051D02* +X40Y1049D01* +X478Y1049D01* +X478Y1051D01* +X40Y1051D01* +G37* +D02* +G36* +X522Y1051D02* +X522Y1049D01* +X1578Y1049D01* +X1578Y1051D01* +X522Y1051D01* +G37* +D02* +G36* +X522Y1051D02* +X522Y1049D01* +X1578Y1049D01* +X1578Y1051D01* +X522Y1051D01* +G37* +D02* +G36* +X522Y1051D02* +X522Y1049D01* +X1578Y1049D01* +X1578Y1051D01* +X522Y1051D01* +G37* +D02* +G36* +X522Y1051D02* +X522Y1049D01* +X1578Y1049D01* +X1578Y1051D01* +X522Y1051D01* +G37* +D02* +G36* +X522Y1051D02* +X522Y1049D01* +X1578Y1049D01* +X1578Y1051D01* +X522Y1051D01* +G37* +D02* +G36* +X40Y1049D02* +X40Y153D01* +X104Y153D01* +X104Y151D01* +X114Y151D01* +X114Y149D01* +X120Y149D01* +X120Y147D01* +X124Y147D01* +X124Y145D01* +X128Y145D01* +X128Y143D01* +X130Y143D01* +X130Y141D01* +X132Y141D01* +X132Y139D01* +X136Y139D01* +X136Y137D01* +X138Y137D01* +X138Y135D01* +X140Y135D01* +X140Y131D01* +X142Y131D01* +X142Y129D01* +X144Y129D01* +X144Y125D01* +X146Y125D01* +X146Y123D01* +X148Y123D01* +X148Y117D01* +X150Y117D01* +X150Y111D01* +X152Y111D01* +X152Y87D01* +X150Y87D01* +X150Y81D01* +X148Y81D01* +X148Y77D01* +X146Y77D01* +X146Y73D01* +X144Y73D01* +X144Y69D01* +X142Y69D01* +X142Y67D01* +X140Y67D01* +X140Y63D01* +X138Y63D01* +X138Y61D01* +X136Y61D01* +X136Y41D01* +X1170Y41D01* +X1170Y61D01* +X1168Y61D01* +X1168Y63D01* +X1166Y63D01* +X1166Y65D01* +X1164Y65D01* +X1164Y67D01* +X1162Y67D01* +X1162Y69D01* +X1160Y69D01* +X1160Y71D01* +X1158Y71D01* +X1158Y75D01* +X1156Y75D01* +X1156Y77D01* +X562Y77D01* +X562Y79D01* +X492Y79D01* +X492Y81D01* +X488Y81D01* +X488Y83D01* +X484Y83D01* +X484Y87D01* +X482Y87D01* +X482Y89D01* +X480Y89D01* +X480Y93D01* +X478Y93D01* +X478Y1049D01* +X40Y1049D01* +G37* +D02* +G36* +X522Y1049D02* +X522Y123D01* +X570Y123D01* +X570Y121D01* +X1156Y121D01* +X1156Y123D01* +X1158Y123D01* +X1158Y127D01* +X1160Y127D01* +X1160Y129D01* +X1162Y129D01* +X1162Y131D01* +X1164Y131D01* +X1164Y133D01* +X1166Y133D01* +X1166Y135D01* +X1168Y135D01* +X1168Y137D01* +X1170Y137D01* +X1170Y139D01* +X1172Y139D01* +X1172Y141D01* +X1176Y141D01* +X1176Y143D01* +X1178Y143D01* +X1178Y207D01* +X1180Y207D01* +X1180Y211D01* +X1182Y211D01* +X1182Y213D01* +X1184Y213D01* +X1184Y215D01* +X1186Y215D01* +X1186Y217D01* +X1188Y217D01* +X1188Y219D01* +X1194Y219D01* +X1194Y221D01* +X1578Y221D01* +X1578Y1049D01* +X522Y1049D01* +G37* +D02* +G36* +X2222Y155D02* +X2222Y153D01* +X2562Y153D01* +X2562Y155D01* +X2222Y155D01* +G37* +D02* +G36* +X2222Y155D02* +X2222Y153D01* +X2562Y153D01* +X2562Y155D01* +X2222Y155D01* +G37* +D02* +G36* +X40Y153D02* +X40Y133D01* +X60Y133D01* +X60Y137D01* +X64Y137D01* +X64Y139D01* +X66Y139D01* +X66Y141D01* +X68Y141D01* +X68Y143D01* +X72Y143D01* +X72Y145D01* +X74Y145D01* +X74Y147D01* +X78Y147D01* +X78Y149D01* +X84Y149D01* +X84Y151D01* +X94Y151D01* +X94Y153D01* +X40Y153D01* +G37* +D02* +G36* +X2222Y153D02* +X2222Y93D01* +X2220Y93D01* +X2220Y89D01* +X2218Y89D01* +X2218Y87D01* +X2216Y87D01* +X2216Y85D01* +X2214Y85D01* +X2214Y83D01* +X2212Y83D01* +X2212Y81D01* +X2208Y81D01* +X2208Y79D01* +X2138Y79D01* +X2138Y77D01* +X1542Y77D01* +X1542Y73D01* +X1540Y73D01* +X1540Y71D01* +X1538Y71D01* +X1538Y69D01* +X1536Y69D01* +X1536Y65D01* +X1534Y65D01* +X1534Y63D01* +X1530Y63D01* +X1530Y61D01* +X1528Y61D01* +X1528Y41D01* +X2464Y41D01* +X2464Y61D01* +X2462Y61D01* +X2462Y63D01* +X2460Y63D01* +X2460Y65D01* +X2458Y65D01* +X2458Y67D01* +X2456Y67D01* +X2456Y69D01* +X2454Y69D01* +X2454Y73D01* +X2452Y73D01* +X2452Y77D01* +X2450Y77D01* +X2450Y81D01* +X2448Y81D01* +X2448Y89D01* +X2446Y89D01* +X2446Y109D01* +X2448Y109D01* +X2448Y117D01* +X2450Y117D01* +X2450Y121D01* +X2452Y121D01* +X2452Y125D01* +X2454Y125D01* +X2454Y129D01* +X2456Y129D01* +X2456Y131D01* +X2458Y131D01* +X2458Y133D01* +X2460Y133D01* +X2460Y137D01* +X2464Y137D01* +X2464Y139D01* +X2466Y139D01* +X2466Y141D01* +X2468Y141D01* +X2468Y143D01* +X2472Y143D01* +X2472Y145D01* +X2474Y145D01* +X2474Y147D01* +X2478Y147D01* +X2478Y149D01* +X2484Y149D01* +X2484Y151D01* +X2494Y151D01* +X2494Y153D01* +X2222Y153D01* +G37* +D02* +G36* +X2504Y153D02* +X2504Y151D01* +X2514Y151D01* +X2514Y149D01* +X2520Y149D01* +X2520Y147D01* +X2524Y147D01* +X2524Y145D01* +X2528Y145D01* +X2528Y143D01* +X2530Y143D01* +X2530Y141D01* +X2532Y141D01* +X2532Y139D01* +X2536Y139D01* +X2536Y137D01* +X2538Y137D01* +X2538Y135D01* +X2540Y135D01* +X2540Y131D01* +X2542Y131D01* +X2542Y129D01* +X2562Y129D01* +X2562Y153D01* +X2504Y153D01* +G37* +D02* +G04 End of Copper1* +M02* \ No newline at end of file diff --git a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_drill.txt b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_drill.txt new file mode 100644 index 0000000..fe270b6 --- /dev/null +++ b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_drill.txt @@ -0,0 +1,65 @@ +; NON-PLATED HOLES START AT T1 +; THROUGH (PLATED) HOLES START AT T100 +M48 +INCH +T1C0.086614 +T100C0.038000 +T101C0.036000 +% +T1 +X024992Y016990 +X000992Y000990 +X024992Y000990 +X000992Y016990 +T100 +X014992Y000990 +X011992Y016990 +X003992Y010990 +X005992Y010990 +X012992Y016990 +X002992Y016990 +X009992Y015990 +X013992Y000990 +X004992Y010990 +X011992Y000990 +X012992Y000990 +X009992Y016990 +X006992Y010990 +X013992Y016990 +X008992Y010990 +X007992Y010990 +X002992Y015990 +X014992Y016990 +T101 +X022992Y009990 +X016992Y015990 +X016992Y011990 +X016992Y001990 +X022992Y013990 +X022992Y015990 +X016992Y005990 +X016992Y008990 +X022992Y010990 +X016992Y009990 +X016992Y006990 +X022992Y001990 +X022992Y002990 +X022992Y006990 +X016992Y003990 +X022992Y012990 +X022992Y014990 +X022992Y004990 +X022992Y003990 +X022992Y011990 +X016992Y007990 +X016992Y010990 +X022992Y005990 +X016992Y002990 +X016992Y004990 +X016992Y013990 +X022992Y007990 +X016992Y014990 +X022992Y008990 +X016992Y012990 +T00 +M30 diff --git a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_maskBottom.gbs b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_maskBottom.gbs new file mode 100644 index 0000000..9293e97 --- /dev/null +++ b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_maskBottom.gbs @@ -0,0 +1,76 @@ +G04 MADE WITH FRITZING* +G04 WWW.FRITZING.ORG* +G04 DOUBLE SIDED* +G04 HOLES PLATED* +G04 CONTOUR ON CENTER OF CONTOUR VECTOR* +%ASAXBY*% +%FSLAX23Y23*% +%MOIN*% +%OFA0B0*% +%SFA1.0B1.0*% +%ADD10C,0.080000*% +%ADD11C,0.088000*% +%ADD12C,0.096614*% +%ADD13R,0.079972X0.080000*% +%LNMASK0*% +G90* +G70* +G54D10* +X1699Y1599D03* +X1699Y1499D03* +X1699Y1399D03* +X1699Y1299D03* +X1699Y1199D03* +X1699Y1099D03* +X1699Y999D03* +X1699Y899D03* +X1699Y799D03* +X1699Y699D03* +X1699Y599D03* +X1699Y499D03* +X1699Y399D03* +X1699Y299D03* +X1699Y199D03* +X2299Y1599D03* +X2299Y1499D03* +X2299Y1399D03* +X2299Y1299D03* +X2299Y1199D03* +X2299Y1099D03* +X2299Y999D03* +X2299Y899D03* +X2299Y799D03* +X2299Y699D03* +X2299Y599D03* +X2299Y499D03* +X2299Y399D03* +X2299Y299D03* +X2299Y199D03* +G54D11* +X1199Y1699D03* +X1299Y1699D03* +X1399Y1699D03* +X1499Y1699D03* +X1199Y99D03* +X1299Y99D03* +X1399Y99D03* +X1499Y99D03* +X399Y1099D03* +X499Y1099D03* +X599Y1099D03* +X699Y1099D03* +X799Y1099D03* +X899Y1099D03* +X299Y1699D03* +X299Y1599D03* +X999Y1699D03* +X999Y1599D03* +G54D12* +X2499Y99D03* +X99Y99D03* +X99Y1699D03* +X2499Y1699D03* +G54D13* +X1699Y1599D03* +G04 End of Mask0* +M02* \ No newline at end of file diff --git a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_maskTop.gts b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_maskTop.gts new file mode 100644 index 0000000..de20a39 --- /dev/null +++ b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_maskTop.gts @@ -0,0 +1,76 @@ +G04 MADE WITH FRITZING* +G04 WWW.FRITZING.ORG* +G04 DOUBLE SIDED* +G04 HOLES PLATED* +G04 CONTOUR ON CENTER OF CONTOUR VECTOR* +%ASAXBY*% +%FSLAX23Y23*% +%MOIN*% +%OFA0B0*% +%SFA1.0B1.0*% +%ADD10C,0.080000*% +%ADD11C,0.088000*% +%ADD12C,0.096614*% +%ADD13R,0.079972X0.080000*% +%LNMASK1*% +G90* +G70* +G54D10* +X1699Y1599D03* +X1699Y1499D03* +X1699Y1399D03* +X1699Y1299D03* +X1699Y1199D03* +X1699Y1099D03* +X1699Y999D03* +X1699Y899D03* +X1699Y799D03* +X1699Y699D03* +X1699Y599D03* +X1699Y499D03* +X1699Y399D03* +X1699Y299D03* +X1699Y199D03* +X2299Y1599D03* +X2299Y1499D03* +X2299Y1399D03* +X2299Y1299D03* +X2299Y1199D03* +X2299Y1099D03* +X2299Y999D03* +X2299Y899D03* +X2299Y799D03* +X2299Y699D03* +X2299Y599D03* +X2299Y499D03* +X2299Y399D03* +X2299Y299D03* +X2299Y199D03* +G54D11* +X1199Y1699D03* +X1299Y1699D03* +X1399Y1699D03* +X1499Y1699D03* +X1199Y99D03* +X1299Y99D03* +X1399Y99D03* +X1499Y99D03* +X399Y1099D03* +X499Y1099D03* +X599Y1099D03* +X699Y1099D03* +X799Y1099D03* +X899Y1099D03* +X299Y1699D03* +X299Y1599D03* +X999Y1699D03* +X999Y1599D03* +G54D12* +X2499Y99D03* +X99Y99D03* +X99Y1699D03* +X2499Y1699D03* +G54D13* +X1699Y1599D03* +G04 End of Mask1* +M02* \ No newline at end of file diff --git a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_pnp.txt b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_pnp.txt new file mode 100644 index 0000000..8c47f66 --- /dev/null +++ b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_pnp.txt @@ -0,0 +1,33 @@ +*Pick And Place List +*Company= +*Author= +*eMail= +* +*Project=emergency_stop +*Date=14:38:19 +*CreatedBy=Fritzing 0.9.10b.2022-07-01.CD-2134-0-40d23c29 +* +* +*Coordinates in mm, always center of component +*Origin 0/0=Lower left corner of PCB +*Rotation in degree (0-360, math. pos.) +* +*No;Value;Package;X;Y;Rotation;Side;Name +1;;;15.6175;-12.3318;0;Bottom;TXT1 +2;;;50.7814;-22.8277;0;Bottom;�p�[�c1 +3;;;2.52128;-43.1561;0;Bottom;Hole2 +4;;THT;16.4914;-27.9161;-90;Bottom;J1 +5;;;25.3492;-22.7586;0;Bottom;Copper Fill5 +6;;THT;25.3814;-41.8861;0;Bottom;J2 +7;;;63.4813;-2.51621;0;Bottom;Hole4 +8;;;33.0454;-22.8602;0;Bottom;Copper Fill3 +9;;;29.21;-21.4886;0;Bottom;Copper Fill4 +10;;THT;34.2714;-2.51612;-90;Bottom;J5 +11;;THT;7.60137;-41.8861;0;Bottom;J3 +12;;;63.4813;-43.1561;0;Bottom;Hole1 +13;;;39.37;-36.7286;0;Bottom;Copper Fill2 +14;;;33.0454;-22.8602;0;Bottom;Copper Fill7 +15;;THT;34.2714;-43.1561;-90;Bottom;J4 +16;;;2.52128;-2.51621;0;Bottom;Hole3 +17;;;44.4754;-22.8094;0;Bottom;Copper Fill6 +18;;;38.1;-35.4586;0;Bottom;Copper Fill1 diff --git a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_silkBottom.gbo b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_silkBottom.gbo new file mode 100644 index 0000000..f015c28 --- /dev/null +++ b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_silkBottom.gbo @@ -0,0 +1,24 @@ +G04 MADE WITH FRITZING* +G04 WWW.FRITZING.ORG* +G04 DOUBLE SIDED* +G04 HOLES PLATED* +G04 CONTOUR ON CENTER OF CONTOUR VECTOR* +%ASAXBY*% +%FSLAX23Y23*% +%MOIN*% +%OFA0B0*% +%SFA1.0B1.0*% +%ADD10R,2.602410X1.799010X2.586410X1.783010*% +%ADD11C,0.008000*% +%LNSILK0*% +G90* +G70* +G54D11* +X4Y1795D02* +X2598Y1795D01* +X2598Y4D01* +X4Y4D01* +X4Y1795D01* +D02* +G04 End of Silk0* +M02* \ No newline at end of file diff --git a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_silkTop.gto b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_silkTop.gto new file mode 100644 index 0000000..5b2ba5c --- /dev/null +++ b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_silkTop.gto @@ -0,0 +1,9583 @@ +G04 MADE WITH FRITZING* +G04 WWW.FRITZING.ORG* +G04 DOUBLE SIDED* +G04 HOLES PLATED* +G04 CONTOUR ON CENTER OF CONTOUR VECTOR* +%ASAXBY*% +%FSLAX23Y23*% +%MOIN*% +%OFA0B0*% +%SFA1.0B1.0*% +%ADD10C,0.010000*% +%ADD11C,0.005000*% +%ADD12C,0.008000*% +%ADD13R,0.001000X0.001000*% +%LNSILK1*% +G90* +G70* +G54D10* +X1149Y1649D02* +X1549Y1649D01* +D02* +X1549Y1649D02* +X1549Y1749D01* +D02* +X1549Y1749D02* +X1149Y1749D01* +D02* +X1149Y1749D02* +X1149Y1649D01* +D02* +X1149Y49D02* +X1549Y49D01* +D02* +X1549Y49D02* +X1549Y149D01* +D02* +X1549Y149D02* +X1149Y149D01* +D02* +X1149Y149D02* +X1149Y49D01* +D02* +X349Y1049D02* +X949Y1049D01* +D02* +X949Y1049D02* +X949Y1149D01* +D02* +X949Y1149D02* +X349Y1149D01* +D02* +X349Y1149D02* +X349Y1049D01* +G54D11* +D02* +X384Y1049D02* +X349Y1084D01* +G54D10* +D02* +X249Y1749D02* +X249Y1549D01* +D02* +X249Y1549D02* +X349Y1549D01* +D02* +X349Y1549D02* +X349Y1749D01* +D02* +X349Y1749D02* +X249Y1749D01* +D02* +X949Y1749D02* +X949Y1549D01* +D02* +X949Y1549D02* +X1049Y1549D01* +D02* +X1049Y1549D02* +X1049Y1749D01* +D02* +X1049Y1749D02* +X949Y1749D01* +G54D12* +X1653Y53D02* +X2345Y53D01* +X2345Y1745D01* +X1653Y1745D01* +X1653Y53D01* +D02* +G54D13* +X1Y1799D02* +X2602Y1799D01* +X1Y1798D02* +X2602Y1798D01* +X1Y1797D02* +X2602Y1797D01* +X1Y1796D02* +X2602Y1796D01* +X1Y1795D02* +X2602Y1795D01* +X1Y1794D02* +X2602Y1794D01* +X1Y1793D02* +X2602Y1793D01* +X1Y1792D02* +X2602Y1792D01* +X1Y1791D02* +X8Y1791D01* +X2595Y1791D02* +X2602Y1791D01* +X1Y1790D02* +X8Y1790D01* +X2595Y1790D02* +X2602Y1790D01* +X1Y1789D02* +X8Y1789D01* +X2595Y1789D02* +X2602Y1789D01* +X1Y1788D02* +X8Y1788D01* +X2595Y1788D02* +X2602Y1788D01* +X1Y1787D02* +X8Y1787D01* +X2595Y1787D02* +X2602Y1787D01* +X1Y1786D02* +X8Y1786D01* +X2595Y1786D02* +X2602Y1786D01* +X1Y1785D02* +X8Y1785D01* +X2595Y1785D02* +X2602Y1785D01* +X1Y1784D02* +X8Y1784D01* +X2595Y1784D02* +X2602Y1784D01* +X1Y1783D02* +X8Y1783D01* +X2595Y1783D02* +X2602Y1783D01* +X1Y1782D02* +X8Y1782D01* +X2595Y1782D02* +X2602Y1782D01* +X1Y1781D02* +X8Y1781D01* +X2595Y1781D02* +X2602Y1781D01* +X1Y1780D02* +X8Y1780D01* +X2595Y1780D02* +X2602Y1780D01* +X1Y1779D02* +X8Y1779D01* +X2595Y1779D02* +X2602Y1779D01* +X1Y1778D02* +X8Y1778D01* +X2595Y1778D02* +X2602Y1778D01* +X1Y1777D02* +X8Y1777D01* +X2595Y1777D02* +X2602Y1777D01* +X1Y1776D02* +X8Y1776D01* +X2595Y1776D02* +X2602Y1776D01* +X1Y1775D02* +X8Y1775D01* +X2595Y1775D02* +X2602Y1775D01* +X1Y1774D02* +X8Y1774D01* +X2595Y1774D02* +X2602Y1774D01* +X1Y1773D02* +X8Y1773D01* +X2595Y1773D02* +X2602Y1773D01* +X1Y1772D02* +X8Y1772D01* +X2595Y1772D02* +X2602Y1772D01* +X1Y1771D02* +X8Y1771D01* +X2595Y1771D02* +X2602Y1771D01* +X1Y1770D02* +X8Y1770D01* +X2595Y1770D02* +X2602Y1770D01* +X1Y1769D02* +X8Y1769D01* +X2595Y1769D02* +X2602Y1769D01* +X1Y1768D02* +X8Y1768D01* +X2595Y1768D02* +X2602Y1768D01* +X1Y1767D02* +X8Y1767D01* +X2595Y1767D02* +X2602Y1767D01* +X1Y1766D02* +X8Y1766D01* +X2595Y1766D02* +X2602Y1766D01* +X1Y1765D02* +X8Y1765D01* +X2595Y1765D02* +X2602Y1765D01* +X1Y1764D02* +X8Y1764D01* +X2595Y1764D02* +X2602Y1764D01* +X1Y1763D02* +X8Y1763D01* +X2595Y1763D02* +X2602Y1763D01* +X1Y1762D02* +X8Y1762D01* +X2595Y1762D02* +X2602Y1762D01* +X1Y1761D02* +X8Y1761D01* +X2595Y1761D02* +X2602Y1761D01* +X1Y1760D02* +X8Y1760D01* +X2595Y1760D02* +X2602Y1760D01* +X1Y1759D02* +X8Y1759D01* +X2595Y1759D02* +X2602Y1759D01* +X1Y1758D02* +X8Y1758D01* +X2595Y1758D02* +X2602Y1758D01* +X1Y1757D02* +X8Y1757D01* +X2595Y1757D02* +X2602Y1757D01* +X1Y1756D02* +X8Y1756D01* +X2595Y1756D02* +X2602Y1756D01* +X1Y1755D02* +X8Y1755D01* +X2595Y1755D02* +X2602Y1755D01* +X1Y1754D02* +X8Y1754D01* +X2595Y1754D02* +X2602Y1754D01* +X1Y1753D02* +X8Y1753D01* +X2595Y1753D02* +X2602Y1753D01* +X1Y1752D02* +X8Y1752D01* +X2595Y1752D02* +X2602Y1752D01* +X1Y1751D02* +X8Y1751D01* +X283Y1751D02* +X283Y1751D01* +X983Y1751D02* +X983Y1751D01* +X2595Y1751D02* +X2602Y1751D01* +X1Y1750D02* +X8Y1750D01* +X282Y1750D02* +X284Y1750D01* +X982Y1750D02* +X984Y1750D01* +X2595Y1750D02* +X2602Y1750D01* +X1Y1749D02* +X8Y1749D01* +X281Y1749D02* +X285Y1749D01* +X981Y1749D02* +X985Y1749D01* +X2595Y1749D02* +X2602Y1749D01* +X1Y1748D02* +X8Y1748D01* +X280Y1748D02* +X286Y1748D01* +X980Y1748D02* +X986Y1748D01* +X2595Y1748D02* +X2602Y1748D01* +X1Y1747D02* +X8Y1747D01* +X279Y1747D02* +X285Y1747D01* +X979Y1747D02* +X985Y1747D01* +X2595Y1747D02* +X2602Y1747D01* +X1Y1746D02* +X8Y1746D01* +X278Y1746D02* +X284Y1746D01* +X978Y1746D02* +X984Y1746D01* +X2595Y1746D02* +X2602Y1746D01* +X1Y1745D02* +X8Y1745D01* +X277Y1745D02* +X283Y1745D01* +X977Y1745D02* +X983Y1745D01* +X2595Y1745D02* +X2602Y1745D01* +X1Y1744D02* +X8Y1744D01* +X276Y1744D02* +X282Y1744D01* +X976Y1744D02* +X982Y1744D01* +X2595Y1744D02* +X2602Y1744D01* +X1Y1743D02* +X8Y1743D01* +X275Y1743D02* +X281Y1743D01* +X975Y1743D02* +X981Y1743D01* +X2595Y1743D02* +X2602Y1743D01* +X1Y1742D02* +X8Y1742D01* +X274Y1742D02* +X280Y1742D01* +X974Y1742D02* +X980Y1742D01* +X2595Y1742D02* +X2602Y1742D01* +X1Y1741D02* +X8Y1741D01* +X273Y1741D02* +X279Y1741D01* +X973Y1741D02* +X979Y1741D01* +X2595Y1741D02* +X2602Y1741D01* +X1Y1740D02* +X8Y1740D01* +X272Y1740D02* +X278Y1740D01* +X972Y1740D02* +X978Y1740D01* +X2595Y1740D02* +X2602Y1740D01* +X1Y1739D02* +X8Y1739D01* +X271Y1739D02* +X277Y1739D01* +X971Y1739D02* +X977Y1739D01* +X2595Y1739D02* +X2602Y1739D01* +X1Y1738D02* +X8Y1738D01* +X270Y1738D02* +X276Y1738D01* +X970Y1738D02* +X976Y1738D01* +X2595Y1738D02* +X2602Y1738D01* +X1Y1737D02* +X8Y1737D01* +X269Y1737D02* +X275Y1737D01* +X969Y1737D02* +X975Y1737D01* +X2595Y1737D02* +X2602Y1737D01* +X1Y1736D02* +X8Y1736D01* +X268Y1736D02* +X274Y1736D01* +X968Y1736D02* +X974Y1736D01* +X2595Y1736D02* +X2602Y1736D01* +X1Y1735D02* +X8Y1735D01* +X267Y1735D02* +X273Y1735D01* +X967Y1735D02* +X973Y1735D01* +X2595Y1735D02* +X2602Y1735D01* +X1Y1734D02* +X8Y1734D01* +X266Y1734D02* +X272Y1734D01* +X966Y1734D02* +X972Y1734D01* +X2595Y1734D02* +X2602Y1734D01* +X1Y1733D02* +X8Y1733D01* +X265Y1733D02* +X271Y1733D01* +X965Y1733D02* +X971Y1733D01* +X2595Y1733D02* +X2602Y1733D01* +X1Y1732D02* +X8Y1732D01* +X264Y1732D02* +X270Y1732D01* +X964Y1732D02* +X969Y1732D01* +X2595Y1732D02* +X2602Y1732D01* +X1Y1731D02* +X8Y1731D01* +X263Y1731D02* +X268Y1731D01* +X963Y1731D02* +X968Y1731D01* +X2595Y1731D02* +X2602Y1731D01* +X1Y1730D02* +X8Y1730D01* +X262Y1730D02* +X268Y1730D01* +X962Y1730D02* +X967Y1730D01* +X2595Y1730D02* +X2602Y1730D01* +X1Y1729D02* +X8Y1729D01* +X261Y1729D02* +X267Y1729D01* +X961Y1729D02* +X967Y1729D01* +X2595Y1729D02* +X2602Y1729D01* +X1Y1728D02* +X8Y1728D01* +X260Y1728D02* +X266Y1728D01* +X960Y1728D02* +X966Y1728D01* +X2595Y1728D02* +X2602Y1728D01* +X1Y1727D02* +X8Y1727D01* +X259Y1727D02* +X265Y1727D01* +X959Y1727D02* +X965Y1727D01* +X2595Y1727D02* +X2602Y1727D01* +X1Y1726D02* +X8Y1726D01* +X258Y1726D02* +X264Y1726D01* +X958Y1726D02* +X964Y1726D01* +X2595Y1726D02* +X2602Y1726D01* +X1Y1725D02* +X8Y1725D01* +X257Y1725D02* +X263Y1725D01* +X957Y1725D02* +X963Y1725D01* +X2595Y1725D02* +X2602Y1725D01* +X1Y1724D02* +X8Y1724D01* +X256Y1724D02* +X262Y1724D01* +X956Y1724D02* +X962Y1724D01* +X2595Y1724D02* +X2602Y1724D01* +X1Y1723D02* +X8Y1723D01* +X255Y1723D02* +X261Y1723D01* +X955Y1723D02* +X961Y1723D01* +X2595Y1723D02* +X2602Y1723D01* +X1Y1722D02* +X8Y1722D01* +X254Y1722D02* +X260Y1722D01* +X954Y1722D02* +X960Y1722D01* +X2595Y1722D02* +X2602Y1722D01* +X1Y1721D02* +X8Y1721D01* +X253Y1721D02* +X259Y1721D01* +X953Y1721D02* +X959Y1721D01* +X2595Y1721D02* +X2602Y1721D01* +X1Y1720D02* +X8Y1720D01* +X252Y1720D02* +X258Y1720D01* +X952Y1720D02* +X958Y1720D01* +X2595Y1720D02* +X2602Y1720D01* +X1Y1719D02* +X8Y1719D01* +X251Y1719D02* +X257Y1719D01* +X951Y1719D02* +X957Y1719D01* +X2595Y1719D02* +X2602Y1719D01* +X1Y1718D02* +X8Y1718D01* +X250Y1718D02* +X256Y1718D01* +X950Y1718D02* +X956Y1718D01* +X2595Y1718D02* +X2602Y1718D01* +X1Y1717D02* +X8Y1717D01* +X249Y1717D02* +X255Y1717D01* +X949Y1717D02* +X955Y1717D01* +X2595Y1717D02* +X2602Y1717D01* +X1Y1716D02* +X8Y1716D01* +X249Y1716D02* +X254Y1716D01* +X949Y1716D02* +X954Y1716D01* +X2595Y1716D02* +X2602Y1716D01* +X1Y1715D02* +X8Y1715D01* +X250Y1715D02* +X253Y1715D01* +X950Y1715D02* +X953Y1715D01* +X2595Y1715D02* +X2602Y1715D01* +X1Y1714D02* +X8Y1714D01* +X251Y1714D02* +X252Y1714D01* +X951Y1714D02* +X952Y1714D01* +X2595Y1714D02* +X2602Y1714D01* +X1Y1713D02* +X8Y1713D01* +X2595Y1713D02* +X2602Y1713D01* +X1Y1712D02* +X8Y1712D01* +X2595Y1712D02* +X2602Y1712D01* +X1Y1711D02* +X8Y1711D01* +X2595Y1711D02* +X2602Y1711D01* +X1Y1710D02* +X8Y1710D01* +X2595Y1710D02* +X2602Y1710D01* +X1Y1709D02* +X8Y1709D01* +X2595Y1709D02* +X2602Y1709D01* +X1Y1708D02* +X8Y1708D01* +X2595Y1708D02* +X2602Y1708D01* +X1Y1707D02* +X8Y1707D01* +X2595Y1707D02* +X2602Y1707D01* +X1Y1706D02* +X8Y1706D01* +X2595Y1706D02* +X2602Y1706D01* +X1Y1705D02* +X8Y1705D01* +X2595Y1705D02* +X2602Y1705D01* +X1Y1704D02* +X8Y1704D01* +X2595Y1704D02* +X2602Y1704D01* +X1Y1703D02* +X8Y1703D01* +X2595Y1703D02* +X2602Y1703D01* +X1Y1702D02* +X8Y1702D01* +X2595Y1702D02* +X2602Y1702D01* +X1Y1701D02* +X8Y1701D01* +X2595Y1701D02* +X2602Y1701D01* +X1Y1700D02* +X8Y1700D01* +X2595Y1700D02* +X2602Y1700D01* +X1Y1699D02* +X8Y1699D01* +X2595Y1699D02* +X2602Y1699D01* +X1Y1698D02* +X8Y1698D01* +X2595Y1698D02* +X2602Y1698D01* +X1Y1697D02* +X8Y1697D01* +X2595Y1697D02* +X2602Y1697D01* +X1Y1696D02* +X8Y1696D01* +X2595Y1696D02* +X2602Y1696D01* +X1Y1695D02* +X8Y1695D01* +X2595Y1695D02* +X2602Y1695D01* +X1Y1694D02* +X8Y1694D01* +X2595Y1694D02* +X2602Y1694D01* +X1Y1693D02* +X8Y1693D01* +X2595Y1693D02* +X2602Y1693D01* +X1Y1692D02* +X8Y1692D01* +X2595Y1692D02* +X2602Y1692D01* +X1Y1691D02* +X8Y1691D01* +X2595Y1691D02* +X2602Y1691D01* +X1Y1690D02* +X8Y1690D01* +X2595Y1690D02* +X2602Y1690D01* +X1Y1689D02* +X8Y1689D01* +X2595Y1689D02* +X2602Y1689D01* +X1Y1688D02* +X8Y1688D01* +X2595Y1688D02* +X2602Y1688D01* +X1Y1687D02* +X8Y1687D01* +X2595Y1687D02* +X2602Y1687D01* +X1Y1686D02* +X8Y1686D01* +X2595Y1686D02* +X2602Y1686D01* +X1Y1685D02* +X8Y1685D01* +X1151Y1685D02* +X1152Y1685D01* +X2595Y1685D02* +X2602Y1685D01* +X1Y1684D02* +X8Y1684D01* +X1150Y1684D02* +X1153Y1684D01* +X2595Y1684D02* +X2602Y1684D01* +X1Y1683D02* +X8Y1683D01* +X1149Y1683D02* +X1154Y1683D01* +X2595Y1683D02* +X2602Y1683D01* +X1Y1682D02* +X8Y1682D01* +X1149Y1682D02* +X1155Y1682D01* +X2595Y1682D02* +X2602Y1682D01* +X1Y1681D02* +X8Y1681D01* +X1150Y1681D02* +X1156Y1681D01* +X2595Y1681D02* +X2602Y1681D01* +X1Y1680D02* +X8Y1680D01* +X1151Y1680D02* +X1157Y1680D01* +X2595Y1680D02* +X2602Y1680D01* +X1Y1679D02* +X8Y1679D01* +X1152Y1679D02* +X1158Y1679D01* +X2595Y1679D02* +X2602Y1679D01* +X1Y1678D02* +X8Y1678D01* +X1153Y1678D02* +X1159Y1678D01* +X2595Y1678D02* +X2602Y1678D01* +X1Y1677D02* +X8Y1677D01* +X1154Y1677D02* +X1160Y1677D01* +X2595Y1677D02* +X2602Y1677D01* +X1Y1676D02* +X8Y1676D01* +X1155Y1676D02* +X1161Y1676D01* +X2595Y1676D02* +X2602Y1676D01* +X1Y1675D02* +X8Y1675D01* +X1156Y1675D02* +X1162Y1675D01* +X2595Y1675D02* +X2602Y1675D01* +X1Y1674D02* +X8Y1674D01* +X1157Y1674D02* +X1163Y1674D01* +X2595Y1674D02* +X2602Y1674D01* +X1Y1673D02* +X8Y1673D01* +X1158Y1673D02* +X1164Y1673D01* +X2595Y1673D02* +X2602Y1673D01* +X1Y1672D02* +X8Y1672D01* +X1159Y1672D02* +X1165Y1672D01* +X2595Y1672D02* +X2602Y1672D01* +X1Y1671D02* +X8Y1671D01* +X1160Y1671D02* +X1166Y1671D01* +X2595Y1671D02* +X2602Y1671D01* +X1Y1670D02* +X8Y1670D01* +X1161Y1670D02* +X1167Y1670D01* +X2595Y1670D02* +X2602Y1670D01* +X1Y1669D02* +X8Y1669D01* +X1162Y1669D02* +X1167Y1669D01* +X2595Y1669D02* +X2602Y1669D01* +X1Y1668D02* +X8Y1668D01* +X1163Y1668D02* +X1168Y1668D01* +X2595Y1668D02* +X2602Y1668D01* +X1Y1667D02* +X8Y1667D01* +X1164Y1667D02* +X1170Y1667D01* +X2595Y1667D02* +X2602Y1667D01* +X1Y1666D02* +X8Y1666D01* +X1165Y1666D02* +X1171Y1666D01* +X2595Y1666D02* +X2602Y1666D01* +X1Y1665D02* +X8Y1665D01* +X1166Y1665D02* +X1172Y1665D01* +X2595Y1665D02* +X2602Y1665D01* +X1Y1664D02* +X8Y1664D01* +X1167Y1664D02* +X1173Y1664D01* +X2595Y1664D02* +X2602Y1664D01* +X1Y1663D02* +X8Y1663D01* +X1168Y1663D02* +X1174Y1663D01* +X2595Y1663D02* +X2602Y1663D01* +X1Y1662D02* +X8Y1662D01* +X1169Y1662D02* +X1175Y1662D01* +X2595Y1662D02* +X2602Y1662D01* +X1Y1661D02* +X8Y1661D01* +X1170Y1661D02* +X1176Y1661D01* +X2595Y1661D02* +X2602Y1661D01* +X1Y1660D02* +X8Y1660D01* +X1171Y1660D02* +X1177Y1660D01* +X2595Y1660D02* +X2602Y1660D01* +X1Y1659D02* +X8Y1659D01* +X1172Y1659D02* +X1178Y1659D01* +X2595Y1659D02* +X2602Y1659D01* +X1Y1658D02* +X8Y1658D01* +X1173Y1658D02* +X1179Y1658D01* +X2595Y1658D02* +X2602Y1658D01* +X1Y1657D02* +X8Y1657D01* +X1174Y1657D02* +X1180Y1657D01* +X2595Y1657D02* +X2602Y1657D01* +X1Y1656D02* +X8Y1656D01* +X1175Y1656D02* +X1181Y1656D01* +X2595Y1656D02* +X2602Y1656D01* +X1Y1655D02* +X8Y1655D01* +X1176Y1655D02* +X1182Y1655D01* +X2595Y1655D02* +X2602Y1655D01* +X1Y1654D02* +X8Y1654D01* +X1177Y1654D02* +X1183Y1654D01* +X2595Y1654D02* +X2602Y1654D01* +X1Y1653D02* +X8Y1653D01* +X1178Y1653D02* +X1184Y1653D01* +X2595Y1653D02* +X2602Y1653D01* +X1Y1652D02* +X8Y1652D01* +X1179Y1652D02* +X1185Y1652D01* +X2595Y1652D02* +X2602Y1652D01* +X1Y1651D02* +X8Y1651D01* +X1180Y1651D02* +X1185Y1651D01* +X2595Y1651D02* +X2602Y1651D01* +X1Y1650D02* +X8Y1650D01* +X1181Y1650D02* +X1185Y1650D01* +X2595Y1650D02* +X2602Y1650D01* +X1Y1649D02* +X8Y1649D01* +X1182Y1649D02* +X1184Y1649D01* +X2595Y1649D02* +X2602Y1649D01* +X1Y1648D02* +X8Y1648D01* +X2595Y1648D02* +X2602Y1648D01* +X1Y1647D02* +X8Y1647D01* +X2595Y1647D02* +X2602Y1647D01* +X1Y1646D02* +X8Y1646D01* +X2595Y1646D02* +X2602Y1646D01* +X1Y1645D02* +X8Y1645D01* +X2595Y1645D02* +X2602Y1645D01* +X1Y1644D02* +X8Y1644D01* +X2595Y1644D02* +X2602Y1644D01* +X1Y1643D02* +X8Y1643D01* +X2595Y1643D02* +X2602Y1643D01* +X1Y1642D02* +X8Y1642D01* +X2595Y1642D02* +X2602Y1642D01* +X1Y1641D02* +X8Y1641D01* +X2595Y1641D02* +X2602Y1641D01* +X1Y1640D02* +X8Y1640D01* +X2595Y1640D02* +X2602Y1640D01* +X1Y1639D02* +X8Y1639D01* +X2595Y1639D02* +X2602Y1639D01* +X1Y1638D02* +X8Y1638D01* +X2595Y1638D02* +X2602Y1638D01* +X1Y1637D02* +X8Y1637D01* +X2595Y1637D02* +X2602Y1637D01* +X1Y1636D02* +X8Y1636D01* +X2595Y1636D02* +X2602Y1636D01* +X1Y1635D02* +X8Y1635D01* +X2595Y1635D02* +X2602Y1635D01* +X1Y1634D02* +X8Y1634D01* +X2595Y1634D02* +X2602Y1634D01* +X1Y1633D02* +X8Y1633D01* +X2595Y1633D02* +X2602Y1633D01* +X1Y1632D02* +X8Y1632D01* +X2595Y1632D02* +X2602Y1632D01* +X1Y1631D02* +X8Y1631D01* +X2595Y1631D02* +X2602Y1631D01* +X1Y1630D02* +X8Y1630D01* +X2595Y1630D02* +X2602Y1630D01* +X1Y1629D02* +X8Y1629D01* +X2595Y1629D02* +X2602Y1629D01* +X1Y1628D02* +X8Y1628D01* +X2595Y1628D02* +X2602Y1628D01* +X1Y1627D02* +X8Y1627D01* +X2595Y1627D02* +X2602Y1627D01* +X1Y1626D02* +X8Y1626D01* +X2595Y1626D02* +X2602Y1626D01* +X1Y1625D02* +X8Y1625D01* +X2595Y1625D02* +X2602Y1625D01* +X1Y1624D02* +X8Y1624D01* +X2595Y1624D02* +X2602Y1624D01* +X1Y1623D02* +X8Y1623D01* +X2595Y1623D02* +X2602Y1623D01* +X1Y1622D02* +X8Y1622D01* +X2595Y1622D02* +X2602Y1622D01* +X1Y1621D02* +X8Y1621D01* +X2595Y1621D02* +X2602Y1621D01* +X1Y1620D02* +X8Y1620D01* +X2595Y1620D02* +X2602Y1620D01* +X1Y1619D02* +X8Y1619D01* +X2595Y1619D02* +X2602Y1619D01* +X1Y1618D02* +X8Y1618D01* +X2595Y1618D02* +X2602Y1618D01* +X1Y1617D02* +X8Y1617D01* +X2595Y1617D02* +X2602Y1617D01* +X1Y1616D02* +X8Y1616D01* +X2595Y1616D02* +X2602Y1616D01* +X1Y1615D02* +X8Y1615D01* +X2595Y1615D02* +X2602Y1615D01* +X1Y1614D02* +X8Y1614D01* +X2595Y1614D02* +X2602Y1614D01* +X1Y1613D02* +X8Y1613D01* +X2595Y1613D02* +X2602Y1613D01* +X1Y1612D02* +X8Y1612D01* +X2595Y1612D02* +X2602Y1612D01* +X1Y1611D02* +X8Y1611D01* +X2595Y1611D02* +X2602Y1611D01* +X1Y1610D02* +X8Y1610D01* +X2595Y1610D02* +X2602Y1610D01* +X1Y1609D02* +X8Y1609D01* +X2595Y1609D02* +X2602Y1609D01* +X1Y1608D02* +X8Y1608D01* +X2595Y1608D02* +X2602Y1608D01* +X1Y1607D02* +X8Y1607D01* +X2595Y1607D02* +X2602Y1607D01* +X1Y1606D02* +X8Y1606D01* +X2595Y1606D02* +X2602Y1606D01* +X1Y1605D02* +X8Y1605D01* +X2595Y1605D02* +X2602Y1605D01* +X1Y1604D02* +X8Y1604D01* +X2595Y1604D02* +X2602Y1604D01* +X1Y1603D02* +X8Y1603D01* +X2595Y1603D02* +X2602Y1603D01* +X1Y1602D02* +X8Y1602D01* +X2595Y1602D02* +X2602Y1602D01* +X1Y1601D02* +X8Y1601D01* +X2595Y1601D02* +X2602Y1601D01* +X1Y1600D02* +X8Y1600D01* +X2595Y1600D02* +X2602Y1600D01* +X1Y1599D02* +X8Y1599D01* +X2595Y1599D02* +X2602Y1599D01* +X1Y1598D02* +X8Y1598D01* +X2595Y1598D02* +X2602Y1598D01* +X1Y1597D02* +X8Y1597D01* +X2595Y1597D02* +X2602Y1597D01* +X1Y1596D02* +X8Y1596D01* +X2595Y1596D02* +X2602Y1596D01* +X1Y1595D02* +X8Y1595D01* +X2595Y1595D02* +X2602Y1595D01* +X1Y1594D02* +X8Y1594D01* +X2595Y1594D02* +X2602Y1594D01* +X1Y1593D02* +X8Y1593D01* +X2595Y1593D02* +X2602Y1593D01* +X1Y1592D02* +X8Y1592D01* +X2595Y1592D02* +X2602Y1592D01* +X1Y1591D02* +X8Y1591D01* +X2595Y1591D02* +X2602Y1591D01* +X1Y1590D02* +X8Y1590D01* +X2595Y1590D02* +X2602Y1590D01* +X1Y1589D02* +X8Y1589D01* +X2595Y1589D02* +X2602Y1589D01* +X1Y1588D02* +X8Y1588D01* +X2595Y1588D02* +X2602Y1588D01* +X1Y1587D02* +X8Y1587D01* +X2595Y1587D02* +X2602Y1587D01* +X1Y1586D02* +X8Y1586D01* +X2595Y1586D02* +X2602Y1586D01* +X1Y1585D02* +X8Y1585D01* +X2595Y1585D02* +X2602Y1585D01* +X1Y1584D02* +X8Y1584D01* +X2595Y1584D02* +X2602Y1584D01* +X1Y1583D02* +X8Y1583D01* +X2595Y1583D02* +X2602Y1583D01* +X1Y1582D02* +X8Y1582D01* +X2595Y1582D02* +X2602Y1582D01* +X1Y1581D02* +X8Y1581D01* +X2595Y1581D02* +X2602Y1581D01* +X1Y1580D02* +X8Y1580D01* +X2595Y1580D02* +X2602Y1580D01* +X1Y1579D02* +X8Y1579D01* +X2595Y1579D02* +X2602Y1579D01* +X1Y1578D02* +X8Y1578D01* +X2595Y1578D02* +X2602Y1578D01* +X1Y1577D02* +X8Y1577D01* +X2595Y1577D02* +X2602Y1577D01* +X1Y1576D02* +X8Y1576D01* +X2595Y1576D02* +X2602Y1576D01* +X1Y1575D02* +X8Y1575D01* +X2595Y1575D02* +X2602Y1575D01* +X1Y1574D02* +X8Y1574D01* +X2595Y1574D02* +X2602Y1574D01* +X1Y1573D02* +X8Y1573D01* +X2595Y1573D02* +X2602Y1573D01* +X1Y1572D02* +X8Y1572D01* +X2595Y1572D02* +X2602Y1572D01* +X1Y1571D02* +X8Y1571D01* +X2595Y1571D02* +X2602Y1571D01* +X1Y1570D02* +X8Y1570D01* +X2595Y1570D02* +X2602Y1570D01* +X1Y1569D02* +X8Y1569D01* +X2595Y1569D02* +X2602Y1569D01* +X1Y1568D02* +X8Y1568D01* +X2595Y1568D02* +X2602Y1568D01* +X1Y1567D02* +X8Y1567D01* +X2595Y1567D02* +X2602Y1567D01* +X1Y1566D02* +X8Y1566D01* +X2595Y1566D02* +X2602Y1566D01* +X1Y1565D02* +X8Y1565D01* +X2595Y1565D02* +X2602Y1565D01* +X1Y1564D02* +X8Y1564D01* +X2595Y1564D02* +X2602Y1564D01* +X1Y1563D02* +X8Y1563D01* +X2595Y1563D02* +X2602Y1563D01* +X1Y1562D02* +X8Y1562D01* +X2595Y1562D02* +X2602Y1562D01* +X1Y1561D02* +X8Y1561D01* +X2595Y1561D02* +X2602Y1561D01* +X1Y1560D02* +X8Y1560D01* +X2595Y1560D02* +X2602Y1560D01* +X1Y1559D02* +X8Y1559D01* +X2595Y1559D02* +X2602Y1559D01* +X1Y1558D02* +X8Y1558D01* +X2595Y1558D02* +X2602Y1558D01* +X1Y1557D02* +X8Y1557D01* +X2595Y1557D02* +X2602Y1557D01* +X1Y1556D02* +X8Y1556D01* +X2595Y1556D02* +X2602Y1556D01* +X1Y1555D02* +X8Y1555D01* +X2595Y1555D02* +X2602Y1555D01* +X1Y1554D02* +X8Y1554D01* +X2595Y1554D02* +X2602Y1554D01* +X1Y1553D02* +X8Y1553D01* +X2595Y1553D02* +X2602Y1553D01* +X1Y1552D02* +X8Y1552D01* +X2595Y1552D02* +X2602Y1552D01* +X1Y1551D02* +X8Y1551D01* +X2595Y1551D02* +X2602Y1551D01* +X1Y1550D02* +X8Y1550D01* +X2595Y1550D02* +X2602Y1550D01* +X1Y1549D02* +X8Y1549D01* +X2595Y1549D02* +X2602Y1549D01* +X1Y1548D02* +X8Y1548D01* +X2595Y1548D02* +X2602Y1548D01* +X1Y1547D02* +X8Y1547D01* +X2595Y1547D02* +X2602Y1547D01* +X1Y1546D02* +X8Y1546D01* +X2595Y1546D02* +X2602Y1546D01* +X1Y1545D02* +X8Y1545D01* +X2595Y1545D02* +X2602Y1545D01* +X1Y1544D02* +X8Y1544D01* +X2595Y1544D02* +X2602Y1544D01* +X1Y1543D02* +X8Y1543D01* +X2595Y1543D02* +X2602Y1543D01* +X1Y1542D02* +X8Y1542D01* +X2595Y1542D02* +X2602Y1542D01* +X1Y1541D02* +X8Y1541D01* +X2595Y1541D02* +X2602Y1541D01* +X1Y1540D02* +X8Y1540D01* +X2595Y1540D02* +X2602Y1540D01* +X1Y1539D02* +X8Y1539D01* +X2595Y1539D02* +X2602Y1539D01* +X1Y1538D02* +X8Y1538D01* +X2595Y1538D02* +X2602Y1538D01* +X1Y1537D02* +X8Y1537D01* +X2595Y1537D02* +X2602Y1537D01* +X1Y1536D02* +X8Y1536D01* +X2595Y1536D02* +X2602Y1536D01* +X1Y1535D02* +X8Y1535D01* +X2595Y1535D02* +X2602Y1535D01* +X1Y1534D02* +X8Y1534D01* +X2595Y1534D02* +X2602Y1534D01* +X1Y1533D02* +X8Y1533D01* +X2595Y1533D02* +X2602Y1533D01* +X1Y1532D02* +X8Y1532D01* +X2595Y1532D02* +X2602Y1532D01* +X1Y1531D02* +X8Y1531D01* +X2595Y1531D02* +X2602Y1531D01* +X1Y1530D02* +X8Y1530D01* +X2595Y1530D02* +X2602Y1530D01* +X1Y1529D02* +X8Y1529D01* +X2595Y1529D02* +X2602Y1529D01* +X1Y1528D02* +X8Y1528D01* +X2595Y1528D02* +X2602Y1528D01* +X1Y1527D02* +X8Y1527D01* +X2595Y1527D02* +X2602Y1527D01* +X1Y1526D02* +X8Y1526D01* +X2595Y1526D02* +X2602Y1526D01* +X1Y1525D02* +X8Y1525D01* +X2595Y1525D02* +X2602Y1525D01* +X1Y1524D02* +X8Y1524D01* +X2595Y1524D02* +X2602Y1524D01* +X1Y1523D02* +X8Y1523D01* +X2595Y1523D02* +X2602Y1523D01* +X1Y1522D02* +X8Y1522D01* +X2595Y1522D02* +X2602Y1522D01* +X1Y1521D02* +X8Y1521D01* +X2595Y1521D02* +X2602Y1521D01* +X1Y1520D02* +X8Y1520D01* +X2595Y1520D02* +X2602Y1520D01* +X1Y1519D02* +X8Y1519D01* +X2595Y1519D02* +X2602Y1519D01* +X1Y1518D02* +X8Y1518D01* +X2595Y1518D02* +X2602Y1518D01* +X1Y1517D02* +X8Y1517D01* +X2595Y1517D02* +X2602Y1517D01* +X1Y1516D02* +X8Y1516D01* +X2595Y1516D02* +X2602Y1516D01* +X1Y1515D02* +X8Y1515D01* +X2595Y1515D02* +X2602Y1515D01* +X1Y1514D02* +X8Y1514D01* +X2595Y1514D02* +X2602Y1514D01* +X1Y1513D02* +X8Y1513D01* +X2595Y1513D02* +X2602Y1513D01* +X1Y1512D02* +X8Y1512D01* +X2595Y1512D02* +X2602Y1512D01* +X1Y1511D02* +X8Y1511D01* +X2595Y1511D02* +X2602Y1511D01* +X1Y1510D02* +X8Y1510D01* +X2595Y1510D02* +X2602Y1510D01* +X1Y1509D02* +X8Y1509D01* +X2595Y1509D02* +X2602Y1509D01* +X1Y1508D02* +X8Y1508D01* +X2595Y1508D02* +X2602Y1508D01* +X1Y1507D02* +X8Y1507D01* +X2595Y1507D02* +X2602Y1507D01* +X1Y1506D02* +X8Y1506D01* +X2595Y1506D02* +X2602Y1506D01* +X1Y1505D02* +X8Y1505D01* +X2595Y1505D02* +X2602Y1505D01* +X1Y1504D02* +X8Y1504D01* +X2595Y1504D02* +X2602Y1504D01* +X1Y1503D02* +X8Y1503D01* +X2595Y1503D02* +X2602Y1503D01* +X1Y1502D02* +X8Y1502D01* +X2595Y1502D02* +X2602Y1502D01* +X1Y1501D02* +X8Y1501D01* +X2595Y1501D02* +X2602Y1501D01* +X1Y1500D02* +X8Y1500D01* +X2595Y1500D02* +X2602Y1500D01* +X1Y1499D02* +X8Y1499D01* +X2595Y1499D02* +X2602Y1499D01* +X1Y1498D02* +X8Y1498D01* +X2595Y1498D02* +X2602Y1498D01* +X1Y1497D02* +X8Y1497D01* +X2595Y1497D02* +X2602Y1497D01* +X1Y1496D02* +X8Y1496D01* +X2595Y1496D02* +X2602Y1496D01* +X1Y1495D02* +X8Y1495D01* +X2595Y1495D02* +X2602Y1495D01* +X1Y1494D02* +X8Y1494D01* +X2595Y1494D02* +X2602Y1494D01* +X1Y1493D02* +X8Y1493D01* +X2595Y1493D02* +X2602Y1493D01* +X1Y1492D02* +X8Y1492D01* +X2595Y1492D02* +X2602Y1492D01* +X1Y1491D02* +X8Y1491D01* +X2595Y1491D02* +X2602Y1491D01* +X1Y1490D02* +X8Y1490D01* +X2595Y1490D02* +X2602Y1490D01* +X1Y1489D02* +X8Y1489D01* +X2595Y1489D02* +X2602Y1489D01* +X1Y1488D02* +X8Y1488D01* +X2595Y1488D02* +X2602Y1488D01* +X1Y1487D02* +X8Y1487D01* +X2595Y1487D02* +X2602Y1487D01* +X1Y1486D02* +X8Y1486D01* +X2595Y1486D02* +X2602Y1486D01* +X1Y1485D02* +X8Y1485D01* +X2595Y1485D02* +X2602Y1485D01* +X1Y1484D02* +X8Y1484D01* +X2595Y1484D02* +X2602Y1484D01* +X1Y1483D02* +X8Y1483D01* +X2595Y1483D02* +X2602Y1483D01* +X1Y1482D02* +X8Y1482D01* +X2595Y1482D02* +X2602Y1482D01* +X1Y1481D02* +X8Y1481D01* +X2595Y1481D02* +X2602Y1481D01* +X1Y1480D02* +X8Y1480D01* +X2595Y1480D02* +X2602Y1480D01* +X1Y1479D02* +X8Y1479D01* +X2595Y1479D02* +X2602Y1479D01* +X1Y1478D02* +X8Y1478D01* +X2595Y1478D02* +X2602Y1478D01* +X1Y1477D02* +X8Y1477D01* +X2595Y1477D02* +X2602Y1477D01* +X1Y1476D02* +X8Y1476D01* +X2595Y1476D02* +X2602Y1476D01* +X1Y1475D02* +X8Y1475D01* +X2595Y1475D02* +X2602Y1475D01* +X1Y1474D02* +X8Y1474D01* +X2595Y1474D02* +X2602Y1474D01* +X1Y1473D02* +X8Y1473D01* +X2595Y1473D02* +X2602Y1473D01* +X1Y1472D02* +X8Y1472D01* +X2595Y1472D02* +X2602Y1472D01* +X1Y1471D02* +X8Y1471D01* +X2595Y1471D02* +X2602Y1471D01* +X1Y1470D02* +X8Y1470D01* +X2595Y1470D02* +X2602Y1470D01* +X1Y1469D02* +X8Y1469D01* +X2595Y1469D02* +X2602Y1469D01* +X1Y1468D02* +X8Y1468D01* +X2595Y1468D02* +X2602Y1468D01* +X1Y1467D02* +X8Y1467D01* +X2595Y1467D02* +X2602Y1467D01* +X1Y1466D02* +X8Y1466D01* +X2595Y1466D02* +X2602Y1466D01* +X1Y1465D02* +X8Y1465D01* +X2595Y1465D02* +X2602Y1465D01* +X1Y1464D02* +X8Y1464D01* +X2595Y1464D02* +X2602Y1464D01* +X1Y1463D02* +X8Y1463D01* +X2595Y1463D02* +X2602Y1463D01* +X1Y1462D02* +X8Y1462D01* +X2595Y1462D02* +X2602Y1462D01* +X1Y1461D02* +X8Y1461D01* +X2595Y1461D02* +X2602Y1461D01* +X1Y1460D02* +X8Y1460D01* +X2595Y1460D02* +X2602Y1460D01* +X1Y1459D02* +X8Y1459D01* +X2595Y1459D02* +X2602Y1459D01* +X1Y1458D02* +X8Y1458D01* +X2595Y1458D02* +X2602Y1458D01* +X1Y1457D02* +X8Y1457D01* +X2595Y1457D02* +X2602Y1457D01* +X1Y1456D02* +X8Y1456D01* +X2595Y1456D02* +X2602Y1456D01* +X1Y1455D02* +X8Y1455D01* +X2595Y1455D02* +X2602Y1455D01* +X1Y1454D02* +X8Y1454D01* +X2595Y1454D02* +X2602Y1454D01* +X1Y1453D02* +X8Y1453D01* +X2595Y1453D02* +X2602Y1453D01* +X1Y1452D02* +X8Y1452D01* +X2595Y1452D02* +X2602Y1452D01* +X1Y1451D02* +X8Y1451D01* +X2595Y1451D02* +X2602Y1451D01* +X1Y1450D02* +X8Y1450D01* +X2595Y1450D02* +X2602Y1450D01* +X1Y1449D02* +X8Y1449D01* +X2595Y1449D02* +X2602Y1449D01* +X1Y1448D02* +X8Y1448D01* +X2595Y1448D02* +X2602Y1448D01* +X1Y1447D02* +X8Y1447D01* +X2595Y1447D02* +X2602Y1447D01* +X1Y1446D02* +X8Y1446D01* +X2595Y1446D02* +X2602Y1446D01* +X1Y1445D02* +X8Y1445D01* +X2595Y1445D02* +X2602Y1445D01* +X1Y1444D02* +X8Y1444D01* +X2595Y1444D02* +X2602Y1444D01* +X1Y1443D02* +X8Y1443D01* +X2595Y1443D02* +X2602Y1443D01* +X1Y1442D02* +X8Y1442D01* +X2595Y1442D02* +X2602Y1442D01* +X1Y1441D02* +X8Y1441D01* +X2595Y1441D02* +X2602Y1441D01* +X1Y1440D02* +X8Y1440D01* +X2595Y1440D02* +X2602Y1440D01* +X1Y1439D02* +X8Y1439D01* +X2595Y1439D02* +X2602Y1439D01* +X1Y1438D02* +X8Y1438D01* +X2595Y1438D02* +X2602Y1438D01* +X1Y1437D02* +X8Y1437D01* +X2595Y1437D02* +X2602Y1437D01* +X1Y1436D02* +X8Y1436D01* +X2595Y1436D02* +X2602Y1436D01* +X1Y1435D02* +X8Y1435D01* +X2595Y1435D02* +X2602Y1435D01* +X1Y1434D02* +X8Y1434D01* +X2595Y1434D02* +X2602Y1434D01* +X1Y1433D02* +X8Y1433D01* +X2595Y1433D02* +X2602Y1433D01* +X1Y1432D02* +X8Y1432D01* +X2595Y1432D02* +X2602Y1432D01* +X1Y1431D02* +X8Y1431D01* +X2595Y1431D02* +X2602Y1431D01* +X1Y1430D02* +X8Y1430D01* +X2595Y1430D02* +X2602Y1430D01* +X1Y1429D02* +X8Y1429D01* +X2595Y1429D02* +X2602Y1429D01* +X1Y1428D02* +X8Y1428D01* +X2595Y1428D02* +X2602Y1428D01* +X1Y1427D02* +X8Y1427D01* +X2595Y1427D02* +X2602Y1427D01* +X1Y1426D02* +X8Y1426D01* +X2595Y1426D02* +X2602Y1426D01* +X1Y1425D02* +X8Y1425D01* +X2595Y1425D02* +X2602Y1425D01* +X1Y1424D02* +X8Y1424D01* +X2595Y1424D02* +X2602Y1424D01* +X1Y1423D02* +X8Y1423D01* +X2595Y1423D02* +X2602Y1423D01* +X1Y1422D02* +X8Y1422D01* +X2595Y1422D02* +X2602Y1422D01* +X1Y1421D02* +X8Y1421D01* +X2595Y1421D02* +X2602Y1421D01* +X1Y1420D02* +X8Y1420D01* +X2595Y1420D02* +X2602Y1420D01* +X1Y1419D02* +X8Y1419D01* +X2595Y1419D02* +X2602Y1419D01* +X1Y1418D02* +X8Y1418D01* +X2595Y1418D02* +X2602Y1418D01* +X1Y1417D02* +X8Y1417D01* +X2595Y1417D02* +X2602Y1417D01* +X1Y1416D02* +X8Y1416D01* +X2595Y1416D02* +X2602Y1416D01* +X1Y1415D02* +X8Y1415D01* +X2595Y1415D02* +X2602Y1415D01* +X1Y1414D02* +X8Y1414D01* +X2595Y1414D02* +X2602Y1414D01* +X1Y1413D02* +X8Y1413D01* +X2595Y1413D02* +X2602Y1413D01* +X1Y1412D02* +X8Y1412D01* +X2595Y1412D02* +X2602Y1412D01* +X1Y1411D02* +X8Y1411D01* +X2595Y1411D02* +X2602Y1411D01* +X1Y1410D02* +X8Y1410D01* +X2595Y1410D02* +X2602Y1410D01* +X1Y1409D02* +X8Y1409D01* +X2595Y1409D02* +X2602Y1409D01* +X1Y1408D02* +X8Y1408D01* +X2595Y1408D02* +X2602Y1408D01* +X1Y1407D02* +X8Y1407D01* +X2595Y1407D02* +X2602Y1407D01* +X1Y1406D02* +X8Y1406D01* +X2595Y1406D02* +X2602Y1406D01* +X1Y1405D02* +X8Y1405D01* +X2595Y1405D02* +X2602Y1405D01* +X1Y1404D02* +X8Y1404D01* +X2595Y1404D02* +X2602Y1404D01* +X1Y1403D02* +X8Y1403D01* +X2595Y1403D02* +X2602Y1403D01* +X1Y1402D02* +X8Y1402D01* +X2595Y1402D02* +X2602Y1402D01* +X1Y1401D02* +X8Y1401D01* +X2595Y1401D02* +X2602Y1401D01* +X1Y1400D02* +X8Y1400D01* +X2595Y1400D02* +X2602Y1400D01* +X1Y1399D02* +X8Y1399D01* +X2595Y1399D02* +X2602Y1399D01* +X1Y1398D02* +X8Y1398D01* +X2595Y1398D02* +X2602Y1398D01* +X1Y1397D02* +X8Y1397D01* +X2595Y1397D02* +X2602Y1397D01* +X1Y1396D02* +X8Y1396D01* +X2595Y1396D02* +X2602Y1396D01* +X1Y1395D02* +X8Y1395D01* +X2595Y1395D02* +X2602Y1395D01* +X1Y1394D02* +X8Y1394D01* +X2595Y1394D02* +X2602Y1394D01* +X1Y1393D02* +X8Y1393D01* +X2595Y1393D02* +X2602Y1393D01* +X1Y1392D02* +X8Y1392D01* +X2595Y1392D02* +X2602Y1392D01* +X1Y1391D02* +X8Y1391D01* +X2595Y1391D02* +X2602Y1391D01* +X1Y1390D02* +X8Y1390D01* +X2595Y1390D02* +X2602Y1390D01* +X1Y1389D02* +X8Y1389D01* +X2595Y1389D02* +X2602Y1389D01* +X1Y1388D02* +X8Y1388D01* +X2595Y1388D02* +X2602Y1388D01* +X1Y1387D02* +X8Y1387D01* +X2595Y1387D02* +X2602Y1387D01* +X1Y1386D02* +X8Y1386D01* +X2595Y1386D02* +X2602Y1386D01* +X1Y1385D02* +X8Y1385D01* +X2595Y1385D02* +X2602Y1385D01* +X1Y1384D02* +X8Y1384D01* +X2595Y1384D02* +X2602Y1384D01* +X1Y1383D02* +X8Y1383D01* +X2595Y1383D02* +X2602Y1383D01* +X1Y1382D02* +X8Y1382D01* +X2595Y1382D02* +X2602Y1382D01* +X1Y1381D02* +X8Y1381D01* +X2595Y1381D02* +X2602Y1381D01* +X1Y1380D02* +X8Y1380D01* +X2595Y1380D02* +X2602Y1380D01* +X1Y1379D02* +X8Y1379D01* +X2595Y1379D02* +X2602Y1379D01* +X1Y1378D02* +X8Y1378D01* +X2595Y1378D02* +X2602Y1378D01* +X1Y1377D02* +X8Y1377D01* +X2595Y1377D02* +X2602Y1377D01* +X1Y1376D02* +X8Y1376D01* +X2595Y1376D02* +X2602Y1376D01* +X1Y1375D02* +X8Y1375D01* +X2595Y1375D02* +X2602Y1375D01* +X1Y1374D02* +X8Y1374D01* +X2595Y1374D02* +X2602Y1374D01* +X1Y1373D02* +X8Y1373D01* +X2595Y1373D02* +X2602Y1373D01* +X1Y1372D02* +X8Y1372D01* +X2595Y1372D02* +X2602Y1372D01* +X1Y1371D02* +X8Y1371D01* +X2595Y1371D02* +X2602Y1371D01* +X1Y1370D02* +X8Y1370D01* +X2595Y1370D02* +X2602Y1370D01* +X1Y1369D02* +X8Y1369D01* +X2595Y1369D02* +X2602Y1369D01* +X1Y1368D02* +X8Y1368D01* +X2595Y1368D02* +X2602Y1368D01* +X1Y1367D02* +X8Y1367D01* +X2595Y1367D02* +X2602Y1367D01* +X1Y1366D02* +X8Y1366D01* +X2595Y1366D02* +X2602Y1366D01* +X1Y1365D02* +X8Y1365D01* +X2595Y1365D02* +X2602Y1365D01* +X1Y1364D02* +X8Y1364D01* +X2595Y1364D02* +X2602Y1364D01* +X1Y1363D02* +X8Y1363D01* +X2595Y1363D02* +X2602Y1363D01* +X1Y1362D02* +X8Y1362D01* +X2595Y1362D02* +X2602Y1362D01* +X1Y1361D02* +X8Y1361D01* +X2595Y1361D02* +X2602Y1361D01* +X1Y1360D02* +X8Y1360D01* +X2595Y1360D02* +X2602Y1360D01* +X1Y1359D02* +X8Y1359D01* +X2595Y1359D02* +X2602Y1359D01* +X1Y1358D02* +X8Y1358D01* +X2595Y1358D02* +X2602Y1358D01* +X1Y1357D02* +X8Y1357D01* +X2595Y1357D02* +X2602Y1357D01* +X1Y1356D02* +X8Y1356D01* +X2595Y1356D02* +X2602Y1356D01* +X1Y1355D02* +X8Y1355D01* +X2595Y1355D02* +X2602Y1355D01* +X1Y1354D02* +X8Y1354D01* +X2595Y1354D02* +X2602Y1354D01* +X1Y1353D02* +X8Y1353D01* +X2595Y1353D02* +X2602Y1353D01* +X1Y1352D02* +X8Y1352D01* +X2595Y1352D02* +X2602Y1352D01* +X1Y1351D02* +X8Y1351D01* +X2595Y1351D02* +X2602Y1351D01* +X1Y1350D02* +X8Y1350D01* +X2595Y1350D02* +X2602Y1350D01* +X1Y1349D02* +X8Y1349D01* +X2595Y1349D02* +X2602Y1349D01* +X1Y1348D02* +X8Y1348D01* +X2595Y1348D02* +X2602Y1348D01* +X1Y1347D02* +X8Y1347D01* +X2595Y1347D02* +X2602Y1347D01* +X1Y1346D02* +X8Y1346D01* +X2595Y1346D02* +X2602Y1346D01* +X1Y1345D02* +X8Y1345D01* +X2595Y1345D02* +X2602Y1345D01* +X1Y1344D02* +X8Y1344D01* +X2595Y1344D02* +X2602Y1344D01* +X1Y1343D02* +X8Y1343D01* +X2595Y1343D02* +X2602Y1343D01* +X1Y1342D02* +X8Y1342D01* +X2595Y1342D02* +X2602Y1342D01* +X1Y1341D02* +X8Y1341D01* +X2595Y1341D02* +X2602Y1341D01* +X1Y1340D02* +X8Y1340D01* +X2595Y1340D02* +X2602Y1340D01* +X1Y1339D02* +X8Y1339D01* +X2595Y1339D02* +X2602Y1339D01* +X1Y1338D02* +X8Y1338D01* +X2595Y1338D02* +X2602Y1338D01* +X1Y1337D02* +X8Y1337D01* +X2595Y1337D02* +X2602Y1337D01* +X1Y1336D02* +X8Y1336D01* +X2595Y1336D02* +X2602Y1336D01* +X1Y1335D02* +X8Y1335D01* +X2595Y1335D02* +X2602Y1335D01* +X1Y1334D02* +X8Y1334D01* +X2595Y1334D02* +X2602Y1334D01* +X1Y1333D02* +X8Y1333D01* +X2595Y1333D02* +X2602Y1333D01* +X1Y1332D02* +X8Y1332D01* +X2595Y1332D02* +X2602Y1332D01* +X1Y1331D02* +X8Y1331D01* +X2595Y1331D02* +X2602Y1331D01* +X1Y1330D02* +X8Y1330D01* +X2595Y1330D02* +X2602Y1330D01* +X1Y1329D02* +X8Y1329D01* +X2595Y1329D02* +X2602Y1329D01* +X1Y1328D02* +X8Y1328D01* +X2595Y1328D02* +X2602Y1328D01* +X1Y1327D02* +X8Y1327D01* +X2595Y1327D02* +X2602Y1327D01* +X1Y1326D02* +X8Y1326D01* +X2595Y1326D02* +X2602Y1326D01* +X1Y1325D02* +X8Y1325D01* +X2595Y1325D02* +X2602Y1325D01* +X1Y1324D02* +X8Y1324D01* +X2595Y1324D02* +X2602Y1324D01* +X1Y1323D02* +X8Y1323D01* +X2595Y1323D02* +X2602Y1323D01* +X1Y1322D02* +X8Y1322D01* +X2595Y1322D02* +X2602Y1322D01* +X1Y1321D02* +X8Y1321D01* +X2595Y1321D02* +X2602Y1321D01* +X1Y1320D02* +X8Y1320D01* +X2595Y1320D02* +X2602Y1320D01* +X1Y1319D02* +X8Y1319D01* +X2595Y1319D02* +X2602Y1319D01* +X1Y1318D02* +X8Y1318D01* +X2595Y1318D02* +X2602Y1318D01* +X1Y1317D02* +X8Y1317D01* +X2595Y1317D02* +X2602Y1317D01* +X1Y1316D02* +X8Y1316D01* +X2595Y1316D02* +X2602Y1316D01* +X1Y1315D02* +X8Y1315D01* +X2595Y1315D02* +X2602Y1315D01* +X1Y1314D02* +X8Y1314D01* +X2595Y1314D02* +X2602Y1314D01* +X1Y1313D02* +X8Y1313D01* +X2595Y1313D02* +X2602Y1313D01* +X1Y1312D02* +X8Y1312D01* +X2595Y1312D02* +X2602Y1312D01* +X1Y1311D02* +X8Y1311D01* +X2595Y1311D02* +X2602Y1311D01* +X1Y1310D02* +X8Y1310D01* +X2595Y1310D02* +X2602Y1310D01* +X1Y1309D02* +X8Y1309D01* +X2595Y1309D02* +X2602Y1309D01* +X1Y1308D02* +X8Y1308D01* +X2595Y1308D02* +X2602Y1308D01* +X1Y1307D02* +X8Y1307D01* +X2595Y1307D02* +X2602Y1307D01* +X1Y1306D02* +X8Y1306D01* +X2595Y1306D02* +X2602Y1306D01* +X1Y1305D02* +X8Y1305D01* +X2595Y1305D02* +X2602Y1305D01* +X1Y1304D02* +X8Y1304D01* +X2595Y1304D02* +X2602Y1304D01* +X1Y1303D02* +X8Y1303D01* +X2595Y1303D02* +X2602Y1303D01* +X1Y1302D02* +X8Y1302D01* +X2595Y1302D02* +X2602Y1302D01* +X1Y1301D02* +X8Y1301D01* +X2595Y1301D02* +X2602Y1301D01* +X1Y1300D02* +X8Y1300D01* +X2595Y1300D02* +X2602Y1300D01* +X1Y1299D02* +X8Y1299D01* +X2595Y1299D02* +X2602Y1299D01* +X1Y1298D02* +X8Y1298D01* +X2595Y1298D02* +X2602Y1298D01* +X1Y1297D02* +X8Y1297D01* +X2595Y1297D02* +X2602Y1297D01* +X1Y1296D02* +X8Y1296D01* +X2595Y1296D02* +X2602Y1296D01* +X1Y1295D02* +X8Y1295D01* +X2595Y1295D02* +X2602Y1295D01* +X1Y1294D02* +X8Y1294D01* +X2595Y1294D02* +X2602Y1294D01* +X1Y1293D02* +X8Y1293D01* +X2595Y1293D02* +X2602Y1293D01* +X1Y1292D02* +X8Y1292D01* +X2595Y1292D02* +X2602Y1292D01* +X1Y1291D02* +X8Y1291D01* +X2595Y1291D02* +X2602Y1291D01* +X1Y1290D02* +X8Y1290D01* +X2595Y1290D02* +X2602Y1290D01* +X1Y1289D02* +X8Y1289D01* +X2595Y1289D02* +X2602Y1289D01* +X1Y1288D02* +X8Y1288D01* +X2595Y1288D02* +X2602Y1288D01* +X1Y1287D02* +X8Y1287D01* +X2595Y1287D02* +X2602Y1287D01* +X1Y1286D02* +X8Y1286D01* +X2595Y1286D02* +X2602Y1286D01* +X1Y1285D02* +X8Y1285D01* +X2595Y1285D02* +X2602Y1285D01* +X1Y1284D02* +X8Y1284D01* +X2595Y1284D02* +X2602Y1284D01* +X1Y1283D02* +X8Y1283D01* +X2595Y1283D02* +X2602Y1283D01* +X1Y1282D02* +X8Y1282D01* +X2595Y1282D02* +X2602Y1282D01* +X1Y1281D02* +X8Y1281D01* +X2595Y1281D02* +X2602Y1281D01* +X1Y1280D02* +X8Y1280D01* +X2595Y1280D02* +X2602Y1280D01* +X1Y1279D02* +X8Y1279D01* +X2595Y1279D02* +X2602Y1279D01* +X1Y1278D02* +X8Y1278D01* +X2595Y1278D02* +X2602Y1278D01* +X1Y1277D02* +X8Y1277D01* +X2595Y1277D02* +X2602Y1277D01* +X1Y1276D02* +X8Y1276D01* +X2595Y1276D02* +X2602Y1276D01* +X1Y1275D02* +X8Y1275D01* +X2595Y1275D02* +X2602Y1275D01* +X1Y1274D02* +X8Y1274D01* +X2595Y1274D02* +X2602Y1274D01* +X1Y1273D02* +X8Y1273D01* +X2595Y1273D02* +X2602Y1273D01* +X1Y1272D02* +X8Y1272D01* +X2595Y1272D02* +X2602Y1272D01* +X1Y1271D02* +X8Y1271D01* +X2595Y1271D02* +X2602Y1271D01* +X1Y1270D02* +X8Y1270D01* +X2595Y1270D02* +X2602Y1270D01* +X1Y1269D02* +X8Y1269D01* +X2595Y1269D02* +X2602Y1269D01* +X1Y1268D02* +X8Y1268D01* +X2595Y1268D02* +X2602Y1268D01* +X1Y1267D02* +X8Y1267D01* +X2595Y1267D02* +X2602Y1267D01* +X1Y1266D02* +X8Y1266D01* +X2595Y1266D02* +X2602Y1266D01* +X1Y1265D02* +X8Y1265D01* +X2595Y1265D02* +X2602Y1265D01* +X1Y1264D02* +X8Y1264D01* +X2595Y1264D02* +X2602Y1264D01* +X1Y1263D02* +X8Y1263D01* +X2595Y1263D02* +X2602Y1263D01* +X1Y1262D02* +X8Y1262D01* +X2595Y1262D02* +X2602Y1262D01* +X1Y1261D02* +X8Y1261D01* +X2595Y1261D02* +X2602Y1261D01* +X1Y1260D02* +X8Y1260D01* +X2595Y1260D02* +X2602Y1260D01* +X1Y1259D02* +X8Y1259D01* +X2595Y1259D02* +X2602Y1259D01* +X1Y1258D02* +X8Y1258D01* +X2595Y1258D02* +X2602Y1258D01* +X1Y1257D02* +X8Y1257D01* +X2595Y1257D02* +X2602Y1257D01* +X1Y1256D02* +X8Y1256D01* +X2595Y1256D02* +X2602Y1256D01* +X1Y1255D02* +X8Y1255D01* +X2595Y1255D02* +X2602Y1255D01* +X1Y1254D02* +X8Y1254D01* +X2595Y1254D02* +X2602Y1254D01* +X1Y1253D02* +X8Y1253D01* +X2595Y1253D02* +X2602Y1253D01* +X1Y1252D02* +X8Y1252D01* +X2595Y1252D02* +X2602Y1252D01* +X1Y1251D02* +X8Y1251D01* +X2595Y1251D02* +X2602Y1251D01* +X1Y1250D02* +X8Y1250D01* +X2595Y1250D02* +X2602Y1250D01* +X1Y1249D02* +X8Y1249D01* +X2595Y1249D02* +X2602Y1249D01* +X1Y1248D02* +X8Y1248D01* +X2595Y1248D02* +X2602Y1248D01* +X1Y1247D02* +X8Y1247D01* +X2595Y1247D02* +X2602Y1247D01* +X1Y1246D02* +X8Y1246D01* +X2595Y1246D02* +X2602Y1246D01* +X1Y1245D02* +X8Y1245D01* +X2595Y1245D02* +X2602Y1245D01* +X1Y1244D02* +X8Y1244D01* +X2595Y1244D02* +X2602Y1244D01* +X1Y1243D02* +X8Y1243D01* +X2595Y1243D02* +X2602Y1243D01* +X1Y1242D02* +X8Y1242D01* +X2595Y1242D02* +X2602Y1242D01* +X1Y1241D02* +X8Y1241D01* +X2595Y1241D02* +X2602Y1241D01* +X1Y1240D02* +X8Y1240D01* +X2595Y1240D02* +X2602Y1240D01* +X1Y1239D02* +X8Y1239D01* +X2595Y1239D02* +X2602Y1239D01* +X1Y1238D02* +X8Y1238D01* +X2595Y1238D02* +X2602Y1238D01* +X1Y1237D02* +X8Y1237D01* +X2595Y1237D02* +X2602Y1237D01* +X1Y1236D02* +X8Y1236D01* +X2595Y1236D02* +X2602Y1236D01* +X1Y1235D02* +X8Y1235D01* +X2595Y1235D02* +X2602Y1235D01* +X1Y1234D02* +X8Y1234D01* +X2595Y1234D02* +X2602Y1234D01* +X1Y1233D02* +X8Y1233D01* +X2595Y1233D02* +X2602Y1233D01* +X1Y1232D02* +X8Y1232D01* +X2595Y1232D02* +X2602Y1232D01* +X1Y1231D02* +X8Y1231D01* +X2595Y1231D02* +X2602Y1231D01* +X1Y1230D02* +X8Y1230D01* +X2595Y1230D02* +X2602Y1230D01* +X1Y1229D02* +X8Y1229D01* +X2595Y1229D02* +X2602Y1229D01* +X1Y1228D02* +X8Y1228D01* +X2595Y1228D02* +X2602Y1228D01* +X1Y1227D02* +X8Y1227D01* +X2595Y1227D02* +X2602Y1227D01* +X1Y1226D02* +X8Y1226D01* +X2595Y1226D02* +X2602Y1226D01* +X1Y1225D02* +X8Y1225D01* +X2595Y1225D02* +X2602Y1225D01* +X1Y1224D02* +X8Y1224D01* +X2595Y1224D02* +X2602Y1224D01* +X1Y1223D02* +X8Y1223D01* +X2595Y1223D02* +X2602Y1223D01* +X1Y1222D02* +X8Y1222D01* +X2595Y1222D02* +X2602Y1222D01* +X1Y1221D02* +X8Y1221D01* +X2595Y1221D02* +X2602Y1221D01* +X1Y1220D02* +X8Y1220D01* +X2595Y1220D02* +X2602Y1220D01* +X1Y1219D02* +X8Y1219D01* +X2595Y1219D02* +X2602Y1219D01* +X1Y1218D02* +X8Y1218D01* +X2595Y1218D02* +X2602Y1218D01* +X1Y1217D02* +X8Y1217D01* +X2595Y1217D02* +X2602Y1217D01* +X1Y1216D02* +X8Y1216D01* +X2595Y1216D02* +X2602Y1216D01* +X1Y1215D02* +X8Y1215D01* +X2595Y1215D02* +X2602Y1215D01* +X1Y1214D02* +X8Y1214D01* +X2595Y1214D02* +X2602Y1214D01* +X1Y1213D02* +X8Y1213D01* +X2595Y1213D02* +X2602Y1213D01* +X1Y1212D02* +X8Y1212D01* +X2595Y1212D02* +X2602Y1212D01* +X1Y1211D02* +X8Y1211D01* +X2595Y1211D02* +X2602Y1211D01* +X1Y1210D02* +X8Y1210D01* +X2595Y1210D02* +X2602Y1210D01* +X1Y1209D02* +X8Y1209D01* +X2595Y1209D02* +X2602Y1209D01* +X1Y1208D02* +X8Y1208D01* +X2595Y1208D02* +X2602Y1208D01* +X1Y1207D02* +X8Y1207D01* +X2595Y1207D02* +X2602Y1207D01* +X1Y1206D02* +X8Y1206D01* +X2595Y1206D02* +X2602Y1206D01* +X1Y1205D02* +X8Y1205D01* +X2595Y1205D02* +X2602Y1205D01* +X1Y1204D02* +X8Y1204D01* +X2595Y1204D02* +X2602Y1204D01* +X1Y1203D02* +X8Y1203D01* +X2595Y1203D02* +X2602Y1203D01* +X1Y1202D02* +X8Y1202D01* +X2595Y1202D02* +X2602Y1202D01* +X1Y1201D02* +X8Y1201D01* +X2595Y1201D02* +X2602Y1201D01* +X1Y1200D02* +X8Y1200D01* +X2595Y1200D02* +X2602Y1200D01* +X1Y1199D02* +X8Y1199D01* +X2595Y1199D02* +X2602Y1199D01* +X1Y1198D02* +X8Y1198D01* +X2595Y1198D02* +X2602Y1198D01* +X1Y1197D02* +X8Y1197D01* +X2595Y1197D02* +X2602Y1197D01* +X1Y1196D02* +X8Y1196D01* +X2595Y1196D02* +X2602Y1196D01* +X1Y1195D02* +X8Y1195D01* +X2595Y1195D02* +X2602Y1195D01* +X1Y1194D02* +X8Y1194D01* +X2595Y1194D02* +X2602Y1194D01* +X1Y1193D02* +X8Y1193D01* +X2595Y1193D02* +X2602Y1193D01* +X1Y1192D02* +X8Y1192D01* +X2595Y1192D02* +X2602Y1192D01* +X1Y1191D02* +X8Y1191D01* +X2595Y1191D02* +X2602Y1191D01* +X1Y1190D02* +X8Y1190D01* +X2595Y1190D02* +X2602Y1190D01* +X1Y1189D02* +X8Y1189D01* +X2595Y1189D02* +X2602Y1189D01* +X1Y1188D02* +X8Y1188D01* +X2595Y1188D02* +X2602Y1188D01* +X1Y1187D02* +X8Y1187D01* +X2595Y1187D02* +X2602Y1187D01* +X1Y1186D02* +X8Y1186D01* +X2595Y1186D02* +X2602Y1186D01* +X1Y1185D02* +X8Y1185D01* +X2595Y1185D02* +X2602Y1185D01* +X1Y1184D02* +X8Y1184D01* +X2595Y1184D02* +X2602Y1184D01* +X1Y1183D02* +X8Y1183D01* +X2595Y1183D02* +X2602Y1183D01* +X1Y1182D02* +X8Y1182D01* +X2595Y1182D02* +X2602Y1182D01* +X1Y1181D02* +X8Y1181D01* +X2595Y1181D02* +X2602Y1181D01* +X1Y1180D02* +X8Y1180D01* +X2595Y1180D02* +X2602Y1180D01* +X1Y1179D02* +X8Y1179D01* +X2595Y1179D02* +X2602Y1179D01* +X1Y1178D02* +X8Y1178D01* +X2595Y1178D02* +X2602Y1178D01* +X1Y1177D02* +X8Y1177D01* +X2595Y1177D02* +X2602Y1177D01* +X1Y1176D02* +X8Y1176D01* +X2595Y1176D02* +X2602Y1176D01* +X1Y1175D02* +X8Y1175D01* +X2595Y1175D02* +X2602Y1175D01* +X1Y1174D02* +X8Y1174D01* +X2595Y1174D02* +X2602Y1174D01* +X1Y1173D02* +X8Y1173D01* +X2595Y1173D02* +X2602Y1173D01* +X1Y1172D02* +X8Y1172D01* +X2595Y1172D02* +X2602Y1172D01* +X1Y1171D02* +X8Y1171D01* +X2595Y1171D02* +X2602Y1171D01* +X1Y1170D02* +X8Y1170D01* +X2595Y1170D02* +X2602Y1170D01* +X1Y1169D02* +X8Y1169D01* +X2595Y1169D02* +X2602Y1169D01* +X1Y1168D02* +X8Y1168D01* +X2595Y1168D02* +X2602Y1168D01* +X1Y1167D02* +X8Y1167D01* +X2595Y1167D02* +X2602Y1167D01* +X1Y1166D02* +X8Y1166D01* +X2595Y1166D02* +X2602Y1166D01* +X1Y1165D02* +X8Y1165D01* +X2595Y1165D02* +X2602Y1165D01* +X1Y1164D02* +X8Y1164D01* +X2595Y1164D02* +X2602Y1164D01* +X1Y1163D02* +X8Y1163D01* +X2595Y1163D02* +X2602Y1163D01* +X1Y1162D02* +X8Y1162D01* +X2595Y1162D02* +X2602Y1162D01* +X1Y1161D02* +X8Y1161D01* +X2595Y1161D02* +X2602Y1161D01* +X1Y1160D02* +X8Y1160D01* +X2595Y1160D02* +X2602Y1160D01* +X1Y1159D02* +X8Y1159D01* +X2595Y1159D02* +X2602Y1159D01* +X1Y1158D02* +X8Y1158D01* +X2595Y1158D02* +X2602Y1158D01* +X1Y1157D02* +X8Y1157D01* +X2595Y1157D02* +X2602Y1157D01* +X1Y1156D02* +X8Y1156D01* +X2595Y1156D02* +X2602Y1156D01* +X1Y1155D02* +X8Y1155D01* +X2595Y1155D02* +X2602Y1155D01* +X1Y1154D02* +X8Y1154D01* +X2595Y1154D02* +X2602Y1154D01* +X1Y1153D02* +X8Y1153D01* +X2595Y1153D02* +X2602Y1153D01* +X1Y1152D02* +X8Y1152D01* +X2595Y1152D02* +X2602Y1152D01* +X1Y1151D02* +X8Y1151D01* +X2595Y1151D02* +X2602Y1151D01* +X1Y1150D02* +X8Y1150D01* +X2595Y1150D02* +X2602Y1150D01* +X1Y1149D02* +X8Y1149D01* +X2595Y1149D02* +X2602Y1149D01* +X1Y1148D02* +X8Y1148D01* +X2595Y1148D02* +X2602Y1148D01* +X1Y1147D02* +X8Y1147D01* +X2595Y1147D02* +X2602Y1147D01* +X1Y1146D02* +X8Y1146D01* +X2595Y1146D02* +X2602Y1146D01* +X1Y1145D02* +X8Y1145D01* +X2595Y1145D02* +X2602Y1145D01* +X1Y1144D02* +X8Y1144D01* +X2595Y1144D02* +X2602Y1144D01* +X1Y1143D02* +X8Y1143D01* +X2595Y1143D02* +X2602Y1143D01* +X1Y1142D02* +X8Y1142D01* +X2595Y1142D02* +X2602Y1142D01* +X1Y1141D02* +X8Y1141D01* +X2595Y1141D02* +X2602Y1141D01* +X1Y1140D02* +X8Y1140D01* +X2595Y1140D02* +X2602Y1140D01* +X1Y1139D02* +X8Y1139D01* +X2595Y1139D02* +X2602Y1139D01* +X1Y1138D02* +X8Y1138D01* +X2595Y1138D02* +X2602Y1138D01* +X1Y1137D02* +X8Y1137D01* +X2595Y1137D02* +X2602Y1137D01* +X1Y1136D02* +X8Y1136D01* +X2595Y1136D02* +X2602Y1136D01* +X1Y1135D02* +X8Y1135D01* +X2595Y1135D02* +X2602Y1135D01* +X1Y1134D02* +X8Y1134D01* +X2595Y1134D02* +X2602Y1134D01* +X1Y1133D02* +X8Y1133D01* +X2595Y1133D02* +X2602Y1133D01* +X1Y1132D02* +X8Y1132D01* +X2595Y1132D02* +X2602Y1132D01* +X1Y1131D02* +X8Y1131D01* +X2595Y1131D02* +X2602Y1131D01* +X1Y1130D02* +X8Y1130D01* +X2595Y1130D02* +X2602Y1130D01* +X1Y1129D02* +X8Y1129D01* +X2595Y1129D02* +X2602Y1129D01* +X1Y1128D02* +X8Y1128D01* +X2595Y1128D02* +X2602Y1128D01* +X1Y1127D02* +X8Y1127D01* +X2595Y1127D02* +X2602Y1127D01* +X1Y1126D02* +X8Y1126D01* +X2595Y1126D02* +X2602Y1126D01* +X1Y1125D02* +X8Y1125D01* +X2595Y1125D02* +X2602Y1125D01* +X1Y1124D02* +X8Y1124D01* +X2595Y1124D02* +X2602Y1124D01* +X1Y1123D02* +X8Y1123D01* +X2595Y1123D02* +X2602Y1123D01* +X1Y1122D02* +X8Y1122D01* +X2595Y1122D02* +X2602Y1122D01* +X1Y1121D02* +X8Y1121D01* +X2595Y1121D02* +X2602Y1121D01* +X1Y1120D02* +X8Y1120D01* +X2595Y1120D02* +X2602Y1120D01* +X1Y1119D02* +X8Y1119D01* +X2595Y1119D02* +X2602Y1119D01* +X1Y1118D02* +X8Y1118D01* +X2595Y1118D02* +X2602Y1118D01* +X1Y1117D02* +X8Y1117D01* +X2595Y1117D02* +X2602Y1117D01* +X1Y1116D02* +X8Y1116D01* +X2595Y1116D02* +X2602Y1116D01* +X1Y1115D02* +X8Y1115D01* +X2595Y1115D02* +X2602Y1115D01* +X1Y1114D02* +X8Y1114D01* +X2595Y1114D02* +X2602Y1114D01* +X1Y1113D02* +X8Y1113D01* +X2595Y1113D02* +X2602Y1113D01* +X1Y1112D02* +X8Y1112D01* +X2595Y1112D02* +X2602Y1112D01* +X1Y1111D02* +X8Y1111D01* +X2595Y1111D02* +X2602Y1111D01* +X1Y1110D02* +X8Y1110D01* +X2595Y1110D02* +X2602Y1110D01* +X1Y1109D02* +X8Y1109D01* +X2595Y1109D02* +X2602Y1109D01* +X1Y1108D02* +X8Y1108D01* +X2595Y1108D02* +X2602Y1108D01* +X1Y1107D02* +X8Y1107D01* +X2595Y1107D02* +X2602Y1107D01* +X1Y1106D02* +X8Y1106D01* +X2595Y1106D02* +X2602Y1106D01* +X1Y1105D02* +X8Y1105D01* +X2595Y1105D02* +X2602Y1105D01* +X1Y1104D02* +X8Y1104D01* +X2595Y1104D02* +X2602Y1104D01* +X1Y1103D02* +X8Y1103D01* +X2595Y1103D02* +X2602Y1103D01* +X1Y1102D02* +X8Y1102D01* +X2595Y1102D02* +X2602Y1102D01* +X1Y1101D02* +X8Y1101D01* +X2595Y1101D02* +X2602Y1101D01* +X1Y1100D02* +X8Y1100D01* +X2595Y1100D02* +X2602Y1100D01* +X1Y1099D02* +X8Y1099D01* +X2595Y1099D02* +X2602Y1099D01* +X1Y1098D02* +X8Y1098D01* +X2595Y1098D02* +X2602Y1098D01* +X1Y1097D02* +X8Y1097D01* +X2595Y1097D02* +X2602Y1097D01* +X1Y1096D02* +X8Y1096D01* +X2595Y1096D02* +X2602Y1096D01* +X1Y1095D02* +X8Y1095D01* +X2595Y1095D02* +X2602Y1095D01* +X1Y1094D02* +X8Y1094D01* +X2595Y1094D02* +X2602Y1094D01* +X1Y1093D02* +X8Y1093D01* +X2595Y1093D02* +X2602Y1093D01* +X1Y1092D02* +X8Y1092D01* +X2595Y1092D02* +X2602Y1092D01* +X1Y1091D02* +X8Y1091D01* +X2595Y1091D02* +X2602Y1091D01* +X1Y1090D02* +X8Y1090D01* +X2595Y1090D02* +X2602Y1090D01* +X1Y1089D02* +X8Y1089D01* +X2595Y1089D02* +X2602Y1089D01* +X1Y1088D02* +X8Y1088D01* +X2595Y1088D02* +X2602Y1088D01* +X1Y1087D02* +X8Y1087D01* +X2595Y1087D02* +X2602Y1087D01* +X1Y1086D02* +X8Y1086D01* +X2595Y1086D02* +X2602Y1086D01* +X1Y1085D02* +X8Y1085D01* +X2595Y1085D02* +X2602Y1085D01* +X1Y1084D02* +X8Y1084D01* +X2595Y1084D02* +X2602Y1084D01* +X1Y1083D02* +X8Y1083D01* +X2595Y1083D02* +X2602Y1083D01* +X1Y1082D02* +X8Y1082D01* +X2595Y1082D02* +X2602Y1082D01* +X1Y1081D02* +X8Y1081D01* +X2595Y1081D02* +X2602Y1081D01* +X1Y1080D02* +X8Y1080D01* +X2595Y1080D02* +X2602Y1080D01* +X1Y1079D02* +X8Y1079D01* +X2595Y1079D02* +X2602Y1079D01* +X1Y1078D02* +X8Y1078D01* +X2595Y1078D02* +X2602Y1078D01* +X1Y1077D02* +X8Y1077D01* +X2595Y1077D02* +X2602Y1077D01* +X1Y1076D02* +X8Y1076D01* +X2595Y1076D02* +X2602Y1076D01* +X1Y1075D02* +X8Y1075D01* +X2595Y1075D02* +X2602Y1075D01* +X1Y1074D02* +X8Y1074D01* +X2595Y1074D02* +X2602Y1074D01* +X1Y1073D02* +X8Y1073D01* +X2595Y1073D02* +X2602Y1073D01* +X1Y1072D02* +X8Y1072D01* +X2595Y1072D02* +X2602Y1072D01* +X1Y1071D02* +X8Y1071D01* +X2595Y1071D02* +X2602Y1071D01* +X1Y1070D02* +X8Y1070D01* +X2595Y1070D02* +X2602Y1070D01* +X1Y1069D02* +X8Y1069D01* +X2595Y1069D02* +X2602Y1069D01* +X1Y1068D02* +X8Y1068D01* +X2595Y1068D02* +X2602Y1068D01* +X1Y1067D02* +X8Y1067D01* +X2595Y1067D02* +X2602Y1067D01* +X1Y1066D02* +X8Y1066D01* +X2595Y1066D02* +X2602Y1066D01* +X1Y1065D02* +X8Y1065D01* +X2595Y1065D02* +X2602Y1065D01* +X1Y1064D02* +X8Y1064D01* +X2595Y1064D02* +X2602Y1064D01* +X1Y1063D02* +X8Y1063D01* +X2595Y1063D02* +X2602Y1063D01* +X1Y1062D02* +X8Y1062D01* +X2595Y1062D02* +X2602Y1062D01* +X1Y1061D02* +X8Y1061D01* +X2595Y1061D02* +X2602Y1061D01* +X1Y1060D02* +X8Y1060D01* +X2595Y1060D02* +X2602Y1060D01* +X1Y1059D02* +X8Y1059D01* +X2595Y1059D02* +X2602Y1059D01* +X1Y1058D02* +X8Y1058D01* +X2595Y1058D02* +X2602Y1058D01* +X1Y1057D02* +X8Y1057D01* +X2595Y1057D02* +X2602Y1057D01* +X1Y1056D02* +X8Y1056D01* +X2595Y1056D02* +X2602Y1056D01* +X1Y1055D02* +X8Y1055D01* +X2595Y1055D02* +X2602Y1055D01* +X1Y1054D02* +X8Y1054D01* +X2595Y1054D02* +X2602Y1054D01* +X1Y1053D02* +X8Y1053D01* +X2595Y1053D02* +X2602Y1053D01* +X1Y1052D02* +X8Y1052D01* +X2595Y1052D02* +X2602Y1052D01* +X1Y1051D02* +X8Y1051D01* +X2595Y1051D02* +X2602Y1051D01* +X1Y1050D02* +X8Y1050D01* +X2595Y1050D02* +X2602Y1050D01* +X1Y1049D02* +X8Y1049D01* +X2595Y1049D02* +X2602Y1049D01* +X1Y1048D02* +X8Y1048D01* +X2595Y1048D02* +X2602Y1048D01* +X1Y1047D02* +X8Y1047D01* +X2595Y1047D02* +X2602Y1047D01* +X1Y1046D02* +X8Y1046D01* +X2595Y1046D02* +X2602Y1046D01* +X1Y1045D02* +X8Y1045D01* +X2595Y1045D02* +X2602Y1045D01* +X1Y1044D02* +X8Y1044D01* +X2595Y1044D02* +X2602Y1044D01* +X1Y1043D02* +X8Y1043D01* +X2595Y1043D02* +X2602Y1043D01* +X1Y1042D02* +X8Y1042D01* +X2595Y1042D02* +X2602Y1042D01* +X1Y1041D02* +X8Y1041D01* +X2595Y1041D02* +X2602Y1041D01* +X1Y1040D02* +X8Y1040D01* +X2595Y1040D02* +X2602Y1040D01* +X1Y1039D02* +X8Y1039D01* +X2595Y1039D02* +X2602Y1039D01* +X1Y1038D02* +X8Y1038D01* +X2595Y1038D02* +X2602Y1038D01* +X1Y1037D02* +X8Y1037D01* +X2595Y1037D02* +X2602Y1037D01* +X1Y1036D02* +X8Y1036D01* +X2595Y1036D02* +X2602Y1036D01* +X1Y1035D02* +X8Y1035D01* +X2595Y1035D02* +X2602Y1035D01* +X1Y1034D02* +X8Y1034D01* +X2595Y1034D02* +X2602Y1034D01* +X1Y1033D02* +X8Y1033D01* +X2595Y1033D02* +X2602Y1033D01* +X1Y1032D02* +X8Y1032D01* +X2595Y1032D02* +X2602Y1032D01* +X1Y1031D02* +X8Y1031D01* +X2595Y1031D02* +X2602Y1031D01* +X1Y1030D02* +X8Y1030D01* +X2595Y1030D02* +X2602Y1030D01* +X1Y1029D02* +X8Y1029D01* +X2595Y1029D02* +X2602Y1029D01* +X1Y1028D02* +X8Y1028D01* +X2595Y1028D02* +X2602Y1028D01* +X1Y1027D02* +X8Y1027D01* +X2595Y1027D02* +X2602Y1027D01* +X1Y1026D02* +X8Y1026D01* +X2595Y1026D02* +X2602Y1026D01* +X1Y1025D02* +X8Y1025D01* +X2595Y1025D02* +X2602Y1025D01* +X1Y1024D02* +X8Y1024D01* +X2595Y1024D02* +X2602Y1024D01* +X1Y1023D02* +X8Y1023D01* +X2595Y1023D02* +X2602Y1023D01* +X1Y1022D02* +X8Y1022D01* +X2595Y1022D02* +X2602Y1022D01* +X1Y1021D02* +X8Y1021D01* +X2595Y1021D02* +X2602Y1021D01* +X1Y1020D02* +X8Y1020D01* +X2595Y1020D02* +X2602Y1020D01* +X1Y1019D02* +X8Y1019D01* +X2595Y1019D02* +X2602Y1019D01* +X1Y1018D02* +X8Y1018D01* +X2595Y1018D02* +X2602Y1018D01* +X1Y1017D02* +X8Y1017D01* +X2595Y1017D02* +X2602Y1017D01* +X1Y1016D02* +X8Y1016D01* +X2595Y1016D02* +X2602Y1016D01* +X1Y1015D02* +X8Y1015D01* +X2595Y1015D02* +X2602Y1015D01* +X1Y1014D02* +X8Y1014D01* +X2595Y1014D02* +X2602Y1014D01* +X1Y1013D02* +X8Y1013D01* +X2595Y1013D02* +X2602Y1013D01* +X1Y1012D02* +X8Y1012D01* +X2595Y1012D02* +X2602Y1012D01* +X1Y1011D02* +X8Y1011D01* +X2595Y1011D02* +X2602Y1011D01* +X1Y1010D02* +X8Y1010D01* +X2595Y1010D02* +X2602Y1010D01* +X1Y1009D02* +X8Y1009D01* +X2595Y1009D02* +X2602Y1009D01* +X1Y1008D02* +X8Y1008D01* +X2595Y1008D02* +X2602Y1008D01* +X1Y1007D02* +X8Y1007D01* +X2595Y1007D02* +X2602Y1007D01* +X1Y1006D02* +X8Y1006D01* +X2595Y1006D02* +X2602Y1006D01* +X1Y1005D02* +X8Y1005D01* +X2595Y1005D02* +X2602Y1005D01* +X1Y1004D02* +X8Y1004D01* +X2595Y1004D02* +X2602Y1004D01* +X1Y1003D02* +X8Y1003D01* +X2595Y1003D02* +X2602Y1003D01* +X1Y1002D02* +X8Y1002D01* +X2595Y1002D02* +X2602Y1002D01* +X1Y1001D02* +X8Y1001D01* +X2595Y1001D02* +X2602Y1001D01* +X1Y1000D02* +X8Y1000D01* +X2595Y1000D02* +X2602Y1000D01* +X1Y999D02* +X8Y999D01* +X2595Y999D02* +X2602Y999D01* +X1Y998D02* +X8Y998D01* +X2595Y998D02* +X2602Y998D01* +X1Y997D02* +X8Y997D01* +X2595Y997D02* +X2602Y997D01* +X1Y996D02* +X8Y996D01* +X2595Y996D02* +X2602Y996D01* +X1Y995D02* +X8Y995D01* +X2595Y995D02* +X2602Y995D01* +X1Y994D02* +X8Y994D01* +X2595Y994D02* +X2602Y994D01* +X1Y993D02* +X8Y993D01* +X2595Y993D02* +X2602Y993D01* +X1Y992D02* +X8Y992D01* +X2595Y992D02* +X2602Y992D01* +X1Y991D02* +X8Y991D01* +X2595Y991D02* +X2602Y991D01* +X1Y990D02* +X8Y990D01* +X2595Y990D02* +X2602Y990D01* +X1Y989D02* +X8Y989D01* +X2595Y989D02* +X2602Y989D01* +X1Y988D02* +X8Y988D01* +X2595Y988D02* +X2602Y988D01* +X1Y987D02* +X8Y987D01* +X2595Y987D02* +X2602Y987D01* +X1Y986D02* +X8Y986D01* +X2595Y986D02* +X2602Y986D01* +X1Y985D02* +X8Y985D01* +X2595Y985D02* +X2602Y985D01* +X1Y984D02* +X8Y984D01* +X2595Y984D02* +X2602Y984D01* +X1Y983D02* +X8Y983D01* +X2595Y983D02* +X2602Y983D01* +X1Y982D02* +X8Y982D01* +X2595Y982D02* +X2602Y982D01* +X1Y981D02* +X8Y981D01* +X2595Y981D02* +X2602Y981D01* +X1Y980D02* +X8Y980D01* +X2595Y980D02* +X2602Y980D01* +X1Y979D02* +X8Y979D01* +X2595Y979D02* +X2602Y979D01* +X1Y978D02* +X8Y978D01* +X2595Y978D02* +X2602Y978D01* +X1Y977D02* +X8Y977D01* +X2595Y977D02* +X2602Y977D01* +X1Y976D02* +X8Y976D01* +X2595Y976D02* +X2602Y976D01* +X1Y975D02* +X8Y975D01* +X2595Y975D02* +X2602Y975D01* +X1Y974D02* +X8Y974D01* +X2595Y974D02* +X2602Y974D01* +X1Y973D02* +X8Y973D01* +X2595Y973D02* +X2602Y973D01* +X1Y972D02* +X8Y972D01* +X2595Y972D02* +X2602Y972D01* +X1Y971D02* +X8Y971D01* +X2595Y971D02* +X2602Y971D01* +X1Y970D02* +X8Y970D01* +X2595Y970D02* +X2602Y970D01* +X1Y969D02* +X8Y969D01* +X2595Y969D02* +X2602Y969D01* +X1Y968D02* +X8Y968D01* +X2595Y968D02* +X2602Y968D01* +X1Y967D02* +X8Y967D01* +X2595Y967D02* +X2602Y967D01* +X1Y966D02* +X8Y966D01* +X2595Y966D02* +X2602Y966D01* +X1Y965D02* +X8Y965D01* +X2595Y965D02* +X2602Y965D01* +X1Y964D02* +X8Y964D01* +X2595Y964D02* +X2602Y964D01* +X1Y963D02* +X8Y963D01* +X2595Y963D02* +X2602Y963D01* +X1Y962D02* +X8Y962D01* +X2595Y962D02* +X2602Y962D01* +X1Y961D02* +X8Y961D01* +X2595Y961D02* +X2602Y961D01* +X1Y960D02* +X8Y960D01* +X2595Y960D02* +X2602Y960D01* +X1Y959D02* +X8Y959D01* +X2595Y959D02* +X2602Y959D01* +X1Y958D02* +X8Y958D01* +X2595Y958D02* +X2602Y958D01* +X1Y957D02* +X8Y957D01* +X2595Y957D02* +X2602Y957D01* +X1Y956D02* +X8Y956D01* +X2595Y956D02* +X2602Y956D01* +X1Y955D02* +X8Y955D01* +X2595Y955D02* +X2602Y955D01* +X1Y954D02* +X8Y954D01* +X2595Y954D02* +X2602Y954D01* +X1Y953D02* +X8Y953D01* +X2595Y953D02* +X2602Y953D01* +X1Y952D02* +X8Y952D01* +X2595Y952D02* +X2602Y952D01* +X1Y951D02* +X8Y951D01* +X2595Y951D02* +X2602Y951D01* +X1Y950D02* +X8Y950D01* +X2595Y950D02* +X2602Y950D01* +X1Y949D02* +X8Y949D01* +X2595Y949D02* +X2602Y949D01* +X1Y948D02* +X8Y948D01* +X2595Y948D02* +X2602Y948D01* +X1Y947D02* +X8Y947D01* +X2595Y947D02* +X2602Y947D01* +X1Y946D02* +X8Y946D01* +X2595Y946D02* +X2602Y946D01* +X1Y945D02* +X8Y945D01* +X2595Y945D02* +X2602Y945D01* +X1Y944D02* +X8Y944D01* +X2595Y944D02* +X2602Y944D01* +X1Y943D02* +X8Y943D01* +X2595Y943D02* +X2602Y943D01* +X1Y942D02* +X8Y942D01* +X2595Y942D02* +X2602Y942D01* +X1Y941D02* +X8Y941D01* +X2595Y941D02* +X2602Y941D01* +X1Y940D02* +X8Y940D01* +X2595Y940D02* +X2602Y940D01* +X1Y939D02* +X8Y939D01* +X2595Y939D02* +X2602Y939D01* +X1Y938D02* +X8Y938D01* +X2595Y938D02* +X2602Y938D01* +X1Y937D02* +X8Y937D01* +X2595Y937D02* +X2602Y937D01* +X1Y936D02* +X8Y936D01* +X2595Y936D02* +X2602Y936D01* +X1Y935D02* +X8Y935D01* +X2595Y935D02* +X2602Y935D01* +X1Y934D02* +X8Y934D01* +X2595Y934D02* +X2602Y934D01* +X1Y933D02* +X8Y933D01* +X2595Y933D02* +X2602Y933D01* +X1Y932D02* +X8Y932D01* +X2595Y932D02* +X2602Y932D01* +X1Y931D02* +X8Y931D01* +X2595Y931D02* +X2602Y931D01* +X1Y930D02* +X8Y930D01* +X2595Y930D02* +X2602Y930D01* +X1Y929D02* +X8Y929D01* +X2595Y929D02* +X2602Y929D01* +X1Y928D02* +X8Y928D01* +X2595Y928D02* +X2602Y928D01* +X1Y927D02* +X8Y927D01* +X2595Y927D02* +X2602Y927D01* +X1Y926D02* +X8Y926D01* +X2595Y926D02* +X2602Y926D01* +X1Y925D02* +X8Y925D01* +X2595Y925D02* +X2602Y925D01* +X1Y924D02* +X8Y924D01* +X2595Y924D02* +X2602Y924D01* +X1Y923D02* +X8Y923D01* +X2595Y923D02* +X2602Y923D01* +X1Y922D02* +X8Y922D01* +X2595Y922D02* +X2602Y922D01* +X1Y921D02* +X8Y921D01* +X2595Y921D02* +X2602Y921D01* +X1Y920D02* +X8Y920D01* +X2595Y920D02* +X2602Y920D01* +X1Y919D02* +X8Y919D01* +X2595Y919D02* +X2602Y919D01* +X1Y918D02* +X8Y918D01* +X2595Y918D02* +X2602Y918D01* +X1Y917D02* +X8Y917D01* +X2595Y917D02* +X2602Y917D01* +X1Y916D02* +X8Y916D01* +X2595Y916D02* +X2602Y916D01* +X1Y915D02* +X8Y915D01* +X2595Y915D02* +X2602Y915D01* +X1Y914D02* +X8Y914D01* +X2595Y914D02* +X2602Y914D01* +X1Y913D02* +X8Y913D01* +X2595Y913D02* +X2602Y913D01* +X1Y912D02* +X8Y912D01* +X2595Y912D02* +X2602Y912D01* +X1Y911D02* +X8Y911D01* +X2595Y911D02* +X2602Y911D01* +X1Y910D02* +X8Y910D01* +X2595Y910D02* +X2602Y910D01* +X1Y909D02* +X8Y909D01* +X2595Y909D02* +X2602Y909D01* +X1Y908D02* +X8Y908D01* +X2595Y908D02* +X2602Y908D01* +X1Y907D02* +X8Y907D01* +X2595Y907D02* +X2602Y907D01* +X1Y906D02* +X8Y906D01* +X2595Y906D02* +X2602Y906D01* +X1Y905D02* +X8Y905D01* +X2595Y905D02* +X2602Y905D01* +X1Y904D02* +X8Y904D01* +X2595Y904D02* +X2602Y904D01* +X1Y903D02* +X8Y903D01* +X2595Y903D02* +X2602Y903D01* +X1Y902D02* +X8Y902D01* +X2595Y902D02* +X2602Y902D01* +X1Y901D02* +X8Y901D01* +X2595Y901D02* +X2602Y901D01* +X1Y900D02* +X8Y900D01* +X2595Y900D02* +X2602Y900D01* +X1Y899D02* +X8Y899D01* +X2595Y899D02* +X2602Y899D01* +X1Y898D02* +X8Y898D01* +X2595Y898D02* +X2602Y898D01* +X1Y897D02* +X8Y897D01* +X2595Y897D02* +X2602Y897D01* +X1Y896D02* +X8Y896D01* +X2595Y896D02* +X2602Y896D01* +X1Y895D02* +X8Y895D01* +X2595Y895D02* +X2602Y895D01* +X1Y894D02* +X8Y894D01* +X2595Y894D02* +X2602Y894D01* +X1Y893D02* +X8Y893D01* +X2595Y893D02* +X2602Y893D01* +X1Y892D02* +X8Y892D01* +X2595Y892D02* +X2602Y892D01* +X1Y891D02* +X8Y891D01* +X2595Y891D02* +X2602Y891D01* +X1Y890D02* +X8Y890D01* +X2595Y890D02* +X2602Y890D01* +X1Y889D02* +X8Y889D01* +X2595Y889D02* +X2602Y889D01* +X1Y888D02* +X8Y888D01* +X2595Y888D02* +X2602Y888D01* +X1Y887D02* +X8Y887D01* +X2595Y887D02* +X2602Y887D01* +X1Y886D02* +X8Y886D01* +X2595Y886D02* +X2602Y886D01* +X1Y885D02* +X8Y885D01* +X2595Y885D02* +X2602Y885D01* +X1Y884D02* +X8Y884D01* +X2595Y884D02* +X2602Y884D01* +X1Y883D02* +X8Y883D01* +X2595Y883D02* +X2602Y883D01* +X1Y882D02* +X8Y882D01* +X2595Y882D02* +X2602Y882D01* +X1Y881D02* +X8Y881D01* +X2595Y881D02* +X2602Y881D01* +X1Y880D02* +X8Y880D01* +X2595Y880D02* +X2602Y880D01* +X1Y879D02* +X8Y879D01* +X2595Y879D02* +X2602Y879D01* +X1Y878D02* +X8Y878D01* +X2595Y878D02* +X2602Y878D01* +X1Y877D02* +X8Y877D01* +X2595Y877D02* +X2602Y877D01* +X1Y876D02* +X8Y876D01* +X2595Y876D02* +X2602Y876D01* +X1Y875D02* +X8Y875D01* +X2595Y875D02* +X2602Y875D01* +X1Y874D02* +X8Y874D01* +X2595Y874D02* +X2602Y874D01* +X1Y873D02* +X8Y873D01* +X2595Y873D02* +X2602Y873D01* +X1Y872D02* +X8Y872D01* +X2595Y872D02* +X2602Y872D01* +X1Y871D02* +X8Y871D01* +X2595Y871D02* +X2602Y871D01* +X1Y870D02* +X8Y870D01* +X2595Y870D02* +X2602Y870D01* +X1Y869D02* +X8Y869D01* +X2595Y869D02* +X2602Y869D01* +X1Y868D02* +X8Y868D01* +X2595Y868D02* +X2602Y868D01* +X1Y867D02* +X8Y867D01* +X2595Y867D02* +X2602Y867D01* +X1Y866D02* +X8Y866D01* +X2595Y866D02* +X2602Y866D01* +X1Y865D02* +X8Y865D01* +X2595Y865D02* +X2602Y865D01* +X1Y864D02* +X8Y864D01* +X2595Y864D02* +X2602Y864D01* +X1Y863D02* +X8Y863D01* +X2595Y863D02* +X2602Y863D01* +X1Y862D02* +X8Y862D01* +X2595Y862D02* +X2602Y862D01* +X1Y861D02* +X8Y861D01* +X2595Y861D02* +X2602Y861D01* +X1Y860D02* +X8Y860D01* +X2595Y860D02* +X2602Y860D01* +X1Y859D02* +X8Y859D01* +X2595Y859D02* +X2602Y859D01* +X1Y858D02* +X8Y858D01* +X2595Y858D02* +X2602Y858D01* +X1Y857D02* +X8Y857D01* +X2595Y857D02* +X2602Y857D01* +X1Y856D02* +X8Y856D01* +X2595Y856D02* +X2602Y856D01* +X1Y855D02* +X8Y855D01* +X2595Y855D02* +X2602Y855D01* +X1Y854D02* +X8Y854D01* +X2595Y854D02* +X2602Y854D01* +X1Y853D02* +X8Y853D01* +X2595Y853D02* +X2602Y853D01* +X1Y852D02* +X8Y852D01* +X2595Y852D02* +X2602Y852D01* +X1Y851D02* +X8Y851D01* +X2595Y851D02* +X2602Y851D01* +X1Y850D02* +X8Y850D01* +X2595Y850D02* +X2602Y850D01* +X1Y849D02* +X8Y849D01* +X2595Y849D02* +X2602Y849D01* +X1Y848D02* +X8Y848D01* +X2595Y848D02* +X2602Y848D01* +X1Y847D02* +X8Y847D01* +X2595Y847D02* +X2602Y847D01* +X1Y846D02* +X8Y846D01* +X2595Y846D02* +X2602Y846D01* +X1Y845D02* +X8Y845D01* +X2595Y845D02* +X2602Y845D01* +X1Y844D02* +X8Y844D01* +X2595Y844D02* +X2602Y844D01* +X1Y843D02* +X8Y843D01* +X2595Y843D02* +X2602Y843D01* +X1Y842D02* +X8Y842D01* +X2595Y842D02* +X2602Y842D01* +X1Y841D02* +X8Y841D01* +X2595Y841D02* +X2602Y841D01* +X1Y840D02* +X8Y840D01* +X2595Y840D02* +X2602Y840D01* +X1Y839D02* +X8Y839D01* +X2595Y839D02* +X2602Y839D01* +X1Y838D02* +X8Y838D01* +X2595Y838D02* +X2602Y838D01* +X1Y837D02* +X8Y837D01* +X2595Y837D02* +X2602Y837D01* +X1Y836D02* +X8Y836D01* +X2595Y836D02* +X2602Y836D01* +X1Y835D02* +X8Y835D01* +X2595Y835D02* +X2602Y835D01* +X1Y834D02* +X8Y834D01* +X2595Y834D02* +X2602Y834D01* +X1Y833D02* +X8Y833D01* +X2595Y833D02* +X2602Y833D01* +X1Y832D02* +X8Y832D01* +X2595Y832D02* +X2602Y832D01* +X1Y831D02* +X8Y831D01* +X2595Y831D02* +X2602Y831D01* +X1Y830D02* +X8Y830D01* +X2595Y830D02* +X2602Y830D01* +X1Y829D02* +X8Y829D01* +X2595Y829D02* +X2602Y829D01* +X1Y828D02* +X8Y828D01* +X2595Y828D02* +X2602Y828D01* +X1Y827D02* +X8Y827D01* +X2595Y827D02* +X2602Y827D01* +X1Y826D02* +X8Y826D01* +X2595Y826D02* +X2602Y826D01* +X1Y825D02* +X8Y825D01* +X2595Y825D02* +X2602Y825D01* +X1Y824D02* +X8Y824D01* +X2595Y824D02* +X2602Y824D01* +X1Y823D02* +X8Y823D01* +X2595Y823D02* +X2602Y823D01* +X1Y822D02* +X8Y822D01* +X2595Y822D02* +X2602Y822D01* +X1Y821D02* +X8Y821D01* +X2595Y821D02* +X2602Y821D01* +X1Y820D02* +X8Y820D01* +X2595Y820D02* +X2602Y820D01* +X1Y819D02* +X8Y819D01* +X2595Y819D02* +X2602Y819D01* +X1Y818D02* +X8Y818D01* +X2595Y818D02* +X2602Y818D01* +X1Y817D02* +X8Y817D01* +X2595Y817D02* +X2602Y817D01* +X1Y816D02* +X8Y816D01* +X2595Y816D02* +X2602Y816D01* +X1Y815D02* +X8Y815D01* +X2595Y815D02* +X2602Y815D01* +X1Y814D02* +X8Y814D01* +X2595Y814D02* +X2602Y814D01* +X1Y813D02* +X8Y813D01* +X2595Y813D02* +X2602Y813D01* +X1Y812D02* +X8Y812D01* +X2595Y812D02* +X2602Y812D01* +X1Y811D02* +X8Y811D01* +X2595Y811D02* +X2602Y811D01* +X1Y810D02* +X8Y810D01* +X2595Y810D02* +X2602Y810D01* +X1Y809D02* +X8Y809D01* +X2595Y809D02* +X2602Y809D01* +X1Y808D02* +X8Y808D01* +X2595Y808D02* +X2602Y808D01* +X1Y807D02* +X8Y807D01* +X2595Y807D02* +X2602Y807D01* +X1Y806D02* +X8Y806D01* +X2595Y806D02* +X2602Y806D01* +X1Y805D02* +X8Y805D01* +X2595Y805D02* +X2602Y805D01* +X1Y804D02* +X8Y804D01* +X2595Y804D02* +X2602Y804D01* +X1Y803D02* +X8Y803D01* +X2595Y803D02* +X2602Y803D01* +X1Y802D02* +X8Y802D01* +X2595Y802D02* +X2602Y802D01* +X1Y801D02* +X8Y801D01* +X2595Y801D02* +X2602Y801D01* +X1Y800D02* +X8Y800D01* +X2595Y800D02* +X2602Y800D01* +X1Y799D02* +X8Y799D01* +X2595Y799D02* +X2602Y799D01* +X1Y798D02* +X8Y798D01* +X2595Y798D02* +X2602Y798D01* +X1Y797D02* +X8Y797D01* +X2595Y797D02* +X2602Y797D01* +X1Y796D02* +X8Y796D01* +X2595Y796D02* +X2602Y796D01* +X1Y795D02* +X8Y795D01* +X2595Y795D02* +X2602Y795D01* +X1Y794D02* +X8Y794D01* +X2595Y794D02* +X2602Y794D01* +X1Y793D02* +X8Y793D01* +X2595Y793D02* +X2602Y793D01* +X1Y792D02* +X8Y792D01* +X2595Y792D02* +X2602Y792D01* +X1Y791D02* +X8Y791D01* +X2595Y791D02* +X2602Y791D01* +X1Y790D02* +X8Y790D01* +X2595Y790D02* +X2602Y790D01* +X1Y789D02* +X8Y789D01* +X2595Y789D02* +X2602Y789D01* +X1Y788D02* +X8Y788D01* +X2595Y788D02* +X2602Y788D01* +X1Y787D02* +X8Y787D01* +X2595Y787D02* +X2602Y787D01* +X1Y786D02* +X8Y786D01* +X2595Y786D02* +X2602Y786D01* +X1Y785D02* +X8Y785D01* +X2595Y785D02* +X2602Y785D01* +X1Y784D02* +X8Y784D01* +X2595Y784D02* +X2602Y784D01* +X1Y783D02* +X8Y783D01* +X2595Y783D02* +X2602Y783D01* +X1Y782D02* +X8Y782D01* +X2595Y782D02* +X2602Y782D01* +X1Y781D02* +X8Y781D01* +X2595Y781D02* +X2602Y781D01* +X1Y780D02* +X8Y780D01* +X2595Y780D02* +X2602Y780D01* +X1Y779D02* +X8Y779D01* +X2595Y779D02* +X2602Y779D01* +X1Y778D02* +X8Y778D01* +X2595Y778D02* +X2602Y778D01* +X1Y777D02* +X8Y777D01* +X2595Y777D02* +X2602Y777D01* +X1Y776D02* +X8Y776D01* +X2595Y776D02* +X2602Y776D01* +X1Y775D02* +X8Y775D01* +X2595Y775D02* +X2602Y775D01* +X1Y774D02* +X8Y774D01* +X2595Y774D02* +X2602Y774D01* +X1Y773D02* +X8Y773D01* +X2595Y773D02* +X2602Y773D01* +X1Y772D02* +X8Y772D01* +X2595Y772D02* +X2602Y772D01* +X1Y771D02* +X8Y771D01* +X2595Y771D02* +X2602Y771D01* +X1Y770D02* +X8Y770D01* +X2595Y770D02* +X2602Y770D01* +X1Y769D02* +X8Y769D01* +X2595Y769D02* +X2602Y769D01* +X1Y768D02* +X8Y768D01* +X2595Y768D02* +X2602Y768D01* +X1Y767D02* +X8Y767D01* +X2595Y767D02* +X2602Y767D01* +X1Y766D02* +X8Y766D01* +X2595Y766D02* +X2602Y766D01* +X1Y765D02* +X8Y765D01* +X2595Y765D02* +X2602Y765D01* +X1Y764D02* +X8Y764D01* +X2595Y764D02* +X2602Y764D01* +X1Y763D02* +X8Y763D01* +X2595Y763D02* +X2602Y763D01* +X1Y762D02* +X8Y762D01* +X2595Y762D02* +X2602Y762D01* +X1Y761D02* +X8Y761D01* +X2595Y761D02* +X2602Y761D01* +X1Y760D02* +X8Y760D01* +X2595Y760D02* +X2602Y760D01* +X1Y759D02* +X8Y759D01* +X2595Y759D02* +X2602Y759D01* +X1Y758D02* +X8Y758D01* +X2595Y758D02* +X2602Y758D01* +X1Y757D02* +X8Y757D01* +X2595Y757D02* +X2602Y757D01* +X1Y756D02* +X8Y756D01* +X2595Y756D02* +X2602Y756D01* +X1Y755D02* +X8Y755D01* +X2595Y755D02* +X2602Y755D01* +X1Y754D02* +X8Y754D01* +X2595Y754D02* +X2602Y754D01* +X1Y753D02* +X8Y753D01* +X2595Y753D02* +X2602Y753D01* +X1Y752D02* +X8Y752D01* +X2595Y752D02* +X2602Y752D01* +X1Y751D02* +X8Y751D01* +X2595Y751D02* +X2602Y751D01* +X1Y750D02* +X8Y750D01* +X2595Y750D02* +X2602Y750D01* +X1Y749D02* +X8Y749D01* +X2595Y749D02* +X2602Y749D01* +X1Y748D02* +X8Y748D01* +X2595Y748D02* +X2602Y748D01* +X1Y747D02* +X8Y747D01* +X2595Y747D02* +X2602Y747D01* +X1Y746D02* +X8Y746D01* +X2595Y746D02* +X2602Y746D01* +X1Y745D02* +X8Y745D01* +X2595Y745D02* +X2602Y745D01* +X1Y744D02* +X8Y744D01* +X2595Y744D02* +X2602Y744D01* +X1Y743D02* +X8Y743D01* +X2595Y743D02* +X2602Y743D01* +X1Y742D02* +X8Y742D01* +X2595Y742D02* +X2602Y742D01* +X1Y741D02* +X8Y741D01* +X2595Y741D02* +X2602Y741D01* +X1Y740D02* +X8Y740D01* +X2595Y740D02* +X2602Y740D01* +X1Y739D02* +X8Y739D01* +X2595Y739D02* +X2602Y739D01* +X1Y738D02* +X8Y738D01* +X2595Y738D02* +X2602Y738D01* +X1Y737D02* +X8Y737D01* +X2595Y737D02* +X2602Y737D01* +X1Y736D02* +X8Y736D01* +X2595Y736D02* +X2602Y736D01* +X1Y735D02* +X8Y735D01* +X2595Y735D02* +X2602Y735D01* +X1Y734D02* +X8Y734D01* +X2595Y734D02* +X2602Y734D01* +X1Y733D02* +X8Y733D01* +X2595Y733D02* +X2602Y733D01* +X1Y732D02* +X8Y732D01* +X2595Y732D02* +X2602Y732D01* +X1Y731D02* +X8Y731D01* +X2595Y731D02* +X2602Y731D01* +X1Y730D02* +X8Y730D01* +X2595Y730D02* +X2602Y730D01* +X1Y729D02* +X8Y729D01* +X2595Y729D02* +X2602Y729D01* +X1Y728D02* +X8Y728D01* +X2595Y728D02* +X2602Y728D01* +X1Y727D02* +X8Y727D01* +X2595Y727D02* +X2602Y727D01* +X1Y726D02* +X8Y726D01* +X2595Y726D02* +X2602Y726D01* +X1Y725D02* +X8Y725D01* +X2595Y725D02* +X2602Y725D01* +X1Y724D02* +X8Y724D01* +X2595Y724D02* +X2602Y724D01* +X1Y723D02* +X8Y723D01* +X2595Y723D02* +X2602Y723D01* +X1Y722D02* +X8Y722D01* +X2595Y722D02* +X2602Y722D01* +X1Y721D02* +X8Y721D01* +X2595Y721D02* +X2602Y721D01* +X1Y720D02* +X8Y720D01* +X2595Y720D02* +X2602Y720D01* +X1Y719D02* +X8Y719D01* +X2595Y719D02* +X2602Y719D01* +X1Y718D02* +X8Y718D01* +X2595Y718D02* +X2602Y718D01* +X1Y717D02* +X8Y717D01* +X2595Y717D02* +X2602Y717D01* +X1Y716D02* +X8Y716D01* +X2595Y716D02* +X2602Y716D01* +X1Y715D02* +X8Y715D01* +X2595Y715D02* +X2602Y715D01* +X1Y714D02* +X8Y714D01* +X2595Y714D02* +X2602Y714D01* +X1Y713D02* +X8Y713D01* +X2595Y713D02* +X2602Y713D01* +X1Y712D02* +X8Y712D01* +X2595Y712D02* +X2602Y712D01* +X1Y711D02* +X8Y711D01* +X2595Y711D02* +X2602Y711D01* +X1Y710D02* +X8Y710D01* +X2595Y710D02* +X2602Y710D01* +X1Y709D02* +X8Y709D01* +X2595Y709D02* +X2602Y709D01* +X1Y708D02* +X8Y708D01* +X2595Y708D02* +X2602Y708D01* +X1Y707D02* +X8Y707D01* +X2595Y707D02* +X2602Y707D01* +X1Y706D02* +X8Y706D01* +X2595Y706D02* +X2602Y706D01* +X1Y705D02* +X8Y705D01* +X2595Y705D02* +X2602Y705D01* +X1Y704D02* +X8Y704D01* +X2595Y704D02* +X2602Y704D01* +X1Y703D02* +X8Y703D01* +X2595Y703D02* +X2602Y703D01* +X1Y702D02* +X8Y702D01* +X2595Y702D02* +X2602Y702D01* +X1Y701D02* +X8Y701D01* +X2595Y701D02* +X2602Y701D01* +X1Y700D02* +X8Y700D01* +X2595Y700D02* +X2602Y700D01* +X1Y699D02* +X8Y699D01* +X2595Y699D02* +X2602Y699D01* +X1Y698D02* +X8Y698D01* +X2595Y698D02* +X2602Y698D01* +X1Y697D02* +X8Y697D01* +X2595Y697D02* +X2602Y697D01* +X1Y696D02* +X8Y696D01* +X2595Y696D02* +X2602Y696D01* +X1Y695D02* +X8Y695D01* +X2595Y695D02* +X2602Y695D01* +X1Y694D02* +X8Y694D01* +X2595Y694D02* +X2602Y694D01* +X1Y693D02* +X8Y693D01* +X2595Y693D02* +X2602Y693D01* +X1Y692D02* +X8Y692D01* +X2595Y692D02* +X2602Y692D01* +X1Y691D02* +X8Y691D01* +X2595Y691D02* +X2602Y691D01* +X1Y690D02* +X8Y690D01* +X2595Y690D02* +X2602Y690D01* +X1Y689D02* +X8Y689D01* +X2595Y689D02* +X2602Y689D01* +X1Y688D02* +X8Y688D01* +X2595Y688D02* +X2602Y688D01* +X1Y687D02* +X8Y687D01* +X2595Y687D02* +X2602Y687D01* +X1Y686D02* +X8Y686D01* +X2595Y686D02* +X2602Y686D01* +X1Y685D02* +X8Y685D01* +X2595Y685D02* +X2602Y685D01* +X1Y684D02* +X8Y684D01* +X2595Y684D02* +X2602Y684D01* +X1Y683D02* +X8Y683D01* +X2595Y683D02* +X2602Y683D01* +X1Y682D02* +X8Y682D01* +X2595Y682D02* +X2602Y682D01* +X1Y681D02* +X8Y681D01* +X2595Y681D02* +X2602Y681D01* +X1Y680D02* +X8Y680D01* +X2595Y680D02* +X2602Y680D01* +X1Y679D02* +X8Y679D01* +X2595Y679D02* +X2602Y679D01* +X1Y678D02* +X8Y678D01* +X2595Y678D02* +X2602Y678D01* +X1Y677D02* +X8Y677D01* +X2595Y677D02* +X2602Y677D01* +X1Y676D02* +X8Y676D01* +X2595Y676D02* +X2602Y676D01* +X1Y675D02* +X8Y675D01* +X2595Y675D02* +X2602Y675D01* +X1Y674D02* +X8Y674D01* +X2595Y674D02* +X2602Y674D01* +X1Y673D02* +X8Y673D01* +X2595Y673D02* +X2602Y673D01* +X1Y672D02* +X8Y672D01* +X2595Y672D02* +X2602Y672D01* +X1Y671D02* +X8Y671D01* +X2595Y671D02* +X2602Y671D01* +X1Y670D02* +X8Y670D01* +X2595Y670D02* +X2602Y670D01* +X1Y669D02* +X8Y669D01* +X2595Y669D02* +X2602Y669D01* +X1Y668D02* +X8Y668D01* +X2595Y668D02* +X2602Y668D01* +X1Y667D02* +X8Y667D01* +X2595Y667D02* +X2602Y667D01* +X1Y666D02* +X8Y666D01* +X2595Y666D02* +X2602Y666D01* +X1Y665D02* +X8Y665D01* +X2595Y665D02* +X2602Y665D01* +X1Y664D02* +X8Y664D01* +X2595Y664D02* +X2602Y664D01* +X1Y663D02* +X8Y663D01* +X2595Y663D02* +X2602Y663D01* +X1Y662D02* +X8Y662D01* +X2595Y662D02* +X2602Y662D01* +X1Y661D02* +X8Y661D01* +X2595Y661D02* +X2602Y661D01* +X1Y660D02* +X8Y660D01* +X2595Y660D02* +X2602Y660D01* +X1Y659D02* +X8Y659D01* +X2595Y659D02* +X2602Y659D01* +X1Y658D02* +X8Y658D01* +X2595Y658D02* +X2602Y658D01* +X1Y657D02* +X8Y657D01* +X2595Y657D02* +X2602Y657D01* +X1Y656D02* +X8Y656D01* +X2595Y656D02* +X2602Y656D01* +X1Y655D02* +X8Y655D01* +X2595Y655D02* +X2602Y655D01* +X1Y654D02* +X8Y654D01* +X2595Y654D02* +X2602Y654D01* +X1Y653D02* +X8Y653D01* +X2595Y653D02* +X2602Y653D01* +X1Y652D02* +X8Y652D01* +X2595Y652D02* +X2602Y652D01* +X1Y651D02* +X8Y651D01* +X2595Y651D02* +X2602Y651D01* +X1Y650D02* +X8Y650D01* +X2595Y650D02* +X2602Y650D01* +X1Y649D02* +X8Y649D01* +X2595Y649D02* +X2602Y649D01* +X1Y648D02* +X8Y648D01* +X2595Y648D02* +X2602Y648D01* +X1Y647D02* +X8Y647D01* +X2595Y647D02* +X2602Y647D01* +X1Y646D02* +X8Y646D01* +X2595Y646D02* +X2602Y646D01* +X1Y645D02* +X8Y645D01* +X2595Y645D02* +X2602Y645D01* +X1Y644D02* +X8Y644D01* +X2595Y644D02* +X2602Y644D01* +X1Y643D02* +X8Y643D01* +X2595Y643D02* +X2602Y643D01* +X1Y642D02* +X8Y642D01* +X2595Y642D02* +X2602Y642D01* +X1Y641D02* +X8Y641D01* +X2595Y641D02* +X2602Y641D01* +X1Y640D02* +X8Y640D01* +X2595Y640D02* +X2602Y640D01* +X1Y639D02* +X8Y639D01* +X2595Y639D02* +X2602Y639D01* +X1Y638D02* +X8Y638D01* +X2595Y638D02* +X2602Y638D01* +X1Y637D02* +X8Y637D01* +X2595Y637D02* +X2602Y637D01* +X1Y636D02* +X8Y636D01* +X2595Y636D02* +X2602Y636D01* +X1Y635D02* +X8Y635D01* +X2595Y635D02* +X2602Y635D01* +X1Y634D02* +X8Y634D01* +X2595Y634D02* +X2602Y634D01* +X1Y633D02* +X8Y633D01* +X2595Y633D02* +X2602Y633D01* +X1Y632D02* +X8Y632D01* +X2595Y632D02* +X2602Y632D01* +X1Y631D02* +X8Y631D01* +X2595Y631D02* +X2602Y631D01* +X1Y630D02* +X8Y630D01* +X2595Y630D02* +X2602Y630D01* +X1Y629D02* +X8Y629D01* +X2595Y629D02* +X2602Y629D01* +X1Y628D02* +X8Y628D01* +X2595Y628D02* +X2602Y628D01* +X1Y627D02* +X8Y627D01* +X2595Y627D02* +X2602Y627D01* +X1Y626D02* +X8Y626D01* +X2595Y626D02* +X2602Y626D01* +X1Y625D02* +X8Y625D01* +X2595Y625D02* +X2602Y625D01* +X1Y624D02* +X8Y624D01* +X2595Y624D02* +X2602Y624D01* +X1Y623D02* +X8Y623D01* +X2595Y623D02* +X2602Y623D01* +X1Y622D02* +X8Y622D01* +X2595Y622D02* +X2602Y622D01* +X1Y621D02* +X8Y621D01* +X2595Y621D02* +X2602Y621D01* +X1Y620D02* +X8Y620D01* +X2595Y620D02* +X2602Y620D01* +X1Y619D02* +X8Y619D01* +X2595Y619D02* +X2602Y619D01* +X1Y618D02* +X8Y618D01* +X2595Y618D02* +X2602Y618D01* +X1Y617D02* +X8Y617D01* +X2595Y617D02* +X2602Y617D01* +X1Y616D02* +X8Y616D01* +X2595Y616D02* +X2602Y616D01* +X1Y615D02* +X8Y615D01* +X2595Y615D02* +X2602Y615D01* +X1Y614D02* +X8Y614D01* +X2595Y614D02* +X2602Y614D01* +X1Y613D02* +X8Y613D01* +X2595Y613D02* +X2602Y613D01* +X1Y612D02* +X8Y612D01* +X2595Y612D02* +X2602Y612D01* +X1Y611D02* +X8Y611D01* +X2595Y611D02* +X2602Y611D01* +X1Y610D02* +X8Y610D01* +X2595Y610D02* +X2602Y610D01* +X1Y609D02* +X8Y609D01* +X2595Y609D02* +X2602Y609D01* +X1Y608D02* +X8Y608D01* +X2595Y608D02* +X2602Y608D01* +X1Y607D02* +X8Y607D01* +X2595Y607D02* +X2602Y607D01* +X1Y606D02* +X8Y606D01* +X2595Y606D02* +X2602Y606D01* +X1Y605D02* +X8Y605D01* +X2595Y605D02* +X2602Y605D01* +X1Y604D02* +X8Y604D01* +X2595Y604D02* +X2602Y604D01* +X1Y603D02* +X8Y603D01* +X2595Y603D02* +X2602Y603D01* +X1Y602D02* +X8Y602D01* +X2595Y602D02* +X2602Y602D01* +X1Y601D02* +X8Y601D01* +X2595Y601D02* +X2602Y601D01* +X1Y600D02* +X8Y600D01* +X2595Y600D02* +X2602Y600D01* +X1Y599D02* +X8Y599D01* +X2595Y599D02* +X2602Y599D01* +X1Y598D02* +X8Y598D01* +X2595Y598D02* +X2602Y598D01* +X1Y597D02* +X8Y597D01* +X2595Y597D02* +X2602Y597D01* +X1Y596D02* +X8Y596D01* +X2595Y596D02* +X2602Y596D01* +X1Y595D02* +X8Y595D01* +X2595Y595D02* +X2602Y595D01* +X1Y594D02* +X8Y594D01* +X2595Y594D02* +X2602Y594D01* +X1Y593D02* +X8Y593D01* +X2595Y593D02* +X2602Y593D01* +X1Y592D02* +X8Y592D01* +X2595Y592D02* +X2602Y592D01* +X1Y591D02* +X8Y591D01* +X2595Y591D02* +X2602Y591D01* +X1Y590D02* +X8Y590D01* +X2595Y590D02* +X2602Y590D01* +X1Y589D02* +X8Y589D01* +X2595Y589D02* +X2602Y589D01* +X1Y588D02* +X8Y588D01* +X2595Y588D02* +X2602Y588D01* +X1Y587D02* +X8Y587D01* +X2595Y587D02* +X2602Y587D01* +X1Y586D02* +X8Y586D01* +X2595Y586D02* +X2602Y586D01* +X1Y585D02* +X8Y585D01* +X2595Y585D02* +X2602Y585D01* +X1Y584D02* +X8Y584D01* +X2595Y584D02* +X2602Y584D01* +X1Y583D02* +X8Y583D01* +X2595Y583D02* +X2602Y583D01* +X1Y582D02* +X8Y582D01* +X2595Y582D02* +X2602Y582D01* +X1Y581D02* +X8Y581D01* +X2595Y581D02* +X2602Y581D01* +X1Y580D02* +X8Y580D01* +X2595Y580D02* +X2602Y580D01* +X1Y579D02* +X8Y579D01* +X2595Y579D02* +X2602Y579D01* +X1Y578D02* +X8Y578D01* +X2595Y578D02* +X2602Y578D01* +X1Y577D02* +X8Y577D01* +X2595Y577D02* +X2602Y577D01* +X1Y576D02* +X8Y576D01* +X2595Y576D02* +X2602Y576D01* +X1Y575D02* +X8Y575D01* +X2595Y575D02* +X2602Y575D01* +X1Y574D02* +X8Y574D01* +X2595Y574D02* +X2602Y574D01* +X1Y573D02* +X8Y573D01* +X2595Y573D02* +X2602Y573D01* +X1Y572D02* +X8Y572D01* +X2595Y572D02* +X2602Y572D01* +X1Y571D02* +X8Y571D01* +X2595Y571D02* +X2602Y571D01* +X1Y570D02* +X8Y570D01* +X2595Y570D02* +X2602Y570D01* +X1Y569D02* +X8Y569D01* +X2595Y569D02* +X2602Y569D01* +X1Y568D02* +X8Y568D01* +X2595Y568D02* +X2602Y568D01* +X1Y567D02* +X8Y567D01* +X2595Y567D02* +X2602Y567D01* +X1Y566D02* +X8Y566D01* +X2595Y566D02* +X2602Y566D01* +X1Y565D02* +X8Y565D01* +X2595Y565D02* +X2602Y565D01* +X1Y564D02* +X8Y564D01* +X2595Y564D02* +X2602Y564D01* +X1Y563D02* +X8Y563D01* +X2595Y563D02* +X2602Y563D01* +X1Y562D02* +X8Y562D01* +X2595Y562D02* +X2602Y562D01* +X1Y561D02* +X8Y561D01* +X2595Y561D02* +X2602Y561D01* +X1Y560D02* +X8Y560D01* +X2595Y560D02* +X2602Y560D01* +X1Y559D02* +X8Y559D01* +X2595Y559D02* +X2602Y559D01* +X1Y558D02* +X8Y558D01* +X2595Y558D02* +X2602Y558D01* +X1Y557D02* +X8Y557D01* +X2595Y557D02* +X2602Y557D01* +X1Y556D02* +X8Y556D01* +X2595Y556D02* +X2602Y556D01* +X1Y555D02* +X8Y555D01* +X2595Y555D02* +X2602Y555D01* +X1Y554D02* +X8Y554D01* +X2595Y554D02* +X2602Y554D01* +X1Y553D02* +X8Y553D01* +X2595Y553D02* +X2602Y553D01* +X1Y552D02* +X8Y552D01* +X2595Y552D02* +X2602Y552D01* +X1Y551D02* +X8Y551D01* +X2595Y551D02* +X2602Y551D01* +X1Y550D02* +X8Y550D01* +X2595Y550D02* +X2602Y550D01* +X1Y549D02* +X8Y549D01* +X2595Y549D02* +X2602Y549D01* +X1Y548D02* +X8Y548D01* +X2595Y548D02* +X2602Y548D01* +X1Y547D02* +X8Y547D01* +X2595Y547D02* +X2602Y547D01* +X1Y546D02* +X8Y546D01* +X2595Y546D02* +X2602Y546D01* +X1Y545D02* +X8Y545D01* +X2595Y545D02* +X2602Y545D01* +X1Y544D02* +X8Y544D01* +X2595Y544D02* +X2602Y544D01* +X1Y543D02* +X8Y543D01* +X2595Y543D02* +X2602Y543D01* +X1Y542D02* +X8Y542D01* +X2595Y542D02* +X2602Y542D01* +X1Y541D02* +X8Y541D01* +X2595Y541D02* +X2602Y541D01* +X1Y540D02* +X8Y540D01* +X2595Y540D02* +X2602Y540D01* +X1Y539D02* +X8Y539D01* +X2595Y539D02* +X2602Y539D01* +X1Y538D02* +X8Y538D01* +X2595Y538D02* +X2602Y538D01* +X1Y537D02* +X8Y537D01* +X2595Y537D02* +X2602Y537D01* +X1Y536D02* +X8Y536D01* +X2595Y536D02* +X2602Y536D01* +X1Y535D02* +X8Y535D01* +X2595Y535D02* +X2602Y535D01* +X1Y534D02* +X8Y534D01* +X2595Y534D02* +X2602Y534D01* +X1Y533D02* +X8Y533D01* +X2595Y533D02* +X2602Y533D01* +X1Y532D02* +X8Y532D01* +X216Y532D02* +X256Y532D01* +X349Y532D02* +X376Y532D01* +X405Y532D02* +X448Y532D01* +X487Y532D02* +X492Y532D01* +X531Y532D02* +X564Y532D01* +X821Y532D02* +X823Y532D01* +X916Y532D02* +X932Y532D01* +X2595Y532D02* +X2602Y532D01* +X1Y531D02* +X8Y531D01* +X216Y531D02* +X257Y531D01* +X347Y531D02* +X378Y531D01* +X405Y531D02* +X448Y531D01* +X484Y531D02* +X494Y531D01* +X531Y531D02* +X566Y531D01* +X819Y531D02* +X825Y531D01* +X915Y531D02* +X933Y531D01* +X2595Y531D02* +X2602Y531D01* +X1Y530D02* +X8Y530D01* +X216Y530D02* +X258Y530D01* +X345Y530D02* +X380Y530D01* +X405Y530D02* +X448Y530D01* +X483Y530D02* +X496Y530D01* +X531Y530D02* +X568Y530D01* +X819Y530D02* +X825Y530D01* +X914Y530D02* +X934Y530D01* +X2595Y530D02* +X2602Y530D01* +X1Y529D02* +X8Y529D01* +X216Y529D02* +X258Y529D01* +X344Y529D02* +X381Y529D01* +X405Y529D02* +X448Y529D01* +X482Y529D02* +X497Y529D01* +X531Y529D02* +X569Y529D01* +X818Y529D02* +X826Y529D01* +X914Y529D02* +X934Y529D01* +X2595Y529D02* +X2602Y529D01* +X1Y528D02* +X8Y528D01* +X216Y528D02* +X258Y528D01* +X344Y528D02* +X382Y528D01* +X405Y528D02* +X448Y528D01* +X481Y528D02* +X498Y528D01* +X531Y528D02* +X570Y528D01* +X818Y528D02* +X826Y528D01* +X914Y528D02* +X935Y528D01* +X2595Y528D02* +X2602Y528D01* +X1Y527D02* +X8Y527D01* +X216Y527D02* +X258Y527D01* +X343Y527D02* +X383Y527D01* +X405Y527D02* +X448Y527D01* +X480Y527D02* +X498Y527D01* +X531Y527D02* +X571Y527D01* +X818Y527D02* +X826Y527D01* +X914Y527D02* +X935Y527D01* +X2595Y527D02* +X2602Y527D01* +X1Y526D02* +X8Y526D01* +X216Y526D02* +X258Y526D01* +X342Y526D02* +X383Y526D01* +X405Y526D02* +X448Y526D01* +X479Y526D02* +X499Y526D01* +X531Y526D02* +X572Y526D01* +X818Y526D02* +X826Y526D01* +X914Y526D02* +X935Y526D01* +X2595Y526D02* +X2602Y526D01* +X1Y525D02* +X8Y525D01* +X216Y525D02* +X257Y525D01* +X342Y525D02* +X384Y525D01* +X405Y525D02* +X448Y525D01* +X479Y525D02* +X500Y525D01* +X531Y525D02* +X572Y525D01* +X818Y525D02* +X826Y525D01* +X915Y525D02* +X935Y525D01* +X2595Y525D02* +X2602Y525D01* +X1Y524D02* +X8Y524D01* +X216Y524D02* +X256Y524D01* +X342Y524D02* +X384Y524D01* +X405Y524D02* +X448Y524D01* +X478Y524D02* +X500Y524D01* +X531Y524D02* +X573Y524D01* +X818Y524D02* +X826Y524D01* +X916Y524D02* +X935Y524D01* +X2595Y524D02* +X2602Y524D01* +X1Y523D02* +X8Y523D01* +X216Y523D02* +X224Y523D01* +X342Y523D02* +X350Y523D01* +X375Y523D02* +X384Y523D01* +X405Y523D02* +X413Y523D01* +X422Y523D02* +X430Y523D01* +X440Y523D02* +X448Y523D01* +X478Y523D02* +X487Y523D01* +X491Y523D02* +X501Y523D01* +X531Y523D02* +X539Y523D01* +X563Y523D02* +X573Y523D01* +X818Y523D02* +X826Y523D01* +X927Y523D02* +X935Y523D01* +X2595Y523D02* +X2602Y523D01* +X1Y522D02* +X8Y522D01* +X216Y522D02* +X224Y522D01* +X342Y522D02* +X350Y522D01* +X376Y522D02* +X384Y522D01* +X405Y522D02* +X413Y522D01* +X422Y522D02* +X430Y522D01* +X440Y522D02* +X448Y522D01* +X477Y522D02* +X486Y522D01* +X492Y522D02* +X501Y522D01* +X531Y522D02* +X539Y522D01* +X565Y522D02* +X573Y522D01* +X818Y522D02* +X826Y522D01* +X927Y522D02* +X935Y522D01* +X2595Y522D02* +X2602Y522D01* +X1Y521D02* +X8Y521D01* +X216Y521D02* +X224Y521D01* +X342Y521D02* +X351Y521D01* +X377Y521D02* +X384Y521D01* +X405Y521D02* +X413Y521D01* +X422Y521D02* +X430Y521D01* +X440Y521D02* +X448Y521D01* +X477Y521D02* +X486Y521D01* +X493Y521D02* +X502Y521D01* +X531Y521D02* +X539Y521D01* +X565Y521D02* +X574Y521D01* +X818Y521D02* +X826Y521D01* +X927Y521D02* +X935Y521D01* +X2595Y521D02* +X2602Y521D01* +X1Y520D02* +X8Y520D01* +X216Y520D02* +X224Y520D01* +X342Y520D02* +X351Y520D01* +X377Y520D02* +X384Y520D01* +X405Y520D02* +X413Y520D01* +X422Y520D02* +X430Y520D01* +X440Y520D02* +X447Y520D01* +X476Y520D02* +X485Y520D01* +X493Y520D02* +X502Y520D01* +X531Y520D02* +X539Y520D01* +X566Y520D02* +X574Y520D01* +X818Y520D02* +X826Y520D01* +X927Y520D02* +X935Y520D01* +X2595Y520D02* +X2602Y520D01* +X1Y519D02* +X8Y519D01* +X216Y519D02* +X224Y519D01* +X342Y519D02* +X352Y519D01* +X377Y519D02* +X384Y519D01* +X405Y519D02* +X412Y519D01* +X422Y519D02* +X430Y519D01* +X440Y519D02* +X447Y519D01* +X476Y519D02* +X485Y519D01* +X494Y519D02* +X503Y519D01* +X531Y519D02* +X539Y519D01* +X566Y519D02* +X574Y519D01* +X818Y519D02* +X826Y519D01* +X927Y519D02* +X935Y519D01* +X2595Y519D02* +X2602Y519D01* +X1Y518D02* +X8Y518D01* +X216Y518D02* +X224Y518D01* +X343Y518D02* +X353Y518D01* +X378Y518D02* +X384Y518D01* +X406Y518D02* +X412Y518D01* +X422Y518D02* +X430Y518D01* +X441Y518D02* +X447Y518D01* +X475Y518D02* +X484Y518D01* +X494Y518D02* +X503Y518D01* +X531Y518D02* +X539Y518D01* +X566Y518D02* +X574Y518D01* +X818Y518D02* +X826Y518D01* +X927Y518D02* +X935Y518D01* +X2595Y518D02* +X2602Y518D01* +X1Y517D02* +X8Y517D01* +X216Y517D02* +X224Y517D01* +X343Y517D02* +X354Y517D01* +X379Y517D02* +X383Y517D01* +X407Y517D02* +X411Y517D01* +X422Y517D02* +X430Y517D01* +X442Y517D02* +X446Y517D01* +X475Y517D02* +X484Y517D01* +X495Y517D02* +X504Y517D01* +X531Y517D02* +X539Y517D01* +X566Y517D02* +X574Y517D01* +X818Y517D02* +X826Y517D01* +X927Y517D02* +X935Y517D01* +X2595Y517D02* +X2602Y517D01* +X1Y516D02* +X8Y516D01* +X216Y516D02* +X224Y516D01* +X344Y516D02* +X354Y516D01* +X422Y516D02* +X430Y516D01* +X474Y516D02* +X483Y516D01* +X495Y516D02* +X504Y516D01* +X531Y516D02* +X539Y516D01* +X566Y516D02* +X574Y516D01* +X818Y516D02* +X826Y516D01* +X927Y516D02* +X935Y516D01* +X2595Y516D02* +X2602Y516D01* +X1Y515D02* +X8Y515D01* +X216Y515D02* +X224Y515D01* +X345Y515D02* +X355Y515D01* +X422Y515D02* +X430Y515D01* +X474Y515D02* +X483Y515D01* +X496Y515D02* +X505Y515D01* +X531Y515D02* +X539Y515D01* +X566Y515D02* +X574Y515D01* +X818Y515D02* +X826Y515D01* +X927Y515D02* +X935Y515D01* +X2595Y515D02* +X2602Y515D01* +X1Y514D02* +X8Y514D01* +X216Y514D02* +X224Y514D01* +X346Y514D02* +X356Y514D01* +X422Y514D02* +X430Y514D01* +X473Y514D02* +X482Y514D01* +X496Y514D02* +X505Y514D01* +X531Y514D02* +X539Y514D01* +X566Y514D02* +X574Y514D01* +X818Y514D02* +X826Y514D01* +X927Y514D02* +X935Y514D01* +X2595Y514D02* +X2602Y514D01* +X1Y513D02* +X8Y513D01* +X216Y513D02* +X224Y513D01* +X346Y513D02* +X357Y513D01* +X422Y513D02* +X430Y513D01* +X473Y513D02* +X482Y513D01* +X497Y513D02* +X506Y513D01* +X531Y513D02* +X539Y513D01* +X566Y513D02* +X574Y513D01* +X658Y513D02* +X662Y513D01* +X669Y513D02* +X676Y513D01* +X686Y513D02* +X692Y513D01* +X732Y513D02* +X751Y513D01* +X795Y513D02* +X810Y513D01* +X818Y513D02* +X826Y513D01* +X848Y513D02* +X852Y513D01* +X883Y513D02* +X887Y513D01* +X927Y513D02* +X935Y513D01* +X984Y513D02* +X1003Y513D01* +X2595Y513D02* +X2602Y513D01* +X1Y512D02* +X8Y512D01* +X216Y512D02* +X224Y512D01* +X347Y512D02* +X358Y512D01* +X422Y512D02* +X430Y512D01* +X472Y512D02* +X481Y512D01* +X497Y512D02* +X506Y512D01* +X531Y512D02* +X539Y512D01* +X566Y512D02* +X574Y512D01* +X657Y512D02* +X663Y512D01* +X667Y512D02* +X678Y512D01* +X684Y512D02* +X694Y512D01* +X730Y512D02* +X753Y512D01* +X793Y512D02* +X812Y512D01* +X818Y512D02* +X826Y512D01* +X847Y512D02* +X853Y512D01* +X882Y512D02* +X888Y512D01* +X927Y512D02* +X935Y512D01* +X982Y512D02* +X1005Y512D01* +X2595Y512D02* +X2602Y512D01* +X1Y511D02* +X8Y511D01* +X216Y511D02* +X224Y511D01* +X348Y511D02* +X358Y511D01* +X422Y511D02* +X430Y511D01* +X472Y511D02* +X481Y511D01* +X498Y511D02* +X507Y511D01* +X531Y511D02* +X539Y511D01* +X566Y511D02* +X574Y511D01* +X657Y511D02* +X679Y511D01* +X683Y511D02* +X695Y511D01* +X728Y511D02* +X755Y511D01* +X792Y511D02* +X813Y511D01* +X818Y511D02* +X826Y511D01* +X847Y511D02* +X854Y511D01* +X881Y511D02* +X889Y511D01* +X927Y511D02* +X935Y511D01* +X981Y511D02* +X1007Y511D01* +X2595Y511D02* +X2602Y511D01* +X1Y510D02* +X8Y510D01* +X216Y510D02* +X224Y510D01* +X349Y510D02* +X359Y510D01* +X422Y510D02* +X430Y510D01* +X471Y510D02* +X480Y510D01* +X498Y510D02* +X507Y510D01* +X531Y510D02* +X539Y510D01* +X566Y510D02* +X574Y510D01* +X657Y510D02* +X680Y510D01* +X682Y510D02* +X697Y510D01* +X727Y510D02* +X756Y510D01* +X790Y510D02* +X815Y510D01* +X818Y510D02* +X826Y510D01* +X846Y510D02* +X854Y510D01* +X881Y510D02* +X889Y510D01* +X927Y510D02* +X935Y510D01* +X979Y510D02* +X1008Y510D01* +X2595Y510D02* +X2602Y510D01* +X1Y509D02* +X8Y509D01* +X216Y509D02* +X224Y509D01* +X350Y509D02* +X360Y509D01* +X422Y509D02* +X430Y509D01* +X471Y509D02* +X480Y509D01* +X499Y509D02* +X508Y509D01* +X531Y509D02* +X539Y509D01* +X566Y509D02* +X574Y509D01* +X656Y509D02* +X697Y509D01* +X726Y509D02* +X757Y509D01* +X789Y509D02* +X816Y509D01* +X818Y509D02* +X826Y509D01* +X846Y509D02* +X854Y509D01* +X881Y509D02* +X889Y509D01* +X927Y509D02* +X935Y509D01* +X978Y509D02* +X1009Y509D01* +X2595Y509D02* +X2602Y509D01* +X1Y508D02* +X8Y508D01* +X216Y508D02* +X224Y508D01* +X350Y508D02* +X361Y508D01* +X422Y508D02* +X430Y508D01* +X470Y508D02* +X479Y508D01* +X499Y508D02* +X508Y508D01* +X531Y508D02* +X539Y508D01* +X566Y508D02* +X574Y508D01* +X656Y508D02* +X698Y508D01* +X725Y508D02* +X758Y508D01* +X788Y508D02* +X826Y508D01* +X846Y508D02* +X854Y508D01* +X881Y508D02* +X889Y508D01* +X927Y508D02* +X935Y508D01* +X977Y508D02* +X1010Y508D01* +X2595Y508D02* +X2602Y508D01* +X1Y507D02* +X8Y507D01* +X216Y507D02* +X224Y507D01* +X351Y507D02* +X361Y507D01* +X422Y507D02* +X430Y507D01* +X470Y507D02* +X479Y507D01* +X500Y507D02* +X509Y507D01* +X531Y507D02* +X539Y507D01* +X566Y507D02* +X574Y507D01* +X656Y507D02* +X698Y507D01* +X724Y507D02* +X759Y507D01* +X787Y507D02* +X826Y507D01* +X846Y507D02* +X854Y507D01* +X881Y507D02* +X889Y507D01* +X927Y507D02* +X935Y507D01* +X976Y507D02* +X1011Y507D01* +X2595Y507D02* +X2602Y507D01* +X1Y506D02* +X8Y506D01* +X216Y506D02* +X224Y506D01* +X352Y506D02* +X362Y506D01* +X422Y506D02* +X430Y506D01* +X470Y506D02* +X478Y506D01* +X500Y506D02* +X509Y506D01* +X531Y506D02* +X539Y506D01* +X566Y506D02* +X574Y506D01* +X656Y506D02* +X699Y506D01* +X723Y506D02* +X760Y506D01* +X786Y506D02* +X826Y506D01* +X846Y506D02* +X854Y506D01* +X881Y506D02* +X889Y506D01* +X927Y506D02* +X935Y506D01* +X975Y506D02* +X1012Y506D01* +X2595Y506D02* +X2602Y506D01* +X1Y505D02* +X8Y505D01* +X216Y505D02* +X224Y505D01* +X353Y505D02* +X363Y505D01* +X422Y505D02* +X430Y505D01* +X469Y505D02* +X478Y505D01* +X501Y505D02* +X509Y505D01* +X531Y505D02* +X539Y505D01* +X566Y505D02* +X574Y505D01* +X656Y505D02* +X671Y505D01* +X673Y505D02* +X699Y505D01* +X722Y505D02* +X736Y505D01* +X747Y505D02* +X761Y505D01* +X785Y505D02* +X799Y505D01* +X806Y505D02* +X826Y505D01* +X847Y505D02* +X854Y505D01* +X881Y505D02* +X889Y505D01* +X927Y505D02* +X935Y505D01* +X975Y505D02* +X988Y505D01* +X1000Y505D02* +X1013Y505D01* +X2595Y505D02* +X2602Y505D01* +X1Y504D02* +X8Y504D01* +X216Y504D02* +X224Y504D01* +X353Y504D02* +X364Y504D01* +X422Y504D02* +X430Y504D01* +X469Y504D02* +X477Y504D01* +X501Y504D02* +X510Y504D01* +X531Y504D02* +X539Y504D01* +X566Y504D02* +X574Y504D01* +X656Y504D02* +X670Y504D01* +X674Y504D02* +X687Y504D01* +X691Y504D02* +X699Y504D01* +X722Y504D02* +X733Y504D01* +X750Y504D02* +X761Y504D01* +X785Y504D02* +X796Y504D01* +X809Y504D02* +X826Y504D01* +X847Y504D02* +X854Y504D01* +X881Y504D02* +X889Y504D01* +X927Y504D02* +X935Y504D01* +X974Y504D02* +X985Y504D01* +X1003Y504D02* +X1014Y504D01* +X2595Y504D02* +X2602Y504D01* +X1Y503D02* +X8Y503D01* +X216Y503D02* +X224Y503D01* +X354Y503D02* +X365Y503D01* +X422Y503D02* +X430Y503D01* +X469Y503D02* +X477Y503D01* +X502Y503D02* +X510Y503D01* +X531Y503D02* +X539Y503D01* +X566Y503D02* +X574Y503D01* +X656Y503D02* +X669Y503D01* +X675Y503D02* +X686Y503D01* +X691Y503D02* +X699Y503D01* +X721Y503D02* +X732Y503D01* +X752Y503D02* +X762Y503D01* +X784Y503D02* +X795Y503D01* +X810Y503D02* +X826Y503D01* +X847Y503D02* +X854Y503D01* +X881Y503D02* +X889Y503D01* +X927Y503D02* +X935Y503D01* +X974Y503D02* +X984Y503D01* +X1004Y503D02* +X1014Y503D01* +X2595Y503D02* +X2602Y503D01* +X1Y502D02* +X8Y502D01* +X216Y502D02* +X239Y502D01* +X281Y502D02* +X319Y502D01* +X355Y502D02* +X365Y502D01* +X422Y502D02* +X430Y502D01* +X468Y502D02* +X477Y502D01* +X502Y502D02* +X510Y502D01* +X531Y502D02* +X539Y502D01* +X566Y502D02* +X574Y502D01* +X656Y502D02* +X667Y502D01* +X675Y502D02* +X685Y502D01* +X691Y502D02* +X699Y502D01* +X721Y502D02* +X730Y502D01* +X753Y502D02* +X762Y502D01* +X784Y502D02* +X793Y502D01* +X811Y502D02* +X826Y502D01* +X847Y502D02* +X854Y502D01* +X881Y502D02* +X889Y502D01* +X927Y502D02* +X935Y502D01* +X973Y502D02* +X983Y502D01* +X1005Y502D02* +X1014Y502D01* +X2595Y502D02* +X2602Y502D01* +X1Y501D02* +X8Y501D01* +X216Y501D02* +X240Y501D01* +X280Y501D02* +X320Y501D01* +X356Y501D02* +X366Y501D01* +X422Y501D02* +X430Y501D01* +X468Y501D02* +X476Y501D01* +X502Y501D02* +X510Y501D01* +X531Y501D02* +X539Y501D01* +X565Y501D02* +X573Y501D01* +X656Y501D02* +X666Y501D01* +X675Y501D02* +X684Y501D01* +X691Y501D02* +X699Y501D01* +X721Y501D02* +X729Y501D01* +X754Y501D02* +X763Y501D01* +X784Y501D02* +X793Y501D01* +X812Y501D02* +X826Y501D01* +X847Y501D02* +X854Y501D01* +X881Y501D02* +X889Y501D01* +X927Y501D02* +X935Y501D01* +X973Y501D02* +X982Y501D01* +X1006Y501D02* +X1015Y501D01* +X2595Y501D02* +X2602Y501D01* +X1Y500D02* +X8Y500D01* +X216Y500D02* +X241Y500D01* +X279Y500D02* +X321Y500D01* +X357Y500D02* +X367Y500D01* +X422Y500D02* +X430Y500D01* +X468Y500D02* +X476Y500D01* +X503Y500D02* +X511Y500D01* +X531Y500D02* +X539Y500D01* +X564Y500D02* +X573Y500D01* +X656Y500D02* +X665Y500D01* +X675Y500D02* +X683Y500D01* +X691Y500D02* +X699Y500D01* +X720Y500D02* +X729Y500D01* +X754Y500D02* +X763Y500D01* +X783Y500D02* +X792Y500D01* +X814Y500D02* +X826Y500D01* +X847Y500D02* +X854Y500D01* +X881Y500D02* +X889Y500D01* +X927Y500D02* +X935Y500D01* +X973Y500D02* +X981Y500D01* +X1007Y500D02* +X1015Y500D01* +X2595Y500D02* +X2602Y500D01* +X1Y499D02* +X8Y499D01* +X216Y499D02* +X241Y499D01* +X279Y499D02* +X321Y499D01* +X357Y499D02* +X368Y499D01* +X422Y499D02* +X430Y499D01* +X468Y499D02* +X476Y499D01* +X503Y499D02* +X511Y499D01* +X531Y499D02* +X539Y499D01* +X561Y499D02* +X573Y499D01* +X656Y499D02* +X664Y499D01* +X675Y499D02* +X682Y499D01* +X692Y499D02* +X699Y499D01* +X720Y499D02* +X728Y499D01* +X755Y499D02* +X763Y499D01* +X783Y499D02* +X791Y499D01* +X815Y499D02* +X826Y499D01* +X847Y499D02* +X855Y499D01* +X881Y499D02* +X889Y499D01* +X927Y499D02* +X935Y499D01* +X973Y499D02* +X981Y499D01* +X1007Y499D02* +X1015Y499D01* +X2595Y499D02* +X2602Y499D01* +X1Y498D02* +X8Y498D01* +X216Y498D02* +X241Y498D01* +X279Y498D02* +X321Y498D01* +X358Y498D02* +X368Y498D01* +X422Y498D02* +X430Y498D01* +X468Y498D02* +X476Y498D01* +X503Y498D02* +X511Y498D01* +X531Y498D02* +X572Y498D01* +X656Y498D02* +X664Y498D01* +X675Y498D02* +X682Y498D01* +X692Y498D02* +X699Y498D01* +X720Y498D02* +X728Y498D01* +X755Y498D02* +X763Y498D01* +X783Y498D02* +X791Y498D01* +X816Y498D02* +X826Y498D01* +X847Y498D02* +X855Y498D01* +X881Y498D02* +X889Y498D01* +X927Y498D02* +X935Y498D01* +X973Y498D02* +X980Y498D01* +X1007Y498D02* +X1015Y498D01* +X2595Y498D02* +X2602Y498D01* +X1Y497D02* +X8Y497D01* +X216Y497D02* +X241Y497D01* +X279Y497D02* +X321Y497D01* +X359Y497D02* +X369Y497D01* +X422Y497D02* +X430Y497D01* +X468Y497D02* +X476Y497D01* +X503Y497D02* +X511Y497D01* +X531Y497D02* +X572Y497D01* +X656Y497D02* +X664Y497D01* +X675Y497D02* +X682Y497D01* +X692Y497D02* +X699Y497D01* +X720Y497D02* +X728Y497D01* +X755Y497D02* +X763Y497D01* +X783Y497D02* +X791Y497D01* +X817Y497D02* +X826Y497D01* +X847Y497D02* +X855Y497D01* +X881Y497D02* +X889Y497D01* +X927Y497D02* +X935Y497D01* +X973Y497D02* +X980Y497D01* +X1007Y497D02* +X1015Y497D01* +X2595Y497D02* +X2602Y497D01* +X1Y496D02* +X8Y496D01* +X216Y496D02* +X240Y496D01* +X279Y496D02* +X321Y496D01* +X360Y496D02* +X370Y496D01* +X422Y496D02* +X430Y496D01* +X468Y496D02* +X476Y496D01* +X502Y496D02* +X510Y496D01* +X531Y496D02* +X571Y496D01* +X656Y496D02* +X664Y496D01* +X675Y496D02* +X682Y496D01* +X692Y496D02* +X699Y496D01* +X720Y496D02* +X728Y496D01* +X755Y496D02* +X763Y496D01* +X783Y496D02* +X791Y496D01* +X818Y496D02* +X826Y496D01* +X847Y496D02* +X855Y496D01* +X881Y496D02* +X889Y496D01* +X927Y496D02* +X935Y496D01* +X973Y496D02* +X980Y496D01* +X1007Y496D02* +X1015Y496D01* +X2595Y496D02* +X2602Y496D01* +X1Y495D02* +X8Y495D01* +X216Y495D02* +X239Y495D01* +X279Y495D02* +X321Y495D01* +X360Y495D02* +X371Y495D01* +X422Y495D02* +X430Y495D01* +X468Y495D02* +X476Y495D01* +X502Y495D02* +X510Y495D01* +X531Y495D02* +X571Y495D01* +X656Y495D02* +X664Y495D01* +X675Y495D02* +X682Y495D01* +X692Y495D02* +X699Y495D01* +X720Y495D02* +X728Y495D01* +X755Y495D02* +X763Y495D01* +X783Y495D02* +X791Y495D01* +X818Y495D02* +X826Y495D01* +X847Y495D02* +X855Y495D01* +X881Y495D02* +X889Y495D01* +X927Y495D02* +X935Y495D01* +X973Y495D02* +X980Y495D01* +X1007Y495D02* +X1015Y495D01* +X2595Y495D02* +X2602Y495D01* +X1Y494D02* +X8Y494D01* +X216Y494D02* +X237Y494D01* +X279Y494D02* +X321Y494D01* +X361Y494D02* +X372Y494D01* +X422Y494D02* +X430Y494D01* +X468Y494D02* +X477Y494D01* +X502Y494D02* +X510Y494D01* +X531Y494D02* +X570Y494D01* +X656Y494D02* +X664Y494D01* +X675Y494D02* +X682Y494D01* +X692Y494D02* +X699Y494D01* +X720Y494D02* +X728Y494D01* +X755Y494D02* +X763Y494D01* +X783Y494D02* +X791Y494D01* +X818Y494D02* +X826Y494D01* +X847Y494D02* +X855Y494D01* +X881Y494D02* +X889Y494D01* +X927Y494D02* +X935Y494D01* +X973Y494D02* +X980Y494D01* +X1007Y494D02* +X1015Y494D01* +X2595Y494D02* +X2602Y494D01* +X1Y493D02* +X8Y493D01* +X216Y493D02* +X224Y493D01* +X279Y493D02* +X321Y493D01* +X362Y493D02* +X372Y493D01* +X422Y493D02* +X430Y493D01* +X469Y493D02* +X477Y493D01* +X501Y493D02* +X510Y493D01* +X531Y493D02* +X568Y493D01* +X656Y493D02* +X664Y493D01* +X675Y493D02* +X682Y493D01* +X692Y493D02* +X700Y493D01* +X720Y493D02* +X728Y493D01* +X755Y493D02* +X763Y493D01* +X783Y493D02* +X791Y493D01* +X818Y493D02* +X826Y493D01* +X847Y493D02* +X855Y493D01* +X881Y493D02* +X889Y493D01* +X927Y493D02* +X935Y493D01* +X973Y493D02* +X980Y493D01* +X1007Y493D02* +X1015Y493D01* +X2595Y493D02* +X2602Y493D01* +X1Y492D02* +X8Y492D01* +X216Y492D02* +X224Y492D01* +X280Y492D02* +X320Y492D01* +X363Y492D02* +X373Y492D01* +X422Y492D02* +X430Y492D01* +X469Y492D02* +X478Y492D01* +X501Y492D02* +X510Y492D01* +X531Y492D02* +X567Y492D01* +X656Y492D02* +X664Y492D01* +X675Y492D02* +X682Y492D01* +X692Y492D02* +X700Y492D01* +X720Y492D02* +X728Y492D01* +X755Y492D02* +X763Y492D01* +X783Y492D02* +X791Y492D01* +X818Y492D02* +X826Y492D01* +X847Y492D02* +X855Y492D01* +X881Y492D02* +X889Y492D01* +X927Y492D02* +X935Y492D01* +X973Y492D02* +X980Y492D01* +X1007Y492D02* +X1015Y492D01* +X2595Y492D02* +X2602Y492D01* +X1Y491D02* +X8Y491D01* +X216Y491D02* +X224Y491D01* +X281Y491D02* +X319Y491D01* +X364Y491D02* +X374Y491D01* +X422Y491D02* +X430Y491D01* +X469Y491D02* +X478Y491D01* +X500Y491D02* +X509Y491D01* +X531Y491D02* +X565Y491D01* +X656Y491D02* +X664Y491D01* +X675Y491D02* +X682Y491D01* +X692Y491D02* +X700Y491D01* +X720Y491D02* +X728Y491D01* +X755Y491D02* +X763Y491D01* +X783Y491D02* +X791Y491D01* +X818Y491D02* +X826Y491D01* +X847Y491D02* +X855Y491D01* +X881Y491D02* +X889Y491D01* +X927Y491D02* +X935Y491D01* +X973Y491D02* +X1015Y491D01* +X2595Y491D02* +X2602Y491D01* +X1Y490D02* +X8Y490D01* +X216Y490D02* +X224Y490D01* +X364Y490D02* +X375Y490D01* +X422Y490D02* +X430Y490D01* +X470Y490D02* +X479Y490D01* +X500Y490D02* +X509Y490D01* +X531Y490D02* +X539Y490D01* +X656Y490D02* +X664Y490D01* +X675Y490D02* +X682Y490D01* +X692Y490D02* +X700Y490D01* +X720Y490D02* +X728Y490D01* +X755Y490D02* +X763Y490D01* +X783Y490D02* +X791Y490D01* +X818Y490D02* +X826Y490D01* +X847Y490D02* +X855Y490D01* +X881Y490D02* +X889Y490D01* +X927Y490D02* +X935Y490D01* +X973Y490D02* +X1015Y490D01* +X2595Y490D02* +X2602Y490D01* +X1Y489D02* +X8Y489D01* +X216Y489D02* +X224Y489D01* +X365Y489D02* +X375Y489D01* +X422Y489D02* +X430Y489D01* +X470Y489D02* +X479Y489D01* +X499Y489D02* +X508Y489D01* +X531Y489D02* +X539Y489D01* +X656Y489D02* +X664Y489D01* +X675Y489D02* +X682Y489D01* +X692Y489D02* +X700Y489D01* +X720Y489D02* +X728Y489D01* +X755Y489D02* +X763Y489D01* +X783Y489D02* +X791Y489D01* +X818Y489D02* +X826Y489D01* +X847Y489D02* +X855Y489D01* +X881Y489D02* +X889Y489D01* +X927Y489D02* +X935Y489D01* +X973Y489D02* +X1015Y489D01* +X2595Y489D02* +X2602Y489D01* +X1Y488D02* +X8Y488D01* +X216Y488D02* +X224Y488D01* +X366Y488D02* +X376Y488D01* +X422Y488D02* +X430Y488D01* +X471Y488D02* +X480Y488D01* +X499Y488D02* +X508Y488D01* +X531Y488D02* +X539Y488D01* +X656Y488D02* +X664Y488D01* +X675Y488D02* +X682Y488D01* +X692Y488D02* +X700Y488D01* +X720Y488D02* +X728Y488D01* +X755Y488D02* +X763Y488D01* +X783Y488D02* +X791Y488D01* +X818Y488D02* +X826Y488D01* +X847Y488D02* +X855Y488D01* +X881Y488D02* +X889Y488D01* +X927Y488D02* +X935Y488D01* +X973Y488D02* +X1015Y488D01* +X2595Y488D02* +X2602Y488D01* +X1Y487D02* +X8Y487D01* +X216Y487D02* +X224Y487D01* +X367Y487D02* +X377Y487D01* +X422Y487D02* +X430Y487D01* +X471Y487D02* +X480Y487D01* +X498Y487D02* +X507Y487D01* +X531Y487D02* +X539Y487D01* +X656Y487D02* +X664Y487D01* +X675Y487D02* +X682Y487D01* +X692Y487D02* +X700Y487D01* +X720Y487D02* +X728Y487D01* +X755Y487D02* +X763Y487D01* +X783Y487D02* +X791Y487D01* +X818Y487D02* +X826Y487D01* +X847Y487D02* +X855Y487D01* +X881Y487D02* +X889Y487D01* +X927Y487D02* +X935Y487D01* +X973Y487D02* +X1015Y487D01* +X2595Y487D02* +X2602Y487D01* +X1Y486D02* +X8Y486D01* +X216Y486D02* +X224Y486D01* +X367Y486D02* +X378Y486D01* +X422Y486D02* +X430Y486D01* +X472Y486D02* +X481Y486D01* +X498Y486D02* +X507Y486D01* +X531Y486D02* +X539Y486D01* +X656Y486D02* +X664Y486D01* +X675Y486D02* +X682Y486D01* +X692Y486D02* +X700Y486D01* +X720Y486D02* +X728Y486D01* +X755Y486D02* +X763Y486D01* +X783Y486D02* +X791Y486D01* +X818Y486D02* +X826Y486D01* +X847Y486D02* +X855Y486D01* +X881Y486D02* +X889Y486D01* +X927Y486D02* +X935Y486D01* +X973Y486D02* +X1015Y486D01* +X2595Y486D02* +X2602Y486D01* +X1Y485D02* +X8Y485D01* +X216Y485D02* +X224Y485D01* +X368Y485D02* +X379Y485D01* +X422Y485D02* +X430Y485D01* +X472Y485D02* +X481Y485D01* +X497Y485D02* +X506Y485D01* +X531Y485D02* +X539Y485D01* +X656Y485D02* +X664Y485D01* +X675Y485D02* +X682Y485D01* +X692Y485D02* +X700Y485D01* +X720Y485D02* +X728Y485D01* +X755Y485D02* +X763Y485D01* +X783Y485D02* +X791Y485D01* +X818Y485D02* +X826Y485D01* +X847Y485D02* +X855Y485D01* +X881Y485D02* +X889Y485D01* +X927Y485D02* +X935Y485D01* +X973Y485D02* +X1015Y485D01* +X2595Y485D02* +X2602Y485D01* +X1Y484D02* +X8Y484D01* +X216Y484D02* +X224Y484D01* +X369Y484D02* +X379Y484D01* +X422Y484D02* +X430Y484D01* +X473Y484D02* +X482Y484D01* +X497Y484D02* +X506Y484D01* +X531Y484D02* +X539Y484D01* +X656Y484D02* +X664Y484D01* +X675Y484D02* +X682Y484D01* +X692Y484D02* +X700Y484D01* +X720Y484D02* +X728Y484D01* +X755Y484D02* +X763Y484D01* +X783Y484D02* +X791Y484D01* +X818Y484D02* +X826Y484D01* +X847Y484D02* +X855Y484D01* +X881Y484D02* +X889Y484D01* +X927Y484D02* +X935Y484D01* +X973Y484D02* +X1014Y484D01* +X2595Y484D02* +X2602Y484D01* +X1Y483D02* +X8Y483D01* +X216Y483D02* +X224Y483D01* +X370Y483D02* +X380Y483D01* +X422Y483D02* +X430Y483D01* +X473Y483D02* +X482Y483D01* +X496Y483D02* +X505Y483D01* +X531Y483D02* +X539Y483D01* +X656Y483D02* +X664Y483D01* +X675Y483D02* +X682Y483D01* +X692Y483D02* +X700Y483D01* +X720Y483D02* +X728Y483D01* +X755Y483D02* +X763Y483D01* +X783Y483D02* +X791Y483D01* +X818Y483D02* +X826Y483D01* +X847Y483D02* +X855Y483D01* +X881Y483D02* +X889Y483D01* +X927Y483D02* +X935Y483D01* +X973Y483D02* +X1012Y483D01* +X2595Y483D02* +X2602Y483D01* +X1Y482D02* +X8Y482D01* +X216Y482D02* +X224Y482D01* +X371Y482D02* +X381Y482D01* +X422Y482D02* +X430Y482D01* +X474Y482D02* +X483Y482D01* +X496Y482D02* +X505Y482D01* +X531Y482D02* +X539Y482D01* +X656Y482D02* +X664Y482D01* +X675Y482D02* +X682Y482D01* +X692Y482D02* +X700Y482D01* +X720Y482D02* +X728Y482D01* +X755Y482D02* +X763Y482D01* +X783Y482D02* +X791Y482D01* +X818Y482D02* +X826Y482D01* +X847Y482D02* +X855Y482D01* +X881Y482D02* +X889Y482D01* +X927Y482D02* +X935Y482D01* +X973Y482D02* +X980Y482D01* +X2595Y482D02* +X2602Y482D01* +X1Y481D02* +X8Y481D01* +X216Y481D02* +X224Y481D01* +X371Y481D02* +X382Y481D01* +X422Y481D02* +X430Y481D01* +X474Y481D02* +X483Y481D01* +X495Y481D02* +X504Y481D01* +X531Y481D02* +X539Y481D01* +X656Y481D02* +X664Y481D01* +X675Y481D02* +X682Y481D01* +X692Y481D02* +X700Y481D01* +X720Y481D02* +X728Y481D01* +X755Y481D02* +X763Y481D01* +X783Y481D02* +X791Y481D01* +X817Y481D02* +X826Y481D01* +X847Y481D02* +X855Y481D01* +X879Y481D02* +X889Y481D01* +X927Y481D02* +X935Y481D01* +X973Y481D02* +X980Y481D01* +X2595Y481D02* +X2602Y481D01* +X1Y480D02* +X8Y480D01* +X216Y480D02* +X224Y480D01* +X345Y480D02* +X347Y480D01* +X372Y480D02* +X382Y480D01* +X422Y480D02* +X430Y480D01* +X475Y480D02* +X484Y480D01* +X495Y480D02* +X504Y480D01* +X531Y480D02* +X539Y480D01* +X656Y480D02* +X664Y480D01* +X675Y480D02* +X682Y480D01* +X692Y480D02* +X700Y480D01* +X720Y480D02* +X728Y480D01* +X755Y480D02* +X763Y480D01* +X783Y480D02* +X791Y480D01* +X816Y480D02* +X826Y480D01* +X847Y480D02* +X855Y480D01* +X878Y480D02* +X889Y480D01* +X927Y480D02* +X935Y480D01* +X973Y480D02* +X980Y480D01* +X2595Y480D02* +X2602Y480D01* +X1Y479D02* +X8Y479D01* +X216Y479D02* +X224Y479D01* +X343Y479D02* +X348Y479D01* +X373Y479D02* +X383Y479D01* +X422Y479D02* +X430Y479D01* +X475Y479D02* +X484Y479D01* +X494Y479D02* +X503Y479D01* +X531Y479D02* +X539Y479D01* +X656Y479D02* +X664Y479D01* +X675Y479D02* +X682Y479D01* +X692Y479D02* +X700Y479D01* +X720Y479D02* +X728Y479D01* +X755Y479D02* +X763Y479D01* +X783Y479D02* +X791Y479D01* +X815Y479D02* +X826Y479D01* +X847Y479D02* +X855Y479D01* +X876Y479D02* +X889Y479D01* +X927Y479D02* +X935Y479D01* +X973Y479D02* +X981Y479D01* +X2595Y479D02* +X2602Y479D01* +X1Y478D02* +X8Y478D01* +X216Y478D02* +X224Y478D01* +X342Y478D02* +X349Y478D01* +X374Y478D02* +X384Y478D01* +X422Y478D02* +X430Y478D01* +X476Y478D02* +X485Y478D01* +X494Y478D02* +X503Y478D01* +X531Y478D02* +X539Y478D01* +X656Y478D02* +X664Y478D01* +X675Y478D02* +X682Y478D01* +X692Y478D02* +X700Y478D01* +X720Y478D02* +X729Y478D01* +X754Y478D02* +X763Y478D01* +X784Y478D02* +X792Y478D01* +X814Y478D02* +X826Y478D01* +X847Y478D02* +X855Y478D01* +X875Y478D02* +X889Y478D01* +X927Y478D02* +X935Y478D01* +X973Y478D02* +X981Y478D01* +X2595Y478D02* +X2602Y478D01* +X1Y477D02* +X8Y477D01* +X216Y477D02* +X224Y477D01* +X342Y477D02* +X350Y477D01* +X374Y477D02* +X384Y477D01* +X422Y477D02* +X430Y477D01* +X476Y477D02* +X485Y477D01* +X493Y477D02* +X502Y477D01* +X531Y477D02* +X539Y477D01* +X656Y477D02* +X664Y477D01* +X675Y477D02* +X682Y477D01* +X692Y477D02* +X700Y477D01* +X721Y477D02* +X729Y477D01* +X754Y477D02* +X763Y477D01* +X784Y477D02* +X792Y477D01* +X812Y477D02* +X826Y477D01* +X847Y477D02* +X855Y477D01* +X873Y477D02* +X889Y477D01* +X927Y477D02* +X935Y477D01* +X973Y477D02* +X982Y477D01* +X2595Y477D02* +X2602Y477D01* +X1Y476D02* +X8Y476D01* +X216Y476D02* +X224Y476D01* +X342Y476D02* +X350Y476D01* +X375Y476D02* +X384Y476D01* +X422Y476D02* +X430Y476D01* +X477Y476D02* +X486Y476D01* +X493Y476D02* +X502Y476D01* +X531Y476D02* +X539Y476D01* +X656Y476D02* +X664Y476D01* +X675Y476D02* +X682Y476D01* +X692Y476D02* +X700Y476D01* +X721Y476D02* +X730Y476D01* +X753Y476D02* +X762Y476D01* +X784Y476D02* +X793Y476D01* +X811Y476D02* +X826Y476D01* +X848Y476D02* +X856Y476D01* +X872Y476D02* +X889Y476D01* +X927Y476D02* +X935Y476D01* +X973Y476D02* +X983Y476D01* +X2595Y476D02* +X2602Y476D01* +X1Y475D02* +X8Y475D01* +X216Y475D02* +X224Y475D01* +X342Y475D02* +X350Y475D01* +X376Y475D02* +X384Y475D01* +X422Y475D02* +X430Y475D01* +X477Y475D02* +X486Y475D01* +X492Y475D02* +X501Y475D01* +X531Y475D02* +X539Y475D01* +X656Y475D02* +X664Y475D01* +X675Y475D02* +X682Y475D01* +X692Y475D02* +X700Y475D01* +X721Y475D02* +X731Y475D01* +X752Y475D02* +X762Y475D01* +X784Y475D02* +X795Y475D01* +X810Y475D02* +X826Y475D01* +X848Y475D02* +X856Y475D01* +X870Y475D02* +X889Y475D01* +X927Y475D02* +X935Y475D01* +X973Y475D02* +X984Y475D01* +X2595Y475D02* +X2602Y475D01* +X1Y474D02* +X8Y474D01* +X216Y474D02* +X224Y474D01* +X342Y474D02* +X351Y474D01* +X377Y474D02* +X384Y474D01* +X422Y474D02* +X430Y474D01* +X478Y474D02* +X487Y474D01* +X492Y474D02* +X501Y474D01* +X531Y474D02* +X539Y474D01* +X656Y474D02* +X664Y474D01* +X675Y474D02* +X682Y474D01* +X692Y474D02* +X700Y474D01* +X722Y474D02* +X733Y474D01* +X750Y474D02* +X761Y474D01* +X785Y474D02* +X796Y474D01* +X809Y474D02* +X826Y474D01* +X848Y474D02* +X857Y474D01* +X868Y474D02* +X889Y474D01* +X927Y474D02* +X935Y474D01* +X974Y474D02* +X985Y474D01* +X2595Y474D02* +X2602Y474D01* +X1Y473D02* +X8Y473D01* +X216Y473D02* +X224Y473D01* +X342Y473D02* +X353Y473D01* +X376Y473D02* +X384Y473D01* +X422Y473D02* +X430Y473D01* +X478Y473D02* +X500Y473D01* +X531Y473D02* +X539Y473D01* +X656Y473D02* +X664Y473D01* +X675Y473D02* +X682Y473D01* +X692Y473D02* +X700Y473D01* +X722Y473D02* +X735Y473D01* +X748Y473D02* +X761Y473D01* +X785Y473D02* +X798Y473D01* +X806Y473D02* +X826Y473D01* +X848Y473D02* +X859Y473D01* +X867Y473D02* +X889Y473D01* +X926Y473D02* +X935Y473D01* +X974Y473D02* +X988Y473D01* +X2595Y473D02* +X2602Y473D01* +X1Y472D02* +X8Y472D01* +X216Y472D02* +X257Y472D01* +X343Y472D02* +X384Y472D01* +X422Y472D02* +X430Y472D01* +X479Y472D02* +X500Y472D01* +X531Y472D02* +X539Y472D01* +X656Y472D02* +X664Y472D01* +X675Y472D02* +X682Y472D01* +X692Y472D02* +X700Y472D01* +X723Y472D02* +X760Y472D01* +X786Y472D02* +X826Y472D01* +X849Y472D02* +X889Y472D01* +X916Y472D02* +X946Y472D01* +X975Y472D02* +X1013Y472D01* +X2595Y472D02* +X2602Y472D01* +X1Y471D02* +X8Y471D01* +X216Y471D02* +X257Y471D01* +X343Y471D02* +X384Y471D01* +X422Y471D02* +X430Y471D01* +X479Y471D02* +X499Y471D01* +X531Y471D02* +X539Y471D01* +X656Y471D02* +X664Y471D01* +X675Y471D02* +X682Y471D01* +X692Y471D02* +X700Y471D01* +X724Y471D02* +X759Y471D01* +X787Y471D02* +X826Y471D01* +X849Y471D02* +X879Y471D01* +X881Y471D02* +X889Y471D01* +X915Y471D02* +X947Y471D01* +X976Y471D02* +X1014Y471D01* +X2595Y471D02* +X2602Y471D01* +X1Y470D02* +X8Y470D01* +X216Y470D02* +X258Y470D01* +X344Y470D02* +X383Y470D01* +X422Y470D02* +X430Y470D01* +X480Y470D02* +X499Y470D01* +X531Y470D02* +X539Y470D01* +X656Y470D02* +X664Y470D01* +X675Y470D02* +X682Y470D01* +X693Y470D02* +X700Y470D01* +X725Y470D02* +X758Y470D01* +X788Y470D02* +X826Y470D01* +X850Y470D02* +X878Y470D01* +X881Y470D02* +X889Y470D01* +X914Y470D02* +X947Y470D01* +X977Y470D02* +X1015Y470D01* +X2595Y470D02* +X2602Y470D01* +X1Y469D02* +X8Y469D01* +X216Y469D02* +X258Y469D01* +X344Y469D02* +X383Y469D01* +X422Y469D02* +X430Y469D01* +X480Y469D02* +X498Y469D01* +X531Y469D02* +X539Y469D01* +X656Y469D02* +X664Y469D01* +X675Y469D02* +X682Y469D01* +X693Y469D02* +X700Y469D01* +X726Y469D02* +X757Y469D01* +X789Y469D02* +X816Y469D01* +X818Y469D02* +X826Y469D01* +X850Y469D02* +X876Y469D01* +X881Y469D02* +X889Y469D01* +X914Y469D02* +X948Y469D01* +X978Y469D02* +X1015Y469D01* +X2595Y469D02* +X2602Y469D01* +X1Y468D02* +X8Y468D01* +X216Y468D02* +X258Y468D01* +X345Y468D02* +X382Y468D01* +X422Y468D02* +X430Y468D01* +X481Y468D02* +X497Y468D01* +X531Y468D02* +X539Y468D01* +X657Y468D02* +X664Y468D01* +X675Y468D02* +X682Y468D01* +X693Y468D02* +X700Y468D01* +X727Y468D02* +X756Y468D01* +X790Y468D02* +X815Y468D01* +X818Y468D02* +X826Y468D01* +X851Y468D02* +X874Y468D01* +X881Y468D02* +X889Y468D01* +X914Y468D02* +X948Y468D01* +X979Y468D02* +X1015Y468D01* +X2595Y468D02* +X2602Y468D01* +X1Y467D02* +X8Y467D01* +X216Y467D02* +X258Y467D01* +X346Y467D02* +X381Y467D01* +X423Y467D02* +X430Y467D01* +X482Y467D02* +X496Y467D01* +X531Y467D02* +X539Y467D01* +X657Y467D02* +X664Y467D01* +X675Y467D02* +X682Y467D01* +X693Y467D02* +X700Y467D01* +X728Y467D02* +X755Y467D01* +X791Y467D02* +X814Y467D01* +X818Y467D02* +X826Y467D01* +X852Y467D02* +X873Y467D01* +X881Y467D02* +X889Y467D01* +X914Y467D02* +X947Y467D01* +X981Y467D02* +X1015Y467D01* +X2595Y467D02* +X2602Y467D01* +X1Y466D02* +X8Y466D01* +X216Y466D02* +X257Y466D01* +X347Y466D02* +X380Y466D01* +X423Y466D02* +X429Y466D01* +X484Y466D02* +X495Y466D01* +X532Y466D02* +X538Y466D01* +X657Y466D02* +X663Y466D01* +X675Y466D02* +X681Y466D01* +X694Y466D02* +X700Y466D01* +X730Y466D02* +X753Y466D01* +X793Y466D02* +X812Y466D01* +X819Y466D02* +X825Y466D01* +X854Y466D02* +X871Y466D01* +X882Y466D02* +X888Y466D01* +X915Y466D02* +X947Y466D01* +X982Y466D02* +X1014Y466D01* +X2595Y466D02* +X2602Y466D01* +X1Y465D02* +X8Y465D01* +X216Y465D02* +X256Y465D01* +X349Y465D02* +X379Y465D01* +X424Y465D02* +X428Y465D01* +X486Y465D02* +X493Y465D01* +X533Y465D02* +X537Y465D01* +X658Y465D02* +X662Y465D01* +X676Y465D02* +X680Y465D01* +X695Y465D02* +X699Y465D01* +X732Y465D02* +X751Y465D01* +X795Y465D02* +X810Y465D01* +X820Y465D02* +X824Y465D01* +X856Y465D02* +X869Y465D01* +X883Y465D02* +X887Y465D01* +X916Y465D02* +X946Y465D01* +X984Y465D02* +X1013Y465D01* +X2595Y465D02* +X2602Y465D01* +X1Y464D02* +X8Y464D01* +X2595Y464D02* +X2602Y464D01* +X1Y463D02* +X8Y463D01* +X2595Y463D02* +X2602Y463D01* +X1Y462D02* +X8Y462D01* +X2595Y462D02* +X2602Y462D01* +X1Y461D02* +X8Y461D01* +X2595Y461D02* +X2602Y461D01* +X1Y460D02* +X8Y460D01* +X2595Y460D02* +X2602Y460D01* +X1Y459D02* +X8Y459D01* +X2595Y459D02* +X2602Y459D01* +X1Y458D02* +X8Y458D01* +X2595Y458D02* +X2602Y458D01* +X1Y457D02* +X8Y457D01* +X2595Y457D02* +X2602Y457D01* +X1Y456D02* +X8Y456D01* +X2595Y456D02* +X2602Y456D01* +X1Y455D02* +X8Y455D01* +X2595Y455D02* +X2602Y455D01* +X1Y454D02* +X8Y454D01* +X2595Y454D02* +X2602Y454D01* +X1Y453D02* +X8Y453D01* +X2595Y453D02* +X2602Y453D01* +X1Y452D02* +X8Y452D01* +X2595Y452D02* +X2602Y452D01* +X1Y451D02* +X8Y451D01* +X2595Y451D02* +X2602Y451D01* +X1Y450D02* +X8Y450D01* +X2595Y450D02* +X2602Y450D01* +X1Y449D02* +X8Y449D01* +X2595Y449D02* +X2602Y449D01* +X1Y448D02* +X8Y448D01* +X2595Y448D02* +X2602Y448D01* +X1Y447D02* +X8Y447D01* +X2595Y447D02* +X2602Y447D01* +X1Y446D02* +X8Y446D01* +X2595Y446D02* +X2602Y446D01* +X1Y445D02* +X8Y445D01* +X2595Y445D02* +X2602Y445D01* +X1Y444D02* +X8Y444D01* +X2595Y444D02* +X2602Y444D01* +X1Y443D02* +X8Y443D01* +X2595Y443D02* +X2602Y443D01* +X1Y442D02* +X8Y442D01* +X2595Y442D02* +X2602Y442D01* +X1Y441D02* +X8Y441D01* +X2595Y441D02* +X2602Y441D01* +X1Y440D02* +X8Y440D01* +X2595Y440D02* +X2602Y440D01* +X1Y439D02* +X8Y439D01* +X2595Y439D02* +X2602Y439D01* +X1Y438D02* +X8Y438D01* +X2595Y438D02* +X2602Y438D01* +X1Y437D02* +X8Y437D01* +X2595Y437D02* +X2602Y437D01* +X1Y436D02* +X8Y436D01* +X2595Y436D02* +X2602Y436D01* +X1Y435D02* +X8Y435D01* +X2595Y435D02* +X2602Y435D01* +X1Y434D02* +X8Y434D01* +X2595Y434D02* +X2602Y434D01* +X1Y433D02* +X8Y433D01* +X2595Y433D02* +X2602Y433D01* +X1Y432D02* +X8Y432D01* +X2595Y432D02* +X2602Y432D01* +X1Y431D02* +X8Y431D01* +X2595Y431D02* +X2602Y431D01* +X1Y430D02* +X8Y430D01* +X2595Y430D02* +X2602Y430D01* +X1Y429D02* +X8Y429D01* +X2595Y429D02* +X2602Y429D01* +X1Y428D02* +X8Y428D01* +X2595Y428D02* +X2602Y428D01* +X1Y427D02* +X8Y427D01* +X2595Y427D02* +X2602Y427D01* +X1Y426D02* +X8Y426D01* +X2595Y426D02* +X2602Y426D01* +X1Y425D02* +X8Y425D01* +X2595Y425D02* +X2602Y425D01* +X1Y424D02* +X8Y424D01* +X2595Y424D02* +X2602Y424D01* +X1Y423D02* +X8Y423D01* +X2595Y423D02* +X2602Y423D01* +X1Y422D02* +X8Y422D01* +X2595Y422D02* +X2602Y422D01* +X1Y421D02* +X8Y421D01* +X2595Y421D02* +X2602Y421D01* +X1Y420D02* +X8Y420D01* +X2595Y420D02* +X2602Y420D01* +X1Y419D02* +X8Y419D01* +X2595Y419D02* +X2602Y419D01* +X1Y418D02* +X8Y418D01* +X2595Y418D02* +X2602Y418D01* +X1Y417D02* +X8Y417D01* +X2595Y417D02* +X2602Y417D01* +X1Y416D02* +X8Y416D01* +X2595Y416D02* +X2602Y416D01* +X1Y415D02* +X8Y415D01* +X2595Y415D02* +X2602Y415D01* +X1Y414D02* +X8Y414D01* +X2595Y414D02* +X2602Y414D01* +X1Y413D02* +X8Y413D01* +X2595Y413D02* +X2602Y413D01* +X1Y412D02* +X8Y412D01* +X2595Y412D02* +X2602Y412D01* +X1Y411D02* +X8Y411D01* +X2595Y411D02* +X2602Y411D01* +X1Y410D02* +X8Y410D01* +X2595Y410D02* +X2602Y410D01* +X1Y409D02* +X8Y409D01* +X2595Y409D02* +X2602Y409D01* +X1Y408D02* +X8Y408D01* +X2595Y408D02* +X2602Y408D01* +X1Y407D02* +X8Y407D01* +X2595Y407D02* +X2602Y407D01* +X1Y406D02* +X8Y406D01* +X2595Y406D02* +X2602Y406D01* +X1Y405D02* +X8Y405D01* +X2595Y405D02* +X2602Y405D01* +X1Y404D02* +X8Y404D01* +X2595Y404D02* +X2602Y404D01* +X1Y403D02* +X8Y403D01* +X2595Y403D02* +X2602Y403D01* +X1Y402D02* +X8Y402D01* +X2595Y402D02* +X2602Y402D01* +X1Y401D02* +X8Y401D01* +X2595Y401D02* +X2602Y401D01* +X1Y400D02* +X8Y400D01* +X2595Y400D02* +X2602Y400D01* +X1Y399D02* +X8Y399D01* +X2595Y399D02* +X2602Y399D01* +X1Y398D02* +X8Y398D01* +X2595Y398D02* +X2602Y398D01* +X1Y397D02* +X8Y397D01* +X2595Y397D02* +X2602Y397D01* +X1Y396D02* +X8Y396D01* +X2595Y396D02* +X2602Y396D01* +X1Y395D02* +X8Y395D01* +X2595Y395D02* +X2602Y395D01* +X1Y394D02* +X8Y394D01* +X2595Y394D02* +X2602Y394D01* +X1Y393D02* +X8Y393D01* +X2595Y393D02* +X2602Y393D01* +X1Y392D02* +X8Y392D01* +X2595Y392D02* +X2602Y392D01* +X1Y391D02* +X8Y391D01* +X2595Y391D02* +X2602Y391D01* +X1Y390D02* +X8Y390D01* +X2595Y390D02* +X2602Y390D01* +X1Y389D02* +X8Y389D01* +X2595Y389D02* +X2602Y389D01* +X1Y388D02* +X8Y388D01* +X2595Y388D02* +X2602Y388D01* +X1Y387D02* +X8Y387D01* +X2595Y387D02* +X2602Y387D01* +X1Y386D02* +X8Y386D01* +X2595Y386D02* +X2602Y386D01* +X1Y385D02* +X8Y385D01* +X2595Y385D02* +X2602Y385D01* +X1Y384D02* +X8Y384D01* +X2595Y384D02* +X2602Y384D01* +X1Y383D02* +X8Y383D01* +X2595Y383D02* +X2602Y383D01* +X1Y382D02* +X8Y382D01* +X2595Y382D02* +X2602Y382D01* +X1Y381D02* +X8Y381D01* +X2595Y381D02* +X2602Y381D01* +X1Y380D02* +X8Y380D01* +X2595Y380D02* +X2602Y380D01* +X1Y379D02* +X8Y379D01* +X2595Y379D02* +X2602Y379D01* +X1Y378D02* +X8Y378D01* +X2595Y378D02* +X2602Y378D01* +X1Y377D02* +X8Y377D01* +X2595Y377D02* +X2602Y377D01* +X1Y376D02* +X8Y376D01* +X2595Y376D02* +X2602Y376D01* +X1Y375D02* +X8Y375D01* +X2595Y375D02* +X2602Y375D01* +X1Y374D02* +X8Y374D01* +X2595Y374D02* +X2602Y374D01* +X1Y373D02* +X8Y373D01* +X2595Y373D02* +X2602Y373D01* +X1Y372D02* +X8Y372D01* +X2595Y372D02* +X2602Y372D01* +X1Y371D02* +X8Y371D01* +X2595Y371D02* +X2602Y371D01* +X1Y370D02* +X8Y370D01* +X2595Y370D02* +X2602Y370D01* +X1Y369D02* +X8Y369D01* +X2595Y369D02* +X2602Y369D01* +X1Y368D02* +X8Y368D01* +X2595Y368D02* +X2602Y368D01* +X1Y367D02* +X8Y367D01* +X2595Y367D02* +X2602Y367D01* +X1Y366D02* +X8Y366D01* +X2595Y366D02* +X2602Y366D01* +X1Y365D02* +X8Y365D01* +X2595Y365D02* +X2602Y365D01* +X1Y364D02* +X8Y364D01* +X2595Y364D02* +X2602Y364D01* +X1Y363D02* +X8Y363D01* +X2595Y363D02* +X2602Y363D01* +X1Y362D02* +X8Y362D01* +X2595Y362D02* +X2602Y362D01* +X1Y361D02* +X8Y361D01* +X2595Y361D02* +X2602Y361D01* +X1Y360D02* +X8Y360D01* +X2595Y360D02* +X2602Y360D01* +X1Y359D02* +X8Y359D01* +X2595Y359D02* +X2602Y359D01* +X1Y358D02* +X8Y358D01* +X2595Y358D02* +X2602Y358D01* +X1Y357D02* +X8Y357D01* +X2595Y357D02* +X2602Y357D01* +X1Y356D02* +X8Y356D01* +X2595Y356D02* +X2602Y356D01* +X1Y355D02* +X8Y355D01* +X2595Y355D02* +X2602Y355D01* +X1Y354D02* +X8Y354D01* +X2595Y354D02* +X2602Y354D01* +X1Y353D02* +X8Y353D01* +X2595Y353D02* +X2602Y353D01* +X1Y352D02* +X8Y352D01* +X2595Y352D02* +X2602Y352D01* +X1Y351D02* +X8Y351D01* +X2595Y351D02* +X2602Y351D01* +X1Y350D02* +X8Y350D01* +X2595Y350D02* +X2602Y350D01* +X1Y349D02* +X8Y349D01* +X2595Y349D02* +X2602Y349D01* +X1Y348D02* +X8Y348D01* +X2595Y348D02* +X2602Y348D01* +X1Y347D02* +X8Y347D01* +X2595Y347D02* +X2602Y347D01* +X1Y346D02* +X8Y346D01* +X2595Y346D02* +X2602Y346D01* +X1Y345D02* +X8Y345D01* +X2595Y345D02* +X2602Y345D01* +X1Y344D02* +X8Y344D01* +X2595Y344D02* +X2602Y344D01* +X1Y343D02* +X8Y343D01* +X2595Y343D02* +X2602Y343D01* +X1Y342D02* +X8Y342D01* +X2595Y342D02* +X2602Y342D01* +X1Y341D02* +X8Y341D01* +X2595Y341D02* +X2602Y341D01* +X1Y340D02* +X8Y340D01* +X2595Y340D02* +X2602Y340D01* +X1Y339D02* +X8Y339D01* +X2595Y339D02* +X2602Y339D01* +X1Y338D02* +X8Y338D01* +X2595Y338D02* +X2602Y338D01* +X1Y337D02* +X8Y337D01* +X2595Y337D02* +X2602Y337D01* +X1Y336D02* +X8Y336D01* +X2595Y336D02* +X2602Y336D01* +X1Y335D02* +X8Y335D01* +X2595Y335D02* +X2602Y335D01* +X1Y334D02* +X8Y334D01* +X2595Y334D02* +X2602Y334D01* +X1Y333D02* +X8Y333D01* +X2595Y333D02* +X2602Y333D01* +X1Y332D02* +X8Y332D01* +X2595Y332D02* +X2602Y332D01* +X1Y331D02* +X8Y331D01* +X2595Y331D02* +X2602Y331D01* +X1Y330D02* +X8Y330D01* +X2595Y330D02* +X2602Y330D01* +X1Y329D02* +X8Y329D01* +X2595Y329D02* +X2602Y329D01* +X1Y328D02* +X8Y328D01* +X2595Y328D02* +X2602Y328D01* +X1Y327D02* +X8Y327D01* +X2595Y327D02* +X2602Y327D01* +X1Y326D02* +X8Y326D01* +X2595Y326D02* +X2602Y326D01* +X1Y325D02* +X8Y325D01* +X2595Y325D02* +X2602Y325D01* +X1Y324D02* +X8Y324D01* +X2595Y324D02* +X2602Y324D01* +X1Y323D02* +X8Y323D01* +X2595Y323D02* +X2602Y323D01* +X1Y322D02* +X8Y322D01* +X2595Y322D02* +X2602Y322D01* +X1Y321D02* +X8Y321D01* +X2595Y321D02* +X2602Y321D01* +X1Y320D02* +X8Y320D01* +X2595Y320D02* +X2602Y320D01* +X1Y319D02* +X8Y319D01* +X2595Y319D02* +X2602Y319D01* +X1Y318D02* +X8Y318D01* +X2595Y318D02* +X2602Y318D01* +X1Y317D02* +X8Y317D01* +X2595Y317D02* +X2602Y317D01* +X1Y316D02* +X8Y316D01* +X2595Y316D02* +X2602Y316D01* +X1Y315D02* +X8Y315D01* +X2595Y315D02* +X2602Y315D01* +X1Y314D02* +X8Y314D01* +X2595Y314D02* +X2602Y314D01* +X1Y313D02* +X8Y313D01* +X2595Y313D02* +X2602Y313D01* +X1Y312D02* +X8Y312D01* +X2595Y312D02* +X2602Y312D01* +X1Y311D02* +X8Y311D01* +X2595Y311D02* +X2602Y311D01* +X1Y310D02* +X8Y310D01* +X2595Y310D02* +X2602Y310D01* +X1Y309D02* +X8Y309D01* +X2595Y309D02* +X2602Y309D01* +X1Y308D02* +X8Y308D01* +X2595Y308D02* +X2602Y308D01* +X1Y307D02* +X8Y307D01* +X2595Y307D02* +X2602Y307D01* +X1Y306D02* +X8Y306D01* +X2595Y306D02* +X2602Y306D01* +X1Y305D02* +X8Y305D01* +X2595Y305D02* +X2602Y305D01* +X1Y304D02* +X8Y304D01* +X2595Y304D02* +X2602Y304D01* +X1Y303D02* +X8Y303D01* +X2595Y303D02* +X2602Y303D01* +X1Y302D02* +X8Y302D01* +X2595Y302D02* +X2602Y302D01* +X1Y301D02* +X8Y301D01* +X2595Y301D02* +X2602Y301D01* +X1Y300D02* +X8Y300D01* +X2595Y300D02* +X2602Y300D01* +X1Y299D02* +X8Y299D01* +X2595Y299D02* +X2602Y299D01* +X1Y298D02* +X8Y298D01* +X2595Y298D02* +X2602Y298D01* +X1Y297D02* +X8Y297D01* +X2595Y297D02* +X2602Y297D01* +X1Y296D02* +X8Y296D01* +X2595Y296D02* +X2602Y296D01* +X1Y295D02* +X8Y295D01* +X2595Y295D02* +X2602Y295D01* +X1Y294D02* +X8Y294D01* +X2595Y294D02* +X2602Y294D01* +X1Y293D02* +X8Y293D01* +X2595Y293D02* +X2602Y293D01* +X1Y292D02* +X8Y292D01* +X2595Y292D02* +X2602Y292D01* +X1Y291D02* +X8Y291D01* +X2595Y291D02* +X2602Y291D01* +X1Y290D02* +X8Y290D01* +X2595Y290D02* +X2602Y290D01* +X1Y289D02* +X8Y289D01* +X2595Y289D02* +X2602Y289D01* +X1Y288D02* +X8Y288D01* +X2595Y288D02* +X2602Y288D01* +X1Y287D02* +X8Y287D01* +X2595Y287D02* +X2602Y287D01* +X1Y286D02* +X8Y286D01* +X2595Y286D02* +X2602Y286D01* +X1Y285D02* +X8Y285D01* +X2595Y285D02* +X2602Y285D01* +X1Y284D02* +X8Y284D01* +X2595Y284D02* +X2602Y284D01* +X1Y283D02* +X8Y283D01* +X2595Y283D02* +X2602Y283D01* +X1Y282D02* +X8Y282D01* +X2595Y282D02* +X2602Y282D01* +X1Y281D02* +X8Y281D01* +X2595Y281D02* +X2602Y281D01* +X1Y280D02* +X8Y280D01* +X2595Y280D02* +X2602Y280D01* +X1Y279D02* +X8Y279D01* +X2595Y279D02* +X2602Y279D01* +X1Y278D02* +X8Y278D01* +X2595Y278D02* +X2602Y278D01* +X1Y277D02* +X8Y277D01* +X2595Y277D02* +X2602Y277D01* +X1Y276D02* +X8Y276D01* +X2595Y276D02* +X2602Y276D01* +X1Y275D02* +X8Y275D01* +X2595Y275D02* +X2602Y275D01* +X1Y274D02* +X8Y274D01* +X2595Y274D02* +X2602Y274D01* +X1Y273D02* +X8Y273D01* +X2595Y273D02* +X2602Y273D01* +X1Y272D02* +X8Y272D01* +X2595Y272D02* +X2602Y272D01* +X1Y271D02* +X8Y271D01* +X2595Y271D02* +X2602Y271D01* +X1Y270D02* +X8Y270D01* +X2595Y270D02* +X2602Y270D01* +X1Y269D02* +X8Y269D01* +X2595Y269D02* +X2602Y269D01* +X1Y268D02* +X8Y268D01* +X2595Y268D02* +X2602Y268D01* +X1Y267D02* +X8Y267D01* +X2595Y267D02* +X2602Y267D01* +X1Y266D02* +X8Y266D01* +X2595Y266D02* +X2602Y266D01* +X1Y265D02* +X8Y265D01* +X2595Y265D02* +X2602Y265D01* +X1Y264D02* +X8Y264D01* +X2595Y264D02* +X2602Y264D01* +X1Y263D02* +X8Y263D01* +X2595Y263D02* +X2602Y263D01* +X1Y262D02* +X8Y262D01* +X2595Y262D02* +X2602Y262D01* +X1Y261D02* +X8Y261D01* +X2595Y261D02* +X2602Y261D01* +X1Y260D02* +X8Y260D01* +X2595Y260D02* +X2602Y260D01* +X1Y259D02* +X8Y259D01* +X2595Y259D02* +X2602Y259D01* +X1Y258D02* +X8Y258D01* +X2595Y258D02* +X2602Y258D01* +X1Y257D02* +X8Y257D01* +X2595Y257D02* +X2602Y257D01* +X1Y256D02* +X8Y256D01* +X2595Y256D02* +X2602Y256D01* +X1Y255D02* +X8Y255D01* +X2595Y255D02* +X2602Y255D01* +X1Y254D02* +X8Y254D01* +X2595Y254D02* +X2602Y254D01* +X1Y253D02* +X8Y253D01* +X2595Y253D02* +X2602Y253D01* +X1Y252D02* +X8Y252D01* +X2595Y252D02* +X2602Y252D01* +X1Y251D02* +X8Y251D01* +X2595Y251D02* +X2602Y251D01* +X1Y250D02* +X8Y250D01* +X2595Y250D02* +X2602Y250D01* +X1Y249D02* +X8Y249D01* +X2595Y249D02* +X2602Y249D01* +X1Y248D02* +X8Y248D01* +X2595Y248D02* +X2602Y248D01* +X1Y247D02* +X8Y247D01* +X2595Y247D02* +X2602Y247D01* +X1Y246D02* +X8Y246D01* +X2595Y246D02* +X2602Y246D01* +X1Y245D02* +X8Y245D01* +X2595Y245D02* +X2602Y245D01* +X1Y244D02* +X8Y244D01* +X2595Y244D02* +X2602Y244D01* +X1Y243D02* +X8Y243D01* +X2595Y243D02* +X2602Y243D01* +X1Y242D02* +X8Y242D01* +X2595Y242D02* +X2602Y242D01* +X1Y241D02* +X8Y241D01* +X2595Y241D02* +X2602Y241D01* +X1Y240D02* +X8Y240D01* +X2595Y240D02* +X2602Y240D01* +X1Y239D02* +X8Y239D01* +X2595Y239D02* +X2602Y239D01* +X1Y238D02* +X8Y238D01* +X2595Y238D02* +X2602Y238D01* +X1Y237D02* +X8Y237D01* +X2595Y237D02* +X2602Y237D01* +X1Y236D02* +X8Y236D01* +X2595Y236D02* +X2602Y236D01* +X1Y235D02* +X8Y235D01* +X2595Y235D02* +X2602Y235D01* +X1Y234D02* +X8Y234D01* +X2595Y234D02* +X2602Y234D01* +X1Y233D02* +X8Y233D01* +X2595Y233D02* +X2602Y233D01* +X1Y232D02* +X8Y232D01* +X2595Y232D02* +X2602Y232D01* +X1Y231D02* +X8Y231D01* +X2595Y231D02* +X2602Y231D01* +X1Y230D02* +X8Y230D01* +X2595Y230D02* +X2602Y230D01* +X1Y229D02* +X8Y229D01* +X2595Y229D02* +X2602Y229D01* +X1Y228D02* +X8Y228D01* +X2595Y228D02* +X2602Y228D01* +X1Y227D02* +X8Y227D01* +X2595Y227D02* +X2602Y227D01* +X1Y226D02* +X8Y226D01* +X2595Y226D02* +X2602Y226D01* +X1Y225D02* +X8Y225D01* +X2595Y225D02* +X2602Y225D01* +X1Y224D02* +X8Y224D01* +X2595Y224D02* +X2602Y224D01* +X1Y223D02* +X8Y223D01* +X2595Y223D02* +X2602Y223D01* +X1Y222D02* +X8Y222D01* +X2595Y222D02* +X2602Y222D01* +X1Y221D02* +X8Y221D01* +X2595Y221D02* +X2602Y221D01* +X1Y220D02* +X8Y220D01* +X2595Y220D02* +X2602Y220D01* +X1Y219D02* +X8Y219D01* +X2595Y219D02* +X2602Y219D01* +X1Y218D02* +X8Y218D01* +X2595Y218D02* +X2602Y218D01* +X1Y217D02* +X8Y217D01* +X2595Y217D02* +X2602Y217D01* +X1Y216D02* +X8Y216D01* +X2595Y216D02* +X2602Y216D01* +X1Y215D02* +X8Y215D01* +X2595Y215D02* +X2602Y215D01* +X1Y214D02* +X8Y214D01* +X2595Y214D02* +X2602Y214D01* +X1Y213D02* +X8Y213D01* +X2595Y213D02* +X2602Y213D01* +X1Y212D02* +X8Y212D01* +X2595Y212D02* +X2602Y212D01* +X1Y211D02* +X8Y211D01* +X2595Y211D02* +X2602Y211D01* +X1Y210D02* +X8Y210D01* +X2595Y210D02* +X2602Y210D01* +X1Y209D02* +X8Y209D01* +X2595Y209D02* +X2602Y209D01* +X1Y208D02* +X8Y208D01* +X2595Y208D02* +X2602Y208D01* +X1Y207D02* +X8Y207D01* +X2595Y207D02* +X2602Y207D01* +X1Y206D02* +X8Y206D01* +X2595Y206D02* +X2602Y206D01* +X1Y205D02* +X8Y205D01* +X2595Y205D02* +X2602Y205D01* +X1Y204D02* +X8Y204D01* +X2595Y204D02* +X2602Y204D01* +X1Y203D02* +X8Y203D01* +X2595Y203D02* +X2602Y203D01* +X1Y202D02* +X8Y202D01* +X2595Y202D02* +X2602Y202D01* +X1Y201D02* +X8Y201D01* +X2595Y201D02* +X2602Y201D01* +X1Y200D02* +X8Y200D01* +X2595Y200D02* +X2602Y200D01* +X1Y199D02* +X8Y199D01* +X2595Y199D02* +X2602Y199D01* +X1Y198D02* +X8Y198D01* +X2595Y198D02* +X2602Y198D01* +X1Y197D02* +X8Y197D01* +X2595Y197D02* +X2602Y197D01* +X1Y196D02* +X8Y196D01* +X2595Y196D02* +X2602Y196D01* +X1Y195D02* +X8Y195D01* +X2595Y195D02* +X2602Y195D01* +X1Y194D02* +X8Y194D01* +X2595Y194D02* +X2602Y194D01* +X1Y193D02* +X8Y193D01* +X2595Y193D02* +X2602Y193D01* +X1Y192D02* +X8Y192D01* +X2595Y192D02* +X2602Y192D01* +X1Y191D02* +X8Y191D01* +X2595Y191D02* +X2602Y191D01* +X1Y190D02* +X8Y190D01* +X2595Y190D02* +X2602Y190D01* +X1Y189D02* +X8Y189D01* +X2595Y189D02* +X2602Y189D01* +X1Y188D02* +X8Y188D01* +X2595Y188D02* +X2602Y188D01* +X1Y187D02* +X8Y187D01* +X2595Y187D02* +X2602Y187D01* +X1Y186D02* +X8Y186D01* +X2595Y186D02* +X2602Y186D01* +X1Y185D02* +X8Y185D01* +X2595Y185D02* +X2602Y185D01* +X1Y184D02* +X8Y184D01* +X2595Y184D02* +X2602Y184D01* +X1Y183D02* +X8Y183D01* +X2595Y183D02* +X2602Y183D01* +X1Y182D02* +X8Y182D01* +X2595Y182D02* +X2602Y182D01* +X1Y181D02* +X8Y181D01* +X2595Y181D02* +X2602Y181D01* +X1Y180D02* +X8Y180D01* +X2595Y180D02* +X2602Y180D01* +X1Y179D02* +X8Y179D01* +X2595Y179D02* +X2602Y179D01* +X1Y178D02* +X8Y178D01* +X2595Y178D02* +X2602Y178D01* +X1Y177D02* +X8Y177D01* +X2595Y177D02* +X2602Y177D01* +X1Y176D02* +X8Y176D01* +X2595Y176D02* +X2602Y176D01* +X1Y175D02* +X8Y175D01* +X2595Y175D02* +X2602Y175D01* +X1Y174D02* +X8Y174D01* +X2595Y174D02* +X2602Y174D01* +X1Y173D02* +X8Y173D01* +X2595Y173D02* +X2602Y173D01* +X1Y172D02* +X8Y172D01* +X2595Y172D02* +X2602Y172D01* +X1Y171D02* +X8Y171D01* +X2595Y171D02* +X2602Y171D01* +X1Y170D02* +X8Y170D01* +X2595Y170D02* +X2602Y170D01* +X1Y169D02* +X8Y169D01* +X2595Y169D02* +X2602Y169D01* +X1Y168D02* +X8Y168D01* +X2595Y168D02* +X2602Y168D01* +X1Y167D02* +X8Y167D01* +X2595Y167D02* +X2602Y167D01* +X1Y166D02* +X8Y166D01* +X2595Y166D02* +X2602Y166D01* +X1Y165D02* +X8Y165D01* +X2595Y165D02* +X2602Y165D01* +X1Y164D02* +X8Y164D01* +X2595Y164D02* +X2602Y164D01* +X1Y163D02* +X8Y163D01* +X2595Y163D02* +X2602Y163D01* +X1Y162D02* +X8Y162D01* +X2595Y162D02* +X2602Y162D01* +X1Y161D02* +X8Y161D01* +X2595Y161D02* +X2602Y161D01* +X1Y160D02* +X8Y160D01* +X2595Y160D02* +X2602Y160D01* +X1Y159D02* +X8Y159D01* +X2595Y159D02* +X2602Y159D01* +X1Y158D02* +X8Y158D01* +X2595Y158D02* +X2602Y158D01* +X1Y157D02* +X8Y157D01* +X2595Y157D02* +X2602Y157D01* +X1Y156D02* +X8Y156D01* +X2595Y156D02* +X2602Y156D01* +X1Y155D02* +X8Y155D01* +X2595Y155D02* +X2602Y155D01* +X1Y154D02* +X8Y154D01* +X2595Y154D02* +X2602Y154D01* +X1Y153D02* +X8Y153D01* +X2595Y153D02* +X2602Y153D01* +X1Y152D02* +X8Y152D01* +X2595Y152D02* +X2602Y152D01* +X1Y151D02* +X8Y151D01* +X2595Y151D02* +X2602Y151D01* +X1Y150D02* +X8Y150D01* +X2595Y150D02* +X2602Y150D01* +X1Y149D02* +X8Y149D01* +X2595Y149D02* +X2602Y149D01* +X1Y148D02* +X8Y148D01* +X2595Y148D02* +X2602Y148D01* +X1Y147D02* +X8Y147D01* +X2595Y147D02* +X2602Y147D01* +X1Y146D02* +X8Y146D01* +X2595Y146D02* +X2602Y146D01* +X1Y145D02* +X8Y145D01* +X2595Y145D02* +X2602Y145D01* +X1Y144D02* +X8Y144D01* +X2595Y144D02* +X2602Y144D01* +X1Y143D02* +X8Y143D01* +X2595Y143D02* +X2602Y143D01* +X1Y142D02* +X8Y142D01* +X2595Y142D02* +X2602Y142D01* +X1Y141D02* +X8Y141D01* +X2595Y141D02* +X2602Y141D01* +X1Y140D02* +X8Y140D01* +X2595Y140D02* +X2602Y140D01* +X1Y139D02* +X8Y139D01* +X2595Y139D02* +X2602Y139D01* +X1Y138D02* +X8Y138D01* +X2595Y138D02* +X2602Y138D01* +X1Y137D02* +X8Y137D01* +X2595Y137D02* +X2602Y137D01* +X1Y136D02* +X8Y136D01* +X2595Y136D02* +X2602Y136D01* +X1Y135D02* +X8Y135D01* +X2595Y135D02* +X2602Y135D01* +X1Y134D02* +X8Y134D01* +X2595Y134D02* +X2602Y134D01* +X1Y133D02* +X8Y133D01* +X2595Y133D02* +X2602Y133D01* +X1Y132D02* +X8Y132D01* +X2595Y132D02* +X2602Y132D01* +X1Y131D02* +X8Y131D01* +X2595Y131D02* +X2602Y131D01* +X1Y130D02* +X8Y130D01* +X2595Y130D02* +X2602Y130D01* +X1Y129D02* +X8Y129D01* +X2595Y129D02* +X2602Y129D01* +X1Y128D02* +X8Y128D01* +X2595Y128D02* +X2602Y128D01* +X1Y127D02* +X8Y127D01* +X2595Y127D02* +X2602Y127D01* +X1Y126D02* +X8Y126D01* +X2595Y126D02* +X2602Y126D01* +X1Y125D02* +X8Y125D01* +X2595Y125D02* +X2602Y125D01* +X1Y124D02* +X8Y124D01* +X2595Y124D02* +X2602Y124D01* +X1Y123D02* +X8Y123D01* +X2595Y123D02* +X2602Y123D01* +X1Y122D02* +X8Y122D01* +X2595Y122D02* +X2602Y122D01* +X1Y121D02* +X8Y121D01* +X2595Y121D02* +X2602Y121D01* +X1Y120D02* +X8Y120D01* +X2595Y120D02* +X2602Y120D01* +X1Y119D02* +X8Y119D01* +X2595Y119D02* +X2602Y119D01* +X1Y118D02* +X8Y118D01* +X2595Y118D02* +X2602Y118D01* +X1Y117D02* +X8Y117D01* +X2595Y117D02* +X2602Y117D01* +X1Y116D02* +X8Y116D01* +X2595Y116D02* +X2602Y116D01* +X1Y115D02* +X8Y115D01* +X2595Y115D02* +X2602Y115D01* +X1Y114D02* +X8Y114D01* +X2595Y114D02* +X2602Y114D01* +X1Y113D02* +X8Y113D01* +X2595Y113D02* +X2602Y113D01* +X1Y112D02* +X8Y112D01* +X2595Y112D02* +X2602Y112D01* +X1Y111D02* +X8Y111D01* +X2595Y111D02* +X2602Y111D01* +X1Y110D02* +X8Y110D01* +X2595Y110D02* +X2602Y110D01* +X1Y109D02* +X8Y109D01* +X2595Y109D02* +X2602Y109D01* +X1Y108D02* +X8Y108D01* +X2595Y108D02* +X2602Y108D01* +X1Y107D02* +X8Y107D01* +X2595Y107D02* +X2602Y107D01* +X1Y106D02* +X8Y106D01* +X2595Y106D02* +X2602Y106D01* +X1Y105D02* +X8Y105D01* +X2595Y105D02* +X2602Y105D01* +X1Y104D02* +X8Y104D01* +X2595Y104D02* +X2602Y104D01* +X1Y103D02* +X8Y103D01* +X2595Y103D02* +X2602Y103D01* +X1Y102D02* +X8Y102D01* +X2595Y102D02* +X2602Y102D01* +X1Y101D02* +X8Y101D01* +X2595Y101D02* +X2602Y101D01* +X1Y100D02* +X8Y100D01* +X2595Y100D02* +X2602Y100D01* +X1Y99D02* +X8Y99D01* +X2595Y99D02* +X2602Y99D01* +X1Y98D02* +X8Y98D01* +X2595Y98D02* +X2602Y98D01* +X1Y97D02* +X8Y97D01* +X2595Y97D02* +X2602Y97D01* +X1Y96D02* +X8Y96D01* +X2595Y96D02* +X2602Y96D01* +X1Y95D02* +X8Y95D01* +X2595Y95D02* +X2602Y95D01* +X1Y94D02* +X8Y94D01* +X2595Y94D02* +X2602Y94D01* +X1Y93D02* +X8Y93D01* +X2595Y93D02* +X2602Y93D01* +X1Y92D02* +X8Y92D01* +X2595Y92D02* +X2602Y92D01* +X1Y91D02* +X8Y91D01* +X2595Y91D02* +X2602Y91D01* +X1Y90D02* +X8Y90D01* +X2595Y90D02* +X2602Y90D01* +X1Y89D02* +X8Y89D01* +X2595Y89D02* +X2602Y89D01* +X1Y88D02* +X8Y88D01* +X2595Y88D02* +X2602Y88D01* +X1Y87D02* +X8Y87D01* +X2595Y87D02* +X2602Y87D01* +X1Y86D02* +X8Y86D01* +X2595Y86D02* +X2602Y86D01* +X1Y85D02* +X8Y85D01* +X1151Y85D02* +X1152Y85D01* +X2595Y85D02* +X2602Y85D01* +X1Y84D02* +X8Y84D01* +X1150Y84D02* +X1153Y84D01* +X2595Y84D02* +X2602Y84D01* +X1Y83D02* +X8Y83D01* +X1149Y83D02* +X1154Y83D01* +X2595Y83D02* +X2602Y83D01* +X1Y82D02* +X8Y82D01* +X1149Y82D02* +X1155Y82D01* +X2595Y82D02* +X2602Y82D01* +X1Y81D02* +X8Y81D01* +X1150Y81D02* +X1156Y81D01* +X2595Y81D02* +X2602Y81D01* +X1Y80D02* +X8Y80D01* +X1151Y80D02* +X1157Y80D01* +X2595Y80D02* +X2602Y80D01* +X1Y79D02* +X8Y79D01* +X1152Y79D02* +X1158Y79D01* +X2595Y79D02* +X2602Y79D01* +X1Y78D02* +X8Y78D01* +X1153Y78D02* +X1159Y78D01* +X2595Y78D02* +X2602Y78D01* +X1Y77D02* +X8Y77D01* +X1154Y77D02* +X1160Y77D01* +X2595Y77D02* +X2602Y77D01* +X1Y76D02* +X8Y76D01* +X1155Y76D02* +X1161Y76D01* +X2595Y76D02* +X2602Y76D01* +X1Y75D02* +X8Y75D01* +X1156Y75D02* +X1162Y75D01* +X2595Y75D02* +X2602Y75D01* +X1Y74D02* +X8Y74D01* +X1157Y74D02* +X1163Y74D01* +X2595Y74D02* +X2602Y74D01* +X1Y73D02* +X8Y73D01* +X1158Y73D02* +X1164Y73D01* +X2595Y73D02* +X2602Y73D01* +X1Y72D02* +X8Y72D01* +X1159Y72D02* +X1165Y72D01* +X2595Y72D02* +X2602Y72D01* +X1Y71D02* +X8Y71D01* +X1160Y71D02* +X1166Y71D01* +X2595Y71D02* +X2602Y71D01* +X1Y70D02* +X8Y70D01* +X1161Y70D02* +X1167Y70D01* +X2595Y70D02* +X2602Y70D01* +X1Y69D02* +X8Y69D01* +X1162Y69D02* +X1167Y69D01* +X2595Y69D02* +X2602Y69D01* +X1Y68D02* +X8Y68D01* +X1163Y68D02* +X1168Y68D01* +X2595Y68D02* +X2602Y68D01* +X1Y67D02* +X8Y67D01* +X1164Y67D02* +X1170Y67D01* +X2595Y67D02* +X2602Y67D01* +X1Y66D02* +X8Y66D01* +X1165Y66D02* +X1171Y66D01* +X2595Y66D02* +X2602Y66D01* +X1Y65D02* +X8Y65D01* +X1166Y65D02* +X1172Y65D01* +X2595Y65D02* +X2602Y65D01* +X1Y64D02* +X8Y64D01* +X1167Y64D02* +X1173Y64D01* +X2595Y64D02* +X2602Y64D01* +X1Y63D02* +X8Y63D01* +X1168Y63D02* +X1174Y63D01* +X2595Y63D02* +X2602Y63D01* +X1Y62D02* +X8Y62D01* +X1169Y62D02* +X1175Y62D01* +X2595Y62D02* +X2602Y62D01* +X1Y61D02* +X8Y61D01* +X1170Y61D02* +X1176Y61D01* +X2595Y61D02* +X2602Y61D01* +X1Y60D02* +X8Y60D01* +X1171Y60D02* +X1177Y60D01* +X2595Y60D02* +X2602Y60D01* +X1Y59D02* +X8Y59D01* +X1172Y59D02* +X1178Y59D01* +X2595Y59D02* +X2602Y59D01* +X1Y58D02* +X8Y58D01* +X1173Y58D02* +X1179Y58D01* +X2595Y58D02* +X2602Y58D01* +X1Y57D02* +X8Y57D01* +X1174Y57D02* +X1180Y57D01* +X2595Y57D02* +X2602Y57D01* +X1Y56D02* +X8Y56D01* +X1175Y56D02* +X1181Y56D01* +X2595Y56D02* +X2602Y56D01* +X1Y55D02* +X8Y55D01* +X1176Y55D02* +X1182Y55D01* +X2595Y55D02* +X2602Y55D01* +X1Y54D02* +X8Y54D01* +X1177Y54D02* +X1183Y54D01* +X2595Y54D02* +X2602Y54D01* +X1Y53D02* +X8Y53D01* +X1178Y53D02* +X1184Y53D01* +X2595Y53D02* +X2602Y53D01* +X1Y52D02* +X8Y52D01* +X1179Y52D02* +X1185Y52D01* +X2595Y52D02* +X2602Y52D01* +X1Y51D02* +X8Y51D01* +X1180Y51D02* +X1185Y51D01* +X2595Y51D02* +X2602Y51D01* +X1Y50D02* +X8Y50D01* +X1181Y50D02* +X1185Y50D01* +X2595Y50D02* +X2602Y50D01* +X1Y49D02* +X8Y49D01* +X1182Y49D02* +X1184Y49D01* +X2595Y49D02* +X2602Y49D01* +X1Y48D02* +X8Y48D01* +X2595Y48D02* +X2602Y48D01* +X1Y47D02* +X8Y47D01* +X2595Y47D02* +X2602Y47D01* +X1Y46D02* +X8Y46D01* +X2595Y46D02* +X2602Y46D01* +X1Y45D02* +X8Y45D01* +X2595Y45D02* +X2602Y45D01* +X1Y44D02* +X8Y44D01* +X2595Y44D02* +X2602Y44D01* +X1Y43D02* +X8Y43D01* +X2595Y43D02* +X2602Y43D01* +X1Y42D02* +X8Y42D01* +X2595Y42D02* +X2602Y42D01* +X1Y41D02* +X8Y41D01* +X2595Y41D02* +X2602Y41D01* +X1Y40D02* +X8Y40D01* +X2595Y40D02* +X2602Y40D01* +X1Y39D02* +X8Y39D01* +X2595Y39D02* +X2602Y39D01* +X1Y38D02* +X8Y38D01* +X2595Y38D02* +X2602Y38D01* +X1Y37D02* +X8Y37D01* +X2595Y37D02* +X2602Y37D01* +X1Y36D02* +X8Y36D01* +X2595Y36D02* +X2602Y36D01* +X1Y35D02* +X8Y35D01* +X2595Y35D02* +X2602Y35D01* +X1Y34D02* +X8Y34D01* +X2595Y34D02* +X2602Y34D01* +X1Y33D02* +X8Y33D01* +X2595Y33D02* +X2602Y33D01* +X1Y32D02* +X8Y32D01* +X2595Y32D02* +X2602Y32D01* +X1Y31D02* +X8Y31D01* +X2595Y31D02* +X2602Y31D01* +X1Y30D02* +X8Y30D01* +X2595Y30D02* +X2602Y30D01* +X1Y29D02* +X8Y29D01* +X2595Y29D02* +X2602Y29D01* +X1Y28D02* +X8Y28D01* +X2595Y28D02* +X2602Y28D01* +X1Y27D02* +X8Y27D01* +X2595Y27D02* +X2602Y27D01* +X1Y26D02* +X8Y26D01* +X2595Y26D02* +X2602Y26D01* +X1Y25D02* +X8Y25D01* +X2595Y25D02* +X2602Y25D01* +X1Y24D02* +X8Y24D01* +X2595Y24D02* +X2602Y24D01* +X1Y23D02* +X8Y23D01* +X2595Y23D02* +X2602Y23D01* +X1Y22D02* +X8Y22D01* +X2595Y22D02* +X2602Y22D01* +X1Y21D02* +X8Y21D01* +X2595Y21D02* +X2602Y21D01* +X1Y20D02* +X8Y20D01* +X2595Y20D02* +X2602Y20D01* +X1Y19D02* +X8Y19D01* +X2595Y19D02* +X2602Y19D01* +X1Y18D02* +X8Y18D01* +X2595Y18D02* +X2602Y18D01* +X1Y17D02* +X8Y17D01* +X2595Y17D02* +X2602Y17D01* +X1Y16D02* +X8Y16D01* +X2595Y16D02* +X2602Y16D01* +X1Y15D02* +X8Y15D01* +X2595Y15D02* +X2602Y15D01* +X1Y14D02* +X8Y14D01* +X2595Y14D02* +X2602Y14D01* +X1Y13D02* +X8Y13D01* +X2595Y13D02* +X2602Y13D01* +X1Y12D02* +X8Y12D01* +X2595Y12D02* +X2602Y12D01* +X1Y11D02* +X8Y11D01* +X2595Y11D02* +X2602Y11D01* +X1Y10D02* +X8Y10D01* +X2595Y10D02* +X2602Y10D01* +X1Y9D02* +X8Y9D01* +X2595Y9D02* +X2602Y9D01* +X1Y8D02* +X2602Y8D01* +X1Y7D02* +X2602Y7D01* +X1Y6D02* +X2602Y6D01* +X1Y5D02* +X2602Y5D01* +X1Y4D02* +X2602Y4D01* +X1Y3D02* +X2602Y3D01* +X1Y2D02* +X2602Y2D01* +X1Y1D02* +X2602Y1D01* +D02* +G04 End of Silk1* +M02* \ No newline at end of file diff --git a/src/zlac8015d_ros/launch/motor_driver_node.launch b/src/zlac8015d_ros/launch/motor_driver_node.launch new file mode 100644 index 0000000..9d10fa5 --- /dev/null +++ b/src/zlac8015d_ros/launch/motor_driver_node.launch @@ -0,0 +1,53 @@ + + +  + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/zlac8015d_ros/params/motor_driver_params.yaml b/src/zlac8015d_ros/params/motor_driver_params.yaml index 5ce5850..b31cdcd 100644 --- a/src/zlac8015d_ros/params/motor_driver_params.yaml +++ b/src/zlac8015d_ros/params/motor_driver_params.yaml @@ -1,25 +1,20 @@ -# Name of USB port for zlac8015d -port: /dev/ttyUSB0 - # Tire & Encoder Parameters # Default: 8 inches wheel ############################### -# Tire circumference -travel_in_one_rev: 0.655 # meter # Tire radius -R_Wheel: 0.105 # meter +left_wheel_radius: 0.0974 # meter 0.1015 +right_wheel_radius: 0.0974 # meter 0.1015 + +# For odometry computation +computation_left_wheel_radius: 0.09806 # meter 0.1015 0.09735 +computation_right_wheel_radius: 0.09794 # meter 0.1015 + # Encoder CPR(counts per revolution) cpr: 16385 ############################### # Distance between tires -wheels_base_width: 0.440 # meter -# Control mode -# 1: relative position control mode -# Subscribe to "/zlac8015d/pos/cmd_deg" and "/zlac8015d/pos/cmd_dist" -# 3: Speed rpm control mode -# Subscribe to "/zlac8015d/twist/cmd_vel", "/zlac8015d/vel/cmd_vel" and "/zlac8015d/vel/cmd_rpm" -control_mode: 3 +wheels_base_width: 0.608 # meter 0.5668 # Motor automatically stops if no topics are received for a certain period of time callback_timeout: 0.5 # seconds # Smaller values will cause small changes in tire motion to have a greater impact on the odometry calculations @@ -27,10 +22,10 @@ decimil_coefficient: 0.001 # Time to reach target position -set_accel_time_left: 200 # ms -set_accel_time_right: 200 # ms -set_decel_time_left: 200 # ms -set_decel_time_right: 200 # ms +set_accel_time_left: 1000 # ms +set_accel_time_right: 1000 # ms +set_decel_time_left: 1000 # ms +set_decel_time_right: 1000 # ms # Maximum rpm max_left_rpm: 150 @@ -38,13 +33,3 @@ # Width of rpm to be regarded as 0 # If 3, then -3 to 3 is considered rpm 0 deadband_rpm: 3 - -# Header flame of TF -TF_header_flame: odom -# Child flame of TF -TF_child_flame: base_link - -# Header flame of odom -odom_header_flame: odom -# Child flame of odom -odom_child_flame: base_link \ No newline at end of file diff --git a/src/zlac8015d_ros/scripts/ZLAC8015D.py b/src/zlac8015d_ros/scripts/ZLAC8015D.py old mode 100644 new mode 100755 index 04b9536..c4ffd1f --- a/src/zlac8015d_ros/scripts/ZLAC8015D.py +++ b/src/zlac8015d_ros/scripts/ZLAC8015D.py @@ -1,8 +1,25 @@ -# This script is taken from the following Python API. -# https://github.com/rasheeddo/ZLAC8015D_python.git +#!/usr/bin/env python3 +""" +Copyright (C) 2022 rasheeddo +Copyright (C) 2022 Alpaca-zip + +This program is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. + +This program is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with this program. If not, see . +""" from pymodbus.client.sync import ModbusSerialClient as ModbusClient import numpy as np +import time class Controller: @@ -96,9 +113,15 @@ ## Odometry ## ############## ## 8 inches wheel - self.travel_in_one_rev = 0.655 + #self.travel_in_one_rev = 0.655 self.cpr = 16385 - self.R_Wheel = 0.105 #meter + #self.R_Wheel = 0.105 #meter + self.left_wheel_radius = 0.105 #meter + self.right_wheel_radius = 0.105 #meter + self.left_circumference = 0.655 + self.right_circumference = 0.655 + self.computation_left_wheel_radius = 0.105 + self.computation_right_wheel_radius = 0.105 ## Some time if read immediatly after write, it would show ModbusIOException when get data from registers def modbus_fail_read_handler(self, ADDR, WORD): @@ -113,19 +136,23 @@ read_success = True except AttributeError as e: print(e) + time.sleep(2) + #time.sleep(0.5) pass return reg def rpm_to_radPerSec(self, rpm): return rpm*2*np.pi/60.0 - + + """ def rpm_to_linear(self, rpm): W_Wheel = self.rpm_to_radPerSec(rpm) V = W_Wheel*self.R_Wheel return V + """ def set_mode(self, MODE): """ @@ -157,6 +184,9 @@ def disable_motor(self): result = self.client.write_register(self.CONTROL_REG, self.DOWN_TIME, unit=self.ID) + + def estop(self): + result = self.client.write_register(self.CONTROL_REG, self.EMER_STOP, unit=self.ID) def get_fault_code(self): @@ -333,7 +363,7 @@ #l_travelled = (float(l_pulse)/self.cpr)*self.travel_in_one_rev # unit in meter #r_travelled = (float(r_pulse)/self.cpr)*self.travel_in_one_rev # unit in meter - l_travelled = (float(l_pulse)/self.cpr)*self.travel_in_one_rev*4 # unit in meter - r_travelled = (float(r_pulse)/self.cpr)*self.travel_in_one_rev*4 # unit in meter + l_travelled = (float(l_pulse)/self.cpr)*self.computation_left_wheel_radius*np.pi*8 # unit in meter + r_travelled = (float(r_pulse)/self.cpr)*self.computation_right_wheel_radius*np.pi*8 # unit in meter return l_travelled, r_travelled diff --git a/src/zlac8015d_ros/scripts/__pycache__/ZLAC8015D.cpython-38.pyc b/src/zlac8015d_ros/scripts/__pycache__/ZLAC8015D.cpython-38.pyc new file mode 100644 index 0000000..7357f31 --- /dev/null +++ b/src/zlac8015d_ros/scripts/__pycache__/ZLAC8015D.cpython-38.pyc Binary files differ diff --git a/src/zlac8015d_ros/scripts/motor_driver_node.py b/src/zlac8015d_ros/scripts/motor_driver_node.py old mode 100644 new mode 100755 index 066c921..a857603 --- a/src/zlac8015d_ros/scripts/motor_driver_node.py +++ b/src/zlac8015d_ros/scripts/motor_driver_node.py @@ -1,13 +1,31 @@ #!/usr/bin/env python3 +""" +Copyright (C) 2022 rasheeddo +Copyright (C) 2022 Alpaca-zip + +This program is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. + +This program is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with this program. If not, see . +""" import rospy import ZLAC8015D +import tf import tf2_ros import numpy as np import time -import yaml from decimal import Decimal, ROUND_HALF_UP from std_msgs.msg import Float32MultiArray +from std_msgs.msg import Bool from geometry_msgs.msg import Twist from nav_msgs.msg import Odometry from tf.transformations import quaternion_from_euler @@ -18,38 +36,39 @@ print("\033[32m" + "Start motor driver node!!" + "\033[0m") print("#########################") #-----Initialize publisher----- - self.wheels_rpm_pub = rospy.Publisher("/wheels_rpm", Float32MultiArray, queue_size=10) - self.wheels_rpm_msg = Float32MultiArray() self.odom_pub = rospy.Publisher("/odom", Odometry, queue_size=10) self.odom_msg = Odometry() #-----Initialize subscriber----- - rospy.Subscriber("/zlac8015d/twist/cmd_vel", Twist, self.zlac8015d_twist_cmd_callback) - rospy.Subscriber("/zlac8015d/vel/cmd_vel", Float32MultiArray, self.zlac8015d_vel_cmd_callback) - rospy.Subscriber("/zlac8015d/vel/cmd_rpm", Float32MultiArray, self.zlac8015d_rpm_cmd_callback) - rospy.Subscriber("/zlac8015d/pos/cmd_deg", Float32MultiArray, self.zlac8015d_deg_cmd_callback) - rospy.Subscriber("/zlac8015d/pos/cmd_dist", Float32MultiArray, self.zlac8015d_dist_cmd_callback) - - #-----Import parameters from yaml file----- - self.load_file = "/home/ubuntu/catkin_ws/src/zlac8015d_ros/params/motor_driver_params.yaml" - with open(self.load_file) as file: - self.obj = yaml.safe_load(file) + rospy.Subscriber(rospy.get_param("/motor_driver_node/twist_cmd_vel_topic"), Twist, self.zlac8015d_twist_cmd_callback) + rospy.Subscriber(rospy.get_param("/motor_driver_node/cmd_vel_topic"), Float32MultiArray, self.zlac8015d_vel_cmd_callback) + rospy.Subscriber(rospy.get_param("/motor_driver_node/cmd_rpm_topic"), Float32MultiArray, self.zlac8015d_rpm_cmd_callback) + rospy.Subscriber(rospy.get_param("/motor_driver_node/cmd_deg_topic"), Float32MultiArray, self.zlac8015d_deg_cmd_callback) + rospy.Subscriber(rospy.get_param("/motor_driver_node/cmd_dist_topic"), Float32MultiArray, self.zlac8015d_dist_cmd_callback) + #-For E-stop- + rospy.Subscriber("/estop", Bool, self.zlac8015d_estop_callback) #-----Initialize ZLAC8015D----- - self.zlc = ZLAC8015D.Controller(self.obj["port"]) - self.zlc.travel_in_one_rev = float(self.obj["travel_in_one_rev"]) - self.zlc.cpr = int(self.obj["cpr"]) - self.zlc.R_Wheel = float(self.obj["R_Wheel"]) - self.control_mode = int(self.obj["control_mode"]) - if self.control_mode == 3: + self.zlc = ZLAC8015D.Controller(rospy.get_param("/motor_driver_node/port")) + self.zlc.cpr = int(rospy.get_param("/motor_driver_node/cpr")) + self.zlc.left_wheel_radius = float(rospy.get_param("/motor_driver_node/left_wheel_radius")) + self.zlc.right_wheel_radius = float(rospy.get_param("/motor_driver_node/right_wheel_radius")) + self.zlc.left_circumference = self.zlc.left_wheel_radius * 2 * np.pi + self.zlc.right_circumference = self.zlc.right_wheel_radius * 2 * np.pi + self.zlc.computation_left_wheel_radius = float(rospy.get_param("/motor_driver_node/computation_left_wheel_radius")) + self.zlc.computation_right_wheel_radius = float(rospy.get_param("/motor_driver_node/computation_right_wheel_radius")) + + + self.control_mode = int(rospy.get_param("/motor_driver_node/control_mode")) + if (self.control_mode == 3): self.zlac8015d_speed_mode_init() - elif self.control_mode == 1: + elif (self.control_mode == 1): self.zlac8015d_position_mode_init() #-----Initialize variable----- self.last_subscribed_time = 0.0 - self.callback_timeout = float(self.obj["callback_timeout"]) - self.deadband_rpm = int(self.obj["deadband_rpm"]) + self.callback_timeout = float(rospy.get_param("/motor_driver_node/callback_timeout")) + self.deadband_rpm = int(rospy.get_param("/motor_driver_node/deadband_rpm")) self.linear_vel_cmd = 0.0 self.angular_vel_cmd = 0.0 self.got_twist_cmd = False @@ -73,15 +92,32 @@ self.theta = 0.0 self.x = 0.0 self.y = 0.0 + self.Wr = 0.0 + self.Wl = 0.0 self.period = 0.05 self.l_meter = 0.0 self.r_meter = 0.0 self.l_meter_init, self.r_meter_init = self.zlc.get_wheels_travelled() self.prev_l_meter = 0.0 self.prev_r_meter = 0.0 + self.wheels_base_width = float(rospy.get_param("/motor_driver_node/wheels_base_width")) self.br = tf2_ros.TransformBroadcaster() self.t = TransformStamped() + self.state_vector = np.zeros((3, 1)) + + #-For E-stop- + self.estop = False + + + """ + ++++++++++++++++++++++++++++++++++++++++++ + zlac8015d_estop_callback function + ++++++++++++++++++++++++++++++++++++++++++ + Callback function to subscribe for "/estop". + """ + def zlac8015d_estop_callback(self, msg): + self.estop = msg.data """ ++++++++++++++++++++++++++++++++++++++++++ @@ -93,7 +129,7 @@ self.linear_vel_cmd = msg.linear.x self.angular_vel_cmd = msg.angular.z self.got_twist_cmd = True - self.last_subscribed_time = rospy.Time.now().nsecs + self.last_subscribed_time = time.perf_counter() """ ++++++++++++++++++++++++++++++++++++++++++ @@ -149,8 +185,8 @@ """ def zlac8015d_speed_mode_init(self): self.zlc.disable_motor() - self.zlc.set_accel_time(int(self.obj["set_accel_time_left"]), int(self.obj["set_accel_time_right"])) - self.zlc.set_decel_time(int(self.obj["set_decel_time_left"]), int(self.obj["set_decel_time_right"])) + self.zlc.set_accel_time(int(rospy.get_param("/motor_driver_node/set_accel_time_left")), int(rospy.get_param("/motor_driver_node/set_accel_time_right"))) + self.zlc.set_decel_time(int(rospy.get_param("/motor_driver_node/set_decel_time_left")), int(rospy.get_param("/motor_driver_node/set_accel_time_right"))) self.zlc.set_mode(3) self.zlc.enable_motor() @@ -162,11 +198,11 @@ """ def zlac8015d_position_mode_init(self): self.zlc.disable_motor() - self.zlc.set_accel_time(int(self.obj["set_accel_time_left"]), int(self.obj["set_accel_time_right"])) - self.zlc.set_decel_time(int(self.obj["set_decel_time_left"]), int(self.obj["set_decel_time_right"])) + self.zlc.set_accel_time(int(rospy.get_param("/motor_driver_node/set_accel_time_left")), int(rospy.get_param("/motor_driver_node/set_accel_time_right"))) + self.zlc.set_decel_time(int(rospy.get_param("/motor_driver_node/set_decel_time_left")), int(rospy.get_param("/motor_driver_node/set_decel_time_right"))) self.zlc.set_mode(1) self.zlc.set_position_async_control() - self.zlc.set_maxRPM_pos(int(self.obj["max_left_rpm"]), int(self.obj["max_right_rpm"])) + self.zlc.set_maxRPM_pos(int(rospy.get_param("/motor_driver_node/max_left_rpm")), int(rospy.get_param("/motor_driver_node/max_right_rpm"))) self.zlc.enable_motor() """ @@ -176,8 +212,8 @@ Convert from twist to rpm. """ def twist_to_rpm(self, linear_vel, angular_vel): - left_vel = linear_vel - float(self.obj["wheels_base_width"]) / 2 * angular_vel - right_vel = linear_vel + float(self.obj["wheels_base_width"]) / 2 * angular_vel + left_vel = linear_vel - self.wheels_base_width / 2 * angular_vel + right_vel = linear_vel + self.wheels_base_width / 2 * angular_vel left_rpm, right_rpm = self.vel_to_rpm(left_vel, -right_vel) return left_rpm, right_rpm @@ -188,8 +224,8 @@ Convert from speed to rpm. """ def vel_to_rpm(self, left_vel, right_vel): - left_rpm = 60 * left_vel / (2 * np.pi * self.zlc.R_Wheel) - right_rpm = 60 * right_vel / (2 * np.pi * self.zlc.R_Wheel) + left_rpm = 60 * left_vel / (2 * np.pi * self.zlc.left_wheel_radius) + right_rpm = 60 * right_vel / (2 * np.pi * self.zlc.right_wheel_radius) return left_rpm, right_rpm """ @@ -199,15 +235,17 @@ Set rpm with limit. """ def zlac8015d_set_rpm_with_limit(self, left_rpm, right_rpm): - if (-int(self.obj["max_left_rpm"]) < left_rpm < int(self.obj["max_left_rpm"])) and (-int(self.obj["max_right_rpm"]) < right_rpm < int(self.obj["max_right_rpm"])): - if (-self.deadband_rpm < left_rpm < self.deadband_rpm): - left_rpm = 0 - if (-self.deadband_rpm < right_rpm < self.deadband_rpm): - right_rpm = 0 - - self.zlc.set_rpm(int(left_rpm), int(right_rpm)) - else: - rospy.logerr("Set RPM exceeds the limit.") + left_rpm_lim = int(rospy.get_param("/motor_driver_node/max_left_rpm")) + right_rpm_lim = int(rospy.get_param("/motor_driver_node/max_right_rpm")) + if ((-left_rpm_lim < left_rpm < left_rpm_lim) and (-right_rpm_lim < right_rpm < right_rpm_lim)): + if (-self.deadband_rpm < left_rpm < self.deadband_rpm): + left_rpm = 0 + if (-self.deadband_rpm < right_rpm < self.deadband_rpm): + right_rpm = 0 + + self.zlc.set_rpm(int(left_rpm), int(right_rpm)) + else: + rospy.logerr("Set RPM exceeds the limit.") """ ++++++++++++++++++++++++++++++++++++++++++ @@ -216,31 +254,101 @@ Odometry computation. """ def calculate_odometry(self): + """ + l_rpm, r_rpm = self.zlc.get_rpm() + self.Wl = self.zlc.rpm_to_radPerSec(l_rpm) + self.Wr = self.zlc.rpm_to_radPerSec(-r_rpm) + """ self.l_meter, self.r_meter = self.zlc.get_wheels_travelled() self.l_meter = self.l_meter - self.l_meter_init self.r_meter = (-1 * self.r_meter) - (-1 * self.r_meter_init) - if self.control_mode == 3: + vl = (self.l_meter - self.prev_l_meter) / self.period + vr = (self.r_meter - self.prev_r_meter) / self.period + self.Wl = vl / self.zlc.computation_left_wheel_radius + self.Wr = vr / self.zlc.computation_right_wheel_radius + + matrix = np.array([[self.zlc.computation_right_wheel_radius / 2, self.zlc.computation_left_wheel_radius / 2], [self.zlc.computation_right_wheel_radius / self.wheels_base_width, -self.zlc.computation_left_wheel_radius / self.wheels_base_width]]) + vector = np.array([[self.Wr], [self.Wl]]) + input_vector = np.dot(matrix, vector) + V = input_vector[0, 0] + Wz = input_vector[1, 0] + + out_matrix = np.array([[1, 0, 0], [0, 1, 0], [0, 0, 1]]) + dirc_matrix = np.array([[np.cos(self.state_vector[2, 0]) * self.period, 0], [np.sin(self.state_vector[2, 0]) * self.period, 0], [0, self.period]]) + out_vector = np.dot(out_matrix, self.state_vector) + np.dot(dirc_matrix, input_vector) + self.x = out_vector[0, 0] + self.y = out_vector[1, 0] + self.theta = out_vector[2, 0] + + #-----Construct tf----- + if(rospy.get_param("/motor_driver_node/publish_TF")): + self.t.header.stamp = rospy.Time.now() + self.t.header.frame_id = rospy.get_param("/motor_driver_node/TF_header_frame") + self.t.child_frame_id = rospy.get_param("/motor_driver_node/TF_child_frame") + self.t.transform.translation.x = self.x + self.t.transform.translation.y = self.y + self.t.transform.translation.z = 0.0 + rotation = tf.transformations.quaternion_from_euler(0, 0, self.theta) + self.t.transform.rotation.x = rotation[0] + self.t.transform.rotation.y = rotation[1] + self.t.transform.rotation.z = rotation[2] + self.t.transform.rotation.w = rotation[3] + self.br.sendTransform(self.t) + + #-----Construct odom message----- + if(rospy.get_param("/motor_driver_node/publish_odom")): + self.odom_msg.header.stamp = rospy.Time.now() + self.odom_msg.header.frame_id = rospy.get_param("/motor_driver_node/odom_header_frame") + self.odom_msg.child_frame_id = rospy.get_param("/motor_driver_node/odom_child_frame") + self.odom_msg.pose.pose.position.x = self.x + self.odom_msg.pose.pose.position.y = self.y + self.odom_msg.pose.pose.position.z = 0.0 + orientation = tf.transformations.quaternion_from_euler(0, 0, self.theta) + self.odom_msg.pose.pose.orientation.x = orientation[0] + self.odom_msg.pose.pose.orientation.y = orientation[1] + self.odom_msg.pose.pose.orientation.z = orientation[2] + self.odom_msg.pose.pose.orientation.w = orientation[3] + self.odom_msg.pose.covariance[0] = 0.0001 + self.odom_msg.pose.covariance[7] = 0.0001 + self.odom_msg.pose.covariance[14] = 0.000001 + self.odom_msg.pose.covariance[21] = 0.000001 + self.odom_msg.pose.covariance[28] = 0.000001 + self.odom_msg.pose.covariance[35] = 0.0001 + self.odom_msg.twist.twist.linear.x = V + self.odom_msg.twist.twist.linear.y = 0.0 + self.odom_msg.twist.twist.angular.z = Wz + self.odom_pub.publish(self.odom_msg) + + self.state_vector[0, 0] = self.x + self.state_vector[1, 0] = self.y + self.state_vector[2, 0] = self.theta + + """ + def calculate_odometry(self): + self.l_meter, self.r_meter = self.zlc.get_wheels_travelled() + self.l_meter = self.l_meter - self.l_meter_init + self.r_meter = (-1 * self.r_meter) - (-1 * self.r_meter_init) + if (self.control_mode == 3): vl, vr = self.zlc.get_linear_velocities() - elif self.control_mode == 1: + elif (self.control_mode == 1): vl = (self.l_meter - self.prev_l_meter) / self.period vr = (self.r_meter - self.prev_r_meter) / self.period - round_vl = float(Decimal(str(vl)).quantize(Decimal(self.obj["decimil_coefficient"]), rounding = ROUND_HALF_UP)) - round_vr = float(Decimal(str(vr)).quantize(Decimal('0.001'), rounding = ROUND_HALF_UP)) - self.obj["TF_header_flame"] + round_vl = float(Decimal(str(vl)).quantize(Decimal(str(rospy.get_param("/motor_driver_node/decimil_coefficient"))), rounding = ROUND_HALF_UP)) + round_vr = float(Decimal(str(vr)).quantize(Decimal(str(rospy.get_param("/motor_driver_node/decimil_coefficient"))), rounding = ROUND_HALF_UP)) #-----Rotatiing----- if ((round_vl * round_vr) < 0.0) and (abs(round_vl) == abs(round_vr)): V = 0.0 - Wz = 2.0 * vr / float(self.obj["wheels_base_width"]) + Wz = 2.0 * vr / self.wheels_base_width self.theta = self.theta + Wz * self.period path = "Rotatiing" #-----Curving----- - elif (round_vl - round_vr) != 0: + elif ((round_vl - round_vr) != 0): V = (vl + vr) / 2.0 - Wz = (vr - vl) / float(self.obj["wheels_base_width"]) - R_ICC = (float(self.obj["wheels_base_width"]) / 2.0) * ((vr + vl) / (vr - vl)) + Wz = (vr - vl) / self.wheels_base_width + R_ICC = (self.wheels_base_width / 2.0) * ((vr + vl) / (vr - vl)) self.x = self.x - R_ICC * np.sin(self.theta) + R_ICC * np.sin(self.theta + Wz * self.period) self.y = self.y + R_ICC * np.cos(self.theta) - R_ICC * np.cos(self.theta + Wz * self.period) self.theta = self.theta + Wz * self.period @@ -256,41 +364,44 @@ #-----Construct tf----- q = quaternion_from_euler(0, 0, self.theta) - self.t.header.stamp = rospy.Time.now() - self.t.header.frame_id = self.obj["TF_header_flame"] - self.t.child_frame_id = self.obj["TF_child_flame"] - self.t.transform.translation.x = self.x - self.t.transform.translation.y = self.y - self.t.transform.translation.z = 0.0 - self.t.transform.rotation.x = q[0] - self.t.transform.rotation.y = q[1] - self.t.transform.rotation.z = q[2] - self.t.transform.rotation.w = q[3] - self.br.sendTransform(self.t) + if(rospy.get_param("/motor_driver_node/publish_TF")): + self.t.header.stamp = rospy.Time.now() + self.t.header.frame_id = rospy.get_param("/motor_driver_node/TF_header_frame") + self.t.child_frame_id = rospy.get_param("/motor_driver_node/TF_child_frame") + self.t.transform.translation.x = self.x + self.t.transform.translation.y = self.y + self.t.transform.translation.z = 0.0 + self.t.transform.rotation.x = q[0] + self.t.transform.rotation.y = q[1] + self.t.transform.rotation.z = q[2] + self.t.transform.rotation.w = q[3] + self.br.sendTransform(self.t) #-----Construct odom message----- - self.odom_msg.header.stamp = rospy.Time.now() - self.odom_msg.header.frame_id = self.obj["odom_header_flame"] - self.odom_msg.child_frame_id = self.obj["odom_child_flame"] - self.odom_msg.pose.pose.position.x = self.x - self.odom_msg.pose.pose.position.y = self.y - self.odom_msg.pose.pose.position.z = 0.0 - self.odom_msg.pose.pose.orientation.x = q[0] - self.odom_msg.pose.pose.orientation.y = q[1] - self.odom_msg.pose.pose.orientation.z = q[2] - self.odom_msg.pose.pose.orientation.w = q[3] - self.odom_msg.pose.covariance[0] = 0.0001 - self.odom_msg.pose.covariance[7] = 0.0001 - self.odom_msg.pose.covariance[14] = 0.000001 - self.odom_msg.pose.covariance[21] = 0.000001 - self.odom_msg.pose.covariance[28] = 0.000001 - self.odom_msg.pose.covariance[35] = 0.0001 - self.odom_msg.twist.twist.linear.x = V - self.odom_msg.twist.twist.linear.y = 0.0 - self.odom_msg.twist.twist.angular.z = Wz - self.odom_pub.publish(self.odom_msg) + if(rospy.get_param("/motor_driver_node/publish_odom")): + self.odom_msg.header.stamp = rospy.Time.now() + self.odom_msg.header.frame_id = rospy.get_param("/motor_driver_node/odom_header_frame") + self.odom_msg.child_frame_id = rospy.get_param("/motor_driver_node/odom_child_frame") + self.odom_msg.pose.pose.position.x = self.x + self.odom_msg.pose.pose.position.y = self.y + self.odom_msg.pose.pose.position.z = 0.0 + self.odom_msg.pose.pose.orientation.x = q[0] + self.odom_msg.pose.pose.orientation.y = q[1] + self.odom_msg.pose.pose.orientation.z = q[2] + self.odom_msg.pose.pose.orientation.w = q[3] + self.odom_msg.pose.covariance[0] = 0.0001 + self.odom_msg.pose.covariance[7] = 0.0001 + self.odom_msg.pose.covariance[14] = 0.000001 + self.odom_msg.pose.covariance[21] = 0.000001 + self.odom_msg.pose.covariance[28] = 0.000001 + self.odom_msg.pose.covariance[35] = 0.0001 + self.odom_msg.twist.twist.linear.x = V + self.odom_msg.twist.twist.linear.y = 0.0 + self.odom_msg.twist.twist.angular.z = Wz + self.odom_pub.publish(self.odom_msg) return vl, vr + """ """ ++++++++++++++++++++++++++++++++++++++++++ @@ -300,64 +411,68 @@ """ def control_loop(self): rate = rospy.Rate(20) # 20Hz + reset_flag = False while True: - if rospy.is_shutdown(): + if (rospy.is_shutdown()): self.zlc.disable_motor() break start_time = time.perf_counter() - - #-----Speed rpm control mode----- - if self.control_mode == 3: - if self.got_twist_cmd: - self.left_rpm_cmd, self.right_rpm_cmd = self.twist_to_rpm(self.linear_vel_cmd, self.angular_vel_cmd) - self.zlac8015d_set_rpm_with_limit(self.left_rpm_cmd, self.right_rpm_cmd) - self.got_twist_cmd = False - elif self.got_vel_cmd: - self.left_rpm_cmd, self.right_rpm_cmd = self.vel_to_rpm(self.left_vel_cmd, self.right_vel_cmd) - self.zlac8015d_set_rpm_with_limit(self.left_rpm_cmd, self.right_rpm_cmd) - self.got_vel_cmd = False - elif self.got_vel_rpm_cmd: - self.zlac8015d_set_rpm_with_limit(self.left_rpm_cmd, self.right_rpm_cmd) - self.got_vel_rpm_cmd = False - elif (time.perf_counter() - self.last_subscribed_time > self.callback_timeout): - self.left_rpm_cmd = 0.0 - self.right_rpm_cmd = 0.0 - self.zlac8015d_set_rpm_with_limit(self.left_rpm_cmd, self.right_rpm_cmd) - - fb_L_rpm, fb_R_rpm = self.zlc.get_rpm() - self.wheels_rpm_msg.data = [fb_L_rpm, fb_R_rpm] - self.wheels_rpm_pub.publish(self.wheels_rpm_msg) - #-----relative position control mode----- - elif self.control_mode == 1: - if self.got_pos_deg_cmd: - self.zlc.set_relative_angle(self.left_pos_deg_cmd ,self.right_pos_deg_cmd) - self.zlc.move_left_wheel() - self.zlc.move_right_wheel() - self.got_pos_deg_cmd = False - elif self.got_pos_dist_cmd: - left_cmd_deg = (self.left_pos_dist_cmd * 360.0) / self.zlc.travel_in_one_rev - right_cmd_deg = (-self.right_pos_dist_cmd * 360.0) / self.zlc.travel_in_one_rev - self.zlc.set_relative_angle(left_cmd_deg, right_cmd_deg) - self.zlc.move_left_wheel() - self.zlc.move_right_wheel() - self.got_pos_dist_cmd = False + if (self.estop == True): + self.zlc.estop() + reset_flag = True + else: + if(reset_flag == True): + self.zlc.clear_alarm() + self.zlc.disable_motor() + self.zlc.enable_motor() + reset_flag = False + #-----Speed rpm control mode----- + if (self.control_mode == 3): + if (self.got_twist_cmd): + self.left_rpm_cmd, self.right_rpm_cmd = self.twist_to_rpm(self.linear_vel_cmd, self.angular_vel_cmd) + self.zlac8015d_set_rpm_with_limit(self.left_rpm_cmd, self.right_rpm_cmd) + self.got_twist_cmd = False + elif (self.got_vel_cmd): + self.left_rpm_cmd, self.right_rpm_cmd = self.vel_to_rpm(self.left_vel_cmd, self.right_vel_cmd) + self.zlac8015d_set_rpm_with_limit(self.left_rpm_cmd, self.right_rpm_cmd) + self.got_vel_cmd = False + elif (self.got_vel_rpm_cmd): + self.zlac8015d_set_rpm_with_limit(self.left_rpm_cmd, self.right_rpm_cmd) + self.got_vel_rpm_cmd = False + elif (time.perf_counter() - self.last_subscribed_time > self.callback_timeout): + self.left_rpm_cmd = 0.0 + self.right_rpm_cmd = 0.0 + self.zlac8015d_set_rpm_with_limit(self.left_rpm_cmd, self.right_rpm_cmd) + + #-----relative position control mode----- + elif (self.control_mode == 1): + if (self.got_pos_deg_cmd): + self.zlc.set_relative_angle(self.left_pos_deg_cmd ,self.right_pos_deg_cmd) + self.zlc.move_left_wheel() + self.zlc.move_right_wheel() + self.got_pos_deg_cmd = False + elif (self.got_pos_dist_cmd): + left_cmd_deg = (self.left_pos_dist_cmd * 360.0) / self.zlc.left_circumference + right_cmd_deg = (-self.right_pos_dist_cmd * 360.0) / self.zlc.right_circumference + self.zlc.set_relative_angle(left_cmd_deg, right_cmd_deg) + self.zlc.move_left_wheel() + self.zlc.move_right_wheel() + self.got_pos_dist_cmd = False #-----Odometry computation----- - vl, vr = self.calculate_odometry() - + self.calculate_odometry() self.period = time.perf_counter() - start_time self.prev_l_meter = self.l_meter self.prev_r_meter = self.r_meter #-----Logging to screen----- - if self.control_mode == 1: - print("\033[32m" + "\rcontrol_mode: {:d} | l_meter: {:.2f} | r_meter: {:.2f} | VL: {:.3f} | VR: {:.3f}".format(\ - self.control_mode, self.l_meter, self.r_meter, vl, vr) + "\033[0m", end = "") + if (rospy.get_param("/motor_driver_node/debug")): + print("\033[32m" + "x: {:f} | y: {:f} | yaw: {:f} | Wr: {:f} | Wl: {:f}".format(self.x, self.y, np.rad2deg(self.theta), self.Wr, self.Wl) + "\033[0m") else: - print("\033[32m" + "\rcontrol_mode: {:d} | left_rpm: {:.2f} | right_rpm: {:.2f} | l_meter: {:.2f} | r_meter: {:.2f} | VL: {:.3f} | VR: {:.3f}".format(\ - self.control_mode, fb_L_rpm, -fb_R_rpm, self.l_meter, self.r_meter, vl, vr) + "\033[0m", end = "") + #print("\033[32m" + "Debugging features disable" + "\033[0m") + pass rate.sleep() @@ -374,4 +489,4 @@ rospy.spin() if __name__ == "__main__": - main() \ No newline at end of file + main()