diff --git a/docs/hardware_docs/UR/Hand-E_Manual_UniversalRobots_PDF_20220114.pdf b/docs/hardware_docs/robotiq_gripper/Hand-E_Manual_UniversalRobots_PDF_20220114.pdf similarity index 100% rename from docs/hardware_docs/UR/Hand-E_Manual_UniversalRobots_PDF_20220114.pdf rename to docs/hardware_docs/robotiq_gripper/Hand-E_Manual_UniversalRobots_PDF_20220114.pdf diff --git a/old_note b/old_note new file mode 100644 index 0000000000000000000000000000000000000000..cdb0c63aa0e2c28ac323ec7ae13d6898a5e194ba --- /dev/null +++ b/old_note @@ -0,0 +1,30 @@ + +1. do a writing demo +--------------------- +- use pinocchio to get fast inverse kinematics and dynamics -> done +- ensure some sim/visualization works -> need to recompile some urdf to get the visual stuff +- use/redo albin's code so that you have the same thing + - read and understand (without all the theory) what is going on + - make an implementation roadmap + - implement +- try out built-in ur force control +- get a nice drawing input interface on some touch screen +- do tests so that you know it works + +2. implement all algorithms up to force control via velocity inputs +----------------------------------------------------------------------------- +- do as the title says +- impedance control done by students in project +- some basic pushing done by other students + +3. can the gripper drop and catch long objects? +------------------------------------------------ +- you literally don't even need to control the arm for this +- the key points to check are: + - can you do force control with the gripper, + i.e. in any way (obv thru hax) get it to hold sth with a certain force + - see how fast this is + + +3. write and test hold + flip +--------------------------------- diff --git a/python/convenience_tool_box/frame_validation.py b/python/convenience_tool_box/frame_validation.py new file mode 100644 index 0000000000000000000000000000000000000000..b7bb55df85ff55b5f68792f9e63639ee4fb06f4f --- /dev/null +++ b/python/convenience_tool_box/frame_validation.py @@ -0,0 +1,78 @@ +import pinocchio as pin +import numpy as np +import matplotlib.pyplot as plt +import sys +import time +import copy +import signal +from ur_simple_control.managers import RobotManager +from ur_simple_control.clik.clik_point_to_point import get_args + +args = get_args() +robot = RobotManager(args) + +#print("payload", robot.rtde_receive.getPayload()) +#print("payload cog", robot.rtde_receive.getPayloadCog()) +#print("payload ixx, iyy, izz, angular", robot.rtde_receive.getPayloadInertia()) + +ft_readings = [] +dt = 1/500 +#while True: +for i in range(5000): + start = time.time() + q = robot.rtde_receive.getActualQ() + ft = robot.rtde_receive.getActualTCPForce() + tau = robot.rtde_control.getJointTorques() + current = robot.rtde_receive.getActualCurrent() + q.append(0.0) + q.append(0.0) + pinMtool = robot.getMtool() + + if i % 25 == 0: + print("ur5:", *np.array(robot.rtde_receive.getActualTCPPose()).round(4)) + print("pin:", *pinMtool.translation.round(4), *pin.rpy.matrixToRpy(pinMtool.rotation).round(4)) + #print("current", current) + #print("getActualTCPForce", ft) + #print("tau", tau) + ft_readings.append(ft) + end = time.time() + diff = end - start + if diff < dt: + time.sleep(dt - diff) + + +ft_readings = np.array(ft_readings) +time = np.arange(len(ft_readings)) +plt.title('fts') +ax = plt.subplot(231) +ax.plot(time, ft_readings[:,0]) +ax = plt.subplot(232) +ax.plot(time, ft_readings[:,1]) +ax = plt.subplot(233) +ax.plot(time, ft_readings[:,2]) +ax = plt.subplot(234) +ax.plot(time, ft_readings[:,3]) +ax = plt.subplot(235) +ax.plot(time, ft_readings[:,4]) +ax = plt.subplot(236) +ax.plot(time, ft_readings[:,5]) +print("average over time", np.average(ft_readings, axis=0)) +plt.savefig('fts.png', dpi=600) +plt.show() +# ft = rtde_receive.getFtRawWrench() +# print("getFtRawWrench", ft) +# print("payload inertia", rtde_receive.getPayloadInertia()) +# print("momentum", rtde_receive.getActualMomentum()) +# print("target qdd", rtde_receive.getTargetQdd()) +# print("robot_current", rtde_receive.getActualRobotCurrent()) +# print("joint_voltage", rtde_receive.getActualJointVoltage()) +# print("robot_voltage", rtde_receive.getActualRobotVoltage()) +# print("getSafetyMode", rtde_receive.getSafetyMode()) +# print("tool_accelerometer", rtde_receive.getActualToolAccelerometer()) +# q.append(0.0) +# q.append(0.0) +# pin.forwardKinematics(model, data, np.array(q)) +# print(data.oMi[6]) +# print("pin:", *data.oMi[6].translation.round(4), *pin.rpy.matrixToRpy(data.oMi[6].rotation).round(4)) +# print("ur5:", *np.array(rtde_receive.getActualTCPPose()).round(4)) +# time.sleep(0.005) diff --git a/python/convenience_tool_box/ft_readings.py b/python/convenience_tool_box/ft_readings.py index a43f9ef772e38d1a0622e25dd972e568ff6151a3..bbe22bfff8dcff03e83bab1587213985fe7bfcd4 100644 --- a/python/convenience_tool_box/ft_readings.py +++ b/python/convenience_tool_box/ft_readings.py @@ -8,10 +8,6 @@ import signal from ur_simple_control.managers import RobotManager from ur_simple_control.clik.clik_point_to_point import get_args - - - - args = get_args() robot = RobotManager(args) diff --git a/python/convenience_tool_box/fts.png b/python/convenience_tool_box/fts.png index 4195055f7686019be819db83f4ba74c68829d9a9..7b3f302d2d66ef6e41abfeafdd890bb0f0526104 100644 Binary files a/python/convenience_tool_box/fts.png and b/python/convenience_tool_box/fts.png differ diff --git a/python/convenience_tool_box/measuring_stick.py b/python/convenience_tool_box/measuring_stick.py index 97708bcdac52fdca7788ca3a48380845848ae40a..189bbe83d4de625928dcde8b2726add4a7e706c4 100644 --- a/python/convenience_tool_box/measuring_stick.py +++ b/python/convenience_tool_box/measuring_stick.py @@ -4,42 +4,30 @@ import sys import os from os.path import dirname, join, abspath import time -from pinocchio.visualize import GepettoVisualizer -import gepetto.corbaserver from rtde_control import RTDEControlInterface as RTDEControl from rtde_receive import RTDEReceiveInterface as RTDEReceive import os import copy import signal -from give_me_the_calibrated_model import get_model +from ur_simple_control.managers import RobotManager +from ur_simple_control.clik.clik_point_to_point import get_args def handler(signum, frame): print('i will end freedrive and exit') rtde_control.endFreedriveMode() exit() +args = get_args() +robot = RobotManager(args) -rtde_control = RTDEControl("192.168.1.102") -rtde_receive = RTDEReceive("192.168.1.102") -while not rtde_control.isConnected(): - continue -print("connected") -rtde_control.freedriveMode() +robot.rtde_control.freedriveMode() signal.signal(signal.SIGINT, handler) -urdf_path_relative = "../robot_descriptions/urdf/ur5e_with_robotiq_hande.urdf" -urdf_path_absolute = os.path.abspath(urdf_path_relative) -mesh_dir = "../robot_descriptions/" -mesh_dir_absolute = os.path.abspath(mesh_dir) -model, data = get_model(urdf_path_absolute, mesh_dir_absolute) while True: - q = rtde_receive.getActualQ() - q.append(0.0) - q.append(0.0) - pin.forwardKinematics(model, data, np.array(q)) - print(data.oMi[6]) - print("pin:", *data.oMi[6].translation.round(4), *pin.rpy.matrixToRpy(data.oMi[6].rotation).round(4)) - print("ur5:", *np.array(rtde_receive.getActualTCPPose()).round(4)) + Mtool = robot.getMtool() + print(Mtool) + print("pin:", *Mtool.translation.round(4), *pin.rpy.matrixToRpy(Mtool.rotation).round(4)) + print("ur5:", *np.array(robot.rtde_receive.getActualTCPPose()).round(4)) time.sleep(0.005) diff --git a/python/convenience_tool_box/open_close_gripper.py b/python/convenience_tool_box/open_close_gripper.py index 64719630427560dcf8df12281903e8a6ea3ea697..168175e4cd797432c034533cfe4fcfbf12dcf24a 100644 --- a/python/convenience_tool_box/open_close_gripper.py +++ b/python/convenience_tool_box/open_close_gripper.py @@ -19,7 +19,7 @@ signal.signal(signal.SIGINT, handler) gripper = RobotiqGripper() gripper.connect("192.168.1.102", 63352) -time.sleep(3) +time.sleep(8) gripper.activate() #time.sleep(3) gripper.move(0,100,100) diff --git a/python/examples/clik.py b/python/examples/clik.py index 512934296fb2fbf38f00cc75a48bb657685f33f6..f066ec8870934cd454dd81387fa071b18f95aa1f 100644 --- a/python/examples/clik.py +++ b/python/examples/clik.py @@ -56,6 +56,8 @@ def get_args(): # maybe you want to scale the control signal parser.add_argument('--controller-speed-scaling', type=float, \ default='1.0', help='not actually_used atm') + parser.add_argument('--debug-prints', action=argparse.BooleanOptionalAction, \ + help="print some debug info", default=False) args = parser.parse_args() if args.gripper and args.simulation: diff --git a/python/examples/data/clik_run_001.pickle b/python/examples/data/clik_run_001.pickle index b6f8dbe767e5519830eb411f9c88c84156970430..846fe62b4ea4080532e231ec924e77c2c703c7f7 100644 Binary files a/python/examples/data/clik_run_001.pickle and b/python/examples/data/clik_run_001.pickle differ diff --git a/python/examples/drawing_from_input_drawing.py b/python/examples/drawing_from_input_drawing.py index f4960c80afce32ba7e4304d63a00bff28ebeec6c..eb98e6ad20bbd1073e21f8f6137707a882ceb088 100644 --- a/python/examples/drawing_from_input_drawing.py +++ b/python/examples/drawing_from_input_drawing.py @@ -25,7 +25,6 @@ from ur_simple_control.clik.clik_point_to_point import getClikController, moveL, from ur_simple_control.clik.clik_trajectory_following import map2DPathTo3DPlane, clikCartesianPathIntoJointPath from ur_simple_control.managers import ControlLoopManager, RobotManager from ur_simple_control.util.calib_board_hacks import calibratePlane, getSpeedInDirectionOfN -from ur_simple_control.visualize.visualize import plotFromDict from ur_simple_control.basics.basics import moveJ ####################################################################### @@ -64,6 +63,8 @@ def getArgs(): BE CAREFUL WITH THIS.", default=1.0) parser.add_argument('--max-iterations', type=int, \ help="maximum allowable iteration number (it runs at 500Hz)", default=50000) + parser.add_argument('--debug-prints', action=argparse.BooleanOptionalAction, \ + help="print some debug info", default=False) ####################################################################### # your controller specific arguments # ####################################################################### @@ -111,7 +112,11 @@ def getArgs(): default=0.001) parser.add_argument('--alpha', type=float, \ help="force feedback proportional coefficient", \ - default=0.007) + #default=0.007) + default=0.05) + parser.add_argument('--beta', type=float, \ + help="low-pass filter beta parameter", \ + default=0.01) # TODO add low pass filtering and make it's parameters arguments too ####################################################################### # task specific arguments # @@ -119,19 +124,25 @@ def getArgs(): # TODO measure this for the new board parser.add_argument('--board-width', type=float, \ help="width of the board (in meters) the robot will write on", \ - default=0.5) + #default=0.5) + default=0.25) parser.add_argument('--board-height', type=float, \ help="height of the board (in meters) the robot will write on", \ - default=0.35) + #default=0.35) + default=0.25) + parser.add_argument('--board-axis', type=str, \ + choices=['z', 'y'], \ + help="(world) axis (direction) in which you want to search for the board", \ + default="z") parser.add_argument('--calibration', action=argparse.BooleanOptionalAction, \ help="whether you want to do calibration", default=False) parser.add_argument('--draw-new', action=argparse.BooleanOptionalAction, \ help="whether draw a new picture, or use the saved path path_in_pixels.csv", default=True) - parser.add_argument('--pick_up_marker', action=argparse.BooleanOptionalAction, \ + parser.add_argument('--pick-up-marker', action=argparse.BooleanOptionalAction, \ help=""" whether the robot should pick up the marker. NOTE: THIS IS FROM A PREDEFINED LOCATION. - """, default=True) + """, default=False) parser.add_argument('--find-marker-offset', action=argparse.BooleanOptionalAction, \ help=""" whether you want to do find marker offset (recalculate TCP @@ -150,45 +161,68 @@ def getArgs(): the simulation yet, sorry :/ . You can have only 1 these flags right now') return args +# go and pick up the marker +# marker position: """ -calibrateFT ------------ -Read from the f/t sensor a bit, average the results -and return the result. -This can be used to offset the bias of the f/t sensor. -NOTE: this is not an ideal solution. -ALSO TODO: test whether the offset changes when -the manipulator is in different poses. + R = + -0.73032 -0.682357 0.0319574 +-0.679774 0.730578 0.0645244 +-0.067376 0.0253997 -0.997404 + p = 0.574534 -0.508343 0.249325 + +pin: 0.5745 -0.5083 0.2493 3.1161 0.0674 -2.392 +ur5: 0.5796 -0.4982 0.0927 -1.1314 2.8725 0.0747 +q: -0.5586 -2.3103 -1.1638 -1.2468 1.6492 0.262 0.0 0.0 + """ -def calibrateFT(robot): - ft_readings = [] - print("Will read from f/t sensors for a some number of seconds") - print("and give you the average.") - print("Use this as offset.") - for i in range(2000): - start = time.time() - q = robot.rtde_receive.getActualQ() - ft = robot.rtde_receive.getActualTCPForce() - tau = robot.rtde_control.getJointTorques() - current = robot.rtde_receive.getActualCurrent() - ft_readings.append(ft) - end = time.time() - diff = end - start - if diff < robot.dt: - time.sleep(robot.dt - diff) - - ft_readings = np.array(ft_readings) - avg = np.average(ft_readings, axis=0) - print("average ft time", avg) - return avg +def getMarker(args, robot): + # init position + Tinit = robot.getMtool().copy() + # goal position, predefined + Tgoal = pin.SE3() + Tgoal.rotation = np.array([ + [ -0.73032, -0.682357, 0.0319574], + [-0.679774, 0.730578, 0.0645244], + [-0.067376, 0.0253997, -0.997404]]) + Tgoal.translation = np.array([0.574534, -0.508343, 0.249325]) + # slighly up from goal to not hit marker weirdly + TgoalUP = Tgoal.copy() + TgoalUP.translation += np.array([0,0,0.1]) -# go and pick up the marker -def getMarker(q_init): - pass + # instantiate controller + clik_controller = getClikController(args) + controlLoop = partial(controlLoopClik, robot, clik_controller) + log_dict = { + 'qs' : np.zeros((args.max_iterations, robot.model.nq)), + 'dqs' : np.zeros((args.max_iterations, robot.model.nq)), + } + loop_manager = ControlLoopManager(robot, controlLoop, args, {}, log_dict) + + print("going to above marker") + robot.Mgoal = TgoalUP.copy() + log_dict, final_iteration = loop_manager.run() + print("going down to marker") + robot.Mgoal = Tgoal.copy() + log_dict, final_iteration = loop_manager.run() + print("picking up marker") + robot.gripper.move(255,255,255) + time.sleep(2) + print("going up") + robot.Mgoal = TgoalUP.copy() + log_dict, final_iteration = loop_manager.run() + print("going back") + robot.Mgoal = Tinit.copy() + log_dict, final_iteration = loop_manager.run() + print("got back") +# robot.stopHandler(None, None) +# robot.stopHandler(None, None) +# robot.stopHandler(None, None) +# print("bye") +# exit() """ -getMarkerOffset +findMarkerOffset --------------- This relies on having the correct orientation of the plane and the correct translation vector for top-left corner. @@ -196,17 +230,22 @@ Idea is you pick up the marker, go to the top corner, touch it, and see the difference between that and the translation vector. Obviously it's just a hacked solution, but it works so who cares. """ -def getMarkerOffset(args, robot, rotation_matrix, translation_vector, q_init): +def findMarkerOffset(args, robot, rotation_matrix, translation_vector, q_init): # TODO make this more general # so TODO: calculate TCP speed based on the rotation matrix # and then go - #z_of_rot = rotation_matrix[:,2] - y_of_rot = rotation_matrix[:,1] + if args.board_axis == 'z': + axis_of_rot = rotation_matrix[:,2] + elif args.board_axis == 'y': + axis_of_rot = rotation_matrix[:,1] + else: + print("you passed", board_axis, ", but it has to be 'z' or 'y'") + exit() # it's going out of the board, and we want to go into the board, right???? # TODO test this #z_of_rot = z_of_rot - print("vector i'm following:", y_of_rot) - speed = getSpeedInDirectionOfN(rotation_matrix) + print("vector i'm following:", axis_of_rot) + speed = getSpeedInDirectionOfN(rotation_matrix, args.board_axis) #speed[2] = speed[2] * -1 #robot.rtde_control.moveUntilContact(speed) moveUntilContact(args, robot, speed) @@ -230,6 +269,7 @@ def getMarkerOffset(args, robot, rotation_matrix, translation_vector, q_init): ####################################################################### # feedforward velocity, feedback position and force for impedance +# TODO: actually write this out def controller(): pass @@ -261,6 +301,7 @@ def controlLoopWriting(wrench_offset, dmp, tc, controller, robot, i, past_data): tau = dmp.tau + tc.update(dmp, robot.dt) * robot.dt dmp.set_tau(tau) q = robot.getQ() + Mtool = robot.getMtool() # TODO look into UR code/api for estimating the same # based on currents in the joints. # it's probably worse, but maybe some sensor fusion-type thing @@ -269,26 +310,28 @@ def controlLoopWriting(wrench_offset, dmp, tc, controller, robot, i, past_data): #Z = np.diag(np.array([0.6, 0.6, 1.0, 0.5, 0.5, 0.5])) #Z = np.diag(np.array([0.6, 1.0, 0.6, 0.5, 0.5, 0.5])) #Z = np.diag(np.array([1.0, 1.0, 1.0, 1.0, 1.0, 1.0])) - Z = np.diag(np.ones(6)) + Z = np.diag(np.array([0.0, 0.0, 2.0, 0.0, 0.0, 0.0])) + #Z = np.diag(np.ones(6)) #Z = np.diag(np.array([0.1, 0.1, 1.0, 0.1, 0.1, 0.1])) #Z = np.diag(np.array([1.0, 0.6, 1.0, 0.5, 0.5, 0.5])) wrench = robot.getWrench() wrench = wrench - wrench_offset - wrench = np.average(np.array(past_data['wrench']), axis=0) + #wrench = np.average(np.array(past_data['wrench']), axis=0) # first-order low pass filtering instead # beta is a smoothing coefficient, smaller values smooth more, has to be in [0,1] - beta = 0.007 - #wrench = beta * wrench + (1 - beta) * past_data['wrench'][-1] - - wrench = robot.getMtool().toDualActionMatrix().T @ wrench - wrench = Z @ robot.getWrench() - # evil hack because wrench is not zeros (why? - no idea whatsoever) - # TODO: run it empty and zero it - #wrench = wrench - np.array([-1.14156273, 11.05155707, 1.88523016, -0.06643418, 0.16550734, 0.09019818]) - #wrench = wrench - np.array([ -2.89005509, 18.11969302, -1.92425821, -0.08124564, 0.08441558, 0.06800772]) - #wrench = wrench - np.array( [ 0.38101014, -0.32524308, 0.50800527, -0.00830584, 0.06112097, 0.01231109]) + wrench = args.beta * wrench + (1 - args.beta) * past_data['wrench'][-1] + + # it's just coordinate change from base to end-effector, + # they're NOT the same rigid body, + # the vector itself is not changing, only the coordinate representation + mapping = np.zeros((6,6)) + mapping[0:3, 0:3] = Mtool.rotation + mapping[3:6, 3:6] = Mtool.rotation + wrench = mapping.T @ wrench + + wrench = Z @ wrench # deepcopy for good coding practise (and correctness here) save_past_dict['wrench'] = copy.deepcopy(wrench) # rolling average @@ -305,9 +348,7 @@ def controlLoopWriting(wrench_offset, dmp, tc, controller, robot, i, past_data): # - feedback the position # TODO: don't use vel for qd, it's confusion (yes, that means changing dmp code too) # TODO: put this in a controller function for easy swapping (or don't if you won't swap) - # solve this q number connundrum - # TODO evil hack - #vel_cmd = dmp.vel + args.kp * (dmp.pos - q[:6].reshape((6,1))) - args.alpha * tau + # solve this q[:6] bs (clean it up) vel_cmd = dmp.vel + args.kp * (dmp.pos - q[:6].reshape((6,1))) + args.alpha * tau robot.sendQd(vel_cmd) @@ -332,11 +373,13 @@ if __name__ == "__main__": # software setup # ####################################################################### args = getArgs() + print(args) clikController = getClikController(args) robot = RobotManager(args) # calibrate FT first - wrench_offset = calibrateFT(robot) + wrench_offset = robot.calibrateFT() + robot.wrench_offset = wrench_offset ####################################################################### # drawing a path, making a joint trajectory for it # ####################################################################### @@ -354,15 +397,22 @@ if __name__ == "__main__": rotation_matrix, translation_vector, q_init = \ calibratePlane(args, robot, args.board_width, args.board_height, \ args.n_calibration_tests) + print(q_init) + print(rotation_matrix) + print(translation_vector) else: # TODO: save this somewhere obviously # also make it prettier if possible print("using predefined values") - q_init = np.array([1.4545, -1.7905, -1.1806, -1.0959, 1.6858, -0.1259, 0.0, 0.0]) - translation_vector = np.array([0.10125722 ,0.43077874 ,0.9110792 ]) - rotation_matrix = np.array([[1. , 0. ,0.00336406], - [-0. , -0.00294646, 0.99999 ], - [ 0. , -0.99999 , -0.00294646]]) + #q_init = np.array([1.4545, -1.7905, -1.1806, -1.0959, 1.6858, -0.1259, 0.0, 0.0]) + #translation_vector = np.array([0.10125722 ,0.43077874 ,0.9110792 ]) + #rotation_matrix = np.array([[1. , 0. ,0.00336406], + # [-0. , -0.00294646, 0.99999 ], + # [ 0. , -0.99999 , -0.00294646]]) + q_init = robot.getQ() + Mtool = robot.getMtool() + translation_vector = Mtool.translation.copy() + rotation_matrix = Mtool.rotation.copy() # make the path 3D path = map2DPathTo3DPlane(pixel_path, args.board_width, args.board_height) @@ -372,13 +422,12 @@ if __name__ == "__main__": # ---> just go to the board while you have the marker ready to find this # ---> do that right here if args.pick_up_marker: - # pick up the marker - #TODO - pass + getMarker(args, robot) + if args.find_marker_offset: # find the marker offset # TODO find a better q init (just moveL away from the board) - marker_offset = getMarkerOffset(args, robot, rotation_matrix, translation_vector, q_init) + marker_offset = findMarkerOffset(args, robot, rotation_matrix, translation_vector, q_init) print('marker_offset', marker_offset) robot.stopHandler(None,None) # Z @@ -400,8 +449,8 @@ if __name__ == "__main__": # NOTE: not a single one is the one, the f/t sensor sucks # and this is the best number to change to get it to work [upside_down_emoji] # but this is very close - path = path + np.array([0.0, 0.0, -0.0785]) - #path = path + np.array([0.0, 0.0, -0.1043]) + #path = path + np.array([0.0, 0.0, -0.0785]) + path = path + np.array([0.0, 0.0, -0.1043]) #path = path + np.array([0.0, 0.0, -0.1000]) #path = path + np.array([0.0, 0.0, -0.1573]) #path = path + np.array([0.0, 0.2938, 0.0]) @@ -479,6 +528,7 @@ if __name__ == "__main__": mtool = robot.getMtool(q_given=first_q) mtool.translation[1] = mtool.translation[1] - 0.0035 #mtool.translation[1] = mtool.translation[1] - 0.04 + print('going to starting write position') moveL(args, robot, mtool) #moveL @@ -486,7 +536,11 @@ if __name__ == "__main__": # and now we can actually run log_dict, final_iteration = loop_manager.run() mtool = robot.getMtool() - mtool.translation[1] = mtool.translation[1] - 0.1 + print("move a bit back") + if args.board_axis == 'z' or args.board_axis == 'y': + mtool.translation[1] = mtool.translation[1] - 0.1 +# if args.board_axis == 'z': +# mtool.translation[2] = mtool.translation[2] - 0.1 moveL(args, robot, mtool) plotFromDict(log_dict, args) diff --git a/python/examples/joint_trajectory.csv b/python/examples/joint_trajectory.csv index e4f0ced8473c19dc1d29e97cbdf3acff06fd9e75..7ebe7e40e3b8dbe54c82d0726088625d1f3a0b86 100644 --- a/python/examples/joint_trajectory.csv +++ b/python/examples/joint_trajectory.csv @@ -1,1979 +1,2512 @@ -0.00000,1.33657,-1.36538,-1.50287,-0.27666,1.80517,0.00400 -0.00253,1.33696,-1.36530,-1.50246,-0.27715,1.80479,0.00400 -0.00506,1.33734,-1.36522,-1.50205,-0.27762,1.80442,0.00400 -0.00758,1.33771,-1.36515,-1.50166,-0.27809,1.80406,0.00401 -0.01011,1.33808,-1.36507,-1.50127,-0.27855,1.80370,0.00401 -0.01264,1.33844,-1.36500,-1.50088,-0.27900,1.80335,0.00401 -0.01517,1.33879,-1.36493,-1.50051,-0.27945,1.80300,0.00401 -0.01769,1.33915,-1.36486,-1.50014,-0.27988,1.80266,0.00401 -0.02022,1.33949,-1.36479,-1.49977,-0.28031,1.80232,0.00401 -0.02275,1.33983,-1.36472,-1.49941,-0.28073,1.80199,0.00401 -0.02528,1.34016,-1.36466,-1.49906,-0.28115,1.80167,0.00402 -0.02781,1.34049,-1.36459,-1.49871,-0.28156,1.80135,0.00402 -0.03033,1.34081,-1.36453,-1.49837,-0.28196,1.80103,0.00402 -0.03286,1.34112,-1.36447,-1.49806,-0.28233,1.80073,0.00402 -0.03539,1.34160,-1.36437,-1.49757,-0.28291,1.80026,0.00402 -0.03792,1.34207,-1.36428,-1.49710,-0.28347,1.79980,0.00402 -0.04044,1.34254,-1.36418,-1.49663,-0.28403,1.79934,0.00402 -0.04297,1.34300,-1.36409,-1.49617,-0.28457,1.79890,0.00402 -0.04550,1.34345,-1.36400,-1.49572,-0.28511,1.79845,0.00403 -0.04803,1.34390,-1.36392,-1.49528,-0.28564,1.79802,0.00403 -0.05056,1.34433,-1.36383,-1.49484,-0.28616,1.79759,0.00403 -0.05308,1.34477,-1.36375,-1.49441,-0.28667,1.79717,0.00403 -0.05561,1.34519,-1.36366,-1.49399,-0.28717,1.79675,0.00403 -0.05814,1.34561,-1.36358,-1.49357,-0.28766,1.79634,0.00403 -0.06067,1.34602,-1.36350,-1.49317,-0.28815,1.79594,0.00403 -0.06320,1.34642,-1.36343,-1.49276,-0.28862,1.79554,0.00403 -0.06572,1.34682,-1.36335,-1.49237,-0.28909,1.79515,0.00404 -0.06825,1.34721,-1.36328,-1.49198,-0.28955,1.79477,0.00404 -0.07078,1.34760,-1.36321,-1.49160,-0.29000,1.79439,0.00404 -0.07331,1.34798,-1.36314,-1.49122,-0.29045,1.79402,0.00404 -0.07583,1.34835,-1.36307,-1.49085,-0.29088,1.79365,0.00404 -0.07836,1.34872,-1.36300,-1.49049,-0.29131,1.79329,0.00404 -0.08089,1.34908,-1.36294,-1.49013,-0.29173,1.79294,0.00404 -0.08342,1.34943,-1.36287,-1.48978,-0.29215,1.79259,0.00404 -0.08595,1.34978,-1.36281,-1.48944,-0.29256,1.79224,0.00404 -0.08847,1.35013,-1.36275,-1.48910,-0.29296,1.79190,0.00404 -0.09100,1.35047,-1.36269,-1.48876,-0.29335,1.79157,0.00404 -0.09353,1.35071,-1.36264,-1.48853,-0.29363,1.79133,0.00404 -0.09606,1.35116,-1.36255,-1.48813,-0.29411,1.79089,0.00404 -0.09858,1.35161,-1.36246,-1.48775,-0.29458,1.79045,0.00404 -0.10111,1.35204,-1.36237,-1.48737,-0.29505,1.79002,0.00405 -0.10364,1.35247,-1.36229,-1.48700,-0.29550,1.78960,0.00405 -0.10617,1.35289,-1.36221,-1.48664,-0.29595,1.78919,0.00405 -0.10870,1.35331,-1.36212,-1.48628,-0.29639,1.78878,0.00405 -0.11122,1.35372,-1.36204,-1.48592,-0.29683,1.78837,0.00405 -0.11375,1.35412,-1.36196,-1.48557,-0.29725,1.78798,0.00405 -0.11628,1.35452,-1.36189,-1.48523,-0.29767,1.78759,0.00405 -0.11881,1.35491,-1.36181,-1.48490,-0.29808,1.78720,0.00405 -0.12133,1.35529,-1.36174,-1.48457,-0.29849,1.78683,0.00405 -0.12386,1.35567,-1.36166,-1.48424,-0.29888,1.78645,0.00405 -0.12639,1.35604,-1.36159,-1.48392,-0.29928,1.78609,0.00405 -0.12892,1.35641,-1.36152,-1.48361,-0.29966,1.78573,0.00405 -0.13145,1.35677,-1.36146,-1.48329,-0.30005,1.78536,0.00405 -0.13397,1.35720,-1.36138,-1.48291,-0.30051,1.78494,0.00405 -0.13650,1.35762,-1.36130,-1.48253,-0.30096,1.78453,0.00405 -0.13903,1.35804,-1.36122,-1.48215,-0.30141,1.78412,0.00405 -0.14156,1.35845,-1.36115,-1.48179,-0.30185,1.78372,0.00406 -0.14408,1.35885,-1.36108,-1.48143,-0.30228,1.78332,0.00406 -0.14661,1.35924,-1.36101,-1.48107,-0.30271,1.78293,0.00406 -0.14914,1.35963,-1.36094,-1.48072,-0.30313,1.78255,0.00406 -0.15167,1.36001,-1.36087,-1.48038,-0.30354,1.78217,0.00406 -0.15420,1.36039,-1.36081,-1.48004,-0.30394,1.78180,0.00406 -0.15672,1.36076,-1.36074,-1.47971,-0.30434,1.78143,0.00406 -0.15925,1.36113,-1.36068,-1.47939,-0.30473,1.78107,0.00406 -0.16178,1.36149,-1.36062,-1.47907,-0.30511,1.78072,0.00406 -0.16431,1.36169,-1.36058,-1.47890,-0.30532,1.78051,0.00406 -0.16684,1.36233,-1.36043,-1.47848,-0.30588,1.77989,0.00406 -0.16936,1.36296,-1.36028,-1.47808,-0.30643,1.77927,0.00406 -0.17189,1.36358,-1.36014,-1.47768,-0.30697,1.77866,0.00406 -0.17442,1.36419,-1.36000,-1.47729,-0.30750,1.77806,0.00406 -0.17695,1.36479,-1.35987,-1.47690,-0.30803,1.77746,0.00406 -0.17947,1.36538,-1.35973,-1.47652,-0.30854,1.77688,0.00407 -0.18200,1.36597,-1.35960,-1.47615,-0.30904,1.77631,0.00407 -0.18453,1.36654,-1.35947,-1.47578,-0.30954,1.77574,0.00407 -0.18706,1.36710,-1.35935,-1.47542,-0.31003,1.77519,0.00407 -0.18959,1.36766,-1.35922,-1.47506,-0.31051,1.77464,0.00407 -0.19211,1.36820,-1.35910,-1.47471,-0.31098,1.77410,0.00407 -0.19464,1.36874,-1.35898,-1.47437,-0.31144,1.77357,0.00407 -0.19717,1.36927,-1.35887,-1.47403,-0.31190,1.77305,0.00407 -0.19970,1.36979,-1.35875,-1.47370,-0.31234,1.77253,0.00407 -0.20222,1.37031,-1.35864,-1.47337,-0.31278,1.77202,0.00407 -0.20475,1.37081,-1.35853,-1.47305,-0.31321,1.77152,0.00407 -0.20728,1.37131,-1.35843,-1.47274,-0.31364,1.77103,0.00407 -0.20981,1.37180,-1.35832,-1.47243,-0.31406,1.77055,0.00408 -0.21234,1.37228,-1.35822,-1.47212,-0.31447,1.77007,0.00408 -0.21486,1.37276,-1.35812,-1.47182,-0.31487,1.76960,0.00408 -0.21739,1.37322,-1.35802,-1.47153,-0.31526,1.76914,0.00408 -0.21992,1.37368,-1.35792,-1.47124,-0.31565,1.76869,0.00408 -0.22245,1.37414,-1.35782,-1.47095,-0.31604,1.76824,0.00408 -0.22497,1.37458,-1.35773,-1.47067,-0.31641,1.76780,0.00408 -0.22750,1.37502,-1.35764,-1.47039,-0.31678,1.76736,0.00408 -0.23003,1.37545,-1.35755,-1.47012,-0.31714,1.76693,0.00408 -0.23256,1.37588,-1.35746,-1.46986,-0.31750,1.76651,0.00408 -0.23509,1.37629,-1.35737,-1.46960,-0.31785,1.76610,0.00408 -0.23761,1.37660,-1.35731,-1.46941,-0.31810,1.76580,0.00408 -0.24014,1.37718,-1.35717,-1.46912,-0.31853,1.76523,0.00408 -0.24267,1.37774,-1.35704,-1.46884,-0.31895,1.76466,0.00408 -0.24520,1.37830,-1.35690,-1.46856,-0.31937,1.76411,0.00408 -0.24772,1.37885,-1.35677,-1.46828,-0.31977,1.76357,0.00408 -0.25025,1.37940,-1.35665,-1.46801,-0.32017,1.76303,0.00408 -0.25278,1.37993,-1.35652,-1.46775,-0.32057,1.76250,0.00408 -0.25531,1.38045,-1.35640,-1.46749,-0.32095,1.76198,0.00409 -0.25784,1.38097,-1.35628,-1.46723,-0.32133,1.76147,0.00409 -0.26036,1.38148,-1.35616,-1.46698,-0.32171,1.76097,0.00409 -0.26289,1.38198,-1.35604,-1.46673,-0.32207,1.76047,0.00409 -0.26542,1.38247,-1.35593,-1.46649,-0.32243,1.75998,0.00409 -0.26795,1.38296,-1.35582,-1.46625,-0.32279,1.75950,0.00409 -0.27048,1.38344,-1.35571,-1.46601,-0.32314,1.75903,0.00409 -0.27300,1.38391,-1.35560,-1.46578,-0.32348,1.75856,0.00409 -0.27553,1.38437,-1.35549,-1.46555,-0.32381,1.75810,0.00409 -0.27806,1.38483,-1.35539,-1.46533,-0.32414,1.75765,0.00409 -0.28059,1.38528,-1.35529,-1.46511,-0.32447,1.75720,0.00409 -0.28311,1.38552,-1.35523,-1.46500,-0.32464,1.75696,0.00409 -0.28564,1.38615,-1.35506,-1.46478,-0.32503,1.75634,0.00409 -0.28817,1.38677,-1.35490,-1.46456,-0.32541,1.75572,0.00409 -0.29070,1.38739,-1.35474,-1.46434,-0.32579,1.75512,0.00409 -0.29323,1.38799,-1.35458,-1.46413,-0.32616,1.75452,0.00410 -0.29575,1.38858,-1.35443,-1.46392,-0.32652,1.75393,0.00410 -0.29828,1.38917,-1.35428,-1.46372,-0.32688,1.75335,0.00410 -0.30081,1.38974,-1.35413,-1.46352,-0.32724,1.75278,0.00410 -0.30334,1.39031,-1.35398,-1.46332,-0.32758,1.75222,0.00410 -0.30586,1.39087,-1.35384,-1.46313,-0.32792,1.75166,0.00410 -0.30839,1.39142,-1.35370,-1.46294,-0.32826,1.75112,0.00410 -0.31092,1.39196,-1.35356,-1.46275,-0.32858,1.75058,0.00410 -0.31345,1.39249,-1.35342,-1.46257,-0.32891,1.75005,0.00410 -0.31598,1.39302,-1.35329,-1.46239,-0.32922,1.74953,0.00410 -0.31850,1.39354,-1.35316,-1.46221,-0.32954,1.74902,0.00410 -0.32103,1.39405,-1.35303,-1.46204,-0.32984,1.74851,0.00410 -0.32356,1.39455,-1.35290,-1.46186,-0.33014,1.74802,0.00411 -0.32609,1.39504,-1.35278,-1.46170,-0.33044,1.74753,0.00411 -0.32861,1.39552,-1.35265,-1.46153,-0.33073,1.74704,0.00411 -0.33114,1.39585,-1.35257,-1.46143,-0.33091,1.74672,0.00411 -0.33367,1.39666,-1.35233,-1.46128,-0.33131,1.74592,0.00411 -0.33620,1.39746,-1.35210,-1.46113,-0.33169,1.74513,0.00411 -0.33873,1.39825,-1.35187,-1.46099,-0.33207,1.74434,0.00411 -0.34125,1.39903,-1.35164,-1.46085,-0.33244,1.74357,0.00411 -0.34378,1.39980,-1.35142,-1.46071,-0.33281,1.74282,0.00412 -0.34631,1.40055,-1.35120,-1.46057,-0.33317,1.74207,0.00412 -0.34884,1.40129,-1.35099,-1.46043,-0.33352,1.74133,0.00412 -0.35137,1.40203,-1.35078,-1.46030,-0.33387,1.74061,0.00412 -0.35389,1.40275,-1.35057,-1.46017,-0.33421,1.73990,0.00412 -0.35642,1.40346,-1.35037,-1.46004,-0.33454,1.73919,0.00412 -0.35895,1.40415,-1.35017,-1.45991,-0.33487,1.73850,0.00412 -0.36148,1.40484,-1.34997,-1.45979,-0.33519,1.73782,0.00413 -0.36400,1.40552,-1.34978,-1.45967,-0.33551,1.73715,0.00413 -0.36653,1.40619,-1.34959,-1.45955,-0.33582,1.73648,0.00413 -0.36906,1.40684,-1.34941,-1.45943,-0.33613,1.73583,0.00413 -0.37159,1.40749,-1.34922,-1.45932,-0.33643,1.73519,0.00413 -0.37412,1.40813,-1.34904,-1.45920,-0.33673,1.73456,0.00413 -0.37664,1.40875,-1.34887,-1.45909,-0.33702,1.73393,0.00413 -0.37917,1.40937,-1.34869,-1.45898,-0.33731,1.73332,0.00413 -0.38170,1.40998,-1.34852,-1.45888,-0.33759,1.73272,0.00414 -0.38423,1.41058,-1.34835,-1.45877,-0.33787,1.73212,0.00414 -0.38675,1.41117,-1.34819,-1.45867,-0.33814,1.73153,0.00414 -0.38928,1.41175,-1.34803,-1.45857,-0.33841,1.73096,0.00414 -0.39181,1.41232,-1.34787,-1.45847,-0.33867,1.73039,0.00414 -0.39434,1.41288,-1.34771,-1.45837,-0.33893,1.72983,0.00414 -0.39687,1.41344,-1.34756,-1.45827,-0.33918,1.72927,0.00414 -0.39939,1.41398,-1.34740,-1.45818,-0.33943,1.72873,0.00414 -0.40192,1.41452,-1.34726,-1.45809,-0.33967,1.72820,0.00414 -0.40445,1.41505,-1.34711,-1.45800,-0.33991,1.72767,0.00415 -0.40698,1.41560,-1.34695,-1.45791,-0.34016,1.72712,0.00415 -0.40950,1.41641,-1.34671,-1.45786,-0.34046,1.72632,0.00415 -0.41203,1.41721,-1.34647,-1.45781,-0.34076,1.72553,0.00415 -0.41456,1.41799,-1.34623,-1.45776,-0.34105,1.72475,0.00415 -0.41709,1.41876,-1.34600,-1.45771,-0.34133,1.72399,0.00415 -0.41962,1.41952,-1.34577,-1.45766,-0.34162,1.72323,0.00416 -0.42214,1.42027,-1.34554,-1.45762,-0.34189,1.72249,0.00416 -0.42467,1.42101,-1.34532,-1.45757,-0.34216,1.72176,0.00416 -0.42720,1.42174,-1.34510,-1.45753,-0.34243,1.72104,0.00416 -0.42973,1.42245,-1.34489,-1.45748,-0.34269,1.72032,0.00416 -0.43225,1.42315,-1.34467,-1.45744,-0.34295,1.71962,0.00416 -0.43478,1.42385,-1.34447,-1.45740,-0.34320,1.71894,0.00417 -0.43731,1.42453,-1.34426,-1.45736,-0.34345,1.71826,0.00417 -0.43984,1.42520,-1.34406,-1.45732,-0.34370,1.71759,0.00417 -0.44237,1.42587,-1.34386,-1.45728,-0.34394,1.71693,0.00417 -0.44489,1.42652,-1.34367,-1.45724,-0.34418,1.71628,0.00417 -0.44742,1.42716,-1.34348,-1.45720,-0.34441,1.71564,0.00417 -0.44995,1.42780,-1.34329,-1.45716,-0.34464,1.71501,0.00418 -0.45248,1.42842,-1.34311,-1.45713,-0.34486,1.71439,0.00418 -0.45501,1.42903,-1.34293,-1.45709,-0.34508,1.71378,0.00418 -0.45753,1.42964,-1.34275,-1.45706,-0.34530,1.71317,0.00418 -0.46006,1.43023,-1.34257,-1.45703,-0.34551,1.71258,0.00418 -0.46259,1.43082,-1.34240,-1.45699,-0.34572,1.71200,0.00418 -0.46512,1.43140,-1.34223,-1.45696,-0.34593,1.71142,0.00418 -0.46764,1.43196,-1.34206,-1.45693,-0.34613,1.71085,0.00419 -0.47017,1.43252,-1.34190,-1.45690,-0.34633,1.71029,0.00419 -0.47270,1.43308,-1.34174,-1.45687,-0.34652,1.70974,0.00419 -0.47523,1.43349,-1.34161,-1.45685,-0.34666,1.70933,0.00419 -0.47776,1.43432,-1.34136,-1.45683,-0.34694,1.70850,0.00419 -0.48028,1.43515,-1.34111,-1.45682,-0.34721,1.70769,0.00419 -0.48281,1.43596,-1.34087,-1.45680,-0.34748,1.70688,0.00420 -0.48534,1.43675,-1.34062,-1.45678,-0.34774,1.70609,0.00420 -0.48787,1.43754,-1.34039,-1.45677,-0.34799,1.70531,0.00420 -0.49039,1.43831,-1.34015,-1.45675,-0.34825,1.70454,0.00420 -0.49292,1.43908,-1.33992,-1.45674,-0.34849,1.70378,0.00420 -0.49545,1.43983,-1.33970,-1.45673,-0.34874,1.70304,0.00421 -0.49798,1.44057,-1.33948,-1.45671,-0.34898,1.70230,0.00421 -0.50051,1.44130,-1.33926,-1.45670,-0.34921,1.70157,0.00421 -0.50303,1.44202,-1.33904,-1.45669,-0.34944,1.70086,0.00421 -0.50556,1.44272,-1.33883,-1.45668,-0.34967,1.70016,0.00421 -0.50809,1.44342,-1.33863,-1.45666,-0.34989,1.69946,0.00422 -0.51062,1.44410,-1.33842,-1.45665,-0.35011,1.69878,0.00422 -0.51314,1.44478,-1.33822,-1.45664,-0.35033,1.69811,0.00422 -0.51567,1.44545,-1.33802,-1.45663,-0.35054,1.69745,0.00422 -0.51820,1.44610,-1.33783,-1.45662,-0.35075,1.69679,0.00422 -0.52073,1.44675,-1.33764,-1.45661,-0.35095,1.69615,0.00422 -0.52326,1.44738,-1.33745,-1.45660,-0.35115,1.69552,0.00423 -0.52578,1.44801,-1.33727,-1.45659,-0.35135,1.69489,0.00423 -0.52831,1.44862,-1.33708,-1.45659,-0.35154,1.69428,0.00423 -0.53084,1.44923,-1.33690,-1.45658,-0.35173,1.69367,0.00423 -0.53337,1.44983,-1.33673,-1.45657,-0.35192,1.69307,0.00423 -0.53589,1.45042,-1.33656,-1.45656,-0.35211,1.69248,0.00423 -0.53842,1.45100,-1.33638,-1.45656,-0.35229,1.69191,0.00424 -0.54095,1.45157,-1.33622,-1.45655,-0.35247,1.69133,0.00424 -0.54348,1.45213,-1.33605,-1.45654,-0.35264,1.69077,0.00424 -0.54601,1.45255,-1.33593,-1.45654,-0.35277,1.69036,0.00424 -0.54853,1.45337,-1.33567,-1.45658,-0.35298,1.68954,0.00424 -0.55106,1.45418,-1.33543,-1.45662,-0.35320,1.68873,0.00424 -0.55359,1.45498,-1.33518,-1.45666,-0.35341,1.68794,0.00425 -0.55612,1.45577,-1.33494,-1.45670,-0.35362,1.68716,0.00425 -0.55865,1.45654,-1.33470,-1.45674,-0.35382,1.68639,0.00425 -0.56117,1.45731,-1.33447,-1.45677,-0.35402,1.68563,0.00425 -0.56370,1.45806,-1.33424,-1.45681,-0.35422,1.68488,0.00426 -0.56623,1.45880,-1.33401,-1.45685,-0.35441,1.68414,0.00426 -0.56876,1.45953,-1.33379,-1.45688,-0.35460,1.68341,0.00426 -0.57128,1.46025,-1.33357,-1.45692,-0.35479,1.68270,0.00426 -0.57381,1.46096,-1.33336,-1.45695,-0.35498,1.68199,0.00426 -0.57634,1.46165,-1.33314,-1.45699,-0.35516,1.68130,0.00427 -0.57887,1.46234,-1.33294,-1.45702,-0.35533,1.68061,0.00427 -0.58140,1.46302,-1.33273,-1.45706,-0.35551,1.67994,0.00427 -0.58392,1.46368,-1.33253,-1.45709,-0.35568,1.67927,0.00427 -0.58645,1.46434,-1.33233,-1.45713,-0.35585,1.67862,0.00427 -0.58898,1.46499,-1.33213,-1.45716,-0.35601,1.67797,0.00428 -0.59151,1.46562,-1.33194,-1.45719,-0.35618,1.67734,0.00428 -0.59403,1.46625,-1.33175,-1.45723,-0.35634,1.67671,0.00428 -0.59656,1.46687,-1.33157,-1.45726,-0.35649,1.67609,0.00428 -0.59909,1.46748,-1.33138,-1.45729,-0.35665,1.67549,0.00428 -0.60162,1.46807,-1.33120,-1.45732,-0.35680,1.67489,0.00429 -0.60415,1.46866,-1.33103,-1.45736,-0.35695,1.67430,0.00429 -0.60667,1.46925,-1.33085,-1.45739,-0.35710,1.67372,0.00429 -0.60920,1.46982,-1.33068,-1.45742,-0.35724,1.67314,0.00429 -0.61173,1.47014,-1.33058,-1.45744,-0.35731,1.67283,0.00429 -0.61426,1.47105,-1.33029,-1.45756,-0.35750,1.67192,0.00429 -0.61678,1.47195,-1.33001,-1.45767,-0.35767,1.67103,0.00430 -0.61931,1.47283,-1.32973,-1.45777,-0.35785,1.67015,0.00430 -0.62184,1.47370,-1.32946,-1.45788,-0.35802,1.66928,0.00430 -0.62437,1.47456,-1.32919,-1.45799,-0.35819,1.66843,0.00431 -0.62690,1.47541,-1.32892,-1.45809,-0.35836,1.66759,0.00431 -0.62942,1.47624,-1.32866,-1.45819,-0.35852,1.66676,0.00431 -0.63195,1.47706,-1.32840,-1.45829,-0.35868,1.66594,0.00431 -0.63448,1.47787,-1.32815,-1.45839,-0.35884,1.66513,0.00432 -0.63701,1.47867,-1.32790,-1.45849,-0.35899,1.66434,0.00432 -0.63953,1.47946,-1.32765,-1.45859,-0.35915,1.66356,0.00432 -0.64206,1.48023,-1.32741,-1.45869,-0.35930,1.66279,0.00432 -0.64459,1.48099,-1.32718,-1.45878,-0.35944,1.66203,0.00433 -0.64712,1.48174,-1.32694,-1.45887,-0.35959,1.66128,0.00433 -0.64965,1.48248,-1.32671,-1.45897,-0.35973,1.66054,0.00433 -0.65217,1.48321,-1.32649,-1.45906,-0.35987,1.65982,0.00433 -0.65470,1.48393,-1.32626,-1.45915,-0.36001,1.65910,0.00434 -0.65723,1.48463,-1.32604,-1.45924,-0.36014,1.65840,0.00434 -0.65976,1.48533,-1.32583,-1.45932,-0.36027,1.65770,0.00434 -0.66229,1.48601,-1.32562,-1.45941,-0.36040,1.65702,0.00434 -0.66481,1.48669,-1.32541,-1.45949,-0.36053,1.65634,0.00435 -0.66734,1.48735,-1.32520,-1.45958,-0.36066,1.65568,0.00435 -0.66987,1.48801,-1.32500,-1.45966,-0.36078,1.65502,0.00435 -0.67240,1.48866,-1.32480,-1.45974,-0.36090,1.65438,0.00435 -0.67492,1.48929,-1.32460,-1.45982,-0.36102,1.65374,0.00435 -0.67745,1.48992,-1.32441,-1.45990,-0.36114,1.65311,0.00436 -0.67998,1.49054,-1.32422,-1.45998,-0.36125,1.65250,0.00436 -0.68251,1.49114,-1.32403,-1.46006,-0.36137,1.65189,0.00436 -0.68504,1.49174,-1.32385,-1.46014,-0.36148,1.65129,0.00436 -0.68756,1.49233,-1.32367,-1.46021,-0.36159,1.65070,0.00436 -0.69009,1.49291,-1.32349,-1.46029,-0.36169,1.65012,0.00437 -0.69262,1.49306,-1.32344,-1.46031,-0.36172,1.64997,0.00437 -0.69515,1.49391,-1.32318,-1.46044,-0.36186,1.64913,0.00437 -0.69767,1.49475,-1.32292,-1.46057,-0.36199,1.64829,0.00437 -0.70020,1.49557,-1.32266,-1.46070,-0.36212,1.64747,0.00438 -0.70273,1.49638,-1.32241,-1.46083,-0.36225,1.64666,0.00438 -0.70526,1.49719,-1.32216,-1.46096,-0.36238,1.64586,0.00438 -0.70779,1.49797,-1.32191,-1.46108,-0.36251,1.64508,0.00438 -0.71031,1.49875,-1.32167,-1.46121,-0.36263,1.64430,0.00439 -0.71284,1.49952,-1.32143,-1.46133,-0.36275,1.64354,0.00439 -0.71537,1.50027,-1.32120,-1.46145,-0.36287,1.64279,0.00439 -0.71790,1.50102,-1.32096,-1.46156,-0.36299,1.64205,0.00440 -0.72042,1.50175,-1.32074,-1.46168,-0.36310,1.64131,0.00440 -0.72295,1.50247,-1.32051,-1.46179,-0.36322,1.64059,0.00440 -0.72548,1.50318,-1.32029,-1.46191,-0.36333,1.63988,0.00440 -0.72801,1.50388,-1.32008,-1.46202,-0.36344,1.63919,0.00441 -0.73054,1.50457,-1.31986,-1.46213,-0.36354,1.63850,0.00441 -0.73306,1.50525,-1.31965,-1.46224,-0.36365,1.63782,0.00441 -0.73559,1.50592,-1.31945,-1.46234,-0.36375,1.63715,0.00441 -0.73812,1.50658,-1.31924,-1.46245,-0.36386,1.63649,0.00442 -0.74065,1.50723,-1.31904,-1.46255,-0.36396,1.63584,0.00442 -0.74317,1.50787,-1.31885,-1.46266,-0.36405,1.63520,0.00442 -0.74570,1.50850,-1.31865,-1.46276,-0.36415,1.63457,0.00442 -0.74823,1.50912,-1.31846,-1.46286,-0.36425,1.63395,0.00443 -0.75076,1.50973,-1.31827,-1.46295,-0.36434,1.63333,0.00443 -0.75329,1.51033,-1.31809,-1.46305,-0.36443,1.63273,0.00443 -0.75581,1.51093,-1.31791,-1.46315,-0.36452,1.63214,0.00443 -0.75834,1.51151,-1.31773,-1.46324,-0.36461,1.63155,0.00443 -0.76087,1.51159,-1.31770,-1.46326,-0.36462,1.63148,0.00443 -0.76340,1.51232,-1.31747,-1.46340,-0.36471,1.63075,0.00444 -0.76593,1.51303,-1.31725,-1.46355,-0.36479,1.63003,0.00444 -0.76845,1.51374,-1.31702,-1.46369,-0.36488,1.62933,0.00444 -0.77098,1.51444,-1.31681,-1.46383,-0.36496,1.62863,0.00444 -0.77351,1.51512,-1.31659,-1.46397,-0.36504,1.62795,0.00445 -0.77604,1.51580,-1.31638,-1.46410,-0.36512,1.62727,0.00445 -0.77856,1.51647,-1.31617,-1.46424,-0.36520,1.62660,0.00445 -0.78109,1.51712,-1.31596,-1.46437,-0.36528,1.62595,0.00446 -0.78362,1.51777,-1.31576,-1.46450,-0.36536,1.62530,0.00446 -0.78615,1.51841,-1.31556,-1.46463,-0.36543,1.62466,0.00446 -0.78868,1.51903,-1.31536,-1.46475,-0.36551,1.62404,0.00446 -0.79120,1.51965,-1.31517,-1.46488,-0.36558,1.62342,0.00446 -0.79373,1.52026,-1.31498,-1.46500,-0.36565,1.62281,0.00447 -0.79626,1.52086,-1.31479,-1.46512,-0.36572,1.62221,0.00447 -0.79879,1.52145,-1.31461,-1.46524,-0.36579,1.62161,0.00447 -0.80131,1.52182,-1.31449,-1.46532,-0.36583,1.62125,0.00447 -0.80384,1.52252,-1.31426,-1.46553,-0.36586,1.62055,0.00448 -0.80637,1.52321,-1.31403,-1.46573,-0.36589,1.61985,0.00448 -0.80890,1.52390,-1.31380,-1.46593,-0.36592,1.61917,0.00448 -0.81143,1.52457,-1.31358,-1.46613,-0.36595,1.61850,0.00448 -0.81395,1.52523,-1.31336,-1.46633,-0.36598,1.61783,0.00449 -0.81648,1.52589,-1.31314,-1.46652,-0.36601,1.61718,0.00449 -0.81901,1.52653,-1.31293,-1.46671,-0.36604,1.61654,0.00449 -0.82154,1.52717,-1.31272,-1.46689,-0.36606,1.61590,0.00450 -0.82406,1.52779,-1.31251,-1.46708,-0.36609,1.61528,0.00450 -0.82659,1.52841,-1.31231,-1.46726,-0.36612,1.61466,0.00450 -0.82912,1.52901,-1.31211,-1.46744,-0.36615,1.61405,0.00450 -0.83165,1.52961,-1.31191,-1.46761,-0.36617,1.61345,0.00451 -0.83418,1.53020,-1.31171,-1.46778,-0.36620,1.61286,0.00451 -0.83670,1.53056,-1.31159,-1.46789,-0.36621,1.61250,0.00451 -0.83923,1.53127,-1.31136,-1.46811,-0.36624,1.61180,0.00451 -0.84176,1.53196,-1.31113,-1.46832,-0.36626,1.61110,0.00451 -0.84429,1.53264,-1.31090,-1.46853,-0.36628,1.61042,0.00452 -0.84681,1.53332,-1.31068,-1.46873,-0.36630,1.60975,0.00452 -0.84934,1.53398,-1.31046,-1.46894,-0.36632,1.60909,0.00452 -0.85187,1.53463,-1.31024,-1.46913,-0.36634,1.60843,0.00453 -0.85440,1.53528,-1.31003,-1.46933,-0.36636,1.60779,0.00453 -0.85693,1.53591,-1.30982,-1.46953,-0.36638,1.60715,0.00453 -0.85945,1.53653,-1.30961,-1.46972,-0.36640,1.60653,0.00453 -0.86198,1.53715,-1.30941,-1.46990,-0.36642,1.60591,0.00454 -0.86451,1.53776,-1.30921,-1.47009,-0.36644,1.60531,0.00454 -0.86704,1.53835,-1.30901,-1.47027,-0.36646,1.60471,0.00454 -0.86957,1.53894,-1.30882,-1.47045,-0.36648,1.60412,0.00454 -0.87209,1.53931,-1.30870,-1.47057,-0.36649,1.60375,0.00455 -0.87462,1.54004,-1.30845,-1.47084,-0.36647,1.60302,0.00455 -0.87715,1.54075,-1.30820,-1.47110,-0.36646,1.60231,0.00455 -0.87968,1.54146,-1.30796,-1.47136,-0.36644,1.60160,0.00456 -0.88220,1.54216,-1.30772,-1.47162,-0.36643,1.60090,0.00456 -0.88473,1.54284,-1.30749,-1.47187,-0.36642,1.60022,0.00456 -0.88726,1.54352,-1.30725,-1.47212,-0.36640,1.59954,0.00457 -0.88979,1.54419,-1.30703,-1.47237,-0.36639,1.59887,0.00457 -0.89232,1.54485,-1.30680,-1.47261,-0.36638,1.59822,0.00457 -0.89484,1.54549,-1.30658,-1.47285,-0.36637,1.59757,0.00457 -0.89737,1.54613,-1.30636,-1.47308,-0.36635,1.59693,0.00458 -0.89990,1.54676,-1.30615,-1.47331,-0.36634,1.59630,0.00458 -0.90243,1.54738,-1.30594,-1.47354,-0.36633,1.59568,0.00458 -0.90495,1.54799,-1.30573,-1.47377,-0.36632,1.59507,0.00459 -0.90748,1.54859,-1.30552,-1.47399,-0.36630,1.59447,0.00459 -0.91001,1.54918,-1.30532,-1.47420,-0.36629,1.59388,0.00459 -0.91254,1.54977,-1.30512,-1.47442,-0.36628,1.59329,0.00459 -0.91507,1.55007,-1.30501,-1.47454,-0.36627,1.59298,0.00459 -0.91759,1.55082,-1.30473,-1.47494,-0.36616,1.59224,0.00460 -0.92012,1.55156,-1.30446,-1.47532,-0.36606,1.59150,0.00460 -0.92265,1.55228,-1.30418,-1.47570,-0.36595,1.59077,0.00461 -0.92518,1.55300,-1.30392,-1.47608,-0.36585,1.59006,0.00461 -0.92770,1.55371,-1.30365,-1.47645,-0.36575,1.58935,0.00461 -0.93023,1.55440,-1.30339,-1.47681,-0.36566,1.58865,0.00462 -0.93276,1.55509,-1.30314,-1.47717,-0.36556,1.58797,0.00462 -0.93529,1.55576,-1.30288,-1.47752,-0.36547,1.58729,0.00462 -0.93782,1.55643,-1.30264,-1.47786,-0.36537,1.58663,0.00463 -0.94034,1.55709,-1.30239,-1.47821,-0.36528,1.58597,0.00463 -0.94287,1.55773,-1.30215,-1.47854,-0.36519,1.58532,0.00463 -0.94540,1.55837,-1.30191,-1.47887,-0.36510,1.58468,0.00464 -0.94793,1.55900,-1.30168,-1.47920,-0.36502,1.58406,0.00464 -0.95046,1.55961,-1.30145,-1.47952,-0.36493,1.58344,0.00464 -0.95298,1.56022,-1.30122,-1.47983,-0.36485,1.58283,0.00465 -0.95551,1.56082,-1.30100,-1.48014,-0.36477,1.58222,0.00465 -0.95804,1.56142,-1.30078,-1.48045,-0.36469,1.58163,0.00465 -0.96057,1.56200,-1.30056,-1.48075,-0.36461,1.58104,0.00465 -0.96309,1.56257,-1.30034,-1.48104,-0.36453,1.58047,0.00466 -0.96562,1.56314,-1.30013,-1.48134,-0.36445,1.57990,0.00466 -0.96815,1.56370,-1.29992,-1.48162,-0.36438,1.57934,0.00466 -0.97068,1.56382,-1.29987,-1.48171,-0.36435,1.57921,0.00466 -0.97321,1.56452,-1.29957,-1.48225,-0.36411,1.57851,0.00467 -0.97573,1.56521,-1.29928,-1.48279,-0.36387,1.57782,0.00467 -0.97826,1.56589,-1.29899,-1.48331,-0.36365,1.57714,0.00468 -0.98079,1.56656,-1.29870,-1.48383,-0.36342,1.57647,0.00468 -0.98332,1.56722,-1.29842,-1.48434,-0.36320,1.57581,0.00468 -0.98584,1.56787,-1.29814,-1.48485,-0.36298,1.57516,0.00469 -0.98837,1.56851,-1.29786,-1.48534,-0.36277,1.57452,0.00469 -0.99090,1.56914,-1.29759,-1.48583,-0.36256,1.57389,0.00470 -0.99343,1.56976,-1.29733,-1.48631,-0.36235,1.57326,0.00470 -0.99596,1.57037,-1.29706,-1.48678,-0.36215,1.57265,0.00470 -0.99848,1.57098,-1.29680,-1.48724,-0.36195,1.57204,0.00471 -1.00101,1.57157,-1.29655,-1.48770,-0.36175,1.57144,0.00471 -1.00354,1.57216,-1.29630,-1.48815,-0.36156,1.57086,0.00471 -1.00607,1.57274,-1.29605,-1.48859,-0.36137,1.57027,0.00472 -1.00859,1.57331,-1.29581,-1.48903,-0.36118,1.56970,0.00472 -1.01112,1.57387,-1.29557,-1.48945,-0.36100,1.56914,0.00472 -1.01365,1.57442,-1.29533,-1.48987,-0.36082,1.56858,0.00473 -1.01618,1.57497,-1.29510,-1.49029,-0.36064,1.56803,0.00473 -1.01871,1.57550,-1.29487,-1.49070,-0.36047,1.56749,0.00473 -1.02123,1.57603,-1.29464,-1.49110,-0.36029,1.56696,0.00474 -1.02376,1.57656,-1.29442,-1.49149,-0.36013,1.56643,0.00474 -1.02629,1.57707,-1.29420,-1.49188,-0.35996,1.56592,0.00474 -1.02882,1.57758,-1.29398,-1.49227,-0.35980,1.56540,0.00475 -1.03134,1.57784,-1.29387,-1.49248,-0.35971,1.56514,0.00475 -1.03387,1.57846,-1.29358,-1.49304,-0.35943,1.56451,0.00475 -1.03640,1.57908,-1.29330,-1.49360,-0.35916,1.56390,0.00475 -1.03893,1.57968,-1.29302,-1.49415,-0.35889,1.56329,0.00476 -1.04146,1.58028,-1.29275,-1.49469,-0.35863,1.56269,0.00476 -1.04398,1.58087,-1.29248,-1.49522,-0.35838,1.56210,0.00477 -1.04651,1.58144,-1.29222,-1.49574,-0.35812,1.56152,0.00477 -1.04904,1.58202,-1.29196,-1.49626,-0.35787,1.56095,0.00477 -1.05157,1.58258,-1.29170,-1.49676,-0.35763,1.56038,0.00478 -1.05410,1.58313,-1.29145,-1.49726,-0.35739,1.55982,0.00478 -1.05662,1.58368,-1.29120,-1.49775,-0.35715,1.55927,0.00478 -1.05915,1.58422,-1.29095,-1.49823,-0.35692,1.55873,0.00479 -1.06168,1.58475,-1.29071,-1.49871,-0.35670,1.55820,0.00479 -1.06421,1.58527,-1.29047,-1.49917,-0.35647,1.55767,0.00479 -1.06673,1.58579,-1.29024,-1.49963,-0.35625,1.55715,0.00480 -1.06926,1.58630,-1.29000,-1.50008,-0.35604,1.55664,0.00480 -1.07179,1.58680,-1.28978,-1.50053,-0.35582,1.55614,0.00480 -1.07432,1.58729,-1.28955,-1.50097,-0.35561,1.55564,0.00481 -1.07685,1.58778,-1.28933,-1.50140,-0.35541,1.55515,0.00481 -1.07937,1.58826,-1.28911,-1.50182,-0.35521,1.55466,0.00481 -1.08190,1.58873,-1.28890,-1.50224,-0.35501,1.55419,0.00482 -1.08443,1.58878,-1.28887,-1.50229,-0.35498,1.55413,0.00482 -1.08696,1.58933,-1.28861,-1.50282,-0.35471,1.55359,0.00482 -1.08948,1.58986,-1.28836,-1.50334,-0.35445,1.55305,0.00482 -1.09201,1.59039,-1.28811,-1.50385,-0.35419,1.55252,0.00483 -1.09454,1.59090,-1.28787,-1.50436,-0.35394,1.55200,0.00483 -1.09707,1.59142,-1.28763,-1.50485,-0.35369,1.55149,0.00483 -1.09960,1.59192,-1.28739,-1.50534,-0.35344,1.55098,0.00484 -1.10212,1.59242,-1.28716,-1.50582,-0.35320,1.55048,0.00484 -1.10465,1.59290,-1.28692,-1.50629,-0.35296,1.54999,0.00484 -1.10718,1.59339,-1.28670,-1.50676,-0.35273,1.54950,0.00485 -1.10971,1.59386,-1.28647,-1.50721,-0.35250,1.54902,0.00485 -1.11223,1.59433,-1.28625,-1.50766,-0.35227,1.54855,0.00485 -1.11476,1.59479,-1.28603,-1.50811,-0.35205,1.54808,0.00486 -1.11729,1.59525,-1.28582,-1.50854,-0.35183,1.54762,0.00486 -1.11982,1.59539,-1.28575,-1.50868,-0.35176,1.54748,0.00486 -1.12235,1.59588,-1.28551,-1.50922,-0.35147,1.54698,0.00486 -1.12487,1.59637,-1.28526,-1.50975,-0.35119,1.54649,0.00487 -1.12740,1.59686,-1.28502,-1.51028,-0.35091,1.54600,0.00487 -1.12993,1.59733,-1.28479,-1.51079,-0.35063,1.54552,0.00487 -1.13246,1.59780,-1.28455,-1.51130,-0.35036,1.54505,0.00488 -1.13498,1.59826,-1.28432,-1.51180,-0.35010,1.54458,0.00488 -1.13751,1.59872,-1.28410,-1.51229,-0.34984,1.54412,0.00488 -1.14004,1.59917,-1.28387,-1.51277,-0.34958,1.54367,0.00489 -1.14257,1.59961,-1.28365,-1.51325,-0.34933,1.54322,0.00489 -1.14510,1.60005,-1.28344,-1.51372,-0.34908,1.54278,0.00489 -1.14762,1.60048,-1.28322,-1.51418,-0.34884,1.54235,0.00490 -1.15015,1.60073,-1.28309,-1.51447,-0.34868,1.54209,0.00490 -1.15268,1.60115,-1.28283,-1.51515,-0.34826,1.54167,0.00490 -1.15521,1.60156,-1.28258,-1.51582,-0.34785,1.54126,0.00491 -1.15774,1.60196,-1.28233,-1.51648,-0.34745,1.54085,0.00491 -1.16026,1.60236,-1.28208,-1.51713,-0.34705,1.54045,0.00491 -1.16279,1.60275,-1.28183,-1.51777,-0.34667,1.54005,0.00492 -1.16532,1.60313,-1.28159,-1.51839,-0.34628,1.53966,0.00492 -1.16785,1.60351,-1.28135,-1.51901,-0.34591,1.53927,0.00492 -1.17037,1.60389,-1.28112,-1.51962,-0.34554,1.53889,0.00493 -1.17290,1.60426,-1.28089,-1.52021,-0.34518,1.53851,0.00493 -1.17543,1.60462,-1.28066,-1.52080,-0.34482,1.53814,0.00493 -1.17796,1.60498,-1.28044,-1.52138,-0.34447,1.53778,0.00494 -1.18049,1.60534,-1.28022,-1.52195,-0.34413,1.53742,0.00494 -1.18301,1.60569,-1.28000,-1.52250,-0.34379,1.53706,0.00494 -1.18554,1.60603,-1.27979,-1.52305,-0.34346,1.53671,0.00494 -1.18807,1.60637,-1.27958,-1.52359,-0.34313,1.53637,0.00495 -1.19060,1.60671,-1.27937,-1.52413,-0.34281,1.53602,0.00495 -1.19312,1.60704,-1.27917,-1.52465,-0.34250,1.53569,0.00495 -1.19565,1.60736,-1.27896,-1.52518,-0.34217,1.53536,0.00496 -1.19818,1.60762,-1.27873,-1.52587,-0.34171,1.53509,0.00496 -1.20071,1.60788,-1.27851,-1.52655,-0.34127,1.53482,0.00496 -1.20324,1.60814,-1.27829,-1.52721,-0.34082,1.53456,0.00496 -1.20576,1.60839,-1.27808,-1.52787,-0.34039,1.53430,0.00497 -1.20829,1.60864,-1.27786,-1.52851,-0.33996,1.53404,0.00497 -1.21082,1.60889,-1.27765,-1.52914,-0.33955,1.53379,0.00497 -1.21335,1.60913,-1.27745,-1.52976,-0.33913,1.53354,0.00498 -1.21587,1.60937,-1.27724,-1.53038,-0.33873,1.53329,0.00498 -1.21840,1.60960,-1.27704,-1.53098,-0.33833,1.53305,0.00498 -1.22093,1.60984,-1.27684,-1.53157,-0.33794,1.53281,0.00498 -1.22346,1.61007,-1.27665,-1.53215,-0.33756,1.53257,0.00499 -1.22599,1.61029,-1.27646,-1.53272,-0.33718,1.53234,0.00499 -1.22851,1.61052,-1.27627,-1.53329,-0.33681,1.53211,0.00499 -1.23104,1.61074,-1.27608,-1.53384,-0.33644,1.53188,0.00499 -1.23357,1.61086,-1.27597,-1.53419,-0.33621,1.53175,0.00500 -1.23610,1.61099,-1.27575,-1.53497,-0.33565,1.53161,0.00500 -1.23862,1.61112,-1.27554,-1.53574,-0.33510,1.53148,0.00500 -1.24115,1.61125,-1.27533,-1.53649,-0.33456,1.53134,0.00500 -1.24368,1.61137,-1.27512,-1.53723,-0.33403,1.53120,0.00501 -1.24621,1.61149,-1.27492,-1.53796,-0.33351,1.53107,0.00501 -1.24874,1.61162,-1.27472,-1.53868,-0.33300,1.53094,0.00501 -1.25126,1.61174,-1.27452,-1.53938,-0.33249,1.53081,0.00501 -1.25379,1.61186,-1.27433,-1.54007,-0.33200,1.53068,0.00502 -1.25632,1.61197,-1.27414,-1.54075,-0.33151,1.53056,0.00502 -1.25885,1.61209,-1.27395,-1.54142,-0.33103,1.53043,0.00502 -1.26138,1.61221,-1.27376,-1.54208,-0.33056,1.53031,0.00502 -1.26390,1.61232,-1.27358,-1.54273,-0.33010,1.53019,0.00503 -1.26643,1.61243,-1.27340,-1.54336,-0.32965,1.53006,0.00503 -1.26896,1.61254,-1.27323,-1.54399,-0.32920,1.52995,0.00503 -1.27149,1.61265,-1.27305,-1.54460,-0.32876,1.52983,0.00503 -1.27401,1.61276,-1.27288,-1.54521,-0.32833,1.52971,0.00503 -1.27654,1.61287,-1.27271,-1.54580,-0.32791,1.52960,0.00504 -1.27907,1.61297,-1.27255,-1.54639,-0.32749,1.52949,0.00504 -1.28160,1.61308,-1.27238,-1.54696,-0.32708,1.52937,0.00504 -1.28413,1.61318,-1.27222,-1.54753,-0.32668,1.52926,0.00504 -1.28665,1.61324,-1.27211,-1.54794,-0.32638,1.52920,0.00504 -1.28918,1.61320,-1.27193,-1.54874,-0.32576,1.52923,0.00505 -1.29171,1.61316,-1.27175,-1.54953,-0.32516,1.52925,0.00505 -1.29424,1.61312,-1.27157,-1.55030,-0.32456,1.52928,0.00505 -1.29676,1.61309,-1.27140,-1.55107,-0.32398,1.52930,0.00505 -1.29929,1.61305,-1.27123,-1.55181,-0.32340,1.52933,0.00505 -1.30182,1.61302,-1.27107,-1.55255,-0.32284,1.52935,0.00505 -1.30435,1.61299,-1.27090,-1.55327,-0.32228,1.52937,0.00506 -1.30688,1.61295,-1.27074,-1.55398,-0.32173,1.52940,0.00506 -1.30940,1.61292,-1.27058,-1.55468,-0.32120,1.52942,0.00506 -1.31193,1.61289,-1.27043,-1.55536,-0.32067,1.52944,0.00506 -1.31446,1.61286,-1.27027,-1.55604,-0.32015,1.52946,0.00506 -1.31699,1.61283,-1.27012,-1.55670,-0.31964,1.52948,0.00507 -1.31951,1.61280,-1.26997,-1.55735,-0.31914,1.52950,0.00507 -1.32204,1.61278,-1.26983,-1.55799,-0.31864,1.52952,0.00507 -1.32457,1.61275,-1.26968,-1.55862,-0.31816,1.52954,0.00507 -1.32710,1.61272,-1.26954,-1.55924,-0.31768,1.52955,0.00507 -1.32963,1.61270,-1.26940,-1.55985,-0.31722,1.52957,0.00507 -1.33215,1.61267,-1.26926,-1.56045,-0.31676,1.52959,0.00507 -1.33468,1.61265,-1.26913,-1.56104,-0.31630,1.52961,0.00508 -1.33721,1.61262,-1.26899,-1.56162,-0.31586,1.52962,0.00508 -1.33974,1.61260,-1.26886,-1.56219,-0.31542,1.52964,0.00508 -1.34226,1.61258,-1.26874,-1.56274,-0.31499,1.52965,0.00508 -1.34479,1.61255,-1.26861,-1.56329,-0.31457,1.52967,0.00508 -1.34732,1.61253,-1.26856,-1.56353,-0.31438,1.52969,0.00508 -1.34985,1.61237,-1.26842,-1.56425,-0.31379,1.52983,0.00508 -1.35238,1.61222,-1.26829,-1.56496,-0.31322,1.52998,0.00508 -1.35490,1.61206,-1.26817,-1.56566,-0.31265,1.53012,0.00509 -1.35743,1.61191,-1.26804,-1.56635,-0.31209,1.53026,0.00509 -1.35996,1.61176,-1.26792,-1.56703,-0.31154,1.53040,0.00509 -1.36249,1.61162,-1.26779,-1.56769,-0.31100,1.53054,0.00509 -1.36502,1.61148,-1.26767,-1.56834,-0.31047,1.53067,0.00509 -1.36754,1.61133,-1.26756,-1.56898,-0.30994,1.53080,0.00509 -1.37007,1.61120,-1.26744,-1.56961,-0.30943,1.53093,0.00509 -1.37260,1.61106,-1.26733,-1.57023,-0.30893,1.53106,0.00509 -1.37513,1.61093,-1.26721,-1.57084,-0.30843,1.53118,0.00509 -1.37765,1.61079,-1.26710,-1.57144,-0.30794,1.53131,0.00509 -1.38018,1.61066,-1.26700,-1.57203,-0.30746,1.53143,0.00510 -1.38271,1.61054,-1.26689,-1.57260,-0.30699,1.53155,0.00510 -1.38524,1.61041,-1.26679,-1.57317,-0.30653,1.53166,0.00510 -1.38777,1.61029,-1.26668,-1.57373,-0.30607,1.53178,0.00510 -1.39029,1.61017,-1.26658,-1.57428,-0.30562,1.53189,0.00510 -1.39282,1.61005,-1.26648,-1.57482,-0.30518,1.53200,0.00510 -1.39535,1.60993,-1.26639,-1.57535,-0.30475,1.53211,0.00510 -1.39788,1.60982,-1.26629,-1.57587,-0.30432,1.53222,0.00510 -1.40040,1.60978,-1.26627,-1.57599,-0.30422,1.53226,0.00510 -1.40293,1.60953,-1.26617,-1.57668,-0.30363,1.53249,0.00510 -1.40546,1.60928,-1.26607,-1.57737,-0.30305,1.53273,0.00510 -1.40799,1.60904,-1.26597,-1.57804,-0.30247,1.53296,0.00510 -1.41052,1.60880,-1.26588,-1.57870,-0.30191,1.53319,0.00510 -1.41304,1.60857,-1.26578,-1.57935,-0.30135,1.53341,0.00510 -1.41557,1.60834,-1.26569,-1.57999,-0.30081,1.53363,0.00510 -1.41810,1.60811,-1.26560,-1.58061,-0.30027,1.53385,0.00511 -1.42063,1.60789,-1.26551,-1.58123,-0.29975,1.53407,0.00511 -1.42315,1.60767,-1.26542,-1.58183,-0.29923,1.53428,0.00511 -1.42568,1.60745,-1.26534,-1.58243,-0.29872,1.53448,0.00511 -1.42821,1.60724,-1.26525,-1.58301,-0.29822,1.53469,0.00511 -1.43074,1.60703,-1.26517,-1.58359,-0.29773,1.53489,0.00511 -1.43327,1.60683,-1.26509,-1.58415,-0.29725,1.53509,0.00511 -1.43579,1.60662,-1.26501,-1.58470,-0.29677,1.53528,0.00511 -1.43832,1.60642,-1.26493,-1.58525,-0.29630,1.53547,0.00511 -1.44085,1.60623,-1.26485,-1.58578,-0.29584,1.53566,0.00511 -1.44338,1.60603,-1.26478,-1.58631,-0.29539,1.53585,0.00511 -1.44590,1.60584,-1.26471,-1.58683,-0.29495,1.53603,0.00511 -1.44843,1.60566,-1.26463,-1.58733,-0.29451,1.53621,0.00511 -1.45096,1.60547,-1.26456,-1.58783,-0.29408,1.53639,0.00511 -1.45349,1.60527,-1.26449,-1.58834,-0.29364,1.53658,0.00511 -1.45602,1.60491,-1.26443,-1.58900,-0.29304,1.53694,0.00511 -1.45854,1.60454,-1.26437,-1.58965,-0.29246,1.53729,0.00511 -1.46107,1.60419,-1.26431,-1.59028,-0.29188,1.53763,0.00511 -1.46360,1.60384,-1.26426,-1.59090,-0.29131,1.53797,0.00511 -1.46613,1.60349,-1.26420,-1.59152,-0.29076,1.53831,0.00511 -1.46866,1.60315,-1.26415,-1.59212,-0.29021,1.53864,0.00511 -1.47118,1.60282,-1.26409,-1.59271,-0.28967,1.53896,0.00511 -1.47371,1.60249,-1.26404,-1.59329,-0.28914,1.53928,0.00511 -1.47624,1.60216,-1.26399,-1.59386,-0.28862,1.53960,0.00511 -1.47877,1.60184,-1.26394,-1.59442,-0.28810,1.53991,0.00511 -1.48129,1.60153,-1.26390,-1.59497,-0.28760,1.54021,0.00511 -1.48382,1.60122,-1.26385,-1.59552,-0.28711,1.54052,0.00511 -1.48635,1.60092,-1.26380,-1.59605,-0.28662,1.54081,0.00511 -1.48888,1.60062,-1.26376,-1.59657,-0.28614,1.54110,0.00511 -1.49141,1.60032,-1.26371,-1.59708,-0.28567,1.54139,0.00511 -1.49393,1.60003,-1.26367,-1.59759,-0.28521,1.54167,0.00511 -1.49646,1.59975,-1.26363,-1.59808,-0.28475,1.54195,0.00511 -1.49899,1.59946,-1.26359,-1.59857,-0.28430,1.54223,0.00511 -1.50152,1.59919,-1.26355,-1.59905,-0.28386,1.54250,0.00511 -1.50404,1.59892,-1.26351,-1.59952,-0.28343,1.54276,0.00511 -1.50657,1.59865,-1.26347,-1.59998,-0.28301,1.54303,0.00511 -1.50910,1.59838,-1.26343,-1.60043,-0.28259,1.54328,0.00511 -1.51163,1.59812,-1.26340,-1.60086,-0.28219,1.54354,0.00511 -1.51416,1.59762,-1.26337,-1.60154,-0.28154,1.54402,0.00511 -1.51668,1.59713,-1.26335,-1.60221,-0.28089,1.54450,0.00511 -1.51921,1.59665,-1.26332,-1.60287,-0.28025,1.54498,0.00511 -1.52174,1.59617,-1.26330,-1.60352,-0.27963,1.54544,0.00511 -1.52427,1.59570,-1.26328,-1.60416,-0.27901,1.54590,0.00511 -1.52679,1.59524,-1.26325,-1.60479,-0.27841,1.54635,0.00511 -1.52932,1.59478,-1.26323,-1.60540,-0.27781,1.54680,0.00511 -1.53185,1.59433,-1.26321,-1.60601,-0.27723,1.54724,0.00511 -1.53438,1.59389,-1.26319,-1.60660,-0.27665,1.54767,0.00511 -1.53691,1.59346,-1.26317,-1.60718,-0.27609,1.54809,0.00510 -1.53943,1.59303,-1.26316,-1.60775,-0.27553,1.54851,0.00510 -1.54196,1.59261,-1.26314,-1.60831,-0.27499,1.54893,0.00510 -1.54449,1.59220,-1.26312,-1.60887,-0.27445,1.54933,0.00510 -1.54702,1.59179,-1.26311,-1.60941,-0.27392,1.54973,0.00510 -1.54954,1.59139,-1.26309,-1.60994,-0.27340,1.55013,0.00510 -1.55207,1.59099,-1.26308,-1.61046,-0.27289,1.55051,0.00510 -1.55460,1.59060,-1.26307,-1.61098,-0.27239,1.55090,0.00510 -1.55713,1.59022,-1.26305,-1.61148,-0.27190,1.55127,0.00510 -1.55966,1.58984,-1.26304,-1.61198,-0.27141,1.55164,0.00510 -1.56218,1.58947,-1.26303,-1.61246,-0.27093,1.55201,0.00510 -1.56471,1.58910,-1.26302,-1.61294,-0.27046,1.55237,0.00510 -1.56724,1.58874,-1.26301,-1.61341,-0.27000,1.55272,0.00510 -1.56977,1.58839,-1.26300,-1.61387,-0.26955,1.55307,0.00510 -1.57230,1.58804,-1.26299,-1.61432,-0.26910,1.55341,0.00510 -1.57482,1.58769,-1.26298,-1.61477,-0.26867,1.55375,0.00510 -1.57735,1.58735,-1.26297,-1.61520,-0.26823,1.55408,0.00510 -1.57988,1.58702,-1.26296,-1.61563,-0.26781,1.55441,0.00510 -1.58241,1.58669,-1.26296,-1.61605,-0.26739,1.55473,0.00510 -1.58493,1.58637,-1.26295,-1.61647,-0.26698,1.55505,0.00509 -1.58746,1.58605,-1.26294,-1.61687,-0.26658,1.55537,0.00509 -1.58999,1.58592,-1.26294,-1.61704,-0.26642,1.55549,0.00509 -1.59252,1.58558,-1.26293,-1.61752,-0.26595,1.55583,0.00509 -1.59505,1.58525,-1.26292,-1.61798,-0.26550,1.55616,0.00509 -1.59757,1.58492,-1.26290,-1.61844,-0.26505,1.55648,0.00509 -1.60010,1.58460,-1.26289,-1.61888,-0.26462,1.55680,0.00509 -1.60263,1.58428,-1.26288,-1.61932,-0.26418,1.55711,0.00509 -1.60516,1.58396,-1.26287,-1.61976,-0.26376,1.55742,0.00509 -1.60768,1.58365,-1.26286,-1.62018,-0.26334,1.55773,0.00509 -1.61021,1.58335,-1.26285,-1.62060,-0.26293,1.55803,0.00509 -1.61274,1.58313,-1.26284,-1.62089,-0.26264,1.55824,0.00509 -1.61527,1.58278,-1.26284,-1.62137,-0.26217,1.55858,0.00509 -1.61780,1.58244,-1.26283,-1.62183,-0.26171,1.55892,0.00509 -1.62032,1.58210,-1.26282,-1.62229,-0.26126,1.55926,0.00509 -1.62285,1.58176,-1.26281,-1.62274,-0.26081,1.55959,0.00509 -1.62538,1.58143,-1.26281,-1.62319,-0.26037,1.55991,0.00509 -1.62791,1.58111,-1.26280,-1.62362,-0.25994,1.56023,0.00509 -1.63043,1.58079,-1.26279,-1.62405,-0.25952,1.56055,0.00509 -1.63296,1.58048,-1.26279,-1.62447,-0.25910,1.56086,0.00509 -1.63549,1.58017,-1.26278,-1.62488,-0.25869,1.56116,0.00509 -1.63802,1.57991,-1.26278,-1.62521,-0.25836,1.56142,0.00509 -1.64055,1.57945,-1.26280,-1.62569,-0.25786,1.56187,0.00508 -1.64307,1.57899,-1.26282,-1.62615,-0.25738,1.56232,0.00508 -1.64560,1.57855,-1.26285,-1.62661,-0.25690,1.56276,0.00508 -1.64813,1.57811,-1.26287,-1.62706,-0.25642,1.56319,0.00508 -1.65066,1.57767,-1.26289,-1.62749,-0.25596,1.56361,0.00508 -1.65319,1.57725,-1.26291,-1.62793,-0.25550,1.56403,0.00508 -1.65571,1.57683,-1.26293,-1.62835,-0.25506,1.56445,0.00508 -1.65824,1.57642,-1.26296,-1.62877,-0.25461,1.56485,0.00508 -1.66077,1.57601,-1.26298,-1.62917,-0.25418,1.56525,0.00508 -1.66330,1.57561,-1.26300,-1.62958,-0.25376,1.56565,0.00508 -1.66582,1.57521,-1.26302,-1.62997,-0.25334,1.56604,0.00508 -1.66835,1.57483,-1.26305,-1.63036,-0.25292,1.56642,0.00508 -1.67088,1.57444,-1.26307,-1.63074,-0.25252,1.56680,0.00507 -1.67341,1.57407,-1.26309,-1.63111,-0.25212,1.56717,0.00507 -1.67594,1.57370,-1.26311,-1.63148,-0.25173,1.56754,0.00507 -1.67846,1.57333,-1.26314,-1.63184,-0.25134,1.56790,0.00507 -1.68099,1.57326,-1.26315,-1.63187,-0.25129,1.56797,0.00507 -1.68352,1.57253,-1.26326,-1.63224,-0.25081,1.56868,0.00507 -1.68605,1.57182,-1.26337,-1.63260,-0.25034,1.56939,0.00507 -1.68857,1.57111,-1.26348,-1.63296,-0.24987,1.57008,0.00506 -1.69110,1.57042,-1.26359,-1.63330,-0.24941,1.57076,0.00506 -1.69363,1.56974,-1.26370,-1.63365,-0.24896,1.57144,0.00506 -1.69616,1.56907,-1.26380,-1.63398,-0.24851,1.57210,0.00506 -1.69869,1.56840,-1.26391,-1.63431,-0.24807,1.57275,0.00506 -1.70121,1.56775,-1.26401,-1.63463,-0.24764,1.57339,0.00505 -1.70374,1.56711,-1.26412,-1.63494,-0.24722,1.57403,0.00505 -1.70627,1.56648,-1.26422,-1.63525,-0.24680,1.57465,0.00505 -1.70880,1.56586,-1.26432,-1.63556,-0.24640,1.57527,0.00505 -1.71132,1.56524,-1.26443,-1.63585,-0.24599,1.57587,0.00505 -1.71385,1.56464,-1.26453,-1.63614,-0.24560,1.57647,0.00504 -1.71638,1.56405,-1.26463,-1.63643,-0.24521,1.57705,0.00504 -1.71891,1.56346,-1.26472,-1.63671,-0.24483,1.57763,0.00504 -1.72144,1.56288,-1.26482,-1.63698,-0.24445,1.57820,0.00504 -1.72396,1.56232,-1.26492,-1.63725,-0.24408,1.57876,0.00504 -1.72649,1.56176,-1.26501,-1.63752,-0.24371,1.57932,0.00503 -1.72902,1.56121,-1.26511,-1.63778,-0.24336,1.57986,0.00503 -1.73155,1.56067,-1.26520,-1.63803,-0.24300,1.58040,0.00503 -1.73407,1.56013,-1.26530,-1.63828,-0.24266,1.58093,0.00503 -1.73660,1.55961,-1.26539,-1.63853,-0.24232,1.58145,0.00503 -1.73913,1.55909,-1.26548,-1.63876,-0.24198,1.58196,0.00503 -1.74166,1.55858,-1.26557,-1.63900,-0.24165,1.58246,0.00502 -1.74419,1.55808,-1.26566,-1.63923,-0.24133,1.58296,0.00502 -1.74671,1.55758,-1.26575,-1.63946,-0.24101,1.58345,0.00502 -1.74924,1.55710,-1.26583,-1.63968,-0.24070,1.58393,0.00502 -1.75177,1.55692,-1.26587,-1.63974,-0.24060,1.58411,0.00502 -1.75430,1.55607,-1.26605,-1.63997,-0.24018,1.58494,0.00502 -1.75683,1.55525,-1.26623,-1.64020,-0.23978,1.58576,0.00501 -1.75935,1.55443,-1.26640,-1.64042,-0.23938,1.58657,0.00501 -1.76188,1.55362,-1.26658,-1.64063,-0.23898,1.58736,0.00501 -1.76441,1.55283,-1.26675,-1.64084,-0.23860,1.58815,0.00500 -1.76694,1.55205,-1.26692,-1.64105,-0.23822,1.58892,0.00500 -1.76946,1.55128,-1.26709,-1.64125,-0.23784,1.58968,0.00500 -1.77199,1.55053,-1.26725,-1.64144,-0.23748,1.59042,0.00500 -1.77452,1.54978,-1.26742,-1.64163,-0.23711,1.59116,0.00499 -1.77705,1.54905,-1.26758,-1.64182,-0.23676,1.59189,0.00499 -1.77958,1.54833,-1.26774,-1.64201,-0.23641,1.59260,0.00499 -1.78210,1.54762,-1.26790,-1.64219,-0.23606,1.59331,0.00499 -1.78463,1.54692,-1.26806,-1.64236,-0.23572,1.59400,0.00498 -1.78716,1.54623,-1.26822,-1.64253,-0.23539,1.59468,0.00498 -1.78969,1.54555,-1.26837,-1.64270,-0.23506,1.59535,0.00498 -1.79221,1.54488,-1.26853,-1.64287,-0.23474,1.59602,0.00498 -1.79474,1.54423,-1.26868,-1.64303,-0.23442,1.59667,0.00497 -1.79727,1.54358,-1.26883,-1.64319,-0.23411,1.59731,0.00497 -1.79980,1.54294,-1.26897,-1.64334,-0.23381,1.59795,0.00497 -1.80233,1.54231,-1.26912,-1.64349,-0.23350,1.59857,0.00497 -1.80485,1.54169,-1.26926,-1.64364,-0.23321,1.59918,0.00496 -1.80738,1.54108,-1.26941,-1.64378,-0.23292,1.59979,0.00496 -1.80991,1.54048,-1.26955,-1.64392,-0.23263,1.60038,0.00496 -1.81244,1.53989,-1.26969,-1.64406,-0.23235,1.60097,0.00496 -1.81496,1.53931,-1.26983,-1.64420,-0.23207,1.60155,0.00496 -1.81749,1.53874,-1.26996,-1.64433,-0.23180,1.60212,0.00495 -1.82002,1.53817,-1.27010,-1.64446,-0.23153,1.60268,0.00495 -1.82255,1.53762,-1.27023,-1.64459,-0.23127,1.60323,0.00495 -1.82508,1.53707,-1.27036,-1.64471,-0.23101,1.60378,0.00495 -1.82760,1.53653,-1.27049,-1.64483,-0.23075,1.60431,0.00495 -1.83013,1.53629,-1.27055,-1.64488,-0.23064,1.60455,0.00495 -1.83266,1.53548,-1.27075,-1.64500,-0.23031,1.60536,0.00494 -1.83519,1.53468,-1.27096,-1.64512,-0.22998,1.60615,0.00494 -1.83771,1.53389,-1.27116,-1.64523,-0.22966,1.60693,0.00494 -1.84024,1.53312,-1.27136,-1.64535,-0.22935,1.60770,0.00493 -1.84277,1.53235,-1.27155,-1.64546,-0.22904,1.60846,0.00493 -1.84530,1.53160,-1.27175,-1.64556,-0.22873,1.60920,0.00493 -1.84783,1.53086,-1.27194,-1.64567,-0.22843,1.60994,0.00493 -1.85035,1.53013,-1.27213,-1.64577,-0.22813,1.61066,0.00492 -1.85288,1.52942,-1.27232,-1.64587,-0.22784,1.61137,0.00492 -1.85541,1.52871,-1.27250,-1.64596,-0.22756,1.61207,0.00492 -1.85794,1.52801,-1.27268,-1.64606,-0.22728,1.61276,0.00491 -1.86047,1.52733,-1.27287,-1.64615,-0.22700,1.61344,0.00491 -1.86299,1.52666,-1.27304,-1.64624,-0.22673,1.61411,0.00491 -1.86552,1.52599,-1.27322,-1.64632,-0.22646,1.61477,0.00491 -1.86805,1.52534,-1.27339,-1.64641,-0.22620,1.61543,0.00491 -1.87058,1.52469,-1.27357,-1.64649,-0.22594,1.61607,0.00490 -1.87310,1.52406,-1.27374,-1.64657,-0.22568,1.61670,0.00490 -1.87563,1.52344,-1.27390,-1.64665,-0.22543,1.61732,0.00490 -1.87816,1.52282,-1.27407,-1.64673,-0.22519,1.61793,0.00490 -1.88069,1.52222,-1.27423,-1.64680,-0.22494,1.61853,0.00489 -1.88322,1.52162,-1.27440,-1.64687,-0.22470,1.61913,0.00489 -1.88574,1.52103,-1.27455,-1.64694,-0.22447,1.61971,0.00489 -1.88827,1.52046,-1.27471,-1.64701,-0.22424,1.62029,0.00489 -1.89080,1.51989,-1.27487,-1.64708,-0.22401,1.62085,0.00489 -1.89333,1.51933,-1.27502,-1.64714,-0.22379,1.62141,0.00488 -1.89585,1.51887,-1.27515,-1.64720,-0.22360,1.62187,0.00488 -1.89838,1.51814,-1.27534,-1.64732,-0.22328,1.62259,0.00488 -1.90091,1.51742,-1.27553,-1.64744,-0.22297,1.62330,0.00488 -1.90344,1.51672,-1.27572,-1.64756,-0.22266,1.62400,0.00487 -1.90597,1.51603,-1.27591,-1.64767,-0.22235,1.62469,0.00487 -1.90849,1.51534,-1.27609,-1.64779,-0.22205,1.62537,0.00487 -1.91102,1.51467,-1.27627,-1.64790,-0.22176,1.62604,0.00487 -1.91355,1.51401,-1.27645,-1.64800,-0.22147,1.62670,0.00486 -1.91608,1.51336,-1.27663,-1.64811,-0.22118,1.62735,0.00486 -1.91860,1.51272,-1.27680,-1.64821,-0.22090,1.62798,0.00486 -1.92113,1.51208,-1.27698,-1.64831,-0.22063,1.62861,0.00486 -1.92366,1.51146,-1.27715,-1.64840,-0.22036,1.62923,0.00486 -1.92619,1.51085,-1.27732,-1.64850,-0.22009,1.62984,0.00485 -1.92872,1.51025,-1.27748,-1.64859,-0.21983,1.63044,0.00485 -1.93124,1.50965,-1.27765,-1.64868,-0.21957,1.63103,0.00485 -1.93377,1.50907,-1.27781,-1.64877,-0.21932,1.63162,0.00485 -1.93630,1.50849,-1.27797,-1.64885,-0.21907,1.63219,0.00485 -1.93883,1.50793,-1.27813,-1.64894,-0.21882,1.63276,0.00484 -1.94135,1.50737,-1.27828,-1.64902,-0.21858,1.63331,0.00484 -1.94388,1.50682,-1.27844,-1.64910,-0.21834,1.63386,0.00484 -1.94641,1.50636,-1.27856,-1.64917,-0.21814,1.63432,0.00484 -1.94894,1.50560,-1.27877,-1.64931,-0.21779,1.63508,0.00483 -1.95147,1.50484,-1.27898,-1.64945,-0.21743,1.63583,0.00483 -1.95399,1.50410,-1.27919,-1.64959,-0.21709,1.63656,0.00483 -1.95652,1.50337,-1.27939,-1.64973,-0.21675,1.63729,0.00483 -1.95905,1.50265,-1.27959,-1.64986,-0.21641,1.63800,0.00482 -1.96158,1.50194,-1.27978,-1.64999,-0.21609,1.63871,0.00482 -1.96411,1.50124,-1.27998,-1.65011,-0.21576,1.63940,0.00482 -1.96663,1.50056,-1.28017,-1.65024,-0.21544,1.64009,0.00482 -1.96916,1.49988,-1.28036,-1.65035,-0.21513,1.64076,0.00481 -1.97169,1.49921,-1.28055,-1.65047,-0.21482,1.64142,0.00481 -1.97422,1.49856,-1.28073,-1.65059,-0.21452,1.64207,0.00481 -1.97674,1.49791,-1.28091,-1.65070,-0.21422,1.64272,0.00481 -1.97927,1.49728,-1.28109,-1.65081,-0.21393,1.64335,0.00481 -1.98180,1.49665,-1.28127,-1.65091,-0.21364,1.64397,0.00480 -1.98433,1.49604,-1.28145,-1.65102,-0.21336,1.64459,0.00480 -1.98686,1.49543,-1.28162,-1.65112,-0.21308,1.64519,0.00480 -1.98938,1.49483,-1.28179,-1.65122,-0.21281,1.64578,0.00480 -1.99191,1.49424,-1.28196,-1.65131,-0.21254,1.64637,0.00480 -1.99444,1.49367,-1.28213,-1.65141,-0.21228,1.64695,0.00479 -1.99697,1.49310,-1.28229,-1.65150,-0.21202,1.64752,0.00479 -1.99949,1.49253,-1.28245,-1.65159,-0.21176,1.64808,0.00479 -2.00202,1.49198,-1.28261,-1.65168,-0.21151,1.64863,0.00479 -2.00455,1.49144,-1.28277,-1.65176,-0.21126,1.64917,0.00479 -2.00708,1.49088,-1.28293,-1.65186,-0.21100,1.64973,0.00478 -2.00961,1.49015,-1.28313,-1.65207,-0.21059,1.65045,0.00478 -2.01213,1.48943,-1.28333,-1.65228,-0.21018,1.65117,0.00478 -2.01466,1.48872,-1.28352,-1.65248,-0.20978,1.65188,0.00478 -2.01719,1.48802,-1.28371,-1.65268,-0.20939,1.65257,0.00477 -2.01972,1.48733,-1.28390,-1.65288,-0.20900,1.65326,0.00477 -2.02224,1.48665,-1.28409,-1.65307,-0.20862,1.65393,0.00477 -2.02477,1.48598,-1.28427,-1.65325,-0.20825,1.65459,0.00477 -2.02730,1.48532,-1.28446,-1.65344,-0.20788,1.65525,0.00476 -2.02983,1.48468,-1.28463,-1.65361,-0.20752,1.65589,0.00476 -2.03236,1.48404,-1.28481,-1.65379,-0.20717,1.65652,0.00476 -2.03488,1.48341,-1.28499,-1.65396,-0.20682,1.65715,0.00476 -2.03741,1.48280,-1.28516,-1.65413,-0.20648,1.65776,0.00476 -2.03994,1.48219,-1.28533,-1.65429,-0.20614,1.65837,0.00475 -2.04247,1.48159,-1.28550,-1.65445,-0.20581,1.65896,0.00475 -2.04499,1.48100,-1.28567,-1.65461,-0.20548,1.65955,0.00475 -2.04752,1.48042,-1.28583,-1.65476,-0.20516,1.66013,0.00475 -2.05005,1.47985,-1.28599,-1.65491,-0.20484,1.66070,0.00475 -2.05258,1.47929,-1.28615,-1.65506,-0.20453,1.66126,0.00474 -2.05511,1.47874,-1.28631,-1.65521,-0.20423,1.66181,0.00474 -2.05763,1.47819,-1.28647,-1.65535,-0.20393,1.66235,0.00474 -2.06016,1.47766,-1.28662,-1.65549,-0.20363,1.66289,0.00474 -2.06269,1.47713,-1.28677,-1.65562,-0.20334,1.66341,0.00474 -2.06522,1.47661,-1.28692,-1.65575,-0.20306,1.66393,0.00474 -2.06775,1.47610,-1.28707,-1.65588,-0.20278,1.66444,0.00473 -2.07027,1.47587,-1.28713,-1.65595,-0.20265,1.66467,0.00473 -2.07280,1.47511,-1.28734,-1.65621,-0.20218,1.66542,0.00473 -2.07533,1.47437,-1.28755,-1.65647,-0.20171,1.66616,0.00473 -2.07786,1.47364,-1.28775,-1.65672,-0.20126,1.66689,0.00473 -2.08038,1.47292,-1.28795,-1.65696,-0.20081,1.66760,0.00472 -2.08291,1.47221,-1.28815,-1.65720,-0.20037,1.66831,0.00472 -2.08544,1.47151,-1.28834,-1.65744,-0.19994,1.66900,0.00472 -2.08797,1.47082,-1.28854,-1.65767,-0.19951,1.66968,0.00472 -2.09050,1.47014,-1.28873,-1.65790,-0.19909,1.67036,0.00471 -2.09302,1.46948,-1.28892,-1.65812,-0.19868,1.67102,0.00471 -2.09555,1.46882,-1.28910,-1.65834,-0.19827,1.67167,0.00471 -2.09808,1.46818,-1.28928,-1.65855,-0.19788,1.67231,0.00471 -2.10061,1.46754,-1.28947,-1.65876,-0.19748,1.67294,0.00471 -2.10313,1.46692,-1.28964,-1.65896,-0.19710,1.67357,0.00470 -2.10566,1.46630,-1.28982,-1.65916,-0.19672,1.67418,0.00470 -2.10819,1.46569,-1.28999,-1.65936,-0.19635,1.67478,0.00470 -2.11072,1.46510,-1.29017,-1.65955,-0.19598,1.67538,0.00470 -2.11325,1.46451,-1.29033,-1.65973,-0.19562,1.67596,0.00470 -2.11577,1.46393,-1.29050,-1.65992,-0.19527,1.67654,0.00469 -2.11830,1.46336,-1.29067,-1.66010,-0.19492,1.67711,0.00469 -2.12083,1.46280,-1.29083,-1.66027,-0.19458,1.67766,0.00469 -2.12336,1.46225,-1.29099,-1.66045,-0.19425,1.67821,0.00469 -2.12588,1.46171,-1.29115,-1.66061,-0.19392,1.67875,0.00469 -2.12841,1.46117,-1.29131,-1.66078,-0.19359,1.67929,0.00469 -2.13094,1.46065,-1.29146,-1.66094,-0.19327,1.67981,0.00468 -2.13347,1.46013,-1.29161,-1.66110,-0.19296,1.68033,0.00468 -2.13600,1.45962,-1.29176,-1.66126,-0.19265,1.68084,0.00468 -2.13852,1.45912,-1.29191,-1.66141,-0.19235,1.68134,0.00468 -2.14105,1.45863,-1.29206,-1.66156,-0.19205,1.68183,0.00468 -2.14358,1.45836,-1.29213,-1.66164,-0.19188,1.68210,0.00468 -2.14611,1.45765,-1.29234,-1.66193,-0.19140,1.68280,0.00467 -2.14863,1.45695,-1.29253,-1.66220,-0.19092,1.68350,0.00467 -2.15116,1.45626,-1.29273,-1.66248,-0.19045,1.68418,0.00467 -2.15369,1.45558,-1.29292,-1.66274,-0.18999,1.68485,0.00467 -2.15622,1.45491,-1.29312,-1.66300,-0.18953,1.68552,0.00467 -2.15875,1.45426,-1.29331,-1.66326,-0.18909,1.68617,0.00466 -2.16127,1.45361,-1.29349,-1.66351,-0.18865,1.68681,0.00466 -2.16380,1.45298,-1.29368,-1.66376,-0.18822,1.68744,0.00466 -2.16633,1.45235,-1.29386,-1.66400,-0.18779,1.68807,0.00466 -2.16886,1.45173,-1.29404,-1.66423,-0.18737,1.68868,0.00466 -2.17139,1.45113,-1.29421,-1.66446,-0.18697,1.68928,0.00465 -2.17391,1.45053,-1.29439,-1.66469,-0.18656,1.68988,0.00465 -2.17644,1.44994,-1.29456,-1.66491,-0.18617,1.69046,0.00465 -2.17897,1.44936,-1.29473,-1.66513,-0.18578,1.69104,0.00465 -2.18150,1.44879,-1.29490,-1.66534,-0.18539,1.69160,0.00465 -2.18402,1.44823,-1.29506,-1.66555,-0.18502,1.69216,0.00464 -2.18655,1.44768,-1.29523,-1.66575,-0.18465,1.69271,0.00464 -2.18908,1.44714,-1.29539,-1.66595,-0.18428,1.69325,0.00464 -2.19161,1.44661,-1.29555,-1.66615,-0.18393,1.69379,0.00464 -2.19414,1.44608,-1.29570,-1.66634,-0.18357,1.69431,0.00464 -2.19666,1.44556,-1.29586,-1.66653,-0.18323,1.69483,0.00464 -2.19919,1.44505,-1.29601,-1.66671,-0.18289,1.69534,0.00463 -2.20172,1.44455,-1.29616,-1.66689,-0.18255,1.69584,0.00463 -2.20425,1.44406,-1.29631,-1.66707,-0.18223,1.69633,0.00463 -2.20677,1.44357,-1.29646,-1.66724,-0.18190,1.69681,0.00463 -2.20930,1.44309,-1.29660,-1.66741,-0.18159,1.69729,0.00463 -2.21183,1.44264,-1.29673,-1.66758,-0.18128,1.69774,0.00463 -2.21436,1.44193,-1.29694,-1.66793,-0.18072,1.69845,0.00463 -2.21689,1.44122,-1.29714,-1.66828,-0.18018,1.69915,0.00462 -2.21941,1.44053,-1.29734,-1.66862,-0.17964,1.69984,0.00462 -2.22194,1.43984,-1.29754,-1.66895,-0.17911,1.70052,0.00462 -2.22447,1.43917,-1.29774,-1.66927,-0.17859,1.70118,0.00462 -2.22700,1.43851,-1.29793,-1.66959,-0.17808,1.70184,0.00461 -2.22952,1.43786,-1.29812,-1.66990,-0.17758,1.70249,0.00461 -2.23205,1.43722,-1.29831,-1.67020,-0.17708,1.70312,0.00461 -2.23458,1.43659,-1.29849,-1.67050,-0.17660,1.70375,0.00461 -2.23711,1.43596,-1.29867,-1.67080,-0.17612,1.70437,0.00461 -2.23964,1.43535,-1.29886,-1.67108,-0.17565,1.70497,0.00460 -2.24216,1.43475,-1.29903,-1.67136,-0.17519,1.70557,0.00460 -2.24469,1.43416,-1.29921,-1.67164,-0.17473,1.70616,0.00460 -2.24722,1.43358,-1.29938,-1.67191,-0.17429,1.70674,0.00460 -2.24975,1.43300,-1.29955,-1.67218,-0.17385,1.70731,0.00460 -2.25228,1.43244,-1.29972,-1.67244,-0.17342,1.70787,0.00460 -2.25480,1.43189,-1.29989,-1.67269,-0.17300,1.70842,0.00459 -2.25733,1.43134,-1.30005,-1.67294,-0.17258,1.70897,0.00459 -2.25986,1.43080,-1.30021,-1.67319,-0.17217,1.70950,0.00459 -2.26239,1.43027,-1.30037,-1.67343,-0.17177,1.71003,0.00459 -2.26491,1.42975,-1.30053,-1.67366,-0.17137,1.71055,0.00459 -2.26744,1.42924,-1.30069,-1.67389,-0.17098,1.71106,0.00459 -2.26997,1.42873,-1.30084,-1.67412,-0.17060,1.71156,0.00458 -2.27250,1.42824,-1.30099,-1.67434,-0.17023,1.71206,0.00458 -2.27503,1.42775,-1.30114,-1.67456,-0.16986,1.71254,0.00458 -2.27755,1.42727,-1.30129,-1.67477,-0.16949,1.71302,0.00458 -2.28008,1.42679,-1.30143,-1.67498,-0.16914,1.71350,0.00458 -2.28261,1.42633,-1.30157,-1.67518,-0.16879,1.71396,0.00458 -2.28514,1.42587,-1.30171,-1.67539,-0.16844,1.71442,0.00458 -2.28766,1.42542,-1.30185,-1.67558,-0.16810,1.71487,0.00458 -2.29019,1.42505,-1.30197,-1.67575,-0.16782,1.71524,0.00457 -2.29272,1.42449,-1.30213,-1.67610,-0.16731,1.71580,0.00457 -2.29525,1.42393,-1.30229,-1.67644,-0.16680,1.71635,0.00457 -2.29778,1.42338,-1.30245,-1.67678,-0.16631,1.71689,0.00457 -2.30030,1.42284,-1.30261,-1.67711,-0.16582,1.71743,0.00457 -2.30283,1.42231,-1.30276,-1.67743,-0.16534,1.71796,0.00457 -2.30536,1.42179,-1.30291,-1.67775,-0.16487,1.71848,0.00456 -2.30789,1.42128,-1.30306,-1.67806,-0.16441,1.71899,0.00456 -2.31041,1.42077,-1.30321,-1.67836,-0.16395,1.71949,0.00456 -2.31294,1.42028,-1.30336,-1.67866,-0.16351,1.71998,0.00456 -2.31547,1.41979,-1.30350,-1.67895,-0.16307,1.72047,0.00456 -2.31800,1.41930,-1.30365,-1.67924,-0.16264,1.72095,0.00456 -2.32053,1.41883,-1.30379,-1.67952,-0.16221,1.72142,0.00456 -2.32305,1.41836,-1.30392,-1.67980,-0.16180,1.72189,0.00455 -2.32558,1.41791,-1.30406,-1.68007,-0.16139,1.72234,0.00455 -2.32811,1.41745,-1.30420,-1.68033,-0.16098,1.72279,0.00455 -2.33064,1.41701,-1.30433,-1.68059,-0.16059,1.72324,0.00455 -2.33316,1.41657,-1.30446,-1.68085,-0.16020,1.72367,0.00455 -2.33569,1.41614,-1.30459,-1.68110,-0.15982,1.72410,0.00455 -2.33822,1.41572,-1.30472,-1.68135,-0.15944,1.72453,0.00455 -2.34075,1.41530,-1.30484,-1.68159,-0.15907,1.72494,0.00455 -2.34328,1.41489,-1.30497,-1.68182,-0.15871,1.72535,0.00455 -2.34580,1.41476,-1.30501,-1.68191,-0.15858,1.72548,0.00454 -2.34833,1.41426,-1.30515,-1.68231,-0.15804,1.72598,0.00454 -2.35086,1.41376,-1.30529,-1.68269,-0.15752,1.72647,0.00454 -2.35339,1.41327,-1.30542,-1.68307,-0.15700,1.72696,0.00454 -2.35592,1.41279,-1.30556,-1.68344,-0.15649,1.72744,0.00454 -2.35844,1.41232,-1.30570,-1.68381,-0.15599,1.72790,0.00454 -2.36097,1.41186,-1.30583,-1.68417,-0.15550,1.72837,0.00454 -2.36350,1.41140,-1.30596,-1.68452,-0.15501,1.72882,0.00454 -2.36603,1.41095,-1.30609,-1.68487,-0.15454,1.72927,0.00453 -2.36855,1.41051,-1.30621,-1.68520,-0.15407,1.72971,0.00453 -2.37108,1.41007,-1.30634,-1.68554,-0.15361,1.73014,0.00453 -2.37361,1.40964,-1.30646,-1.68586,-0.15316,1.73057,0.00453 -2.37614,1.40922,-1.30659,-1.68618,-0.15271,1.73099,0.00453 -2.37867,1.40881,-1.30671,-1.68650,-0.15228,1.73140,0.00453 -2.38119,1.40840,-1.30682,-1.68681,-0.15185,1.73181,0.00453 -2.38372,1.40800,-1.30694,-1.68711,-0.15143,1.73221,0.00453 -2.38625,1.40760,-1.30706,-1.68741,-0.15101,1.73260,0.00453 -2.38878,1.40721,-1.30717,-1.68770,-0.15061,1.73299,0.00452 -2.39130,1.40683,-1.30728,-1.68798,-0.15021,1.73337,0.00452 -2.39383,1.40645,-1.30739,-1.68826,-0.14981,1.73375,0.00452 -2.39636,1.40608,-1.30750,-1.68854,-0.14943,1.73412,0.00452 -2.39889,1.40596,-1.30753,-1.68864,-0.14929,1.73424,0.00452 -2.40142,1.40552,-1.30765,-1.68912,-0.14870,1.73467,0.00452 -2.40394,1.40509,-1.30776,-1.68958,-0.14812,1.73510,0.00452 -2.40647,1.40466,-1.30788,-1.69004,-0.14755,1.73553,0.00452 -2.40900,1.40424,-1.30799,-1.69049,-0.14699,1.73594,0.00452 -2.41153,1.40383,-1.30810,-1.69093,-0.14644,1.73635,0.00452 -2.41405,1.40342,-1.30820,-1.69137,-0.14590,1.73676,0.00451 -2.41658,1.40302,-1.30831,-1.69179,-0.14537,1.73715,0.00451 -2.41911,1.40263,-1.30841,-1.69221,-0.14484,1.73754,0.00451 -2.42164,1.40224,-1.30852,-1.69262,-0.14433,1.73793,0.00451 -2.42417,1.40186,-1.30862,-1.69302,-0.14382,1.73831,0.00451 -2.42669,1.40149,-1.30872,-1.69341,-0.14333,1.73868,0.00451 -2.42922,1.40112,-1.30882,-1.69380,-0.14284,1.73905,0.00451 -2.43175,1.40076,-1.30892,-1.69418,-0.14236,1.73941,0.00451 -2.43428,1.40040,-1.30901,-1.69456,-0.14189,1.73976,0.00451 -2.43680,1.40005,-1.30911,-1.69492,-0.14142,1.74011,0.00451 -2.43933,1.39970,-1.30920,-1.69528,-0.14097,1.74046,0.00451 -2.44186,1.39936,-1.30930,-1.69564,-0.14052,1.74079,0.00450 -2.44439,1.39903,-1.30939,-1.69598,-0.14008,1.74113,0.00450 -2.44692,1.39870,-1.30948,-1.69632,-0.13965,1.74146,0.00450 -2.44944,1.39837,-1.30957,-1.69666,-0.13922,1.74178,0.00450 -2.45197,1.39806,-1.30965,-1.69699,-0.13881,1.74210,0.00450 -2.45450,1.39773,-1.30974,-1.69733,-0.13837,1.74242,0.00450 -2.45703,1.39727,-1.30987,-1.69787,-0.13771,1.74288,0.00450 -2.45956,1.39682,-1.30999,-1.69840,-0.13706,1.74332,0.00450 -2.46208,1.39637,-1.31011,-1.69892,-0.13642,1.74376,0.00450 -2.46461,1.39593,-1.31023,-1.69942,-0.13580,1.74420,0.00450 -2.46714,1.39550,-1.31034,-1.69992,-0.13518,1.74462,0.00449 -2.46967,1.39508,-1.31046,-1.70041,-0.13458,1.74504,0.00449 -2.47219,1.39467,-1.31057,-1.70089,-0.13398,1.74545,0.00449 -2.47472,1.39426,-1.31068,-1.70137,-0.13340,1.74586,0.00449 -2.47725,1.39385,-1.31079,-1.70183,-0.13282,1.74626,0.00449 -2.47978,1.39346,-1.31090,-1.70228,-0.13226,1.74665,0.00449 -2.48231,1.39307,-1.31101,-1.70273,-0.13170,1.74704,0.00449 -2.48483,1.39268,-1.31112,-1.70317,-0.13116,1.74742,0.00449 -2.48736,1.39230,-1.31122,-1.70360,-0.13062,1.74779,0.00449 -2.48989,1.39193,-1.31133,-1.70402,-0.13009,1.74816,0.00448 -2.49242,1.39157,-1.31143,-1.70444,-0.12957,1.74852,0.00448 -2.49494,1.39121,-1.31153,-1.70485,-0.12907,1.74888,0.00448 -2.49747,1.39085,-1.31163,-1.70525,-0.12856,1.74923,0.00448 -2.50000,1.39051,-1.31173,-1.70564,-0.12807,1.74957,0.00448 -2.50253,1.39016,-1.31182,-1.70602,-0.12759,1.74991,0.00448 -2.50506,1.38983,-1.31192,-1.70640,-0.12711,1.75025,0.00448 -2.50758,1.38950,-1.31201,-1.70677,-0.12665,1.75058,0.00448 -2.51011,1.38917,-1.31210,-1.70714,-0.12619,1.75090,0.00448 -2.51264,1.38885,-1.31219,-1.70750,-0.12574,1.75122,0.00448 -2.51517,1.38853,-1.31228,-1.70785,-0.12529,1.75154,0.00448 -2.51769,1.38822,-1.31237,-1.70819,-0.12486,1.75185,0.00448 -2.52022,1.38792,-1.31246,-1.70853,-0.12443,1.75215,0.00448 -2.52275,1.38761,-1.31254,-1.70887,-0.12401,1.75245,0.00448 -2.52528,1.38746,-1.31259,-1.70906,-0.12377,1.75261,0.00448 -2.52781,1.38706,-1.31269,-1.70969,-0.12304,1.75300,0.00447 -2.53033,1.38667,-1.31279,-1.71031,-0.12232,1.75338,0.00447 -2.53286,1.38629,-1.31288,-1.71092,-0.12162,1.75376,0.00447 -2.53539,1.38591,-1.31298,-1.71151,-0.12093,1.75413,0.00447 -2.53792,1.38554,-1.31307,-1.71210,-0.12025,1.75450,0.00447 -2.54044,1.38517,-1.31317,-1.71267,-0.11958,1.75486,0.00447 -2.54297,1.38481,-1.31326,-1.71324,-0.11893,1.75521,0.00447 -2.54550,1.38446,-1.31335,-1.71379,-0.11828,1.75556,0.00447 -2.54803,1.38411,-1.31344,-1.71434,-0.11765,1.75591,0.00447 -2.55056,1.38377,-1.31353,-1.71487,-0.11702,1.75624,0.00446 -2.55308,1.38343,-1.31362,-1.71540,-0.11641,1.75658,0.00446 -2.55561,1.38310,-1.31371,-1.71591,-0.11581,1.75690,0.00446 -2.55814,1.38278,-1.31379,-1.71642,-0.11522,1.75723,0.00446 -2.56067,1.38246,-1.31387,-1.71692,-0.11463,1.75754,0.00446 -2.56320,1.38214,-1.31396,-1.71740,-0.11406,1.75785,0.00446 -2.56572,1.38183,-1.31404,-1.71788,-0.11350,1.75816,0.00446 -2.56825,1.38153,-1.31412,-1.71835,-0.11295,1.75846,0.00446 -2.57078,1.38123,-1.31420,-1.71881,-0.11240,1.75876,0.00446 -2.57331,1.38093,-1.31428,-1.71927,-0.11187,1.75905,0.00446 -2.57583,1.38064,-1.31436,-1.71971,-0.11135,1.75934,0.00446 -2.57836,1.38036,-1.31443,-1.72015,-0.11083,1.75962,0.00446 -2.58089,1.38008,-1.31451,-1.72058,-0.11032,1.75990,0.00446 -2.58342,1.37980,-1.31458,-1.72100,-0.10983,1.76018,0.00446 -2.58595,1.37953,-1.31465,-1.72142,-0.10934,1.76045,0.00446 -2.58847,1.37926,-1.31473,-1.72182,-0.10886,1.76071,0.00446 -2.59100,1.37900,-1.31480,-1.72222,-0.10838,1.76097,0.00446 -2.59353,1.37874,-1.31487,-1.72262,-0.10792,1.76123,0.00446 -2.59606,1.37848,-1.31494,-1.72300,-0.10746,1.76148,0.00445 -2.59858,1.37823,-1.31500,-1.72338,-0.10701,1.76173,0.00445 -2.60111,1.37799,-1.31507,-1.72375,-0.10657,1.76198,0.00445 -2.60364,1.37779,-1.31512,-1.72406,-0.10621,1.76217,0.00445 -2.60617,1.37752,-1.31519,-1.72454,-0.10566,1.76243,0.00445 -2.60870,1.37726,-1.31526,-1.72501,-0.10512,1.76269,0.00445 -2.61122,1.37700,-1.31532,-1.72547,-0.10459,1.76295,0.00445 -2.61375,1.37675,-1.31539,-1.72593,-0.10407,1.76320,0.00445 -2.61628,1.37650,-1.31545,-1.72638,-0.10356,1.76344,0.00445 -2.61881,1.37626,-1.31552,-1.72682,-0.10305,1.76369,0.00445 -2.62133,1.37602,-1.31558,-1.72725,-0.10256,1.76393,0.00445 -2.62386,1.37578,-1.31564,-1.72767,-0.10207,1.76416,0.00445 -2.62639,1.37555,-1.31570,-1.72809,-0.10159,1.76439,0.00445 -2.62892,1.37532,-1.31576,-1.72850,-0.10112,1.76462,0.00445 -2.63145,1.37509,-1.31582,-1.72890,-0.10066,1.76484,0.00445 -2.63397,1.37487,-1.31588,-1.72929,-0.10021,1.76506,0.00445 -2.63650,1.37465,-1.31593,-1.72968,-0.09976,1.76528,0.00445 -2.63903,1.37450,-1.31597,-1.72995,-0.09945,1.76543,0.00445 -2.64156,1.37429,-1.31602,-1.73039,-0.09896,1.76564,0.00445 -2.64408,1.37408,-1.31608,-1.73081,-0.09849,1.76585,0.00445 -2.64661,1.37387,-1.31613,-1.73122,-0.09802,1.76605,0.00445 -2.64914,1.37367,-1.31618,-1.73163,-0.09756,1.76625,0.00445 -2.65167,1.37347,-1.31623,-1.73203,-0.09711,1.76645,0.00445 -2.65420,1.37327,-1.31628,-1.73243,-0.09666,1.76665,0.00445 -2.65672,1.37308,-1.31632,-1.73285,-0.09619,1.76684,0.00445 -2.65925,1.37289,-1.31637,-1.73327,-0.09573,1.76703,0.00445 -2.66178,1.37270,-1.31641,-1.73368,-0.09527,1.76721,0.00445 -2.66431,1.37252,-1.31645,-1.73408,-0.09482,1.76740,0.00445 -2.66684,1.37247,-1.31648,-1.73401,-0.09487,1.76744,0.00445 -2.66936,1.37205,-1.31669,-1.73328,-0.09537,1.76786,0.00445 -2.67189,1.37163,-1.31691,-1.73256,-0.09586,1.76828,0.00445 -2.67442,1.37122,-1.31712,-1.73185,-0.09634,1.76869,0.00445 -2.67695,1.37082,-1.31733,-1.73115,-0.09681,1.76910,0.00445 -2.67947,1.37042,-1.31754,-1.73047,-0.09727,1.76950,0.00445 -2.68200,1.37003,-1.31774,-1.72980,-0.09773,1.76989,0.00445 -2.68453,1.36965,-1.31794,-1.72913,-0.09818,1.77028,0.00445 -2.68706,1.36927,-1.31814,-1.72848,-0.09862,1.77066,0.00445 -2.68959,1.36890,-1.31834,-1.72784,-0.09905,1.77103,0.00445 -2.69211,1.36853,-1.31853,-1.72721,-0.09947,1.77140,0.00445 -2.69464,1.36817,-1.31872,-1.72659,-0.09989,1.77177,0.00445 -2.69717,1.36781,-1.31891,-1.72598,-0.10030,1.77213,0.00445 -2.69970,1.36746,-1.31910,-1.72538,-0.10070,1.77248,0.00445 -2.70222,1.36711,-1.31928,-1.72479,-0.10110,1.77283,0.00445 -2.70475,1.36677,-1.31946,-1.72421,-0.10148,1.77317,0.00445 -2.70728,1.36644,-1.31964,-1.72364,-0.10187,1.77351,0.00445 -2.70981,1.36611,-1.31982,-1.72308,-0.10224,1.77384,0.00445 -2.71234,1.36578,-1.31999,-1.72252,-0.10261,1.77417,0.00445 -2.71486,1.36546,-1.32016,-1.72198,-0.10297,1.77449,0.00445 -2.71739,1.36515,-1.32033,-1.72145,-0.10333,1.77481,0.00445 -2.71992,1.36484,-1.32050,-1.72092,-0.10368,1.77512,0.00445 -2.72245,1.36454,-1.32067,-1.72040,-0.10402,1.77543,0.00445 -2.72497,1.36423,-1.32083,-1.71989,-0.10436,1.77573,0.00445 -2.72750,1.36394,-1.32099,-1.71939,-0.10469,1.77603,0.00445 -2.73003,1.36365,-1.32115,-1.71890,-0.10502,1.77633,0.00445 -2.73256,1.36352,-1.32122,-1.71867,-0.10517,1.77646,0.00445 -2.73509,1.36310,-1.32146,-1.71785,-0.10574,1.77688,0.00445 -2.73761,1.36268,-1.32169,-1.71704,-0.10630,1.77730,0.00445 -2.74014,1.36228,-1.32193,-1.71625,-0.10685,1.77771,0.00445 -2.74267,1.36187,-1.32216,-1.71547,-0.10739,1.77811,0.00445 -2.74520,1.36148,-1.32238,-1.71470,-0.10792,1.77851,0.00445 -2.74772,1.36109,-1.32261,-1.71394,-0.10845,1.77890,0.00445 -2.75025,1.36070,-1.32283,-1.71320,-0.10896,1.77929,0.00445 -2.75278,1.36033,-1.32305,-1.71246,-0.10946,1.77967,0.00445 -2.75531,1.35995,-1.32326,-1.71174,-0.10996,1.78005,0.00445 -2.75784,1.35959,-1.32347,-1.71104,-0.11045,1.78042,0.00445 -2.76036,1.35923,-1.32368,-1.71034,-0.11093,1.78078,0.00445 -2.76289,1.35887,-1.32389,-1.70965,-0.11140,1.78114,0.00444 -2.76542,1.35852,-1.32409,-1.70898,-0.11186,1.78149,0.00444 -2.76795,1.35818,-1.32430,-1.70832,-0.11231,1.78184,0.00444 -2.77048,1.35784,-1.32450,-1.70766,-0.11276,1.78218,0.00444 -2.77300,1.35751,-1.32469,-1.70702,-0.11320,1.78252,0.00444 -2.77553,1.35718,-1.32489,-1.70639,-0.11363,1.78285,0.00444 -2.77806,1.35686,-1.32508,-1.70577,-0.11405,1.78318,0.00444 -2.78059,1.35654,-1.32526,-1.70516,-0.11447,1.78350,0.00444 -2.78311,1.35622,-1.32545,-1.70456,-0.11487,1.78382,0.00444 -2.78564,1.35591,-1.32563,-1.70397,-0.11528,1.78413,0.00444 -2.78817,1.35561,-1.32582,-1.70338,-0.11567,1.78444,0.00444 -2.79070,1.35531,-1.32599,-1.70281,-0.11606,1.78474,0.00444 -2.79323,1.35502,-1.32617,-1.70225,-0.11644,1.78504,0.00444 -2.79575,1.35473,-1.32634,-1.70170,-0.11681,1.78533,0.00444 -2.79828,1.35444,-1.32652,-1.70115,-0.11718,1.78562,0.00444 -2.80081,1.35416,-1.32669,-1.70062,-0.11754,1.78591,0.00443 -2.80334,1.35388,-1.32685,-1.70009,-0.11790,1.78619,0.00443 -2.80586,1.35361,-1.32702,-1.69957,-0.11825,1.78646,0.00443 -2.80839,1.35334,-1.32718,-1.69906,-0.11859,1.78674,0.00443 -2.81092,1.35311,-1.32732,-1.69863,-0.11888,1.78697,0.00443 -2.81345,1.35272,-1.32756,-1.69785,-0.11941,1.78737,0.00443 -2.81598,1.35233,-1.32780,-1.69708,-0.11994,1.78776,0.00443 -2.81850,1.35194,-1.32803,-1.69632,-0.12045,1.78815,0.00443 -2.82103,1.35156,-1.32826,-1.69558,-0.12096,1.78853,0.00443 -2.82356,1.35119,-1.32849,-1.69485,-0.12145,1.78891,0.00443 -2.82609,1.35082,-1.32872,-1.69413,-0.12194,1.78928,0.00443 -2.82861,1.35046,-1.32894,-1.69342,-0.12242,1.78964,0.00442 -2.83114,1.35010,-1.32916,-1.69272,-0.12289,1.79000,0.00442 -2.83367,1.34975,-1.32938,-1.69203,-0.12336,1.79036,0.00442 -2.83620,1.34941,-1.32959,-1.69136,-0.12381,1.79071,0.00442 -2.83873,1.34907,-1.32980,-1.69069,-0.12426,1.79105,0.00442 -2.84125,1.34873,-1.33001,-1.69004,-0.12470,1.79139,0.00442 -2.84378,1.34840,-1.33021,-1.68940,-0.12513,1.79172,0.00442 -2.84631,1.34808,-1.33042,-1.68877,-0.12556,1.79205,0.00442 -2.84884,1.34776,-1.33062,-1.68815,-0.12598,1.79238,0.00442 -2.85137,1.34744,-1.33081,-1.68753,-0.12639,1.79269,0.00441 -2.85389,1.34713,-1.33101,-1.68693,-0.12679,1.79301,0.00441 -2.85642,1.34683,-1.33120,-1.68634,-0.12718,1.79332,0.00441 -2.85895,1.34653,-1.33139,-1.68576,-0.12757,1.79362,0.00441 -2.86148,1.34623,-1.33158,-1.68519,-0.12796,1.79392,0.00441 -2.86400,1.34594,-1.33176,-1.68462,-0.12833,1.79422,0.00441 -2.86653,1.34565,-1.33194,-1.68407,-0.12870,1.79451,0.00441 -2.86906,1.34537,-1.33212,-1.68352,-0.12906,1.79479,0.00441 -2.87159,1.34509,-1.33230,-1.68299,-0.12942,1.79507,0.00440 -2.87412,1.34482,-1.33247,-1.68246,-0.12977,1.79535,0.00440 -2.87664,1.34455,-1.33264,-1.68194,-0.13012,1.79563,0.00440 -2.87917,1.34428,-1.33281,-1.68143,-0.13045,1.79590,0.00440 -2.88170,1.34421,-1.33286,-1.68131,-0.13053,1.79596,0.00440 -2.88423,1.34379,-1.33311,-1.68059,-0.13100,1.79639,0.00440 -2.88675,1.34338,-1.33337,-1.67987,-0.13145,1.79680,0.00440 -2.88928,1.34297,-1.33362,-1.67918,-0.13189,1.79721,0.00440 -2.89181,1.34257,-1.33386,-1.67849,-0.13233,1.79762,0.00439 -2.89434,1.34218,-1.33411,-1.67781,-0.13276,1.79802,0.00439 -2.89687,1.34179,-1.33434,-1.67714,-0.13318,1.79841,0.00439 -2.89939,1.34140,-1.33458,-1.67649,-0.13360,1.79879,0.00439 -2.90192,1.34103,-1.33481,-1.67584,-0.13401,1.79917,0.00439 -2.90445,1.34066,-1.33504,-1.67521,-0.13441,1.79955,0.00439 -2.90698,1.34029,-1.33527,-1.67459,-0.13480,1.79991,0.00439 -2.90950,1.33993,-1.33549,-1.67397,-0.13519,1.80028,0.00438 -2.91203,1.33958,-1.33571,-1.67337,-0.13557,1.80063,0.00438 -2.91456,1.33923,-1.33593,-1.67277,-0.13595,1.80099,0.00438 -2.91709,1.33888,-1.33615,-1.67219,-0.13631,1.80133,0.00438 -2.91962,1.33855,-1.33636,-1.67161,-0.13667,1.80167,0.00438 -2.92214,1.33821,-1.33657,-1.67105,-0.13703,1.80201,0.00438 -2.92467,1.33789,-1.33677,-1.67049,-0.13738,1.80234,0.00437 -2.92720,1.33756,-1.33697,-1.66994,-0.13772,1.80266,0.00437 -2.92973,1.33725,-1.33717,-1.66940,-0.13806,1.80299,0.00437 -2.93225,1.33693,-1.33737,-1.66887,-0.13839,1.80330,0.00437 -2.93478,1.33663,-1.33757,-1.66835,-0.13872,1.80361,0.00437 -2.93731,1.33632,-1.33776,-1.66784,-0.13903,1.80392,0.00437 -2.93984,1.33603,-1.33795,-1.66734,-0.13935,1.80422,0.00437 -2.94237,1.33598,-1.33797,-1.66726,-0.13939,1.80426,0.00437 -2.94489,1.33555,-1.33824,-1.66655,-0.13984,1.80469,0.00436 -2.94742,1.33513,-1.33850,-1.66585,-0.14027,1.80512,0.00436 -2.94995,1.33472,-1.33876,-1.66516,-0.14070,1.80554,0.00436 -2.95248,1.33431,-1.33902,-1.66449,-0.14111,1.80595,0.00436 -2.95501,1.33390,-1.33927,-1.66382,-0.14153,1.80635,0.00436 -2.95753,1.33351,-1.33952,-1.66316,-0.14193,1.80675,0.00436 -2.96006,1.33312,-1.33976,-1.66252,-0.14233,1.80715,0.00435 -2.96259,1.33273,-1.34000,-1.66188,-0.14272,1.80753,0.00435 -2.96512,1.33235,-1.34024,-1.66126,-0.14310,1.80791,0.00435 -2.96764,1.33198,-1.34048,-1.66064,-0.14348,1.80829,0.00435 -2.97017,1.33161,-1.34071,-1.66004,-0.14385,1.80866,0.00435 -2.97270,1.33125,-1.34094,-1.65944,-0.14422,1.80902,0.00434 -2.97523,1.33090,-1.34116,-1.65886,-0.14457,1.80938,0.00434 -2.97776,1.33055,-1.34139,-1.65828,-0.14493,1.80973,0.00434 -2.98028,1.33020,-1.34160,-1.65771,-0.14527,1.81008,0.00434 -2.98281,1.32987,-1.34182,-1.65716,-0.14561,1.81042,0.00434 -2.98534,1.32953,-1.34203,-1.65661,-0.14595,1.81076,0.00434 -2.98787,1.32920,-1.34224,-1.65607,-0.14628,1.81109,0.00433 -2.99039,1.32888,-1.34245,-1.65554,-0.14660,1.81142,0.00433 -2.99292,1.32856,-1.34265,-1.65501,-0.14692,1.81174,0.00433 -2.99545,1.32825,-1.34285,-1.65450,-0.14723,1.81206,0.00433 -2.99798,1.32794,-1.34305,-1.65399,-0.14753,1.81237,0.00433 -3.00051,1.32783,-1.34312,-1.65382,-0.14764,1.81248,0.00433 -3.00303,1.32732,-1.34344,-1.65304,-0.14810,1.81299,0.00433 -3.00556,1.32682,-1.34375,-1.65228,-0.14855,1.81349,0.00432 -3.00809,1.32633,-1.34405,-1.65153,-0.14899,1.81398,0.00432 -3.01062,1.32585,-1.34435,-1.65079,-0.14942,1.81446,0.00432 -3.01314,1.32538,-1.34465,-1.65007,-0.14985,1.81494,0.00432 -3.01567,1.32491,-1.34494,-1.64935,-0.15027,1.81541,0.00431 -3.01820,1.32445,-1.34523,-1.64865,-0.15068,1.81587,0.00431 -3.02073,1.32400,-1.34551,-1.64796,-0.15108,1.81632,0.00431 -3.02326,1.32355,-1.34579,-1.64728,-0.15148,1.81677,0.00431 -3.02578,1.32311,-1.34607,-1.64661,-0.15187,1.81721,0.00431 -3.02831,1.32268,-1.34634,-1.64595,-0.15226,1.81765,0.00430 -3.03084,1.32226,-1.34661,-1.64530,-0.15263,1.81807,0.00430 -3.03337,1.32184,-1.34687,-1.64467,-0.15300,1.81849,0.00430 -3.03589,1.32143,-1.34713,-1.64404,-0.15337,1.81891,0.00430 -3.03842,1.32102,-1.34739,-1.64342,-0.15373,1.81932,0.00430 -3.04095,1.32062,-1.34764,-1.64281,-0.15408,1.81972,0.00429 -3.04348,1.32023,-1.34789,-1.64222,-0.15443,1.82011,0.00429 -3.04601,1.31984,-1.34814,-1.64163,-0.15477,1.82050,0.00429 -3.04853,1.31946,-1.34838,-1.64105,-0.15510,1.82089,0.00429 -3.05106,1.31909,-1.34862,-1.64048,-0.15543,1.82126,0.00429 -3.05359,1.31872,-1.34886,-1.63992,-0.15575,1.82163,0.00428 -3.05612,1.31836,-1.34909,-1.63937,-0.15607,1.82200,0.00428 -3.05865,1.31800,-1.34932,-1.63883,-0.15638,1.82236,0.00428 -3.06117,1.31765,-1.34954,-1.63829,-0.15669,1.82271,0.00428 -3.06370,1.31730,-1.34976,-1.63777,-0.15699,1.82306,0.00428 -3.06623,1.31696,-1.34998,-1.63725,-0.15729,1.82341,0.00428 -3.06876,1.31663,-1.35020,-1.63674,-0.15758,1.82375,0.00427 -3.07128,1.31630,-1.35041,-1.63624,-0.15787,1.82408,0.00427 -3.07381,1.31621,-1.35047,-1.63612,-0.15794,1.82416,0.00427 -3.07634,1.31571,-1.35078,-1.63541,-0.15833,1.82467,0.00427 -3.07887,1.31521,-1.35109,-1.63472,-0.15871,1.82517,0.00427 -3.08140,1.31472,-1.35139,-1.63403,-0.15909,1.82565,0.00426 -3.08392,1.31424,-1.35170,-1.63336,-0.15946,1.82614,0.00426 -3.08645,1.31377,-1.35199,-1.63270,-0.15982,1.82661,0.00426 -3.08898,1.31331,-1.35228,-1.63205,-0.16018,1.82708,0.00426 -3.09151,1.31285,-1.35257,-1.63140,-0.16053,1.82754,0.00426 -3.09403,1.31240,-1.35286,-1.63077,-0.16088,1.82799,0.00425 -3.09656,1.31195,-1.35314,-1.63015,-0.16122,1.82844,0.00425 -3.09909,1.31152,-1.35341,-1.62954,-0.16155,1.82887,0.00425 -3.10162,1.31109,-1.35368,-1.62894,-0.16188,1.82931,0.00425 -3.10415,1.31066,-1.35395,-1.62834,-0.16220,1.82973,0.00424 -3.10667,1.31025,-1.35422,-1.62776,-0.16252,1.83015,0.00424 -3.10920,1.30984,-1.35448,-1.62719,-0.16283,1.83056,0.00424 -3.11173,1.30944,-1.35473,-1.62662,-0.16314,1.83097,0.00424 -3.11426,1.30904,-1.35498,-1.62607,-0.16344,1.83137,0.00424 -3.11678,1.30865,-1.35523,-1.62552,-0.16374,1.83176,0.00423 -3.11931,1.30826,-1.35548,-1.62498,-0.16403,1.83215,0.00423 -3.12184,1.30789,-1.35572,-1.62445,-0.16432,1.83253,0.00423 -3.12437,1.30751,-1.35596,-1.62393,-0.16460,1.83290,0.00423 -3.12690,1.30715,-1.35619,-1.62342,-0.16488,1.83327,0.00423 -3.12942,1.30679,-1.35643,-1.62292,-0.16515,1.83364,0.00422 -3.13195,1.30643,-1.35665,-1.62242,-0.16542,1.83400,0.00422 -3.13448,1.30614,-1.35684,-1.62200,-0.16564,1.83429,0.00422 -3.13701,1.30566,-1.35715,-1.62126,-0.16607,1.83477,0.00422 -3.13953,1.30519,-1.35746,-1.62053,-0.16649,1.83524,0.00422 -3.14206,1.30473,-1.35776,-1.61981,-0.16690,1.83571,0.00421 -3.14459,1.30427,-1.35806,-1.61911,-0.16731,1.83616,0.00421 -3.14712,1.30383,-1.35836,-1.61841,-0.16770,1.83661,0.00421 -3.14965,1.30339,-1.35865,-1.61773,-0.16810,1.83706,0.00421 -3.15217,1.30295,-1.35893,-1.61706,-0.16848,1.83749,0.00421 -3.15470,1.30253,-1.35922,-1.61639,-0.16886,1.83792,0.00420 -3.15723,1.30211,-1.35949,-1.61574,-0.16923,1.83834,0.00420 -3.15976,1.30169,-1.35977,-1.61510,-0.16960,1.83876,0.00420 -3.16229,1.30129,-1.36004,-1.61447,-0.16996,1.83917,0.00420 -3.16481,1.30089,-1.36030,-1.61385,-0.17031,1.83957,0.00420 -3.16734,1.30049,-1.36056,-1.61324,-0.17066,1.83997,0.00419 -3.16987,1.30010,-1.36082,-1.61264,-0.17100,1.84036,0.00419 -3.17240,1.29972,-1.36108,-1.61204,-0.17133,1.84075,0.00419 -3.17492,1.29935,-1.36133,-1.61146,-0.17166,1.84113,0.00419 -3.17745,1.29898,-1.36158,-1.61089,-0.17199,1.84150,0.00419 -3.17998,1.29861,-1.36182,-1.61033,-0.17230,1.84187,0.00418 -3.18251,1.29825,-1.36206,-1.60977,-0.17262,1.84223,0.00418 -3.18504,1.29790,-1.36230,-1.60923,-0.17293,1.84258,0.00418 -3.18756,1.29755,-1.36253,-1.60869,-0.17323,1.84294,0.00418 -3.19009,1.29721,-1.36276,-1.60816,-0.17353,1.84328,0.00418 -3.19262,1.29688,-1.36299,-1.60764,-0.17382,1.84362,0.00417 -3.19515,1.29655,-1.36321,-1.60713,-0.17411,1.84395,0.00417 -3.19767,1.29626,-1.36340,-1.60670,-0.17435,1.84424,0.00417 -3.20020,1.29574,-1.36374,-1.60596,-0.17475,1.84476,0.00417 -3.20273,1.29523,-1.36407,-1.60522,-0.17514,1.84527,0.00417 -3.20526,1.29473,-1.36440,-1.60450,-0.17553,1.84578,0.00416 -3.20779,1.29423,-1.36473,-1.60379,-0.17592,1.84628,0.00416 -3.21031,1.29374,-1.36505,-1.60309,-0.17629,1.84677,0.00416 -3.21284,1.29326,-1.36536,-1.60241,-0.17666,1.84725,0.00416 -3.21537,1.29279,-1.36567,-1.60173,-0.17702,1.84773,0.00415 -3.21790,1.29232,-1.36598,-1.60107,-0.17738,1.84819,0.00415 -3.22042,1.29186,-1.36628,-1.60041,-0.17773,1.84866,0.00415 -3.22295,1.29141,-1.36658,-1.59977,-0.17808,1.84911,0.00415 -3.22548,1.29097,-1.36687,-1.59913,-0.17842,1.84955,0.00415 -3.22801,1.29053,-1.36716,-1.59851,-0.17875,1.84999,0.00414 -3.23054,1.29010,-1.36745,-1.59789,-0.17908,1.85043,0.00414 -3.23306,1.28968,-1.36773,-1.59729,-0.17940,1.85085,0.00414 -3.23559,1.28926,-1.36800,-1.59669,-0.17972,1.85127,0.00414 -3.23812,1.28885,-1.36828,-1.59611,-0.18003,1.85168,0.00413 -3.24065,1.28845,-1.36854,-1.59553,-0.18034,1.85209,0.00413 -3.24317,1.28805,-1.36881,-1.59496,-0.18064,1.85249,0.00413 -3.24570,1.28766,-1.36907,-1.59440,-0.18094,1.85288,0.00413 -3.24823,1.28728,-1.36933,-1.59386,-0.18123,1.85327,0.00413 -3.25076,1.28690,-1.36958,-1.59332,-0.18152,1.85365,0.00412 -3.25329,1.28653,-1.36983,-1.59278,-0.18180,1.85403,0.00412 -3.25581,1.28616,-1.37008,-1.59226,-0.18207,1.85440,0.00412 -3.25834,1.28580,-1.37032,-1.59175,-0.18235,1.85476,0.00412 -3.26087,1.28545,-1.37056,-1.59124,-0.18261,1.85512,0.00412 -3.26340,1.28510,-1.37079,-1.59074,-0.18288,1.85547,0.00411 -3.26593,1.28498,-1.37087,-1.59057,-0.18297,1.85559,0.00411 -3.26845,1.28448,-1.37120,-1.58987,-0.18334,1.85609,0.00411 -3.27098,1.28399,-1.37152,-1.58918,-0.18370,1.85658,0.00411 -3.27351,1.28352,-1.37184,-1.58850,-0.18406,1.85706,0.00411 -3.27604,1.28304,-1.37216,-1.58783,-0.18441,1.85753,0.00410 -3.27856,1.28258,-1.37247,-1.58717,-0.18476,1.85800,0.00410 -3.28109,1.28212,-1.37277,-1.58652,-0.18510,1.85846,0.00410 -3.28362,1.28167,-1.37308,-1.58588,-0.18544,1.85891,0.00410 -3.28615,1.28123,-1.37337,-1.58525,-0.18577,1.85935,0.00410 -3.28868,1.28079,-1.37367,-1.58464,-0.18609,1.85979,0.00409 -3.29120,1.28037,-1.37395,-1.58403,-0.18641,1.86022,0.00409 -3.29373,1.27994,-1.37424,-1.58343,-0.18672,1.86065,0.00409 -3.29626,1.27953,-1.37452,-1.58284,-0.18703,1.86107,0.00409 -3.29879,1.27912,-1.37479,-1.58226,-0.18733,1.86148,0.00408 -3.30131,1.27872,-1.37506,-1.58169,-0.18763,1.86188,0.00408 -3.30384,1.27832,-1.37533,-1.58113,-0.18792,1.86228,0.00408 -3.30637,1.27793,-1.37560,-1.58058,-0.18821,1.86267,0.00408 -3.30890,1.27755,-1.37586,-1.58003,-0.18849,1.86306,0.00408 -3.31143,1.27717,-1.37611,-1.57950,-0.18877,1.86344,0.00407 -3.31395,1.27680,-1.37636,-1.57897,-0.18904,1.86381,0.00407 -3.31648,1.27644,-1.37661,-1.57845,-0.18931,1.86418,0.00407 -3.31901,1.27608,-1.37686,-1.57794,-0.18958,1.86454,0.00407 -3.32154,1.27573,-1.37710,-1.57744,-0.18984,1.86490,0.00407 -3.32406,1.27550,-1.37725,-1.57713,-0.19000,1.86513,0.00406 -3.32659,1.27498,-1.37760,-1.57645,-0.19033,1.86565,0.00406 -3.32912,1.27447,-1.37793,-1.57579,-0.19065,1.86616,0.00406 -3.33165,1.27396,-1.37827,-1.57513,-0.19097,1.86667,0.00406 -3.33418,1.27347,-1.37859,-1.57449,-0.19129,1.86716,0.00405 -3.33670,1.27298,-1.37892,-1.57386,-0.19160,1.86765,0.00405 -3.33923,1.27250,-1.37923,-1.57324,-0.19190,1.86813,0.00405 -3.34176,1.27203,-1.37955,-1.57262,-0.19220,1.86861,0.00405 -3.34429,1.27157,-1.37986,-1.57202,-0.19249,1.86907,0.00405 -3.34681,1.27111,-1.38016,-1.57143,-0.19278,1.86953,0.00404 -3.34934,1.27066,-1.38046,-1.57084,-0.19306,1.86998,0.00404 -3.35187,1.27022,-1.38076,-1.57027,-0.19334,1.87043,0.00404 -3.35440,1.26978,-1.38105,-1.56970,-0.19362,1.87086,0.00404 -3.35693,1.26936,-1.38133,-1.56914,-0.19389,1.87129,0.00403 -3.35945,1.26893,-1.38161,-1.56859,-0.19415,1.87172,0.00403 -3.36198,1.26852,-1.38189,-1.56805,-0.19441,1.87213,0.00403 -3.36451,1.26811,-1.38217,-1.56752,-0.19467,1.87254,0.00403 -3.36704,1.26771,-1.38244,-1.56700,-0.19492,1.87295,0.00403 -3.36957,1.26732,-1.38270,-1.56649,-0.19517,1.87335,0.00402 -3.37209,1.26693,-1.38296,-1.56598,-0.19541,1.87374,0.00402 -3.37462,1.26655,-1.38322,-1.56548,-0.19565,1.87412,0.00402 -3.37715,1.26617,-1.38348,-1.56499,-0.19589,1.87450,0.00402 -3.37968,1.26585,-1.38369,-1.56458,-0.19609,1.87482,0.00401 -3.38220,1.26529,-1.38407,-1.56383,-0.19646,1.87538,0.00401 -3.38473,1.26474,-1.38444,-1.56309,-0.19683,1.87593,0.00401 -3.38726,1.26420,-1.38480,-1.56236,-0.19718,1.87647,0.00401 -3.38979,1.26367,-1.38516,-1.56165,-0.19754,1.87701,0.00401 -3.39232,1.26314,-1.38552,-1.56094,-0.19788,1.87753,0.00400 -3.39484,1.26263,-1.38587,-1.56025,-0.19822,1.87805,0.00400 -3.39737,1.26212,-1.38621,-1.55957,-0.19856,1.87856,0.00400 -3.39990,1.26162,-1.38655,-1.55889,-0.19889,1.87906,0.00400 -3.40243,1.26113,-1.38689,-1.55823,-0.19921,1.87955,0.00399 -3.40495,1.26065,-1.38722,-1.55758,-0.19953,1.88004,0.00399 -3.40748,1.26017,-1.38754,-1.55694,-0.19985,1.88052,0.00399 -3.41001,1.25970,-1.38786,-1.55631,-0.20015,1.88099,0.00399 -3.41254,1.25924,-1.38818,-1.55569,-0.20046,1.88145,0.00398 -3.41507,1.25879,-1.38849,-1.55508,-0.20076,1.88190,0.00398 -3.41759,1.25835,-1.38879,-1.55448,-0.20105,1.88235,0.00398 -3.42012,1.25791,-1.38909,-1.55389,-0.20134,1.88279,0.00398 -3.42265,1.25748,-1.38939,-1.55331,-0.20162,1.88323,0.00398 -3.42518,1.25705,-1.38968,-1.55274,-0.20190,1.88366,0.00397 -3.42770,1.25663,-1.38997,-1.55217,-0.20218,1.88408,0.00397 -3.43023,1.25622,-1.39026,-1.55162,-0.20245,1.88449,0.00397 -3.43276,1.25582,-1.39054,-1.55107,-0.20271,1.88490,0.00397 -3.43529,1.25542,-1.39081,-1.55053,-0.20297,1.88530,0.00396 -3.43782,1.25503,-1.39108,-1.55000,-0.20323,1.88569,0.00396 -3.44034,1.25464,-1.39135,-1.54948,-0.20348,1.88608,0.00396 -3.44287,1.25426,-1.39161,-1.54897,-0.20373,1.88646,0.00396 -3.44540,1.25389,-1.39187,-1.54847,-0.20397,1.88684,0.00396 -3.44793,1.25352,-1.39213,-1.54797,-0.20422,1.88721,0.00395 -3.45046,1.25329,-1.39229,-1.54766,-0.20437,1.88744,0.00395 -3.45298,1.25281,-1.39263,-1.54696,-0.20472,1.88793,0.00395 -3.45551,1.25233,-1.39297,-1.54628,-0.20507,1.88841,0.00395 -3.45804,1.25186,-1.39330,-1.54561,-0.20541,1.88888,0.00395 -3.46057,1.25140,-1.39362,-1.54494,-0.20574,1.88934,0.00394 -3.46309,1.25095,-1.39394,-1.54429,-0.20607,1.88980,0.00394 -3.46562,1.25050,-1.39426,-1.54365,-0.20639,1.89025,0.00394 -3.46815,1.25006,-1.39457,-1.54302,-0.20671,1.89069,0.00394 -3.47068,1.24963,-1.39488,-1.54240,-0.20702,1.89113,0.00394 -3.47321,1.24920,-1.39518,-1.54179,-0.20733,1.89156,0.00393 -3.47573,1.24878,-1.39548,-1.54119,-0.20763,1.89198,0.00393 -3.47826,1.24837,-1.39577,-1.54059,-0.20793,1.89240,0.00393 -3.48079,1.24796,-1.39606,-1.54001,-0.20822,1.89280,0.00393 -3.48332,1.24756,-1.39634,-1.53944,-0.20851,1.89321,0.00392 -3.48584,1.24717,-1.39662,-1.53887,-0.20879,1.89360,0.00392 -3.48837,1.24678,-1.39690,-1.53832,-0.20907,1.89399,0.00392 -3.49090,1.24640,-1.39717,-1.53777,-0.20934,1.89438,0.00392 -3.49343,1.24603,-1.39744,-1.53723,-0.20961,1.89475,0.00392 -3.49596,1.24566,-1.39771,-1.53670,-0.20988,1.89513,0.00391 -3.49848,1.24530,-1.39797,-1.53618,-0.21014,1.89549,0.00391 -3.50101,1.24494,-1.39822,-1.53567,-0.21040,1.89585,0.00391 -3.50354,1.24459,-1.39847,-1.53516,-0.21065,1.89621,0.00391 -3.50607,1.24448,-1.39856,-1.53499,-0.21073,1.89632,0.00391 -3.50859,1.24403,-1.39889,-1.53430,-0.21110,1.89677,0.00391 -3.51112,1.24359,-1.39921,-1.53361,-0.21146,1.89722,0.00390 -3.51365,1.24315,-1.39953,-1.53294,-0.21182,1.89765,0.00390 -3.51618,1.24273,-1.39984,-1.53227,-0.21217,1.89808,0.00390 -3.51871,1.24231,-1.40015,-1.53162,-0.21251,1.89851,0.00390 -3.52123,1.24190,-1.40045,-1.53097,-0.21285,1.89892,0.00390 -3.52376,1.24149,-1.40075,-1.53034,-0.21318,1.89933,0.00389 -3.52629,1.24109,-1.40105,-1.52972,-0.21351,1.89973,0.00389 -3.52882,1.24069,-1.40134,-1.52910,-0.21383,1.90013,0.00389 -3.53134,1.24031,-1.40163,-1.52850,-0.21414,1.90052,0.00389 -3.53387,1.23993,-1.40191,-1.52790,-0.21445,1.90091,0.00389 -3.53640,1.23955,-1.40219,-1.52732,-0.21476,1.90128,0.00388 -3.53893,1.23918,-1.40246,-1.52674,-0.21506,1.90166,0.00388 -3.54146,1.23882,-1.40273,-1.52617,-0.21536,1.90202,0.00388 -3.54398,1.23846,-1.40300,-1.52562,-0.21565,1.90238,0.00388 -3.54651,1.23811,-1.40326,-1.52507,-0.21593,1.90274,0.00388 -3.54904,1.23776,-1.40352,-1.52453,-0.21621,1.90309,0.00387 -3.55157,1.23742,-1.40377,-1.52400,-0.21649,1.90343,0.00387 -3.55410,1.23709,-1.40402,-1.52347,-0.21676,1.90377,0.00387 -3.55662,1.23678,-1.40425,-1.52299,-0.21701,1.90408,0.00387 -3.55915,1.23638,-1.40456,-1.52229,-0.21740,1.90449,0.00387 -3.56168,1.23598,-1.40487,-1.52160,-0.21778,1.90490,0.00386 -3.56421,1.23558,-1.40518,-1.52092,-0.21816,1.90529,0.00386 -3.56673,1.23519,-1.40548,-1.52025,-0.21853,1.90568,0.00386 -3.56926,1.23481,-1.40577,-1.51959,-0.21889,1.90607,0.00386 -3.57179,1.23444,-1.40606,-1.51894,-0.21924,1.90645,0.00386 -3.57432,1.23407,-1.40635,-1.51830,-0.21959,1.90682,0.00385 -3.57685,1.23370,-1.40663,-1.51767,-0.21994,1.90719,0.00385 -3.57937,1.23335,-1.40691,-1.51705,-0.22028,1.90755,0.00385 -3.58190,1.23299,-1.40718,-1.51644,-0.22061,1.90791,0.00385 -3.58443,1.23265,-1.40745,-1.51585,-0.22094,1.90826,0.00385 -3.58696,1.23231,-1.40772,-1.51526,-0.22126,1.90860,0.00385 -3.58948,1.23197,-1.40798,-1.51468,-0.22158,1.90894,0.00384 -3.59201,1.23164,-1.40824,-1.51411,-0.22189,1.90927,0.00384 -3.59454,1.23132,-1.40849,-1.51354,-0.22220,1.90960,0.00384 -3.59707,1.23100,-1.40874,-1.51299,-0.22250,1.90993,0.00384 -3.59960,1.23068,-1.40899,-1.51245,-0.22279,1.91025,0.00384 -3.60212,1.23037,-1.40923,-1.51191,-0.22309,1.91056,0.00383 -3.60465,1.23018,-1.40938,-1.51158,-0.22327,1.91075,0.00383 -3.60718,1.22982,-1.40967,-1.51089,-0.22366,1.91112,0.00383 -3.60971,1.22946,-1.40996,-1.51021,-0.22405,1.91148,0.00383 -3.61223,1.22911,-1.41025,-1.50954,-0.22443,1.91183,0.00383 -3.61476,1.22877,-1.41053,-1.50889,-0.22481,1.91218,0.00383 -3.61729,1.22843,-1.41080,-1.50824,-0.22517,1.91253,0.00382 -3.61982,1.22809,-1.41107,-1.50761,-0.22554,1.91286,0.00382 -3.62235,1.22777,-1.41134,-1.50698,-0.22589,1.91320,0.00382 -3.62487,1.22744,-1.41160,-1.50637,-0.22624,1.91353,0.00382 -3.62740,1.22712,-1.41186,-1.50576,-0.22659,1.91385,0.00382 -3.62993,1.22681,-1.41212,-1.50516,-0.22693,1.91417,0.00382 -3.63246,1.22650,-1.41237,-1.50458,-0.22726,1.91448,0.00381 -3.63498,1.22620,-1.41262,-1.50400,-0.22759,1.91479,0.00381 -3.63751,1.22590,-1.41287,-1.50343,-0.22791,1.91509,0.00381 -3.64004,1.22560,-1.41311,-1.50287,-0.22823,1.91539,0.00381 -3.64257,1.22531,-1.41335,-1.50232,-0.22854,1.91568,0.00381 -3.64510,1.22502,-1.41359,-1.50176,-0.22886,1.91598,0.00380 -3.64762,1.22468,-1.41388,-1.50104,-0.22928,1.91632,0.00380 -3.65015,1.22435,-1.41416,-1.50033,-0.22971,1.91666,0.00380 -3.65268,1.22402,-1.41444,-1.49963,-0.23012,1.91699,0.00380 -3.65521,1.22369,-1.41472,-1.49895,-0.23053,1.91732,0.00380 -3.65774,1.22337,-1.41499,-1.49827,-0.23093,1.91765,0.00380 -3.66026,1.22306,-1.41526,-1.49760,-0.23132,1.91797,0.00379 -3.66279,1.22275,-1.41553,-1.49695,-0.23171,1.91828,0.00379 -3.66532,1.22245,-1.41579,-1.49631,-0.23209,1.91859,0.00379 -3.66785,1.22215,-1.41605,-1.49567,-0.23246,1.91889,0.00379 -3.67037,1.22185,-1.41630,-1.49505,-0.23283,1.91919,0.00379 -3.67290,1.22156,-1.41655,-1.49443,-0.23320,1.91948,0.00379 -3.67543,1.22128,-1.41680,-1.49383,-0.23355,1.91977,0.00378 -3.67796,1.22100,-1.41704,-1.49324,-0.23390,1.92006,0.00378 -3.68049,1.22072,-1.41728,-1.49265,-0.23425,1.92034,0.00378 -3.68301,1.22045,-1.41752,-1.49207,-0.23459,1.92062,0.00378 -3.68554,1.22018,-1.41775,-1.49151,-0.23492,1.92089,0.00378 -3.68807,1.21992,-1.41798,-1.49095,-0.23525,1.92116,0.00377 -3.69060,1.21975,-1.41812,-1.49060,-0.23545,1.92132,0.00377 -3.69312,1.21941,-1.41842,-1.48988,-0.23588,1.92167,0.00377 -3.69565,1.21908,-1.41871,-1.48917,-0.23630,1.92200,0.00377 -3.69818,1.21875,-1.41899,-1.48847,-0.23671,1.92233,0.00377 -3.70071,1.21843,-1.41927,-1.48778,-0.23711,1.92266,0.00377 -3.70324,1.21811,-1.41955,-1.48711,-0.23751,1.92298,0.00376 -3.70576,1.21780,-1.41982,-1.48644,-0.23791,1.92330,0.00376 -3.70829,1.21749,-1.42009,-1.48579,-0.23829,1.92361,0.00376 -3.71082,1.21719,-1.42035,-1.48514,-0.23867,1.92391,0.00376 -3.71335,1.21689,-1.42061,-1.48451,-0.23904,1.92422,0.00376 -3.71587,1.21660,-1.42087,-1.48388,-0.23941,1.92451,0.00376 -3.71840,1.21631,-1.42112,-1.48327,-0.23977,1.92481,0.00375 -3.72093,1.21603,-1.42137,-1.48266,-0.24013,1.92509,0.00375 -3.72346,1.21575,-1.42162,-1.48207,-0.24048,1.92538,0.00375 -3.72599,1.21548,-1.42186,-1.48148,-0.24082,1.92565,0.00375 -3.72851,1.21521,-1.42210,-1.48090,-0.24116,1.92593,0.00375 -3.73104,1.21494,-1.42233,-1.48033,-0.24149,1.92620,0.00374 -3.73357,1.21468,-1.42256,-1.47978,-0.24181,1.92647,0.00374 -3.73610,1.21457,-1.42266,-1.47953,-0.24196,1.92658,0.00374 -3.73862,1.21423,-1.42297,-1.47877,-0.24242,1.92692,0.00374 -3.74115,1.21390,-1.42326,-1.47801,-0.24287,1.92725,0.00374 -3.74368,1.21358,-1.42356,-1.47727,-0.24332,1.92758,0.00374 -3.74621,1.21326,-1.42385,-1.47654,-0.24375,1.92791,0.00374 -3.74874,1.21294,-1.42413,-1.47583,-0.24418,1.92822,0.00373 -3.75126,1.21263,-1.42441,-1.47512,-0.24461,1.92854,0.00373 -3.75379,1.21233,-1.42469,-1.47442,-0.24502,1.92885,0.00373 -3.75632,1.21202,-1.42496,-1.47374,-0.24543,1.92915,0.00373 -3.75885,1.21173,-1.42523,-1.47307,-0.24584,1.92945,0.00373 -3.76138,1.21144,-1.42550,-1.47240,-0.24623,1.92975,0.00372 -3.76390,1.21115,-1.42576,-1.47175,-0.24662,1.93004,0.00372 -3.76643,1.21087,-1.42602,-1.47111,-0.24701,1.93032,0.00372 -3.76896,1.21059,-1.42627,-1.47048,-0.24738,1.93060,0.00372 -3.77149,1.21032,-1.42652,-1.46986,-0.24775,1.93088,0.00372 -3.77401,1.21005,-1.42677,-1.46924,-0.24812,1.93115,0.00372 -3.77654,1.20979,-1.42701,-1.46864,-0.24848,1.93142,0.00371 -3.77907,1.20953,-1.42725,-1.46805,-0.24883,1.93169,0.00371 -3.78160,1.20927,-1.42749,-1.46746,-0.24918,1.93195,0.00371 -3.78413,1.20902,-1.42772,-1.46689,-0.24952,1.93220,0.00371 -3.78665,1.20877,-1.42795,-1.46633,-0.24985,1.93245,0.00371 -3.78918,1.20870,-1.42802,-1.46614,-0.24996,1.93253,0.00371 -3.79171,1.20844,-1.42828,-1.46544,-0.25041,1.93280,0.00370 -3.79424,1.20818,-1.42854,-1.46474,-0.25084,1.93306,0.00370 -3.79676,1.20793,-1.42879,-1.46406,-0.25127,1.93331,0.00370 -3.79929,1.20768,-1.42903,-1.46339,-0.25170,1.93357,0.00370 -3.80182,1.20744,-1.42928,-1.46273,-0.25211,1.93382,0.00370 -3.80435,1.20719,-1.42952,-1.46208,-0.25252,1.93406,0.00370 -3.80688,1.20696,-1.42976,-1.46144,-0.25292,1.93430,0.00369 -3.80940,1.20672,-1.42999,-1.46081,-0.25332,1.93454,0.00369 -3.81193,1.20650,-1.43022,-1.46019,-0.25370,1.93477,0.00369 -3.81446,1.20627,-1.43045,-1.45958,-0.25409,1.93500,0.00369 -3.81699,1.20605,-1.43067,-1.45898,-0.25446,1.93523,0.00369 -3.81951,1.20583,-1.43089,-1.45839,-0.25483,1.93546,0.00368 -3.82204,1.20561,-1.43111,-1.45781,-0.25520,1.93568,0.00368 -3.82457,1.20540,-1.43133,-1.45723,-0.25555,1.93589,0.00368 -3.82710,1.20538,-1.43135,-1.45715,-0.25561,1.93591,0.00368 -3.82963,1.20516,-1.43162,-1.45627,-0.25622,1.93614,0.00368 -3.83215,1.20494,-1.43189,-1.45541,-0.25681,1.93637,0.00368 -3.83468,1.20472,-1.43215,-1.45456,-0.25739,1.93659,0.00368 -3.83721,1.20451,-1.43241,-1.45372,-0.25796,1.93681,0.00368 -3.83974,1.20430,-1.43267,-1.45290,-0.25853,1.93702,0.00368 -3.84226,1.20410,-1.43292,-1.45209,-0.25908,1.93723,0.00367 -3.84479,1.20390,-1.43317,-1.45130,-0.25963,1.93744,0.00367 -3.84732,1.20370,-1.43341,-1.45051,-0.26016,1.93764,0.00367 -3.84985,1.20350,-1.43366,-1.44974,-0.26069,1.93785,0.00367 -3.85238,1.20331,-1.43389,-1.44898,-0.26121,1.93804,0.00367 -3.85490,1.20312,-1.43413,-1.44824,-0.26171,1.93824,0.00367 -3.85743,1.20293,-1.43436,-1.44750,-0.26221,1.93843,0.00367 -3.85996,1.20275,-1.43459,-1.44678,-0.26271,1.93862,0.00366 -3.86249,1.20257,-1.43482,-1.44607,-0.26319,1.93881,0.00366 -3.86502,1.20239,-1.43504,-1.44537,-0.26367,1.93899,0.00366 -3.86754,1.20221,-1.43526,-1.44468,-0.26414,1.93918,0.00366 -3.87007,1.20204,-1.43548,-1.44400,-0.26460,1.93935,0.00366 -3.87260,1.20187,-1.43569,-1.44333,-0.26505,1.93953,0.00366 -3.87513,1.20170,-1.43590,-1.44267,-0.26549,1.93970,0.00365 -3.87765,1.20153,-1.43611,-1.44203,-0.26593,1.93988,0.00365 -3.88018,1.20137,-1.43632,-1.44139,-0.26636,1.94004,0.00365 -3.88271,1.20121,-1.43652,-1.44076,-0.26679,1.94021,0.00365 -3.88524,1.20105,-1.43672,-1.44015,-0.26720,1.94037,0.00365 -3.88777,1.20090,-1.43692,-1.43954,-0.26761,1.94053,0.00365 -3.89029,1.20074,-1.43711,-1.43894,-0.26801,1.94069,0.00364 -3.89282,1.20059,-1.43731,-1.43836,-0.26841,1.94085,0.00364 -3.89535,1.20047,-1.43746,-1.43785,-0.26876,1.94097,0.00364 -3.89788,1.20034,-1.43772,-1.43685,-0.26950,1.94111,0.00364 -3.90040,1.20020,-1.43797,-1.43586,-0.27023,1.94126,0.00364 -3.90293,1.20007,-1.43822,-1.43490,-0.27094,1.94140,0.00364 -3.90546,1.19994,-1.43847,-1.43394,-0.27165,1.94153,0.00364 -3.90799,1.19981,-1.43871,-1.43300,-0.27234,1.94167,0.00364 -3.91052,1.19969,-1.43895,-1.43208,-0.27302,1.94180,0.00363 -3.91304,1.19956,-1.43919,-1.43117,-0.27369,1.94194,0.00363 -3.91557,1.19944,-1.43942,-1.43028,-0.27434,1.94207,0.00363 -3.91810,1.19932,-1.43965,-1.42939,-0.27499,1.94219,0.00363 -3.92063,1.19920,-1.43988,-1.42853,-0.27563,1.94232,0.00363 -3.92315,1.19908,-1.44010,-1.42767,-0.27625,1.94245,0.00363 -3.92568,1.19896,-1.44033,-1.42683,-0.27687,1.94257,0.00363 -3.92821,1.19885,-1.44055,-1.42601,-0.27747,1.94269,0.00363 -3.93074,1.19873,-1.44076,-1.42519,-0.27807,1.94281,0.00362 -3.93327,1.19862,-1.44098,-1.42439,-0.27865,1.94293,0.00362 -3.93579,1.19851,-1.44119,-1.42361,-0.27923,1.94304,0.00362 -3.93832,1.19840,-1.44140,-1.42283,-0.27979,1.94316,0.00362 -3.94085,1.19830,-1.44161,-1.42207,-0.28035,1.94327,0.00362 -3.94338,1.19819,-1.44181,-1.42132,-0.28089,1.94338,0.00362 -3.94590,1.19809,-1.44201,-1.42058,-0.28143,1.94349,0.00361 -3.94843,1.19799,-1.44221,-1.41985,-0.28196,1.94360,0.00361 -3.95096,1.19789,-1.44241,-1.41913,-0.28248,1.94371,0.00361 -3.95349,1.19779,-1.44260,-1.41843,-0.28299,1.94381,0.00361 -3.95602,1.19769,-1.44279,-1.41773,-0.28349,1.94392,0.00361 -3.95854,1.19759,-1.44298,-1.41705,-0.28399,1.94402,0.00361 -3.96107,1.19750,-1.44317,-1.41638,-0.28447,1.94412,0.00360 -3.96360,1.19740,-1.44335,-1.41572,-0.28495,1.94422,0.00360 -3.96613,1.19731,-1.44353,-1.41507,-0.28542,1.94432,0.00360 -3.96866,1.19722,-1.44371,-1.41443,-0.28588,1.94442,0.00360 -3.97118,1.19713,-1.44389,-1.41380,-0.28634,1.94451,0.00360 -3.97371,1.19704,-1.44406,-1.41318,-0.28678,1.94461,0.00359 -3.97624,1.19695,-1.44423,-1.41257,-0.28722,1.94470,0.00359 -3.97877,1.19686,-1.44440,-1.41197,-0.28765,1.94479,0.00359 -3.98129,1.19678,-1.44457,-1.41137,-0.28808,1.94488,0.00359 -3.98382,1.19670,-1.44474,-1.41079,-0.28850,1.94497,0.00359 -3.98635,1.19669,-1.44476,-1.41069,-0.28857,1.94498,0.00359 -3.98888,1.19662,-1.44499,-1.40971,-0.28932,1.94506,0.00359 -3.99141,1.19655,-1.44522,-1.40874,-0.29006,1.94514,0.00358 -3.99393,1.19648,-1.44545,-1.40778,-0.29078,1.94522,0.00358 -3.99646,1.19641,-1.44567,-1.40684,-0.29150,1.94529,0.00358 -3.99899,1.19634,-1.44590,-1.40591,-0.29220,1.94537,0.00358 -4.00152,1.19627,-1.44612,-1.40500,-0.29289,1.94544,0.00358 -4.00404,1.19620,-1.44633,-1.40411,-0.29356,1.94552,0.00358 -4.00657,1.19614,-1.44655,-1.40322,-0.29423,1.94559,0.00358 -4.00910,1.19607,-1.44676,-1.40235,-0.29488,1.94566,0.00358 -4.01163,1.19601,-1.44697,-1.40150,-0.29553,1.94573,0.00357 -4.01416,1.19594,-1.44718,-1.40066,-0.29616,1.94580,0.00357 -4.01668,1.19588,-1.44738,-1.39983,-0.29679,1.94587,0.00357 -4.01921,1.19582,-1.44758,-1.39901,-0.29740,1.94594,0.00357 -4.02174,1.19576,-1.44778,-1.39821,-0.29800,1.94601,0.00357 -4.02427,1.19570,-1.44798,-1.39742,-0.29859,1.94608,0.00357 -4.02679,1.19564,-1.44818,-1.39664,-0.29917,1.94614,0.00356 -4.02932,1.19558,-1.44837,-1.39588,-0.29975,1.94621,0.00356 -4.03185,1.19552,-1.44856,-1.39512,-0.30031,1.94627,0.00356 -4.03438,1.19546,-1.44875,-1.39438,-0.30086,1.94634,0.00356 -4.03691,1.19540,-1.44893,-1.39365,-0.30141,1.94640,0.00356 -4.03943,1.19535,-1.44911,-1.39294,-0.30194,1.94646,0.00355 -4.04196,1.19529,-1.44930,-1.39223,-0.30247,1.94653,0.00355 -4.04449,1.19523,-1.44947,-1.39153,-0.30299,1.94659,0.00355 -4.04702,1.19518,-1.44965,-1.39085,-0.30350,1.94665,0.00355 -4.04954,1.19513,-1.44982,-1.39017,-0.30400,1.94671,0.00355 -4.05207,1.19507,-1.45000,-1.38951,-0.30449,1.94676,0.00354 -4.05460,1.19502,-1.45017,-1.38886,-0.30497,1.94682,0.00354 -4.05713,1.19497,-1.45033,-1.38821,-0.30545,1.94688,0.00354 -4.05966,1.19492,-1.45050,-1.38758,-0.30592,1.94694,0.00354 -4.06218,1.19487,-1.45066,-1.38696,-0.30638,1.94699,0.00354 -4.06471,1.19482,-1.45082,-1.38635,-0.30683,1.94705,0.00353 -4.06724,1.19477,-1.45098,-1.38574,-0.30728,1.94710,0.00353 -4.06977,1.19472,-1.45114,-1.38515,-0.30771,1.94716,0.00353 -4.07230,1.19467,-1.45130,-1.38457,-0.30815,1.94721,0.00353 -4.07482,1.19466,-1.45135,-1.38437,-0.30829,1.94722,0.00353 -4.07735,1.19461,-1.45153,-1.38361,-0.30886,1.94727,0.00353 -4.07988,1.19457,-1.45172,-1.38286,-0.30943,1.94732,0.00352 -4.08241,1.19453,-1.45190,-1.38213,-0.30998,1.94737,0.00352 -4.08493,1.19449,-1.45208,-1.38140,-0.31053,1.94741,0.00352 -4.08746,1.19445,-1.45226,-1.38069,-0.31107,1.94746,0.00352 -4.08999,1.19441,-1.45243,-1.37998,-0.31159,1.94751,0.00352 -4.09252,1.19437,-1.45260,-1.37929,-0.31211,1.94755,0.00351 -4.09505,1.19433,-1.45278,-1.37861,-0.31262,1.94760,0.00351 -4.09757,1.19429,-1.45294,-1.37794,-0.31313,1.94764,0.00351 -4.10010,1.19425,-1.45311,-1.37728,-0.31362,1.94769,0.00351 -4.10263,1.19421,-1.45328,-1.37663,-0.31411,1.94773,0.00351 -4.10516,1.19418,-1.45344,-1.37599,-0.31458,1.94777,0.00350 -4.10768,1.19414,-1.45360,-1.37536,-0.31505,1.94781,0.00350 -4.11021,1.19410,-1.45376,-1.37474,-0.31551,1.94786,0.00350 -4.11274,1.19406,-1.45392,-1.37413,-0.31597,1.94790,0.00350 -4.11527,1.19403,-1.45407,-1.37353,-0.31642,1.94794,0.00350 -4.11780,1.19399,-1.45422,-1.37294,-0.31685,1.94798,0.00349 -4.12032,1.19396,-1.45438,-1.37235,-0.31730,1.94802,0.00349 -4.12285,1.19395,-1.45453,-1.37168,-0.31781,1.94804,0.00349 -4.12538,1.19394,-1.45469,-1.37102,-0.31831,1.94805,0.00349 -4.12791,1.19392,-1.45484,-1.37038,-0.31881,1.94807,0.00349 -4.13043,1.19391,-1.45499,-1.36974,-0.31929,1.94809,0.00349 -4.13296,1.19390,-1.45514,-1.36911,-0.31977,1.94810,0.00348 -4.13549,1.19389,-1.45528,-1.36850,-0.32024,1.94812,0.00348 -4.13802,1.19388,-1.45543,-1.36789,-0.32071,1.94814,0.00348 -4.14055,1.19386,-1.45557,-1.36729,-0.32116,1.94816,0.00348 -4.14307,1.19385,-1.45572,-1.36670,-0.32161,1.94817,0.00348 -4.14560,1.19384,-1.45586,-1.36612,-0.32205,1.94819,0.00347 -4.14813,1.19386,-1.45591,-1.36585,-0.32227,1.94817,0.00347 -4.15066,1.19412,-1.45589,-1.36541,-0.32274,1.94792,0.00347 -4.15319,1.19437,-1.45586,-1.36498,-0.32319,1.94768,0.00347 -4.15571,1.19462,-1.45584,-1.36456,-0.32364,1.94744,0.00347 -4.15824,1.19486,-1.45582,-1.36414,-0.32408,1.94721,0.00347 -4.16077,1.19510,-1.45580,-1.36373,-0.32451,1.94697,0.00347 -4.16330,1.19534,-1.45579,-1.36332,-0.32494,1.94675,0.00347 -4.16582,1.19543,-1.45577,-1.36321,-0.32506,1.94667,0.00347 -4.16835,1.19580,-1.45567,-1.36288,-0.32550,1.94630,0.00347 -4.17088,1.19617,-1.45557,-1.36256,-0.32592,1.94594,0.00346 -4.17341,1.19653,-1.45547,-1.36224,-0.32634,1.94559,0.00346 -4.17594,1.19689,-1.45537,-1.36193,-0.32675,1.94524,0.00346 -4.17846,1.19724,-1.45528,-1.36162,-0.32716,1.94490,0.00346 -4.18099,1.19759,-1.45519,-1.36132,-0.32756,1.94456,0.00346 -4.18352,1.19793,-1.45510,-1.36102,-0.32795,1.94423,0.00346 -4.18605,1.19827,-1.45501,-1.36073,-0.32833,1.94390,0.00346 -4.18857,1.19859,-1.45492,-1.36044,-0.32871,1.94358,0.00346 -4.19110,1.19864,-1.45490,-1.36042,-0.32875,1.94354,0.00346 -4.19363,1.19911,-1.45473,-1.36023,-0.32912,1.94308,0.00346 -4.19616,1.19957,-1.45456,-1.36004,-0.32948,1.94263,0.00346 -4.19869,1.20002,-1.45439,-1.35985,-0.32984,1.94219,0.00346 -4.20121,1.20047,-1.45423,-1.35967,-0.33019,1.94175,0.00346 -4.20374,1.20091,-1.45407,-1.35949,-0.33054,1.94132,0.00346 -4.20627,1.20134,-1.45391,-1.35931,-0.33088,1.94090,0.00346 -4.20880,1.20176,-1.45375,-1.35913,-0.33121,1.94048,0.00346 -4.21132,1.20218,-1.45360,-1.35896,-0.33154,1.94007,0.00346 -4.21385,1.20259,-1.45345,-1.35879,-0.33186,1.93967,0.00345 -4.21638,1.20300,-1.45331,-1.35862,-0.33218,1.93928,0.00345 -4.21891,1.20326,-1.45321,-1.35853,-0.33237,1.93902,0.00345 -4.22144,1.20384,-1.45296,-1.35846,-0.33270,1.93845,0.00345 -4.22396,1.20441,-1.45271,-1.35838,-0.33303,1.93789,0.00345 -4.22649,1.20497,-1.45247,-1.35831,-0.33335,1.93734,0.00345 -4.22902,1.20553,-1.45223,-1.35824,-0.33366,1.93679,0.00345 -4.23155,1.20607,-1.45200,-1.35817,-0.33397,1.93626,0.00345 -4.23407,1.20661,-1.45177,-1.35810,-0.33428,1.93573,0.00345 -4.23660,1.20714,-1.45154,-1.35803,-0.33457,1.93521,0.00345 -4.23913,1.20766,-1.45132,-1.35796,-0.33487,1.93470,0.00345 -4.24166,1.20817,-1.45110,-1.35789,-0.33515,1.93420,0.00345 -4.24419,1.20867,-1.45089,-1.35783,-0.33544,1.93370,0.00345 -4.24671,1.20917,-1.45068,-1.35777,-0.33571,1.93322,0.00345 -4.24924,1.20966,-1.45048,-1.35770,-0.33599,1.93274,0.00345 -4.25177,1.21013,-1.45027,-1.35764,-0.33625,1.93226,0.00345 -4.25430,1.21061,-1.45007,-1.35758,-0.33652,1.93180,0.00345 -4.25683,1.21107,-1.44988,-1.35752,-0.33678,1.93134,0.00345 -4.25935,1.21153,-1.44969,-1.35746,-0.33703,1.93089,0.00345 -4.26188,1.21198,-1.44950,-1.35741,-0.33728,1.93045,0.00345 -4.26441,1.21208,-1.44946,-1.35740,-0.33733,1.93035,0.00345 -4.26694,1.21267,-1.44919,-1.35741,-0.33759,1.92977,0.00345 -4.26946,1.21325,-1.44892,-1.35742,-0.33785,1.92920,0.00345 -4.27199,1.21382,-1.44866,-1.35743,-0.33810,1.92863,0.00345 -4.27452,1.21438,-1.44841,-1.35744,-0.33835,1.92808,0.00345 -4.27705,1.21493,-1.44816,-1.35745,-0.33860,1.92754,0.00345 -4.27958,1.21547,-1.44792,-1.35746,-0.33884,1.92700,0.00345 -4.28210,1.21601,-1.44767,-1.35747,-0.33907,1.92647,0.00345 -4.28463,1.21653,-1.44744,-1.35748,-0.33930,1.92595,0.00345 -4.28716,1.21705,-1.44720,-1.35749,-0.33953,1.92544,0.00345 -4.28969,1.21756,-1.44698,-1.35750,-0.33975,1.92494,0.00345 -4.29221,1.21806,-1.44675,-1.35751,-0.33997,1.92445,0.00345 -4.29474,1.21855,-1.44653,-1.35752,-0.34019,1.92396,0.00345 -4.29727,1.21904,-1.44631,-1.35753,-0.34040,1.92348,0.00345 -4.29980,1.21952,-1.44610,-1.35754,-0.34061,1.92301,0.00345 -4.30233,1.21996,-1.44590,-1.35756,-0.34079,1.92257,0.00345 -4.30485,1.22057,-1.44561,-1.35763,-0.34101,1.92197,0.00345 -4.30738,1.22117,-1.44533,-1.35771,-0.34123,1.92137,0.00345 -4.30991,1.22176,-1.44505,-1.35778,-0.34144,1.92079,0.00345 -4.31244,1.22235,-1.44477,-1.35785,-0.34165,1.92021,0.00345 -4.31496,1.22292,-1.44450,-1.35792,-0.34185,1.91964,0.00345 -4.31749,1.22348,-1.44424,-1.35799,-0.34205,1.91908,0.00346 -4.32002,1.22404,-1.44398,-1.35806,-0.34225,1.91853,0.00346 -4.32255,1.22459,-1.44372,-1.35813,-0.34244,1.91799,0.00346 -4.32508,1.22513,-1.44347,-1.35820,-0.34263,1.91746,0.00346 -4.32760,1.22566,-1.44322,-1.35826,-0.34281,1.91693,0.00346 -4.33013,1.22618,-1.44298,-1.35833,-0.34300,1.91642,0.00346 -4.33266,1.22669,-1.44274,-1.35839,-0.34318,1.91591,0.00346 -4.33519,1.22720,-1.44250,-1.35846,-0.34335,1.91541,0.00346 -4.33771,1.22769,-1.44227,-1.35852,-0.34352,1.91491,0.00346 -4.34024,1.22818,-1.44205,-1.35858,-0.34369,1.91443,0.00346 -4.34277,1.22849,-1.44190,-1.35863,-0.34379,1.91413,0.00346 -4.34530,1.22909,-1.44160,-1.35878,-0.34394,1.91353,0.00346 -4.34783,1.22968,-1.44131,-1.35894,-0.34408,1.91294,0.00346 -4.35035,1.23027,-1.44102,-1.35909,-0.34422,1.91236,0.00346 -4.35288,1.23085,-1.44073,-1.35925,-0.34436,1.91179,0.00346 -4.35541,1.23141,-1.44045,-1.35939,-0.34450,1.91123,0.00346 -4.35794,1.23197,-1.44018,-1.35954,-0.34463,1.91067,0.00346 -4.36047,1.23252,-1.43990,-1.35969,-0.34476,1.91013,0.00346 -4.36299,1.23306,-1.43964,-1.35983,-0.34489,1.90959,0.00346 -4.36552,1.23359,-1.43938,-1.35997,-0.34502,1.90906,0.00346 -4.36805,1.23412,-1.43912,-1.36011,-0.34514,1.90854,0.00346 -4.37058,1.23463,-1.43887,-1.36024,-0.34526,1.90803,0.00346 -4.37310,1.23514,-1.43862,-1.36038,-0.34538,1.90752,0.00346 -4.37563,1.23564,-1.43837,-1.36051,-0.34550,1.90703,0.00347 -4.37816,1.23585,-1.43827,-1.36057,-0.34555,1.90682,0.00347 -4.38069,1.23647,-1.43795,-1.36080,-0.34564,1.90621,0.00347 -4.38322,1.23707,-1.43763,-1.36102,-0.34574,1.90560,0.00347 -4.38574,1.23767,-1.43733,-1.36124,-0.34583,1.90501,0.00347 -4.38827,1.23826,-1.43702,-1.36146,-0.34592,1.90443,0.00347 -4.39080,1.23884,-1.43673,-1.36167,-0.34601,1.90385,0.00347 -4.39333,1.23941,-1.43643,-1.36188,-0.34610,1.90329,0.00347 -4.39585,1.23997,-1.43615,-1.36209,-0.34618,1.90273,0.00347 -4.39838,1.24052,-1.43586,-1.36229,-0.34627,1.90218,0.00347 -4.40091,1.24106,-1.43559,-1.36249,-0.34635,1.90164,0.00347 -4.40344,1.24160,-1.43531,-1.36269,-0.34643,1.90111,0.00347 -4.40597,1.24212,-1.43504,-1.36289,-0.34651,1.90058,0.00347 -4.40849,1.24264,-1.43478,-1.36308,-0.34658,1.90007,0.00347 -4.41102,1.24315,-1.43452,-1.36327,-0.34666,1.89956,0.00348 -4.41355,1.24366,-1.43426,-1.36345,-0.34673,1.89906,0.00348 -4.41608,1.24376,-1.43421,-1.36350,-0.34675,1.89895,0.00348 -4.41860,1.24434,-1.43390,-1.36373,-0.34681,1.89838,0.00348 -4.42113,1.24491,-1.43361,-1.36397,-0.34688,1.89781,0.00348 -4.42366,1.24547,-1.43332,-1.36420,-0.34694,1.89725,0.00348 -4.42619,1.24602,-1.43303,-1.36443,-0.34701,1.89670,0.00348 -4.42872,1.24657,-1.43275,-1.36466,-0.34707,1.89616,0.00348 -4.43124,1.24710,-1.43247,-1.36488,-0.34713,1.89563,0.00348 -4.43377,1.24763,-1.43220,-1.36510,-0.34719,1.89510,0.00348 -4.43630,1.24815,-1.43193,-1.36531,-0.34724,1.89459,0.00348 -4.43883,1.24866,-1.43166,-1.36553,-0.34730,1.89408,0.00348 -4.44135,1.24916,-1.43140,-1.36573,-0.34736,1.89358,0.00349 -4.44388,1.24922,-1.43137,-1.36576,-0.34736,1.89352,0.00349 -4.44641,1.24977,-1.43107,-1.36604,-0.34739,1.89296,0.00349 -4.44894,1.25032,-1.43078,-1.36631,-0.34741,1.89242,0.00349 -4.45147,1.25086,-1.43049,-1.36657,-0.34744,1.89188,0.00349 -4.45399,1.25140,-1.43021,-1.36684,-0.34747,1.89135,0.00349 -4.45652,1.25192,-1.42993,-1.36709,-0.34749,1.89083,0.00349 -4.45905,1.25244,-1.42965,-1.36735,-0.34752,1.89031,0.00349 -4.46158,1.25294,-1.42938,-1.36760,-0.34754,1.88981,0.00349 -4.46411,1.25346,-1.42911,-1.36786,-0.34756,1.88929,0.00349 -4.46663,1.25408,-1.42876,-1.36826,-0.34751,1.88868,0.00350 -4.46916,1.25469,-1.42841,-1.36866,-0.34747,1.88807,0.00350 -4.47169,1.25529,-1.42807,-1.36905,-0.34742,1.88747,0.00350 -4.47422,1.25588,-1.42773,-1.36944,-0.34738,1.88688,0.00350 -4.47674,1.25646,-1.42740,-1.36981,-0.34734,1.88630,0.00350 -4.47927,1.25703,-1.42708,-1.37019,-0.34729,1.88573,0.00350 -4.48180,1.25760,-1.42676,-1.37055,-0.34725,1.88516,0.00350 -4.48433,1.25815,-1.42644,-1.37091,-0.34721,1.88461,0.00350 -4.48686,1.25870,-1.42613,-1.37127,-0.34717,1.88406,0.00351 -4.48938,1.25924,-1.42583,-1.37162,-0.34713,1.88352,0.00351 -4.49191,1.25977,-1.42553,-1.37196,-0.34709,1.88299,0.00351 -4.49444,1.26029,-1.42524,-1.37230,-0.34705,1.88247,0.00351 -4.49697,1.26081,-1.42495,-1.37264,-0.34701,1.88196,0.00351 -4.49949,1.26131,-1.42466,-1.37297,-0.34697,1.88145,0.00351 -4.50202,1.26181,-1.42438,-1.37329,-0.34693,1.88095,0.00351 -4.50455,1.26230,-1.42410,-1.37361,-0.34689,1.88046,0.00351 -4.50708,1.26246,-1.42401,-1.37372,-0.34688,1.88031,0.00351 -4.50961,1.26307,-1.42365,-1.37419,-0.34677,1.87970,0.00352 -4.51213,1.26367,-1.42330,-1.37465,-0.34667,1.87910,0.00352 -4.51466,1.26426,-1.42295,-1.37511,-0.34656,1.87851,0.00352 -4.51719,1.26484,-1.42260,-1.37556,-0.34646,1.87793,0.00352 -4.51972,1.26542,-1.42227,-1.37600,-0.34636,1.87735,0.00352 -4.52224,1.26598,-1.42193,-1.37644,-0.34627,1.87679,0.00352 -4.52477,1.26654,-1.42161,-1.37686,-0.34617,1.87624,0.00353 -4.52730,1.26709,-1.42128,-1.37729,-0.34607,1.87569,0.00353 -4.52983,1.26762,-1.42097,-1.37770,-0.34598,1.87515,0.00353 -4.53236,1.26815,-1.42066,-1.37811,-0.34589,1.87462,0.00353 -4.53488,1.26868,-1.42035,-1.37851,-0.34580,1.87410,0.00353 -4.53741,1.26919,-1.42005,-1.37891,-0.34571,1.87358,0.00353 -4.53994,1.26970,-1.41975,-1.37930,-0.34562,1.87308,0.00353 -4.54247,1.27019,-1.41946,-1.37968,-0.34553,1.87258,0.00354 -4.54499,1.27069,-1.41917,-1.38006,-0.34545,1.87209,0.00354 -4.54752,1.27117,-1.41889,-1.38043,-0.34536,1.87160,0.00354 -4.55005,1.27164,-1.41861,-1.38079,-0.34528,1.87113,0.00354 -4.55258,1.27175,-1.41854,-1.38089,-0.34525,1.87102,0.00354 -4.55511,1.27237,-1.41815,-1.38148,-0.34505,1.87040,0.00354 -4.55763,1.27298,-1.41777,-1.38206,-0.34486,1.86979,0.00354 -4.56016,1.27358,-1.41740,-1.38263,-0.34467,1.86919,0.00355 -4.56269,1.27417,-1.41703,-1.38320,-0.34448,1.86860,0.00355 -4.56522,1.27475,-1.41667,-1.38375,-0.34430,1.86802,0.00355 -4.56775,1.27532,-1.41631,-1.38429,-0.34411,1.86745,0.00355 -4.57027,1.27588,-1.41596,-1.38483,-0.34393,1.86689,0.00355 -4.57280,1.27644,-1.41561,-1.38536,-0.34376,1.86633,0.00356 -4.57533,1.27698,-1.41527,-1.38588,-0.34358,1.86579,0.00356 -4.57786,1.27752,-1.41494,-1.38639,-0.34341,1.86525,0.00356 -4.58038,1.27805,-1.41461,-1.38689,-0.34324,1.86472,0.00356 -4.58291,1.27857,-1.41428,-1.38738,-0.34308,1.86420,0.00356 -4.58544,1.27908,-1.41396,-1.38787,-0.34292,1.86368,0.00356 -4.58797,1.27959,-1.41365,-1.38835,-0.34276,1.86318,0.00357 -4.59050,1.28009,-1.41334,-1.38882,-0.34260,1.86268,0.00357 -4.59302,1.28058,-1.41303,-1.38929,-0.34244,1.86219,0.00357 -4.59555,1.28106,-1.41273,-1.38974,-0.34229,1.86170,0.00357 -4.59808,1.28153,-1.41244,-1.39019,-0.34214,1.86122,0.00357 -4.60061,1.28200,-1.41215,-1.39064,-0.34199,1.86075,0.00357 -4.60313,1.28246,-1.41186,-1.39107,-0.34184,1.86029,0.00358 -4.60566,1.28292,-1.41158,-1.39150,-0.34170,1.85984,0.00358 -4.60819,1.28332,-1.41132,-1.39189,-0.34156,1.85943,0.00358 -4.61072,1.28380,-1.41101,-1.39243,-0.34135,1.85894,0.00358 -4.61325,1.28428,-1.41070,-1.39296,-0.34113,1.85847,0.00358 -4.61577,1.28475,-1.41039,-1.39349,-0.34092,1.85800,0.00358 -4.61830,1.28521,-1.41009,-1.39400,-0.34071,1.85753,0.00359 -4.62083,1.28566,-1.40979,-1.39451,-0.34051,1.85708,0.00359 -4.62336,1.28611,-1.40950,-1.39500,-0.34031,1.85663,0.00359 -4.62588,1.28655,-1.40921,-1.39549,-0.34011,1.85619,0.00359 -4.62841,1.28698,-1.40892,-1.39598,-0.33991,1.85575,0.00359 -4.63094,1.28741,-1.40864,-1.39645,-0.33972,1.85532,0.00360 -4.63347,1.28783,-1.40837,-1.39692,-0.33953,1.85490,0.00360 -4.63600,1.28800,-1.40826,-1.39711,-0.33945,1.85473,0.00360 -4.63852,1.28845,-1.40795,-1.39767,-0.33921,1.85427,0.00360 -4.64105,1.28890,-1.40764,-1.39822,-0.33896,1.85382,0.00360 -4.64358,1.28934,-1.40735,-1.39876,-0.33873,1.85338,0.00360 -4.64611,1.28977,-1.40705,-1.39929,-0.33849,1.85294,0.00360 -4.64863,1.29020,-1.40676,-1.39982,-0.33826,1.85252,0.00361 -4.65116,1.29062,-1.40648,-1.40033,-0.33804,1.85209,0.00361 -4.65369,1.29103,-1.40620,-1.40084,-0.33781,1.85168,0.00361 -4.65622,1.29144,-1.40592,-1.40134,-0.33759,1.85127,0.00361 -4.65875,1.29184,-1.40565,-1.40183,-0.33738,1.85086,0.00361 -4.66127,1.29212,-1.40546,-1.40218,-0.33722,1.85058,0.00361 -4.66380,1.29253,-1.40516,-1.40275,-0.33695,1.85017,0.00362 -4.66633,1.29293,-1.40488,-1.40331,-0.33668,1.84976,0.00362 -4.66886,1.29333,-1.40459,-1.40387,-0.33641,1.84936,0.00362 -4.67139,1.29372,-1.40431,-1.40441,-0.33615,1.84896,0.00362 -4.67391,1.29411,-1.40404,-1.40495,-0.33589,1.84857,0.00362 -4.67644,1.29449,-1.40377,-1.40547,-0.33564,1.84818,0.00363 -4.67897,1.29487,-1.40350,-1.40599,-0.33539,1.84781,0.00363 -4.68150,1.29524,-1.40323,-1.40651,-0.33514,1.84743,0.00363 -4.68402,1.29562,-1.40295,-1.40708,-0.33485,1.84704,0.00363 -4.68655,1.29600,-1.40267,-1.40765,-0.33457,1.84666,0.00363 -4.68908,1.29637,-1.40240,-1.40820,-0.33429,1.84628,0.00363 -4.69161,1.29674,-1.40213,-1.40875,-0.33402,1.84591,0.00364 -4.69414,1.29710,-1.40187,-1.40929,-0.33375,1.84555,0.00364 -4.69666,1.29746,-1.40160,-1.40982,-0.33348,1.84519,0.00364 -4.69919,1.29774,-1.40139,-1.41026,-0.33326,1.84490,0.00364 -4.70172,1.29811,-1.40109,-1.41099,-0.33283,1.84453,0.00364 -4.70425,1.29846,-1.40078,-1.41172,-0.33242,1.84417,0.00364 -4.70677,1.29882,-1.40049,-1.41243,-0.33201,1.84381,0.00365 -4.70930,1.29916,-1.40019,-1.41313,-0.33161,1.84346,0.00365 -4.71183,1.29951,-1.39990,-1.41382,-0.33121,1.84311,0.00365 -4.71436,1.29984,-1.39962,-1.41449,-0.33082,1.84277,0.00365 -4.71689,1.30018,-1.39934,-1.41516,-0.33044,1.84243,0.00365 -4.71941,1.30050,-1.39906,-1.41582,-0.33007,1.84210,0.00365 -4.72194,1.30083,-1.39879,-1.41646,-0.32970,1.84177,0.00366 -4.72447,1.30114,-1.39853,-1.41710,-0.32933,1.84145,0.00366 -4.72700,1.30146,-1.39826,-1.41772,-0.32897,1.84113,0.00366 -4.72952,1.30176,-1.39800,-1.41833,-0.32862,1.84082,0.00366 -4.73205,1.30207,-1.39775,-1.41894,-0.32828,1.84051,0.00366 -4.73458,1.30237,-1.39750,-1.41953,-0.32794,1.84021,0.00367 -4.73711,1.30266,-1.39725,-1.42012,-0.32760,1.83991,0.00367 -4.73964,1.30295,-1.39701,-1.42069,-0.32727,1.83961,0.00367 -4.74216,1.30324,-1.39677,-1.42126,-0.32695,1.83932,0.00367 -4.74469,1.30352,-1.39653,-1.42183,-0.32662,1.83904,0.00367 -4.74722,1.30379,-1.39626,-1.42255,-0.32617,1.83876,0.00367 -4.74975,1.30406,-1.39600,-1.42326,-0.32573,1.83848,0.00368 -4.75228,1.30432,-1.39574,-1.42395,-0.32530,1.83821,0.00368 -4.75480,1.30459,-1.39549,-1.42463,-0.32487,1.83795,0.00368 -4.75733,1.30484,-1.39524,-1.42530,-0.32445,1.83768,0.00368 -4.75986,1.30510,-1.39499,-1.42596,-0.32404,1.83743,0.00368 -4.76239,1.30534,-1.39475,-1.42661,-0.32364,1.83717,0.00368 -4.76491,1.30559,-1.39451,-1.42725,-0.32324,1.83692,0.00369 -4.76744,1.30583,-1.39428,-1.42788,-0.32285,1.83667,0.00369 -4.76997,1.30607,-1.39405,-1.42850,-0.32247,1.83643,0.00369 -4.77250,1.30631,-1.39382,-1.42911,-0.32209,1.83619,0.00369 -4.77503,1.30654,-1.39359,-1.42971,-0.32172,1.83595,0.00369 -4.77755,1.30677,-1.39337,-1.43030,-0.32135,1.83572,0.00369 -4.78008,1.30699,-1.39316,-1.43088,-0.32099,1.83548,0.00370 -4.78261,1.30715,-1.39300,-1.43130,-0.32073,1.83532,0.00370 -4.78514,1.30739,-1.39274,-1.43206,-0.32023,1.83508,0.00370 -4.78766,1.30762,-1.39249,-1.43281,-0.31974,1.83484,0.00370 -4.79019,1.30785,-1.39223,-1.43354,-0.31926,1.83460,0.00370 -4.79272,1.30808,-1.39199,-1.43427,-0.31879,1.83437,0.00370 -4.79525,1.30830,-1.39174,-1.43498,-0.31832,1.83414,0.00371 -4.79778,1.30852,-1.39150,-1.43568,-0.31787,1.83392,0.00371 -4.80030,1.30874,-1.39127,-1.43637,-0.31742,1.83369,0.00371 -4.80283,1.30895,-1.39103,-1.43705,-0.31697,1.83347,0.00371 -4.80536,1.30916,-1.39080,-1.43771,-0.31654,1.83326,0.00371 -4.80789,1.30937,-1.39058,-1.43837,-0.31611,1.83304,0.00371 -4.81041,1.30957,-1.39036,-1.43901,-0.31569,1.83283,0.00372 -4.81294,1.30978,-1.39014,-1.43965,-0.31528,1.83262,0.00372 -4.81547,1.30998,-1.38992,-1.44027,-0.31487,1.83242,0.00372 -4.81800,1.31017,-1.38971,-1.44089,-0.31447,1.83222,0.00372 -4.82053,1.31036,-1.38950,-1.44149,-0.31408,1.83202,0.00372 -4.82305,1.31055,-1.38929,-1.44208,-0.31369,1.83182,0.00372 -4.82558,1.31074,-1.38909,-1.44267,-0.31331,1.83163,0.00373 -4.82811,1.31091,-1.38890,-1.44321,-0.31296,1.83146,0.00373 -4.83064,1.31108,-1.38867,-1.44398,-0.31243,1.83128,0.00373 -4.83316,1.31126,-1.38844,-1.44475,-0.31190,1.83110,0.00373 -4.83569,1.31143,-1.38821,-1.44550,-0.31138,1.83092,0.00373 -4.83822,1.31160,-1.38798,-1.44623,-0.31087,1.83074,0.00373 -4.84075,1.31177,-1.38776,-1.44696,-0.31037,1.83057,0.00374 -4.84328,1.31193,-1.38754,-1.44767,-0.30988,1.83040,0.00374 -4.84580,1.31210,-1.38732,-1.44838,-0.30940,1.83023,0.00374 -4.84833,1.31226,-1.38711,-1.44907,-0.30892,1.83006,0.00374 -4.85086,1.31241,-1.38690,-1.44975,-0.30845,1.82990,0.00374 -4.85339,1.31257,-1.38669,-1.45041,-0.30799,1.82973,0.00374 -4.85592,1.31272,-1.38649,-1.45107,-0.30754,1.82957,0.00375 -4.85844,1.31287,-1.38629,-1.45172,-0.30710,1.82942,0.00375 -4.86097,1.31302,-1.38609,-1.45235,-0.30666,1.82926,0.00375 -4.86350,1.31317,-1.38590,-1.45298,-0.30623,1.82911,0.00375 -4.86603,1.31332,-1.38571,-1.45359,-0.30581,1.82896,0.00375 -4.86855,1.31346,-1.38552,-1.45420,-0.30539,1.82881,0.00375 -4.87108,1.31360,-1.38533,-1.45479,-0.30498,1.82866,0.00376 -4.87361,1.31374,-1.38515,-1.45538,-0.30458,1.82852,0.00376 -4.87614,1.31388,-1.38497,-1.45596,-0.30418,1.82837,0.00376 -4.87867,1.31403,-1.38477,-1.45662,-0.30373,1.82821,0.00376 -4.88119,1.31419,-1.38457,-1.45726,-0.30328,1.82805,0.00376 -4.88372,1.31434,-1.38437,-1.45790,-0.30285,1.82790,0.00376 -4.88625,1.31449,-1.38417,-1.45853,-0.30242,1.82774,0.00377 -4.88878,1.31463,-1.38398,-1.45914,-0.30200,1.82759,0.00377 -4.89130,1.31478,-1.38379,-1.45975,-0.30158,1.82744,0.00377 -4.89383,1.31492,-1.38361,-1.46034,-0.30117,1.82729,0.00377 -4.89636,1.31506,-1.38343,-1.46093,-0.30077,1.82714,0.00377 -4.89889,1.31520,-1.38325,-1.46150,-0.30038,1.82700,0.00377 -4.90142,1.31522,-1.38323,-1.46157,-0.30033,1.82698,0.00378 -4.90394,1.31538,-1.38302,-1.46222,-0.29988,1.82682,0.00378 -4.90647,1.31553,-1.38282,-1.46287,-0.29943,1.82666,0.00378 -4.90900,1.31568,-1.38263,-1.46350,-0.29900,1.82650,0.00378 -4.91153,1.31583,-1.38243,-1.46413,-0.29857,1.82634,0.00378 -4.91405,1.31598,-1.38224,-1.46474,-0.29815,1.82619,0.00378 -4.91658,1.31613,-1.38205,-1.46534,-0.29773,1.82604,0.00379 -4.91911,1.31628,-1.38187,-1.46594,-0.29732,1.82589,0.00379 -4.92164,1.31642,-1.38169,-1.46652,-0.29692,1.82574,0.00379 -4.92417,1.31656,-1.38151,-1.46710,-0.29653,1.82560,0.00379 -4.92669,1.31657,-1.38149,-1.46716,-0.29648,1.82558,0.00379 -4.92922,1.31673,-1.38128,-1.46782,-0.29603,1.82542,0.00379 -4.93175,1.31689,-1.38108,-1.46846,-0.29559,1.82525,0.00379 -4.93428,1.31704,-1.38089,-1.46910,-0.29515,1.82509,0.00380 -4.93680,1.31720,-1.38069,-1.46972,-0.29472,1.82494,0.00380 -4.93933,1.31735,-1.38050,-1.47033,-0.29430,1.82478,0.00380 -4.94186,1.31750,-1.38032,-1.47093,-0.29389,1.82463,0.00380 -4.94439,1.31764,-1.38013,-1.47153,-0.29348,1.82448,0.00380 -4.94692,1.31779,-1.37995,-1.47211,-0.29308,1.82433,0.00381 -4.94944,1.31793,-1.37977,-1.47268,-0.29269,1.82418,0.00381 -4.95197,1.31796,-1.37973,-1.47280,-0.29261,1.82415,0.00381 -4.95450,1.31814,-1.37952,-1.47344,-0.29218,1.82396,0.00381 -4.95703,1.31833,-1.37932,-1.47407,-0.29175,1.82377,0.00381 -4.95956,1.31850,-1.37911,-1.47469,-0.29134,1.82359,0.00381 -4.96208,1.31868,-1.37891,-1.47530,-0.29093,1.82341,0.00382 -4.96461,1.31885,-1.37872,-1.47590,-0.29053,1.82323,0.00382 -4.96714,1.31902,-1.37852,-1.47649,-0.29013,1.82306,0.00382 -4.96967,1.31919,-1.37833,-1.47707,-0.28974,1.82289,0.00382 -4.97219,1.31934,-1.37817,-1.47758,-0.28940,1.82273,0.00382 -4.97472,1.31951,-1.37798,-1.47816,-0.28901,1.82257,0.00382 -4.97725,1.31967,-1.37779,-1.47874,-0.28862,1.82240,0.00383 -4.97978,1.31970,-1.37775,-1.47885,-0.28854,1.82237,0.00383 -4.98231,1.31986,-1.37756,-1.47945,-0.28813,1.82221,0.00383 -4.98483,1.32001,-1.37738,-1.48005,-0.28772,1.82205,0.00383 -4.98736,1.32016,-1.37719,-1.48063,-0.28732,1.82189,0.00383 -4.98989,1.32031,-1.37701,-1.48120,-0.28693,1.82173,0.00383 -4.99242,1.32036,-1.37696,-1.48138,-0.28682,1.82168,0.00383 -4.99494,1.32056,-1.37675,-1.48197,-0.28642,1.82149,0.00384 -4.99747,1.32075,-1.37655,-1.48256,-0.28604,1.82129,0.00384 -5.00000,1.32093,-1.37636,-1.48314,-0.28566,1.82110,0.00384 +0.00000,1.32865,-1.25488,-1.44331,-1.11130,1.76804,-0.14802 +0.00199,1.32836,-1.25533,-1.44271,-1.11148,1.76827,-0.14821 +0.00398,1.32806,-1.25578,-1.44212,-1.11165,1.76850,-0.14839 +0.00597,1.32777,-1.25622,-1.44154,-1.11182,1.76872,-0.14857 +0.00796,1.32749,-1.25666,-1.44096,-1.11199,1.76894,-0.14875 +0.00996,1.32721,-1.25708,-1.44040,-1.11216,1.76916,-0.14893 +0.01195,1.32693,-1.25750,-1.43984,-1.11233,1.76937,-0.14910 +0.01394,1.32666,-1.25792,-1.43929,-1.11249,1.76958,-0.14927 +0.01593,1.32639,-1.25832,-1.43875,-1.11265,1.76979,-0.14944 +0.01792,1.32617,-1.25865,-1.43832,-1.11278,1.76996,-0.14958 +0.01991,1.32583,-1.25915,-1.43766,-1.11297,1.77022,-0.14979 +0.02190,1.32550,-1.25964,-1.43702,-1.11317,1.77048,-0.15000 +0.02389,1.32517,-1.26011,-1.43638,-1.11335,1.77073,-0.15021 +0.02589,1.32485,-1.26059,-1.43576,-1.11354,1.77098,-0.15041 +0.02788,1.32453,-1.26105,-1.43515,-1.11372,1.77123,-0.15061 +0.02987,1.32422,-1.26151,-1.43454,-1.11391,1.77147,-0.15081 +0.03186,1.32391,-1.26196,-1.43395,-1.11409,1.77171,-0.15100 +0.03385,1.32361,-1.26240,-1.43336,-1.11426,1.77195,-0.15119 +0.03584,1.32331,-1.26283,-1.43278,-1.11444,1.77218,-0.15138 +0.03783,1.32301,-1.26326,-1.43222,-1.11461,1.77241,-0.15157 +0.03982,1.32272,-1.26368,-1.43166,-1.11478,1.77263,-0.15175 +0.04182,1.32244,-1.26409,-1.43111,-1.11495,1.77285,-0.15193 +0.04381,1.32216,-1.26450,-1.43057,-1.11512,1.77307,-0.15211 +0.04580,1.32188,-1.26490,-1.43003,-1.11528,1.77329,-0.15228 +0.04779,1.32179,-1.26502,-1.42987,-1.11533,1.77335,-0.15234 +0.04978,1.32145,-1.26548,-1.42926,-1.11551,1.77362,-0.15255 +0.05177,1.32112,-1.26594,-1.42866,-1.11569,1.77387,-0.15276 +0.05376,1.32080,-1.26638,-1.42808,-1.11587,1.77413,-0.15297 +0.05575,1.32048,-1.26682,-1.42750,-1.11605,1.77438,-0.15317 +0.05775,1.32016,-1.26725,-1.42693,-1.11622,1.77462,-0.15337 +0.05974,1.31985,-1.26768,-1.42637,-1.11639,1.77486,-0.15357 +0.06173,1.31954,-1.26809,-1.42582,-1.11656,1.77510,-0.15376 +0.06372,1.31924,-1.26850,-1.42528,-1.11673,1.77534,-0.15395 +0.06571,1.31894,-1.26891,-1.42474,-1.11689,1.77557,-0.15414 +0.06770,1.31865,-1.26930,-1.42421,-1.11706,1.77580,-0.15432 +0.06969,1.31852,-1.26947,-1.42400,-1.11712,1.77589,-0.15440 +0.07168,1.31814,-1.26996,-1.42337,-1.11731,1.77619,-0.15465 +0.07368,1.31776,-1.27043,-1.42275,-1.11750,1.77649,-0.15489 +0.07567,1.31738,-1.27091,-1.42214,-1.11768,1.77678,-0.15512 +0.07766,1.31701,-1.27137,-1.42153,-1.11786,1.77707,-0.15536 +0.07965,1.31665,-1.27182,-1.42094,-1.11804,1.77735,-0.15559 +0.08164,1.31630,-1.27227,-1.42036,-1.11822,1.77763,-0.15581 +0.08363,1.31594,-1.27271,-1.41979,-1.11839,1.77790,-0.15603 +0.08562,1.31560,-1.27314,-1.41922,-1.11857,1.77817,-0.15625 +0.08761,1.31526,-1.27357,-1.41867,-1.11874,1.77843,-0.15647 +0.08961,1.31492,-1.27399,-1.41812,-1.11890,1.77869,-0.15668 +0.09160,1.31459,-1.27440,-1.41758,-1.11907,1.77895,-0.15689 +0.09359,1.31427,-1.27481,-1.41705,-1.11923,1.77920,-0.15710 +0.09558,1.31395,-1.27521,-1.41653,-1.11940,1.77945,-0.15730 +0.09757,1.31364,-1.27560,-1.41601,-1.11956,1.77970,-0.15750 +0.09956,1.31350,-1.27576,-1.41580,-1.11962,1.77980,-0.15758 +0.10155,1.31313,-1.27621,-1.41521,-1.11980,1.78009,-0.15782 +0.10354,1.31277,-1.27666,-1.41464,-1.11998,1.78038,-0.15805 +0.10554,1.31241,-1.27710,-1.41407,-1.12015,1.78066,-0.15828 +0.10753,1.31205,-1.27753,-1.41351,-1.12033,1.78093,-0.15850 +0.10952,1.31170,-1.27795,-1.41295,-1.12050,1.78121,-0.15873 +0.11151,1.31136,-1.27837,-1.41241,-1.12066,1.78147,-0.15895 +0.11350,1.31102,-1.27878,-1.41188,-1.12083,1.78174,-0.15916 +0.11549,1.31069,-1.27919,-1.41135,-1.12099,1.78200,-0.15937 +0.11748,1.31036,-1.27958,-1.41083,-1.12116,1.78225,-0.15958 +0.11947,1.31004,-1.27997,-1.41032,-1.12132,1.78251,-0.15979 +0.12147,1.30985,-1.28019,-1.41004,-1.12140,1.78265,-0.15990 +0.12346,1.30931,-1.28080,-1.40928,-1.12163,1.78307,-0.16025 +0.12545,1.30877,-1.28139,-1.40853,-1.12184,1.78349,-0.16059 +0.12744,1.30824,-1.28198,-1.40779,-1.12206,1.78390,-0.16092 +0.12943,1.30772,-1.28256,-1.40706,-1.12228,1.78430,-0.16125 +0.13142,1.30721,-1.28313,-1.40634,-1.12249,1.78470,-0.16158 +0.13341,1.30671,-1.28369,-1.40563,-1.12270,1.78509,-0.16190 +0.13540,1.30621,-1.28424,-1.40494,-1.12291,1.78548,-0.16221 +0.13740,1.30573,-1.28478,-1.40425,-1.12311,1.78586,-0.16252 +0.13939,1.30525,-1.28531,-1.40358,-1.12331,1.78623,-0.16282 +0.14138,1.30477,-1.28584,-1.40291,-1.12351,1.78660,-0.16312 +0.14337,1.30431,-1.28635,-1.40226,-1.12371,1.78696,-0.16342 +0.14536,1.30385,-1.28686,-1.40161,-1.12391,1.78731,-0.16371 +0.14735,1.30340,-1.28736,-1.40098,-1.12410,1.78766,-0.16400 +0.14934,1.30296,-1.28785,-1.40035,-1.12429,1.78801,-0.16428 +0.15133,1.30253,-1.28833,-1.39974,-1.12448,1.78835,-0.16456 +0.15333,1.30210,-1.28881,-1.39913,-1.12467,1.78868,-0.16483 +0.15532,1.30168,-1.28928,-1.39854,-1.12485,1.78901,-0.16510 +0.15731,1.30126,-1.28974,-1.39795,-1.12503,1.78933,-0.16536 +0.15930,1.30086,-1.29019,-1.39737,-1.12521,1.78965,-0.16562 +0.16129,1.30045,-1.29063,-1.39680,-1.12539,1.78997,-0.16588 +0.16328,1.30006,-1.29107,-1.39624,-1.12557,1.79028,-0.16613 +0.16527,1.29967,-1.29150,-1.39569,-1.12574,1.79058,-0.16638 +0.16726,1.29929,-1.29193,-1.39514,-1.12591,1.79088,-0.16662 +0.16926,1.29891,-1.29234,-1.39461,-1.12608,1.79117,-0.16686 +0.17125,1.29854,-1.29275,-1.39408,-1.12625,1.79146,-0.16710 +0.17324,1.29818,-1.29316,-1.39356,-1.12641,1.79175,-0.16733 +0.17523,1.29782,-1.29355,-1.39305,-1.12658,1.79203,-0.16756 +0.17722,1.29746,-1.29394,-1.39254,-1.12674,1.79231,-0.16779 +0.17921,1.29712,-1.29433,-1.39205,-1.12690,1.79258,-0.16801 +0.18120,1.29683,-1.29464,-1.39164,-1.12702,1.79280,-0.16820 +0.18319,1.29636,-1.29513,-1.39103,-1.12721,1.79317,-0.16850 +0.18519,1.29589,-1.29561,-1.39043,-1.12739,1.79353,-0.16879 +0.18718,1.29544,-1.29609,-1.38984,-1.12757,1.79389,-0.16908 +0.18917,1.29499,-1.29655,-1.38925,-1.12775,1.79424,-0.16937 +0.19116,1.29455,-1.29701,-1.38868,-1.12793,1.79458,-0.16965 +0.19315,1.29411,-1.29746,-1.38811,-1.12810,1.79492,-0.16993 +0.19514,1.29369,-1.29790,-1.38755,-1.12827,1.79526,-0.17021 +0.19713,1.29326,-1.29834,-1.38700,-1.12844,1.79558,-0.17047 +0.19912,1.29285,-1.29877,-1.38646,-1.12861,1.79591,-0.17074 +0.20112,1.29244,-1.29919,-1.38593,-1.12878,1.79623,-0.17100 +0.20311,1.29204,-1.29961,-1.38541,-1.12894,1.79654,-0.17126 +0.20510,1.29165,-1.30001,-1.38489,-1.12911,1.79685,-0.17151 +0.20709,1.29126,-1.30042,-1.38438,-1.12927,1.79715,-0.17176 +0.20908,1.29088,-1.30081,-1.38388,-1.12942,1.79745,-0.17200 +0.21107,1.29050,-1.30120,-1.38339,-1.12958,1.79774,-0.17225 +0.21306,1.29013,-1.30158,-1.38290,-1.12974,1.79803,-0.17248 +0.21505,1.28977,-1.30196,-1.38242,-1.12989,1.79832,-0.17272 +0.21705,1.28953,-1.30220,-1.38213,-1.12998,1.79850,-0.17287 +0.21904,1.28899,-1.30269,-1.38153,-1.13015,1.79893,-0.17322 +0.22103,1.28845,-1.30318,-1.38095,-1.13032,1.79935,-0.17356 +0.22302,1.28792,-1.30366,-1.38038,-1.13049,1.79976,-0.17390 +0.22501,1.28740,-1.30414,-1.37981,-1.13065,1.80016,-0.17423 +0.22700,1.28689,-1.30460,-1.37926,-1.13081,1.80056,-0.17456 +0.22899,1.28639,-1.30506,-1.37871,-1.13097,1.80095,-0.17488 +0.23098,1.28589,-1.30551,-1.37817,-1.13113,1.80134,-0.17520 +0.23297,1.28540,-1.30596,-1.37763,-1.13129,1.80172,-0.17551 +0.23497,1.28493,-1.30639,-1.37711,-1.13145,1.80209,-0.17582 +0.23696,1.28445,-1.30682,-1.37659,-1.13160,1.80246,-0.17612 +0.23895,1.28399,-1.30725,-1.37608,-1.13175,1.80282,-0.17642 +0.24094,1.28353,-1.30766,-1.37558,-1.13190,1.80318,-0.17671 +0.24293,1.28309,-1.30807,-1.37509,-1.13205,1.80353,-0.17700 +0.24492,1.28264,-1.30847,-1.37460,-1.13220,1.80387,-0.17728 +0.24691,1.28221,-1.30887,-1.37412,-1.13235,1.80421,-0.17756 +0.24890,1.28178,-1.30926,-1.37365,-1.13249,1.80455,-0.17784 +0.25090,1.28136,-1.30964,-1.37319,-1.13263,1.80488,-0.17811 +0.25289,1.28095,-1.31002,-1.37273,-1.13277,1.80520,-0.17837 +0.25488,1.28054,-1.31039,-1.37228,-1.13291,1.80552,-0.17864 +0.25687,1.28014,-1.31076,-1.37184,-1.13305,1.80583,-0.17889 +0.25886,1.27975,-1.31112,-1.37140,-1.13318,1.80614,-0.17915 +0.26085,1.27969,-1.31116,-1.37135,-1.13320,1.80618,-0.17918 +0.26284,1.27918,-1.31159,-1.37086,-1.13334,1.80658,-0.17951 +0.26483,1.27868,-1.31200,-1.37037,-1.13348,1.80697,-0.17983 +0.26683,1.27819,-1.31242,-1.36990,-1.13361,1.80736,-0.18015 +0.26882,1.27770,-1.31282,-1.36943,-1.13375,1.80774,-0.18046 +0.27081,1.27722,-1.31322,-1.36897,-1.13388,1.80811,-0.18077 +0.27280,1.27675,-1.31361,-1.36851,-1.13402,1.80848,-0.18107 +0.27479,1.27629,-1.31400,-1.36806,-1.13415,1.80884,-0.18137 +0.27678,1.27583,-1.31438,-1.36762,-1.13428,1.80920,-0.18167 +0.27877,1.27538,-1.31475,-1.36718,-1.13441,1.80955,-0.18196 +0.28076,1.27494,-1.31512,-1.36675,-1.13453,1.80989,-0.18224 +0.28276,1.27451,-1.31548,-1.36633,-1.13466,1.81023,-0.18252 +0.28475,1.27408,-1.31584,-1.36591,-1.13478,1.81056,-0.18279 +0.28674,1.27366,-1.31619,-1.36550,-1.13490,1.81089,-0.18307 +0.28873,1.27331,-1.31647,-1.36517,-1.13500,1.81116,-0.18329 +0.29072,1.27276,-1.31690,-1.36471,-1.13513,1.81159,-0.18364 +0.29271,1.27222,-1.31731,-1.36425,-1.13525,1.81201,-0.18399 +0.29470,1.27169,-1.31772,-1.36380,-1.13538,1.81242,-0.18433 +0.29669,1.27117,-1.31812,-1.36335,-1.13550,1.81283,-0.18467 +0.29869,1.27065,-1.31852,-1.36291,-1.13562,1.81323,-0.18500 +0.30068,1.27015,-1.31891,-1.36248,-1.13574,1.81363,-0.18533 +0.30267,1.26965,-1.31929,-1.36205,-1.13586,1.81401,-0.18565 +0.30466,1.26916,-1.31967,-1.36163,-1.13598,1.81440,-0.18596 +0.30665,1.26868,-1.32004,-1.36121,-1.13610,1.81477,-0.18627 +0.30864,1.26821,-1.32040,-1.36081,-1.13621,1.81514,-0.18658 +0.31063,1.26774,-1.32076,-1.36040,-1.13633,1.81550,-0.18688 +0.31262,1.26728,-1.32112,-1.36001,-1.13644,1.81586,-0.18718 +0.31462,1.26683,-1.32146,-1.35962,-1.13655,1.81621,-0.18747 +0.31661,1.26639,-1.32181,-1.35923,-1.13666,1.81656,-0.18775 +0.31860,1.26595,-1.32214,-1.35885,-1.13677,1.81690,-0.18804 +0.32059,1.26568,-1.32235,-1.35862,-1.13684,1.81711,-0.18821 +0.32258,1.26511,-1.32276,-1.35818,-1.13695,1.81755,-0.18858 +0.32457,1.26456,-1.32316,-1.35775,-1.13707,1.81798,-0.18894 +0.32656,1.26401,-1.32356,-1.35733,-1.13718,1.81841,-0.18929 +0.32855,1.26347,-1.32395,-1.35691,-1.13729,1.81883,-0.18964 +0.33055,1.26294,-1.32434,-1.35649,-1.13740,1.81924,-0.18998 +0.33254,1.26242,-1.32472,-1.35609,-1.13751,1.81965,-0.19031 +0.33453,1.26191,-1.32509,-1.35568,-1.13762,1.82004,-0.19065 +0.33652,1.26141,-1.32545,-1.35529,-1.13773,1.82044,-0.19097 +0.33851,1.26091,-1.32582,-1.35490,-1.13784,1.82082,-0.19129 +0.34050,1.26043,-1.32617,-1.35451,-1.13794,1.82120,-0.19161 +0.34249,1.25995,-1.32652,-1.35414,-1.13805,1.82158,-0.19192 +0.34448,1.25948,-1.32686,-1.35376,-1.13815,1.82194,-0.19222 +0.34648,1.25901,-1.32720,-1.35340,-1.13825,1.82230,-0.19252 +0.34847,1.25856,-1.32754,-1.35303,-1.13835,1.82266,-0.19282 +0.35046,1.25811,-1.32786,-1.35268,-1.13845,1.82301,-0.19311 +0.35245,1.25774,-1.32813,-1.35239,-1.13853,1.82330,-0.19335 +0.35444,1.25716,-1.32852,-1.35199,-1.13863,1.82375,-0.19372 +0.35643,1.25659,-1.32890,-1.35161,-1.13873,1.82419,-0.19409 +0.35842,1.25604,-1.32928,-1.35122,-1.13882,1.82462,-0.19445 +0.36041,1.25548,-1.32965,-1.35084,-1.13892,1.82505,-0.19481 +0.36241,1.25494,-1.33001,-1.35047,-1.13901,1.82547,-0.19516 +0.36440,1.25441,-1.33037,-1.35010,-1.13911,1.82589,-0.19551 +0.36639,1.25389,-1.33072,-1.34974,-1.13920,1.82630,-0.19584 +0.36838,1.25337,-1.33107,-1.34939,-1.13929,1.82670,-0.19618 +0.37037,1.25287,-1.33141,-1.34903,-1.13938,1.82709,-0.19651 +0.37236,1.25237,-1.33175,-1.34869,-1.13947,1.82748,-0.19683 +0.37435,1.25188,-1.33208,-1.34835,-1.13956,1.82786,-0.19715 +0.37634,1.25140,-1.33241,-1.34801,-1.13965,1.82824,-0.19746 +0.37834,1.25092,-1.33273,-1.34768,-1.13974,1.82861,-0.19777 +0.38033,1.25046,-1.33305,-1.34735,-1.13983,1.82897,-0.19807 +0.38232,1.25000,-1.33336,-1.34703,-1.13991,1.82933,-0.19837 +0.38431,1.24980,-1.33349,-1.34689,-1.13995,1.82948,-0.19850 +0.38630,1.24923,-1.33385,-1.34654,-1.14003,1.82992,-0.19887 +0.38829,1.24867,-1.33421,-1.34618,-1.14012,1.83036,-0.19924 +0.39028,1.24811,-1.33457,-1.34584,-1.14020,1.83079,-0.19960 +0.39227,1.24757,-1.33492,-1.34549,-1.14028,1.83121,-0.19995 +0.39427,1.24703,-1.33526,-1.34516,-1.14037,1.83163,-0.20030 +0.39626,1.24651,-1.33560,-1.34482,-1.14045,1.83204,-0.20064 +0.39825,1.24599,-1.33593,-1.34449,-1.14053,1.83244,-0.20098 +0.40024,1.24548,-1.33626,-1.34417,-1.14061,1.83284,-0.20131 +0.40223,1.24498,-1.33658,-1.34385,-1.14069,1.83323,-0.20164 +0.40422,1.24448,-1.33690,-1.34354,-1.14077,1.83361,-0.20196 +0.40621,1.24400,-1.33721,-1.34323,-1.14085,1.83399,-0.20227 +0.40820,1.24352,-1.33752,-1.34292,-1.14093,1.83436,-0.20258 +0.41020,1.24305,-1.33782,-1.34262,-1.14100,1.83473,-0.20289 +0.41219,1.24267,-1.33806,-1.34238,-1.14106,1.83503,-0.20314 +0.41418,1.24209,-1.33841,-1.34206,-1.14113,1.83548,-0.20352 +0.41617,1.24151,-1.33875,-1.34175,-1.14120,1.83592,-0.20389 +0.41816,1.24095,-1.33908,-1.34145,-1.14127,1.83636,-0.20426 +0.42015,1.24040,-1.33941,-1.34115,-1.14133,1.83679,-0.20462 +0.42214,1.23985,-1.33973,-1.34085,-1.14140,1.83722,-0.20498 +0.42413,1.23931,-1.34005,-1.34055,-1.14146,1.83763,-0.20533 +0.42613,1.23879,-1.34037,-1.34027,-1.14153,1.83804,-0.20567 +0.42812,1.23827,-1.34068,-1.33998,-1.14159,1.83845,-0.20601 +0.43011,1.23776,-1.34098,-1.33970,-1.14166,1.83884,-0.20634 +0.43210,1.23726,-1.34128,-1.33942,-1.14172,1.83923,-0.20667 +0.43409,1.23676,-1.34157,-1.33915,-1.14179,1.83962,-0.20699 +0.43608,1.23628,-1.34186,-1.33888,-1.14185,1.84000,-0.20731 +0.43807,1.23580,-1.34215,-1.33861,-1.14191,1.84037,-0.20762 +0.44006,1.23555,-1.34229,-1.33848,-1.14194,1.84056,-0.20778 +0.44205,1.23500,-1.34260,-1.33821,-1.14200,1.84099,-0.20815 +0.44405,1.23445,-1.34291,-1.33794,-1.14205,1.84142,-0.20850 +0.44604,1.23391,-1.34321,-1.33768,-1.14210,1.84184,-0.20886 +0.44803,1.23338,-1.34351,-1.33742,-1.14216,1.84225,-0.20920 +0.45002,1.23286,-1.34380,-1.33717,-1.14221,1.84265,-0.20954 +0.45201,1.23234,-1.34409,-1.33692,-1.14226,1.84305,-0.20988 +0.45400,1.23184,-1.34437,-1.33667,-1.14231,1.84344,-0.21021 +0.45599,1.23134,-1.34465,-1.33642,-1.14237,1.84383,-0.21054 +0.45798,1.23086,-1.34492,-1.33618,-1.14242,1.84421,-0.21086 +0.45998,1.23038,-1.34519,-1.33594,-1.14247,1.84458,-0.21117 +0.46197,1.23031,-1.34523,-1.33592,-1.14247,1.84463,-0.21121 +0.46396,1.22969,-1.34554,-1.33568,-1.14251,1.84511,-0.21162 +0.46595,1.22908,-1.34585,-1.33544,-1.14254,1.84558,-0.21201 +0.46794,1.22848,-1.34616,-1.33521,-1.14258,1.84605,-0.21241 +0.46993,1.22789,-1.34646,-1.33497,-1.14261,1.84651,-0.21279 +0.47192,1.22731,-1.34675,-1.33475,-1.14265,1.84695,-0.21317 +0.47391,1.22674,-1.34704,-1.33452,-1.14268,1.84740,-0.21355 +0.47591,1.22618,-1.34733,-1.33430,-1.14272,1.84783,-0.21391 +0.47790,1.22563,-1.34761,-1.33408,-1.14275,1.84826,-0.21427 +0.47989,1.22509,-1.34789,-1.33386,-1.14279,1.84868,-0.21463 +0.48188,1.22456,-1.34816,-1.33365,-1.14283,1.84909,-0.21498 +0.48387,1.22403,-1.34843,-1.33344,-1.14286,1.84950,-0.21532 +0.48586,1.22352,-1.34869,-1.33323,-1.14290,1.84990,-0.21566 +0.48785,1.22301,-1.34895,-1.33302,-1.14293,1.85029,-0.21599 +0.48984,1.22251,-1.34921,-1.33282,-1.14297,1.85068,-0.21632 +0.49184,1.22202,-1.34946,-1.33262,-1.14300,1.85106,-0.21664 +0.49383,1.22181,-1.34957,-1.33254,-1.14302,1.85122,-0.21678 +0.49582,1.22118,-1.34985,-1.33236,-1.14303,1.85171,-0.21720 +0.49781,1.22056,-1.35013,-1.33218,-1.14304,1.85219,-0.21760 +0.49980,1.21995,-1.35041,-1.33200,-1.14305,1.85267,-0.21800 +0.50179,1.21935,-1.35068,-1.33183,-1.14306,1.85313,-0.21840 +0.50378,1.21876,-1.35095,-1.33165,-1.14307,1.85359,-0.21879 +0.50577,1.21818,-1.35121,-1.33148,-1.14309,1.85404,-0.21917 +0.50777,1.21761,-1.35147,-1.33131,-1.14310,1.85448,-0.21954 +0.50976,1.21705,-1.35173,-1.33114,-1.14311,1.85491,-0.21991 +0.51175,1.21649,-1.35198,-1.33098,-1.14313,1.85534,-0.22028 +0.51374,1.21595,-1.35223,-1.33082,-1.14314,1.85576,-0.22063 +0.51573,1.21542,-1.35247,-1.33065,-1.14316,1.85617,-0.22098 +0.51772,1.21489,-1.35271,-1.33049,-1.14317,1.85658,-0.22133 +0.51971,1.21438,-1.35295,-1.33034,-1.14319,1.85698,-0.22167 +0.52170,1.21387,-1.35318,-1.33018,-1.14321,1.85737,-0.22200 +0.52370,1.21337,-1.35341,-1.33003,-1.14322,1.85776,-0.22233 +0.52569,1.21302,-1.35357,-1.32993,-1.14323,1.85804,-0.22257 +0.52768,1.21239,-1.35381,-1.32982,-1.14321,1.85852,-0.22298 +0.52967,1.21178,-1.35405,-1.32971,-1.14320,1.85900,-0.22338 +0.53166,1.21117,-1.35428,-1.32960,-1.14318,1.85946,-0.22378 +0.53365,1.21058,-1.35451,-1.32950,-1.14317,1.85992,-0.22417 +0.53564,1.21000,-1.35474,-1.32940,-1.14315,1.86037,-0.22456 +0.53763,1.20942,-1.35496,-1.32929,-1.14314,1.86082,-0.22494 +0.53963,1.20886,-1.35518,-1.32919,-1.14313,1.86125,-0.22531 +0.54162,1.20830,-1.35540,-1.32909,-1.14312,1.86168,-0.22567 +0.54361,1.20776,-1.35561,-1.32899,-1.14311,1.86211,-0.22603 +0.54560,1.20722,-1.35582,-1.32889,-1.14310,1.86252,-0.22639 +0.54759,1.20670,-1.35603,-1.32879,-1.14309,1.86293,-0.22674 +0.54958,1.20618,-1.35623,-1.32869,-1.14308,1.86333,-0.22708 +0.55157,1.20567,-1.35643,-1.32860,-1.14307,1.86372,-0.22742 +0.55356,1.20517,-1.35663,-1.32850,-1.14306,1.86411,-0.22775 +0.55556,1.20496,-1.35671,-1.32847,-1.14306,1.86428,-0.22789 +0.55755,1.20433,-1.35693,-1.32839,-1.14303,1.86476,-0.22830 +0.55954,1.20372,-1.35715,-1.32832,-1.14300,1.86523,-0.22871 +0.56153,1.20312,-1.35737,-1.32824,-1.14297,1.86570,-0.22910 +0.56352,1.20252,-1.35758,-1.32817,-1.14294,1.86616,-0.22950 +0.56551,1.20194,-1.35779,-1.32810,-1.14292,1.86661,-0.22988 +0.56750,1.20137,-1.35800,-1.32803,-1.14289,1.86705,-0.23026 +0.56949,1.20080,-1.35820,-1.32795,-1.14287,1.86748,-0.23063 +0.57149,1.20025,-1.35840,-1.32788,-1.14284,1.86791,-0.23100 +0.57348,1.19971,-1.35860,-1.32781,-1.14282,1.86833,-0.23136 +0.57547,1.19917,-1.35879,-1.32774,-1.14280,1.86875,-0.23172 +0.57746,1.19865,-1.35899,-1.32767,-1.14278,1.86915,-0.23207 +0.57945,1.19813,-1.35918,-1.32760,-1.14276,1.86955,-0.23241 +0.58144,1.19762,-1.35936,-1.32753,-1.14274,1.86995,-0.23275 +0.58343,1.19712,-1.35954,-1.32747,-1.14272,1.87033,-0.23308 +0.58542,1.19696,-1.35960,-1.32745,-1.14271,1.87046,-0.23319 +0.58742,1.19635,-1.35980,-1.32741,-1.14267,1.87093,-0.23359 +0.58941,1.19576,-1.36000,-1.32737,-1.14263,1.87139,-0.23398 +0.59140,1.19517,-1.36019,-1.32732,-1.14259,1.87184,-0.23437 +0.59339,1.19460,-1.36039,-1.32728,-1.14255,1.87228,-0.23475 +0.59538,1.19403,-1.36058,-1.32724,-1.14252,1.87272,-0.23513 +0.59737,1.19347,-1.36076,-1.32720,-1.14248,1.87315,-0.23550 +0.59936,1.19293,-1.36095,-1.32716,-1.14245,1.87357,-0.23586 +0.60135,1.19239,-1.36113,-1.32711,-1.14241,1.87399,-0.23622 +0.60335,1.19186,-1.36130,-1.32707,-1.14238,1.87440,-0.23657 +0.60534,1.19134,-1.36148,-1.32703,-1.14235,1.87480,-0.23692 +0.60733,1.19083,-1.36165,-1.32699,-1.14232,1.87519,-0.23726 +0.60932,1.19033,-1.36182,-1.32695,-1.14229,1.87558,-0.23759 +0.61131,1.18992,-1.36196,-1.32692,-1.14227,1.87590,-0.23786 +0.61330,1.18935,-1.36213,-1.32692,-1.14221,1.87633,-0.23824 +0.61529,1.18879,-1.36229,-1.32691,-1.14216,1.87677,-0.23862 +0.61728,1.18824,-1.36246,-1.32691,-1.14211,1.87719,-0.23898 +0.61928,1.18770,-1.36262,-1.32690,-1.14206,1.87761,-0.23934 +0.62127,1.18716,-1.36278,-1.32690,-1.14202,1.87802,-0.23970 +0.62326,1.18664,-1.36293,-1.32689,-1.14197,1.87843,-0.24005 +0.62525,1.18613,-1.36309,-1.32689,-1.14192,1.87882,-0.24039 +0.62724,1.18562,-1.36324,-1.32688,-1.14188,1.87921,-0.24073 +0.62923,1.18512,-1.36339,-1.32687,-1.14184,1.87960,-0.24106 +0.63122,1.18492,-1.36345,-1.32687,-1.14182,1.87976,-0.24120 +0.63321,1.18436,-1.36361,-1.32688,-1.14176,1.88019,-0.24157 +0.63521,1.18380,-1.36377,-1.32689,-1.14171,1.88062,-0.24194 +0.63720,1.18326,-1.36393,-1.32690,-1.14165,1.88104,-0.24231 +0.63919,1.18272,-1.36408,-1.32690,-1.14160,1.88145,-0.24266 +0.64118,1.18220,-1.36423,-1.32691,-1.14155,1.88186,-0.24301 +0.64317,1.18168,-1.36438,-1.32691,-1.14150,1.88226,-0.24336 +0.64516,1.18117,-1.36453,-1.32692,-1.14145,1.88265,-0.24370 +0.64715,1.18067,-1.36467,-1.32692,-1.14140,1.88303,-0.24403 +0.64914,1.18027,-1.36479,-1.32693,-1.14136,1.88334,-0.24430 +0.65114,1.17974,-1.36493,-1.32696,-1.14130,1.88375,-0.24465 +0.65313,1.17922,-1.36506,-1.32699,-1.14124,1.88415,-0.24500 +0.65512,1.17871,-1.36520,-1.32702,-1.14118,1.88454,-0.24534 +0.65711,1.17821,-1.36533,-1.32705,-1.14112,1.88493,-0.24568 +0.65910,1.17772,-1.36546,-1.32708,-1.14107,1.88531,-0.24601 +0.66109,1.17757,-1.36550,-1.32709,-1.14105,1.88543,-0.24611 +0.66308,1.17702,-1.36563,-1.32714,-1.14098,1.88585,-0.24648 +0.66507,1.17649,-1.36576,-1.32719,-1.14091,1.88626,-0.24683 +0.66706,1.17596,-1.36589,-1.32723,-1.14084,1.88666,-0.24719 +0.66906,1.17545,-1.36602,-1.32728,-1.14077,1.88706,-0.24753 +0.67105,1.17494,-1.36614,-1.32732,-1.14071,1.88745,-0.24787 +0.67304,1.17444,-1.36626,-1.32737,-1.14065,1.88784,-0.24821 +0.67503,1.17395,-1.36639,-1.32741,-1.14058,1.88822,-0.24854 +0.67702,1.17385,-1.36641,-1.32742,-1.14057,1.88830,-0.24861 +0.67901,1.17330,-1.36652,-1.32750,-1.14048,1.88872,-0.24897 +0.68100,1.17276,-1.36664,-1.32759,-1.14040,1.88913,-0.24933 +0.68299,1.17224,-1.36675,-1.32767,-1.14032,1.88953,-0.24968 +0.68499,1.17172,-1.36686,-1.32775,-1.14024,1.88993,-0.25003 +0.68698,1.17121,-1.36697,-1.32782,-1.14016,1.89033,-0.25038 +0.68897,1.17071,-1.36707,-1.32790,-1.14008,1.89071,-0.25071 +0.69096,1.17021,-1.36718,-1.32797,-1.14001,1.89109,-0.25104 +0.69295,1.16977,-1.36727,-1.32804,-1.13994,1.89143,-0.25134 +0.69494,1.16923,-1.36737,-1.32816,-1.13984,1.89185,-0.25171 +0.69693,1.16869,-1.36746,-1.32827,-1.13975,1.89226,-0.25206 +0.69892,1.16817,-1.36756,-1.32838,-1.13965,1.89266,-0.25242 +0.70092,1.16766,-1.36765,-1.32848,-1.13956,1.89306,-0.25276 +0.70291,1.16715,-1.36774,-1.32859,-1.13947,1.89345,-0.25310 +0.70490,1.16665,-1.36783,-1.32869,-1.13939,1.89383,-0.25344 +0.70689,1.16616,-1.36792,-1.32879,-1.13930,1.89421,-0.25377 +0.70888,1.16568,-1.36801,-1.32889,-1.13922,1.89458,-0.25409 +0.71087,1.16563,-1.36802,-1.32891,-1.13920,1.89462,-0.25413 +0.71286,1.16508,-1.36809,-1.32907,-1.13909,1.89504,-0.25449 +0.71485,1.16455,-1.36816,-1.32923,-1.13898,1.89545,-0.25485 +0.71685,1.16402,-1.36822,-1.32938,-1.13886,1.89585,-0.25521 +0.71884,1.16351,-1.36829,-1.32953,-1.13875,1.89625,-0.25555 +0.72083,1.16300,-1.36836,-1.32968,-1.13865,1.89664,-0.25590 +0.72282,1.16250,-1.36842,-1.32983,-1.13854,1.89702,-0.25623 +0.72481,1.16201,-1.36849,-1.32997,-1.13844,1.89740,-0.25656 +0.72680,1.16153,-1.36855,-1.33011,-1.13834,1.89777,-0.25689 +0.72879,1.16106,-1.36862,-1.33025,-1.13824,1.89813,-0.25721 +0.73078,1.16100,-1.36862,-1.33027,-1.13823,1.89818,-0.25724 +0.73278,1.16045,-1.36868,-1.33046,-1.13810,1.89860,-0.25762 +0.73477,1.15991,-1.36873,-1.33065,-1.13797,1.89902,-0.25798 +0.73676,1.15938,-1.36879,-1.33083,-1.13784,1.89943,-0.25834 +0.73875,1.15885,-1.36884,-1.33102,-1.13772,1.89983,-0.25869 +0.74074,1.15834,-1.36890,-1.33119,-1.13760,1.90022,-0.25904 +0.74273,1.15783,-1.36895,-1.33137,-1.13748,1.90061,-0.25938 +0.74472,1.15733,-1.36900,-1.33154,-1.13737,1.90100,-0.25972 +0.74671,1.15684,-1.36906,-1.33171,-1.13725,1.90137,-0.26005 +0.74871,1.15636,-1.36911,-1.33187,-1.13714,1.90174,-0.26038 +0.75070,1.15589,-1.36916,-1.33204,-1.13703,1.90210,-0.26070 +0.75269,1.15551,-1.36920,-1.33217,-1.13694,1.90240,-0.26095 +0.75468,1.15498,-1.36923,-1.33239,-1.13680,1.90280,-0.26131 +0.75667,1.15446,-1.36926,-1.33261,-1.13667,1.90320,-0.26166 +0.75866,1.15395,-1.36930,-1.33282,-1.13653,1.90359,-0.26201 +0.76065,1.15345,-1.36933,-1.33303,-1.13640,1.90398,-0.26235 +0.76264,1.15295,-1.36936,-1.33324,-1.13627,1.90436,-0.26268 +0.76464,1.15247,-1.36939,-1.33344,-1.13615,1.90473,-0.26301 +0.76663,1.15199,-1.36943,-1.33363,-1.13602,1.90510,-0.26333 +0.76862,1.15152,-1.36946,-1.33383,-1.13590,1.90546,-0.26365 +0.77061,1.15106,-1.36949,-1.33402,-1.13578,1.90581,-0.26397 +0.77260,1.15091,-1.36950,-1.33409,-1.13574,1.90592,-0.26407 +0.77459,1.15036,-1.36949,-1.33439,-1.13556,1.90635,-0.26444 +0.77658,1.14981,-1.36948,-1.33470,-1.13539,1.90677,-0.26481 +0.77857,1.14928,-1.36947,-1.33499,-1.13522,1.90718,-0.26517 +0.78057,1.14875,-1.36947,-1.33528,-1.13505,1.90758,-0.26553 +0.78256,1.14823,-1.36946,-1.33557,-1.13489,1.90797,-0.26588 +0.78455,1.14773,-1.36946,-1.33585,-1.13473,1.90836,-0.26622 +0.78654,1.14723,-1.36945,-1.33613,-1.13457,1.90875,-0.26656 +0.78853,1.14674,-1.36945,-1.33640,-1.13441,1.90912,-0.26690 +0.79052,1.14625,-1.36944,-1.33666,-1.13426,1.90949,-0.26722 +0.79251,1.14578,-1.36944,-1.33692,-1.13411,1.90986,-0.26755 +0.79450,1.14531,-1.36943,-1.33718,-1.13396,1.91022,-0.26786 +0.79650,1.14485,-1.36943,-1.33743,-1.13382,1.91057,-0.26818 +0.79849,1.14440,-1.36943,-1.33768,-1.13368,1.91091,-0.26848 +0.80048,1.14396,-1.36942,-1.33792,-1.13354,1.91125,-0.26878 +0.80247,1.14382,-1.36942,-1.33800,-1.13349,1.91136,-0.26888 +0.80446,1.14331,-1.36939,-1.33832,-1.13331,1.91175,-0.26922 +0.80645,1.14281,-1.36936,-1.33864,-1.13314,1.91213,-0.26957 +0.80844,1.14232,-1.36934,-1.33895,-1.13296,1.91251,-0.26990 +0.81043,1.14183,-1.36931,-1.33925,-1.13280,1.91288,-0.27023 +0.81243,1.14136,-1.36928,-1.33955,-1.13263,1.91324,-0.27055 +0.81442,1.14089,-1.36926,-1.33985,-1.13247,1.91360,-0.27087 +0.81641,1.14043,-1.36923,-1.34014,-1.13231,1.91395,-0.27118 +0.81840,1.13998,-1.36921,-1.34042,-1.13215,1.91430,-0.27149 +0.82039,1.13954,-1.36919,-1.34070,-1.13199,1.91464,-0.27179 +0.82238,1.13910,-1.36916,-1.34098,-1.13184,1.91497,-0.27209 +0.82437,1.13871,-1.36914,-1.34123,-1.13170,1.91528,-0.27236 +0.82636,1.13821,-1.36909,-1.34158,-1.13151,1.91566,-0.27270 +0.82836,1.13772,-1.36905,-1.34192,-1.13133,1.91603,-0.27303 +0.83035,1.13724,-1.36900,-1.34226,-1.13115,1.91640,-0.27336 +0.83234,1.13676,-1.36896,-1.34259,-1.13097,1.91676,-0.27368 +0.83433,1.13630,-1.36892,-1.34292,-1.13079,1.91712,-0.27400 +0.83632,1.13584,-1.36888,-1.34324,-1.13062,1.91747,-0.27431 +0.83831,1.13539,-1.36883,-1.34355,-1.13045,1.91781,-0.27462 +0.84030,1.13495,-1.36879,-1.34386,-1.13028,1.91815,-0.27492 +0.84229,1.13452,-1.36875,-1.34417,-1.13012,1.91848,-0.27522 +0.84429,1.13409,-1.36872,-1.34446,-1.12996,1.91881,-0.27551 +0.84628,1.13366,-1.36868,-1.34476,-1.12979,1.91913,-0.27580 +0.84827,1.13317,-1.36861,-1.34514,-1.12960,1.91951,-0.27613 +0.85026,1.13269,-1.36855,-1.34550,-1.12940,1.91987,-0.27646 +0.85225,1.13222,-1.36849,-1.34586,-1.12921,1.92023,-0.27679 +0.85424,1.13176,-1.36844,-1.34622,-1.12902,1.92059,-0.27710 +0.85623,1.13130,-1.36838,-1.34656,-1.12884,1.92094,-0.27741 +0.85822,1.13085,-1.36832,-1.34690,-1.12866,1.92128,-0.27772 +0.86022,1.13041,-1.36827,-1.34724,-1.12848,1.92162,-0.27802 +0.86221,1.12998,-1.36822,-1.34757,-1.12831,1.92195,-0.27832 +0.86420,1.12956,-1.36816,-1.34789,-1.12813,1.92227,-0.27861 +0.86619,1.12914,-1.36811,-1.34821,-1.12797,1.92259,-0.27890 +0.86818,1.12873,-1.36806,-1.34852,-1.12780,1.92291,-0.27918 +0.87017,1.12868,-1.36806,-1.34856,-1.12778,1.92295,-0.27921 +0.87216,1.12816,-1.36799,-1.34896,-1.12757,1.92334,-0.27957 +0.87415,1.12765,-1.36793,-1.34935,-1.12736,1.92373,-0.27991 +0.87614,1.12715,-1.36787,-1.34973,-1.12715,1.92411,-0.28026 +0.87814,1.12666,-1.36781,-1.35011,-1.12695,1.92448,-0.28059 +0.88013,1.12618,-1.36775,-1.35048,-1.12676,1.92485,-0.28092 +0.88212,1.12570,-1.36769,-1.35084,-1.12656,1.92521,-0.28125 +0.88411,1.12523,-1.36763,-1.35120,-1.12637,1.92557,-0.28157 +0.88610,1.12478,-1.36758,-1.35155,-1.12618,1.92592,-0.28188 +0.88809,1.12433,-1.36752,-1.35190,-1.12600,1.92626,-0.28219 +0.89008,1.12388,-1.36747,-1.35223,-1.12582,1.92660,-0.28250 +0.89207,1.12345,-1.36742,-1.35257,-1.12564,1.92693,-0.28279 +0.89407,1.12302,-1.36737,-1.35289,-1.12547,1.92726,-0.28309 +0.89606,1.12260,-1.36732,-1.35322,-1.12530,1.92758,-0.28338 +0.89805,1.12219,-1.36727,-1.35353,-1.12513,1.92790,-0.28366 +0.90004,1.12193,-1.36724,-1.35373,-1.12502,1.92809,-0.28384 +0.90203,1.12145,-1.36715,-1.35414,-1.12481,1.92846,-0.28417 +0.90402,1.12097,-1.36707,-1.35454,-1.12460,1.92882,-0.28449 +0.90601,1.12051,-1.36699,-1.35494,-1.12439,1.92918,-0.28482 +0.90800,1.12005,-1.36692,-1.35533,-1.12419,1.92953,-0.28513 +0.91000,1.11960,-1.36684,-1.35572,-1.12399,1.92987,-0.28544 +0.91199,1.11915,-1.36677,-1.35609,-1.12379,1.93021,-0.28575 +0.91398,1.11872,-1.36669,-1.35646,-1.12360,1.93054,-0.28605 +0.91597,1.11829,-1.36662,-1.35683,-1.12341,1.93087,-0.28634 +0.91796,1.11787,-1.36655,-1.35718,-1.12323,1.93119,-0.28663 +0.91995,1.11745,-1.36648,-1.35754,-1.12304,1.93151,-0.28692 +0.92194,1.11704,-1.36642,-1.35788,-1.12286,1.93182,-0.28720 +0.92393,1.11664,-1.36635,-1.35822,-1.12269,1.93212,-0.28747 +0.92593,1.11639,-1.36633,-1.35840,-1.12258,1.93232,-0.28765 +0.92792,1.11579,-1.36644,-1.35857,-1.12245,1.93277,-0.28806 +0.92991,1.11520,-1.36655,-1.35873,-1.12232,1.93321,-0.28846 +0.93190,1.11463,-1.36666,-1.35888,-1.12219,1.93365,-0.28886 +0.93389,1.11406,-1.36676,-1.35904,-1.12207,1.93408,-0.28925 +0.93588,1.11351,-1.36687,-1.35919,-1.12195,1.93450,-0.28963 +0.93787,1.11296,-1.36697,-1.35934,-1.12183,1.93491,-0.29001 +0.93986,1.11242,-1.36707,-1.35948,-1.12171,1.93532,-0.29038 +0.94186,1.11190,-1.36717,-1.35962,-1.12159,1.93572,-0.29074 +0.94385,1.11138,-1.36727,-1.35976,-1.12148,1.93612,-0.29110 +0.94584,1.11087,-1.36736,-1.35990,-1.12137,1.93650,-0.29145 +0.94783,1.11037,-1.36746,-1.36003,-1.12126,1.93689,-0.29180 +0.94982,1.10987,-1.36755,-1.36016,-1.12116,1.93726,-0.29214 +0.95181,1.10939,-1.36765,-1.36029,-1.12105,1.93763,-0.29247 +0.95380,1.10891,-1.36774,-1.36041,-1.12095,1.93799,-0.29280 +0.95579,1.10844,-1.36783,-1.36053,-1.12085,1.93834,-0.29313 +0.95779,1.10811,-1.36790,-1.36061,-1.12079,1.93860,-0.29336 +0.95978,1.10749,-1.36813,-1.36060,-1.12072,1.93907,-0.29379 +0.96177,1.10688,-1.36834,-1.36059,-1.12065,1.93953,-0.29421 +0.96376,1.10629,-1.36856,-1.36059,-1.12059,1.93998,-0.29462 +0.96575,1.10570,-1.36877,-1.36058,-1.12052,1.94042,-0.29503 +0.96774,1.10512,-1.36898,-1.36057,-1.12046,1.94086,-0.29542 +0.96973,1.10456,-1.36918,-1.36056,-1.12040,1.94129,-0.29582 +0.97172,1.10400,-1.36939,-1.36055,-1.12035,1.94171,-0.29620 +0.97372,1.10345,-1.36958,-1.36054,-1.12029,1.94213,-0.29658 +0.97571,1.10292,-1.36978,-1.36053,-1.12024,1.94253,-0.29695 +0.97770,1.10239,-1.36997,-1.36052,-1.12018,1.94293,-0.29732 +0.97969,1.10187,-1.37016,-1.36051,-1.12013,1.94333,-0.29768 +0.98168,1.10136,-1.37035,-1.36050,-1.12008,1.94371,-0.29804 +0.98367,1.10086,-1.37053,-1.36049,-1.12003,1.94409,-0.29838 +0.98566,1.10036,-1.37071,-1.36047,-1.11999,1.94447,-0.29873 +0.98765,1.09988,-1.37089,-1.36046,-1.11994,1.94484,-0.29906 +0.98965,1.09940,-1.37106,-1.36045,-1.11989,1.94520,-0.29940 +0.99164,1.09901,-1.37121,-1.36042,-1.11986,1.94549,-0.29967 +0.99363,1.09842,-1.37150,-1.36030,-1.11985,1.94594,-0.30008 +0.99562,1.09784,-1.37178,-1.36018,-1.11983,1.94638,-0.30048 +0.99761,1.09727,-1.37205,-1.36006,-1.11982,1.94681,-0.30088 +0.99960,1.09671,-1.37232,-1.35994,-1.11981,1.94724,-0.30127 +1.00159,1.09616,-1.37259,-1.35982,-1.11980,1.94766,-0.30166 +1.00358,1.09561,-1.37285,-1.35970,-1.11979,1.94807,-0.30203 +1.00558,1.09508,-1.37311,-1.35958,-1.11978,1.94847,-0.30241 +1.00757,1.09456,-1.37336,-1.35947,-1.11977,1.94887,-0.30277 +1.00956,1.09404,-1.37361,-1.35935,-1.11976,1.94926,-0.30313 +1.01155,1.09354,-1.37386,-1.35924,-1.11975,1.94964,-0.30348 +1.01354,1.09304,-1.37410,-1.35913,-1.11975,1.95002,-0.30383 +1.01553,1.09255,-1.37434,-1.35902,-1.11974,1.95039,-0.30417 +1.01752,1.09207,-1.37457,-1.35891,-1.11974,1.95075,-0.30451 +1.01951,1.09160,-1.37480,-1.35880,-1.11973,1.95111,-0.30484 +1.02151,1.09113,-1.37503,-1.35869,-1.11973,1.95146,-0.30517 +1.02350,1.09094,-1.37513,-1.35865,-1.11973,1.95161,-0.30530 +1.02549,1.09038,-1.37543,-1.35847,-1.11974,1.95203,-0.30569 +1.02748,1.08983,-1.37573,-1.35829,-1.11976,1.95245,-0.30607 +1.02947,1.08930,-1.37603,-1.35811,-1.11977,1.95285,-0.30645 +1.03146,1.08877,-1.37632,-1.35794,-1.11979,1.95325,-0.30682 +1.03345,1.08825,-1.37660,-1.35777,-1.11981,1.95364,-0.30718 +1.03544,1.08774,-1.37688,-1.35760,-1.11982,1.95403,-0.30754 +1.03744,1.08724,-1.37716,-1.35743,-1.11984,1.95441,-0.30789 +1.03943,1.08674,-1.37743,-1.35727,-1.11986,1.95478,-0.30824 +1.04142,1.08626,-1.37770,-1.35710,-1.11988,1.95515,-0.30858 +1.04341,1.08578,-1.37796,-1.35694,-1.11989,1.95551,-0.30892 +1.04540,1.08531,-1.37822,-1.35678,-1.11991,1.95587,-0.30924 +1.04739,1.08485,-1.37848,-1.35663,-1.11993,1.95622,-0.30957 +1.04938,1.08439,-1.37874,-1.35646,-1.11995,1.95657,-0.30989 +1.05137,1.08384,-1.37907,-1.35624,-1.11999,1.95698,-0.31028 +1.05337,1.08331,-1.37939,-1.35601,-1.12003,1.95739,-0.31066 +1.05536,1.08278,-1.37971,-1.35579,-1.12007,1.95778,-0.31103 +1.05735,1.08226,-1.38003,-1.35557,-1.12010,1.95818,-0.31139 +1.05934,1.08175,-1.38034,-1.35535,-1.12014,1.95856,-0.31175 +1.06133,1.08125,-1.38064,-1.35514,-1.12018,1.95894,-0.31211 +1.06332,1.08076,-1.38094,-1.35493,-1.12022,1.95931,-0.31245 +1.06531,1.08027,-1.38123,-1.35472,-1.12026,1.95968,-0.31280 +1.06730,1.07979,-1.38152,-1.35452,-1.12029,1.96004,-0.31313 +1.06930,1.07933,-1.38181,-1.35431,-1.12033,1.96040,-0.31346 +1.07129,1.07887,-1.38209,-1.35411,-1.12037,1.96074,-0.31379 +1.07328,1.07841,-1.38237,-1.35392,-1.12041,1.96109,-0.31411 +1.07527,1.07797,-1.38264,-1.35372,-1.12045,1.96142,-0.31442 +1.07726,1.07783,-1.38273,-1.35365,-1.12046,1.96153,-0.31452 +1.07925,1.07732,-1.38308,-1.35337,-1.12053,1.96192,-0.31488 +1.08124,1.07681,-1.38342,-1.35310,-1.12059,1.96230,-0.31524 +1.08323,1.07631,-1.38376,-1.35282,-1.12065,1.96268,-0.31559 +1.08523,1.07582,-1.38409,-1.35256,-1.12072,1.96304,-0.31594 +1.08722,1.07534,-1.38442,-1.35229,-1.12078,1.96341,-0.31628 +1.08921,1.07487,-1.38474,-1.35203,-1.12084,1.96376,-0.31661 +1.09120,1.07441,-1.38506,-1.35177,-1.12091,1.96412,-0.31694 +1.09319,1.07395,-1.38537,-1.35152,-1.12097,1.96446,-0.31726 +1.09518,1.07350,-1.38567,-1.35126,-1.12103,1.96480,-0.31758 +1.09717,1.07306,-1.38598,-1.35102,-1.12109,1.96513,-0.31789 +1.09916,1.07263,-1.38627,-1.35077,-1.12116,1.96546,-0.31820 +1.10115,1.07228,-1.38652,-1.35057,-1.12121,1.96573,-0.31845 +1.10315,1.07176,-1.38690,-1.35023,-1.12129,1.96611,-0.31882 +1.10514,1.07126,-1.38727,-1.34990,-1.12138,1.96650,-0.31917 +1.10713,1.07076,-1.38764,-1.34958,-1.12147,1.96687,-0.31953 +1.10912,1.07027,-1.38801,-1.34926,-1.12156,1.96724,-0.31987 +1.11111,1.06979,-1.38837,-1.34894,-1.12164,1.96760,-0.32021 +1.11310,1.06932,-1.38872,-1.34863,-1.12173,1.96796,-0.32055 +1.11509,1.06886,-1.38907,-1.34832,-1.12181,1.96831,-0.32088 +1.11708,1.06840,-1.38941,-1.34802,-1.12189,1.96865,-0.32120 +1.11908,1.06795,-1.38974,-1.34772,-1.12198,1.96899,-0.32152 +1.12107,1.06751,-1.39007,-1.34742,-1.12206,1.96932,-0.32184 +1.12306,1.06708,-1.39040,-1.34713,-1.12214,1.96965,-0.32215 +1.12505,1.06666,-1.39072,-1.34684,-1.12223,1.96997,-0.32245 +1.12704,1.06624,-1.39103,-1.34656,-1.12231,1.97029,-0.32275 +1.12903,1.06589,-1.39130,-1.34631,-1.12238,1.97055,-0.32299 +1.13102,1.06534,-1.39179,-1.34582,-1.12253,1.97096,-0.32338 +1.13301,1.06480,-1.39228,-1.34533,-1.12268,1.97137,-0.32377 +1.13501,1.06427,-1.39275,-1.34484,-1.12282,1.97177,-0.32415 +1.13700,1.06375,-1.39322,-1.34437,-1.12297,1.97216,-0.32452 +1.13899,1.06323,-1.39369,-1.34390,-1.12311,1.97255,-0.32489 +1.14098,1.06273,-1.39414,-1.34343,-1.12326,1.97293,-0.32525 +1.14297,1.06223,-1.39459,-1.34298,-1.12340,1.97330,-0.32560 +1.14496,1.06175,-1.39503,-1.34253,-1.12354,1.97367,-0.32595 +1.14695,1.06127,-1.39546,-1.34208,-1.12368,1.97403,-0.32629 +1.14894,1.06080,-1.39589,-1.34165,-1.12382,1.97438,-0.32663 +1.15094,1.06033,-1.39631,-1.34122,-1.12395,1.97473,-0.32696 +1.15293,1.05988,-1.39672,-1.34079,-1.12409,1.97508,-0.32728 +1.15492,1.05943,-1.39712,-1.34037,-1.12422,1.97541,-0.32761 +1.15691,1.05899,-1.39752,-1.33996,-1.12436,1.97575,-0.32792 +1.15890,1.05856,-1.39791,-1.33956,-1.12449,1.97607,-0.32823 +1.16089,1.05814,-1.39830,-1.33916,-1.12462,1.97639,-0.32853 +1.16288,1.05772,-1.39868,-1.33876,-1.12475,1.97671,-0.32883 +1.16487,1.05731,-1.39905,-1.33837,-1.12488,1.97702,-0.32913 +1.16687,1.05691,-1.39942,-1.33799,-1.12500,1.97732,-0.32942 +1.16886,1.05651,-1.39978,-1.33761,-1.12513,1.97762,-0.32970 +1.17085,1.05612,-1.40013,-1.33724,-1.12525,1.97791,-0.32998 +1.17284,1.05574,-1.40048,-1.33687,-1.12538,1.97820,-0.33026 +1.17483,1.05536,-1.40083,-1.33651,-1.12550,1.97849,-0.33053 +1.17682,1.05532,-1.40087,-1.33647,-1.12551,1.97852,-0.33056 +1.17881,1.05490,-1.40127,-1.33604,-1.12566,1.97883,-0.33086 +1.18080,1.05449,-1.40166,-1.33561,-1.12580,1.97914,-0.33116 +1.18280,1.05409,-1.40205,-1.33520,-1.12594,1.97945,-0.33145 +1.18479,1.05369,-1.40243,-1.33479,-1.12608,1.97975,-0.33173 +1.18678,1.05330,-1.40280,-1.33438,-1.12622,1.98004,-0.33201 +1.18877,1.05292,-1.40317,-1.33398,-1.12636,1.98033,-0.33229 +1.19076,1.05255,-1.40354,-1.33359,-1.12650,1.98061,-0.33256 +1.19275,1.05218,-1.40389,-1.33320,-1.12663,1.98089,-0.33283 +1.19474,1.05181,-1.40425,-1.33281,-1.12677,1.98117,-0.33309 +1.19673,1.05140,-1.40466,-1.33236,-1.12692,1.98147,-0.33338 +1.19873,1.05101,-1.40506,-1.33191,-1.12707,1.98177,-0.33367 +1.20072,1.05062,-1.40545,-1.33147,-1.12723,1.98207,-0.33395 +1.20271,1.05023,-1.40584,-1.33104,-1.12738,1.98236,-0.33423 +1.20470,1.04985,-1.40622,-1.33062,-1.12753,1.98264,-0.33450 +1.20669,1.04948,-1.40660,-1.33020,-1.12767,1.98292,-0.33477 +1.20868,1.04912,-1.40697,-1.32978,-1.12782,1.98320,-0.33504 +1.21067,1.04876,-1.40733,-1.32938,-1.12796,1.98347,-0.33530 +1.21266,1.04841,-1.40769,-1.32897,-1.12811,1.98373,-0.33555 +1.21466,1.04837,-1.40773,-1.32893,-1.12812,1.98376,-0.33558 +1.21665,1.04798,-1.40815,-1.32846,-1.12829,1.98406,-0.33586 +1.21864,1.04759,-1.40856,-1.32799,-1.12845,1.98435,-0.33614 +1.22063,1.04721,-1.40896,-1.32754,-1.12861,1.98463,-0.33642 +1.22262,1.04684,-1.40935,-1.32709,-1.12877,1.98492,-0.33669 +1.22461,1.04647,-1.40974,-1.32665,-1.12893,1.98519,-0.33695 +1.22660,1.04611,-1.41012,-1.32621,-1.12909,1.98546,-0.33721 +1.22859,1.04576,-1.41050,-1.32578,-1.12924,1.98573,-0.33747 +1.23059,1.04541,-1.41087,-1.32536,-1.12940,1.98599,-0.33772 +1.23258,1.04507,-1.41123,-1.32494,-1.12955,1.98625,-0.33797 +1.23457,1.04503,-1.41127,-1.32489,-1.12957,1.98628,-0.33800 +1.23656,1.04464,-1.41171,-1.32437,-1.12975,1.98657,-0.33828 +1.23855,1.04425,-1.41215,-1.32386,-1.12993,1.98686,-0.33856 +1.24054,1.04388,-1.41258,-1.32336,-1.13011,1.98715,-0.33884 +1.24253,1.04351,-1.41300,-1.32287,-1.13029,1.98743,-0.33911 +1.24452,1.04314,-1.41341,-1.32239,-1.13047,1.98770,-0.33937 +1.24652,1.04278,-1.41381,-1.32191,-1.13064,1.98797,-0.33963 +1.24851,1.04243,-1.41421,-1.32144,-1.13082,1.98824,-0.33989 +1.25050,1.04208,-1.41461,-1.32097,-1.13099,1.98850,-0.34014 +1.25249,1.04174,-1.41499,-1.32051,-1.13116,1.98875,-0.34039 +1.25448,1.04141,-1.41537,-1.32006,-1.13132,1.98901,-0.34063 +1.25647,1.04108,-1.41575,-1.31962,-1.13149,1.98925,-0.34087 +1.25846,1.04088,-1.41598,-1.31934,-1.13159,1.98941,-0.34102 +1.26045,1.04049,-1.41644,-1.31880,-1.13179,1.98970,-0.34130 +1.26245,1.04011,-1.41689,-1.31826,-1.13198,1.98999,-0.34158 +1.26444,1.03973,-1.41733,-1.31773,-1.13218,1.99027,-0.34185 +1.26643,1.03936,-1.41777,-1.31720,-1.13237,1.99055,-0.34212 +1.26842,1.03900,-1.41820,-1.31669,-1.13256,1.99082,-0.34239 +1.27041,1.03864,-1.41862,-1.31618,-1.13275,1.99109,-0.34265 +1.27240,1.03829,-1.41904,-1.31568,-1.13293,1.99135,-0.34291 +1.27439,1.03794,-1.41945,-1.31519,-1.13312,1.99161,-0.34316 +1.27638,1.03760,-1.41985,-1.31470,-1.13330,1.99187,-0.34341 +1.27838,1.03727,-1.42025,-1.31422,-1.13348,1.99212,-0.34365 +1.28037,1.03694,-1.42064,-1.31375,-1.13366,1.99237,-0.34389 +1.28236,1.03662,-1.42102,-1.31329,-1.13383,1.99261,-0.34413 +1.28435,1.03630,-1.42140,-1.31283,-1.13400,1.99285,-0.34436 +1.28634,1.03617,-1.42155,-1.31264,-1.13408,1.99295,-0.34445 +1.28833,1.03579,-1.42202,-1.31208,-1.13429,1.99323,-0.34473 +1.29032,1.03542,-1.42247,-1.31152,-1.13449,1.99351,-0.34500 +1.29231,1.03506,-1.42292,-1.31098,-1.13469,1.99378,-0.34527 +1.29431,1.03470,-1.42336,-1.31044,-1.13489,1.99405,-0.34553 +1.29630,1.03434,-1.42380,-1.30991,-1.13509,1.99432,-0.34579 +1.29829,1.03400,-1.42422,-1.30939,-1.13529,1.99458,-0.34604 +1.30028,1.03366,-1.42464,-1.30887,-1.13548,1.99483,-0.34629 +1.30227,1.03332,-1.42506,-1.30837,-1.13568,1.99508,-0.34654 +1.30426,1.03299,-1.42546,-1.30787,-1.13586,1.99533,-0.34678 +1.30625,1.03267,-1.42586,-1.30738,-1.13605,1.99558,-0.34702 +1.30824,1.03235,-1.42625,-1.30689,-1.13624,1.99581,-0.34725 +1.31023,1.03204,-1.42664,-1.30641,-1.13642,1.99605,-0.34748 +1.31223,1.03173,-1.42702,-1.30594,-1.13660,1.99628,-0.34771 +1.31422,1.03160,-1.42719,-1.30574,-1.13668,1.99638,-0.34780 +1.31621,1.03116,-1.42772,-1.30510,-1.13691,1.99671,-0.34812 +1.31820,1.03074,-1.42824,-1.30447,-1.13714,1.99702,-0.34843 +1.32019,1.03032,-1.42876,-1.30385,-1.13737,1.99734,-0.34874 +1.32218,1.02991,-1.42926,-1.30324,-1.13760,1.99764,-0.34904 +1.32417,1.02950,-1.42976,-1.30264,-1.13782,1.99795,-0.34933 +1.32616,1.02910,-1.43025,-1.30205,-1.13804,1.99824,-0.34963 +1.32816,1.02871,-1.43073,-1.30146,-1.13826,1.99854,-0.34991 +1.33015,1.02833,-1.43120,-1.30089,-1.13848,1.99882,-0.35019 +1.33214,1.02795,-1.43167,-1.30032,-1.13869,1.99911,-0.35047 +1.33413,1.02758,-1.43213,-1.29976,-1.13890,1.99938,-0.35074 +1.33612,1.02722,-1.43258,-1.29921,-1.13911,1.99966,-0.35101 +1.33811,1.02686,-1.43302,-1.29867,-1.13932,1.99993,-0.35128 +1.34010,1.02651,-1.43346,-1.29813,-1.13952,2.00019,-0.35153 +1.34209,1.02616,-1.43388,-1.29760,-1.13972,2.00045,-0.35179 +1.34409,1.02582,-1.43431,-1.29708,-1.13992,2.00070,-0.35204 +1.34608,1.02548,-1.43472,-1.29657,-1.14012,2.00095,-0.35229 +1.34807,1.02516,-1.43513,-1.29607,-1.14031,2.00120,-0.35253 +1.35006,1.02483,-1.43553,-1.29557,-1.14050,2.00144,-0.35277 +1.35205,1.02451,-1.43593,-1.29508,-1.14070,2.00168,-0.35300 +1.35404,1.02420,-1.43631,-1.29460,-1.14088,2.00192,-0.35323 +1.35603,1.02389,-1.43670,-1.29413,-1.14107,2.00215,-0.35346 +1.35802,1.02365,-1.43700,-1.29374,-1.14122,2.00233,-0.35364 +1.36002,1.02329,-1.43745,-1.29320,-1.14143,2.00260,-0.35391 +1.36201,1.02294,-1.43789,-1.29266,-1.14164,2.00286,-0.35417 +1.36400,1.02260,-1.43832,-1.29212,-1.14184,2.00312,-0.35442 +1.36599,1.02226,-1.43874,-1.29160,-1.14204,2.00337,-0.35467 +1.36798,1.02193,-1.43916,-1.29108,-1.14224,2.00362,-0.35492 +1.36997,1.02160,-1.43957,-1.29057,-1.14244,2.00387,-0.35516 +1.37196,1.02128,-1.43997,-1.29007,-1.14264,2.00411,-0.35540 +1.37395,1.02096,-1.44037,-1.28958,-1.14283,2.00434,-0.35563 +1.37595,1.02065,-1.44076,-1.28909,-1.14302,2.00458,-0.35586 +1.37794,1.02034,-1.44115,-1.28861,-1.14321,2.00481,-0.35609 +1.37993,1.02004,-1.44153,-1.28813,-1.14340,2.00503,-0.35631 +1.38192,1.01969,-1.44198,-1.28758,-1.14361,2.00530,-0.35657 +1.38391,1.01934,-1.44242,-1.28704,-1.14382,2.00556,-0.35683 +1.38590,1.01900,-1.44285,-1.28650,-1.14403,2.00581,-0.35708 +1.38789,1.01866,-1.44327,-1.28597,-1.14423,2.00606,-0.35733 +1.38988,1.01833,-1.44369,-1.28545,-1.14443,2.00631,-0.35757 +1.39188,1.01801,-1.44410,-1.28494,-1.14463,2.00655,-0.35781 +1.39387,1.01769,-1.44451,-1.28444,-1.14483,2.00679,-0.35805 +1.39586,1.01738,-1.44491,-1.28394,-1.14503,2.00702,-0.35828 +1.39785,1.01707,-1.44530,-1.28345,-1.14522,2.00725,-0.35851 +1.39984,1.01677,-1.44568,-1.28297,-1.14541,2.00748,-0.35874 +1.40183,1.01647,-1.44607,-1.28248,-1.14560,2.00771,-0.35896 +1.40382,1.01613,-1.44650,-1.28194,-1.14582,2.00796,-0.35921 +1.40581,1.01580,-1.44693,-1.28140,-1.14603,2.00820,-0.35945 +1.40781,1.01548,-1.44736,-1.28087,-1.14623,2.00845,-0.35970 +1.40980,1.01516,-1.44777,-1.28035,-1.14644,2.00868,-0.35993 +1.41179,1.01484,-1.44818,-1.27983,-1.14664,2.00892,-0.36017 +1.41378,1.01454,-1.44858,-1.27932,-1.14684,2.00915,-0.36039 +1.41577,1.01423,-1.44898,-1.27882,-1.14704,2.00938,-0.36062 +1.41776,1.01393,-1.44937,-1.27833,-1.14724,2.00960,-0.36084 +1.41975,1.01364,-1.44975,-1.27785,-1.14743,2.00982,-0.36106 +1.42174,1.01355,-1.44987,-1.27770,-1.14749,2.00989,-0.36113 +1.42374,1.01321,-1.45030,-1.27716,-1.14770,2.01014,-0.36138 +1.42573,1.01288,-1.45072,-1.27664,-1.14790,2.01038,-0.36162 +1.42772,1.01256,-1.45113,-1.27612,-1.14811,2.01062,-0.36186 +1.42971,1.01224,-1.45154,-1.27561,-1.14831,2.01086,-0.36210 +1.43170,1.01193,-1.45194,-1.27511,-1.14850,2.01110,-0.36234 +1.43369,1.01162,-1.45234,-1.27462,-1.14870,2.01133,-0.36256 +1.43568,1.01132,-1.45273,-1.27413,-1.14889,2.01155,-0.36279 +1.43767,1.01102,-1.45311,-1.27365,-1.14909,2.01177,-0.36301 +1.43967,1.01087,-1.45330,-1.27340,-1.14918,2.01189,-0.36312 +1.44166,1.01055,-1.45373,-1.27287,-1.14940,2.01212,-0.36336 +1.44365,1.01024,-1.45415,-1.27233,-1.14961,2.01236,-0.36360 +1.44564,1.00993,-1.45456,-1.27181,-1.14981,2.01259,-0.36383 +1.44763,1.00963,-1.45496,-1.27130,-1.15002,2.01282,-0.36405 +1.44962,1.00933,-1.45536,-1.27079,-1.15022,2.01304,-0.36428 +1.45161,1.00903,-1.45576,-1.27029,-1.15042,2.01326,-0.36449 +1.45360,1.00875,-1.45614,-1.26979,-1.15062,2.01347,-0.36471 +1.45560,1.00857,-1.45637,-1.26950,-1.15074,2.01360,-0.36484 +1.45759,1.00827,-1.45678,-1.26898,-1.15095,2.01383,-0.36506 +1.45958,1.00798,-1.45718,-1.26846,-1.15115,2.01405,-0.36529 +1.46157,1.00768,-1.45758,-1.26796,-1.15135,2.01426,-0.36550 +1.46356,1.00740,-1.45797,-1.26746,-1.15155,2.01448,-0.36572 +1.46555,1.00717,-1.45827,-1.26706,-1.15171,2.01465,-0.36589 +1.46754,1.00686,-1.45867,-1.26656,-1.15191,2.01488,-0.36612 +1.46953,1.00656,-1.45907,-1.26607,-1.15211,2.01510,-0.36634 +1.47153,1.00627,-1.45945,-1.26558,-1.15231,2.01532,-0.36656 +1.47352,1.00598,-1.45983,-1.26509,-1.15250,2.01554,-0.36678 +1.47551,1.00567,-1.46024,-1.26458,-1.15271,2.01577,-0.36701 +1.47750,1.00537,-1.46064,-1.26407,-1.15291,2.01599,-0.36724 +1.47949,1.00507,-1.46103,-1.26357,-1.15311,2.01621,-0.36746 +1.48148,1.00478,-1.46142,-1.26308,-1.15330,2.01643,-0.36768 +1.48347,1.00455,-1.46173,-1.26269,-1.15346,2.01660,-0.36785 +1.48546,1.00422,-1.46217,-1.26213,-1.15368,2.01684,-0.36809 +1.48746,1.00391,-1.46260,-1.26158,-1.15390,2.01708,-0.36833 +1.48945,1.00359,-1.46303,-1.26104,-1.15412,2.01731,-0.36857 +1.49144,1.00328,-1.46344,-1.26051,-1.15433,2.01754,-0.36880 +1.49343,1.00298,-1.46386,-1.25998,-1.15454,2.01777,-0.36902 +1.49542,1.00268,-1.46426,-1.25946,-1.15475,2.01799,-0.36925 +1.49741,1.00239,-1.46466,-1.25895,-1.15495,2.01821,-0.36947 +1.49940,1.00210,-1.46505,-1.25845,-1.15515,2.01842,-0.36968 +1.50139,1.00182,-1.46543,-1.25796,-1.15535,2.01863,-0.36989 +1.50339,1.00173,-1.46555,-1.25780,-1.15542,2.01870,-0.36996 +1.50538,1.00143,-1.46599,-1.25725,-1.15564,2.01892,-0.37019 +1.50737,1.00113,-1.46641,-1.25670,-1.15586,2.01915,-0.37041 +1.50936,1.00084,-1.46683,-1.25616,-1.15608,2.01936,-0.37063 +1.51135,1.00055,-1.46723,-1.25563,-1.15629,2.01958,-0.37085 +1.51334,1.00026,-1.46764,-1.25510,-1.15650,2.01979,-0.37107 +1.51533,0.99998,-1.46803,-1.25459,-1.15671,2.02000,-0.37128 +1.51732,0.99971,-1.46842,-1.25408,-1.15692,2.02021,-0.37148 +1.51932,0.99954,-1.46866,-1.25377,-1.15704,2.02033,-0.37161 +1.52131,0.99922,-1.46912,-1.25318,-1.15728,2.02057,-0.37185 +1.52330,0.99890,-1.46957,-1.25261,-1.15751,2.02081,-0.37209 +1.52529,0.99859,-1.47001,-1.25204,-1.15773,2.02104,-0.37233 +1.52728,0.99828,-1.47044,-1.25148,-1.15796,2.02127,-0.37256 +1.52927,0.99798,-1.47087,-1.25093,-1.15818,2.02149,-0.37278 +1.53126,0.99768,-1.47129,-1.25038,-1.15840,2.02171,-0.37301 +1.53325,0.99739,-1.47170,-1.24985,-1.15862,2.02193,-0.37322 +1.53524,0.99710,-1.47211,-1.24932,-1.15883,2.02214,-0.37344 +1.53724,0.99682,-1.47251,-1.24880,-1.15904,2.02235,-0.37365 +1.53923,0.99655,-1.47290,-1.24829,-1.15925,2.02255,-0.37386 +1.54122,0.99627,-1.47329,-1.24778,-1.15946,2.02276,-0.37407 +1.54321,0.99624,-1.47334,-1.24772,-1.15948,2.02278,-0.37409 +1.54520,0.99590,-1.47383,-1.24707,-1.15974,2.02303,-0.37434 +1.54719,0.99557,-1.47432,-1.24643,-1.15999,2.02328,-0.37459 +1.54918,0.99525,-1.47480,-1.24580,-1.16024,2.02352,-0.37484 +1.55117,0.99493,-1.47528,-1.24518,-1.16049,2.02375,-0.37508 +1.55317,0.99462,-1.47574,-1.24457,-1.16074,2.02398,-0.37531 +1.55516,0.99431,-1.47620,-1.24397,-1.16098,2.02421,-0.37555 +1.55715,0.99401,-1.47665,-1.24338,-1.16122,2.02444,-0.37577 +1.55914,0.99371,-1.47710,-1.24280,-1.16145,2.02466,-0.37600 +1.56113,0.99341,-1.47753,-1.24222,-1.16169,2.02488,-0.37622 +1.56312,0.99313,-1.47796,-1.24165,-1.16192,2.02509,-0.37644 +1.56511,0.99284,-1.47839,-1.24110,-1.16215,2.02530,-0.37665 +1.56710,0.99257,-1.47880,-1.24055,-1.16237,2.02551,-0.37686 +1.56910,0.99229,-1.47921,-1.24000,-1.16259,2.02571,-0.37707 +1.57109,0.99202,-1.47961,-1.23947,-1.16281,2.02591,-0.37727 +1.57308,0.99176,-1.48001,-1.23894,-1.16303,2.02611,-0.37747 +1.57507,0.99149,-1.48041,-1.23841,-1.16325,2.02630,-0.37768 +1.57706,0.99118,-1.48086,-1.23781,-1.16349,2.02653,-0.37791 +1.57905,0.99088,-1.48132,-1.23722,-1.16373,2.02676,-0.37814 +1.58104,0.99058,-1.48176,-1.23664,-1.16397,2.02698,-0.37837 +1.58303,0.99029,-1.48220,-1.23606,-1.16420,2.02720,-0.37859 +1.58503,0.99000,-1.48263,-1.23550,-1.16443,2.02741,-0.37881 +1.58702,0.98971,-1.48305,-1.23494,-1.16466,2.02762,-0.37902 +1.58901,0.98943,-1.48347,-1.23439,-1.16489,2.02783,-0.37923 +1.59100,0.98916,-1.48387,-1.23385,-1.16511,2.02804,-0.37944 +1.59299,0.98889,-1.48428,-1.23331,-1.16533,2.02824,-0.37965 +1.59498,0.98862,-1.48467,-1.23279,-1.16555,2.02843,-0.37985 +1.59697,0.98836,-1.48506,-1.23227,-1.16576,2.02863,-0.38005 +1.59896,0.98833,-1.48511,-1.23220,-1.16579,2.02865,-0.38007 +1.60096,0.98800,-1.48560,-1.23156,-1.16605,2.02890,-0.38032 +1.60295,0.98768,-1.48609,-1.23093,-1.16630,2.02914,-0.38057 +1.60494,0.98736,-1.48656,-1.23031,-1.16655,2.02937,-0.38081 +1.60693,0.98704,-1.48703,-1.22970,-1.16680,2.02960,-0.38105 +1.60892,0.98673,-1.48749,-1.22909,-1.16704,2.02983,-0.38128 +1.61091,0.98643,-1.48794,-1.22850,-1.16729,2.03005,-0.38151 +1.61290,0.98613,-1.48839,-1.22791,-1.16753,2.03027,-0.38173 +1.61489,0.98584,-1.48882,-1.22734,-1.16776,2.03049,-0.38196 +1.61689,0.98555,-1.48925,-1.22677,-1.16800,2.03070,-0.38218 +1.61888,0.98527,-1.48968,-1.22620,-1.16823,2.03091,-0.38239 +1.62087,0.98499,-1.49010,-1.22565,-1.16846,2.03112,-0.38260 +1.62286,0.98472,-1.49051,-1.22511,-1.16868,2.03132,-0.38281 +1.62485,0.98445,-1.49091,-1.22457,-1.16891,2.03152,-0.38301 +1.62684,0.98419,-1.49131,-1.22404,-1.16913,2.03172,-0.38322 +1.62883,0.98393,-1.49170,-1.22352,-1.16934,2.03191,-0.38341 +1.63082,0.98386,-1.49179,-1.22339,-1.16939,2.03196,-0.38346 +1.63282,0.98348,-1.49236,-1.22266,-1.16968,2.03224,-0.38375 +1.63481,0.98311,-1.49292,-1.22194,-1.16997,2.03251,-0.38403 +1.63680,0.98274,-1.49347,-1.22122,-1.17026,2.03278,-0.38431 +1.63879,0.98238,-1.49401,-1.22052,-1.17054,2.03305,-0.38458 +1.64078,0.98203,-1.49454,-1.21983,-1.17081,2.03331,-0.38485 +1.64277,0.98168,-1.49506,-1.21915,-1.17109,2.03357,-0.38512 +1.64476,0.98134,-1.49558,-1.21847,-1.17136,2.03382,-0.38538 +1.64675,0.98100,-1.49608,-1.21781,-1.17163,2.03407,-0.38563 +1.64875,0.98067,-1.49658,-1.21716,-1.17189,2.03431,-0.38589 +1.65074,0.98034,-1.49707,-1.21651,-1.17216,2.03455,-0.38613 +1.65273,0.98002,-1.49755,-1.21588,-1.17242,2.03479,-0.38638 +1.65472,0.97971,-1.49803,-1.21525,-1.17267,2.03502,-0.38662 +1.65671,0.97940,-1.49849,-1.21464,-1.17292,2.03525,-0.38685 +1.65870,0.97909,-1.49895,-1.21403,-1.17317,2.03547,-0.38708 +1.66069,0.97880,-1.49941,-1.21343,-1.17342,2.03569,-0.38731 +1.66268,0.97850,-1.49985,-1.21284,-1.17367,2.03591,-0.38754 +1.66468,0.97821,-1.50029,-1.21226,-1.17391,2.03612,-0.38776 +1.66667,0.97793,-1.50072,-1.21169,-1.17415,2.03633,-0.38797 +1.66866,0.97765,-1.50114,-1.21112,-1.17438,2.03654,-0.38819 +1.67065,0.97738,-1.50156,-1.21057,-1.17461,2.03674,-0.38840 +1.67264,0.97711,-1.50197,-1.21002,-1.17484,2.03694,-0.38860 +1.67463,0.97684,-1.50237,-1.20948,-1.17507,2.03714,-0.38881 +1.67662,0.97658,-1.50277,-1.20894,-1.17530,2.03733,-0.38901 +1.67861,0.97633,-1.50316,-1.20842,-1.17552,2.03752,-0.38920 +1.68061,0.97630,-1.50320,-1.20836,-1.17554,2.03754,-0.38923 +1.68260,0.97599,-1.50366,-1.20775,-1.17580,2.03777,-0.38946 +1.68459,0.97570,-1.50411,-1.20715,-1.17604,2.03799,-0.38969 +1.68658,0.97540,-1.50456,-1.20656,-1.17629,2.03820,-0.38991 +1.68857,0.97512,-1.50500,-1.20598,-1.17653,2.03841,-0.39013 +1.69056,0.97483,-1.50543,-1.20540,-1.17677,2.03862,-0.39035 +1.69255,0.97455,-1.50585,-1.20484,-1.17701,2.03883,-0.39056 +1.69454,0.97428,-1.50627,-1.20428,-1.17724,2.03903,-0.39077 +1.69654,0.97401,-1.50668,-1.20373,-1.17747,2.03923,-0.39098 +1.69853,0.97375,-1.50708,-1.20319,-1.17770,2.03943,-0.39118 +1.70052,0.97349,-1.50748,-1.20266,-1.17792,2.03962,-0.39138 +1.70251,0.97323,-1.50787,-1.20213,-1.17815,2.03981,-0.39158 +1.70450,0.97320,-1.50791,-1.20208,-1.17817,2.03983,-0.39160 +1.70649,0.97291,-1.50835,-1.20150,-1.17841,2.04005,-0.39183 +1.70848,0.97262,-1.50879,-1.20093,-1.17865,2.04026,-0.39205 +1.71047,0.97233,-1.50921,-1.20037,-1.17888,2.04047,-0.39227 +1.71247,0.97205,-1.50963,-1.19982,-1.17911,2.04068,-0.39249 +1.71446,0.97177,-1.51004,-1.19927,-1.17934,2.04088,-0.39270 +1.71645,0.97150,-1.51044,-1.19873,-1.17957,2.04108,-0.39291 +1.71844,0.97124,-1.51084,-1.19820,-1.17979,2.04128,-0.39311 +1.72043,0.97097,-1.51123,-1.19768,-1.18001,2.04147,-0.39331 +1.72242,0.97082,-1.51147,-1.19737,-1.18014,2.04159,-0.39344 +1.72441,0.97053,-1.51190,-1.19681,-1.18038,2.04180,-0.39366 +1.72640,0.97025,-1.51231,-1.19625,-1.18061,2.04201,-0.39387 +1.72840,0.96997,-1.51273,-1.19571,-1.18084,2.04221,-0.39409 +1.73039,0.96970,-1.51313,-1.19517,-1.18106,2.04241,-0.39430 +1.73238,0.96943,-1.51353,-1.19464,-1.18129,2.04261,-0.39450 +1.73437,0.96916,-1.51392,-1.19412,-1.18151,2.04281,-0.39471 +1.73636,0.96898,-1.51420,-1.19376,-1.18166,2.04294,-0.39485 +1.73835,0.96869,-1.51462,-1.19320,-1.18189,2.04316,-0.39507 +1.74034,0.96841,-1.51504,-1.19265,-1.18213,2.04336,-0.39529 +1.74233,0.96813,-1.51545,-1.19210,-1.18235,2.04357,-0.39550 +1.74432,0.96786,-1.51586,-1.19157,-1.18258,2.04377,-0.39572 +1.74632,0.96759,-1.51626,-1.19104,-1.18280,2.04397,-0.39592 +1.74831,0.96732,-1.51665,-1.19052,-1.18302,2.04416,-0.39613 +1.75030,0.96711,-1.51697,-1.19010,-1.18320,2.04432,-0.39629 +1.75229,0.96681,-1.51740,-1.18953,-1.18343,2.04454,-0.39652 +1.75428,0.96651,-1.51783,-1.18897,-1.18367,2.04476,-0.39675 +1.75627,0.96622,-1.51825,-1.18842,-1.18390,2.04497,-0.39697 +1.75826,0.96594,-1.51867,-1.18787,-1.18412,2.04518,-0.39719 +1.76025,0.96566,-1.51908,-1.18734,-1.18435,2.04539,-0.39741 +1.76225,0.96538,-1.51948,-1.18681,-1.18457,2.04559,-0.39762 +1.76424,0.96511,-1.51988,-1.18629,-1.18479,2.04579,-0.39783 +1.76623,0.96484,-1.52027,-1.18578,-1.18501,2.04599,-0.39804 +1.76822,0.96471,-1.52046,-1.18552,-1.18512,2.04609,-0.39814 +1.77021,0.96442,-1.52089,-1.18496,-1.18535,2.04630,-0.39837 +1.77220,0.96413,-1.52130,-1.18442,-1.18558,2.04651,-0.39859 +1.77419,0.96385,-1.52172,-1.18388,-1.18580,2.04672,-0.39881 +1.77618,0.96357,-1.52212,-1.18335,-1.18603,2.04692,-0.39902 +1.77818,0.96330,-1.52252,-1.18282,-1.18625,2.04712,-0.39923 +1.78017,0.96304,-1.52291,-1.18231,-1.18647,2.04732,-0.39944 +1.78216,0.96282,-1.52322,-1.18190,-1.18664,2.04748,-0.39960 +1.78415,0.96250,-1.52366,-1.18135,-1.18687,2.04771,-0.39985 +1.78614,0.96218,-1.52409,-1.18080,-1.18709,2.04794,-0.40010 +1.78813,0.96187,-1.52451,-1.18027,-1.18732,2.04817,-0.40034 +1.79012,0.96156,-1.52493,-1.17974,-1.18753,2.04840,-0.40057 +1.79211,0.96126,-1.52534,-1.17922,-1.18775,2.04862,-0.40081 +1.79411,0.96097,-1.52574,-1.17870,-1.18797,2.04883,-0.40103 +1.79610,0.96068,-1.52613,-1.17820,-1.18818,2.04905,-0.40126 +1.79809,0.96039,-1.52652,-1.17770,-1.18839,2.04926,-0.40148 +1.80008,0.96011,-1.52691,-1.17721,-1.18860,2.04946,-0.40170 +1.80207,0.95994,-1.52714,-1.17691,-1.18872,2.04959,-0.40183 +1.80406,0.95962,-1.52756,-1.17639,-1.18894,2.04982,-0.40208 +1.80605,0.95930,-1.52797,-1.17588,-1.18915,2.05006,-0.40232 +1.80804,0.95899,-1.52838,-1.17537,-1.18936,2.05028,-0.40257 +1.81004,0.95868,-1.52878,-1.17487,-1.18957,2.05051,-0.40280 +1.81203,0.95838,-1.52917,-1.17438,-1.18977,2.05073,-0.40304 +1.81402,0.95808,-1.52955,-1.17390,-1.18998,2.05095,-0.40327 +1.81601,0.95779,-1.52994,-1.17342,-1.19018,2.05116,-0.40349 +1.81800,0.95753,-1.53028,-1.17299,-1.19036,2.05135,-0.40370 +1.81999,0.95719,-1.53070,-1.17247,-1.19057,2.05160,-0.40396 +1.82198,0.95685,-1.53112,-1.17197,-1.19078,2.05185,-0.40422 +1.82397,0.95652,-1.53153,-1.17147,-1.19098,2.05209,-0.40448 +1.82597,0.95619,-1.53194,-1.17097,-1.19119,2.05233,-0.40473 +1.82796,0.95587,-1.53234,-1.17049,-1.19139,2.05257,-0.40498 +1.82995,0.95555,-1.53273,-1.17001,-1.19159,2.05280,-0.40522 +1.83194,0.95525,-1.53312,-1.16953,-1.19178,2.05302,-0.40547 +1.83393,0.95494,-1.53350,-1.16907,-1.19198,2.05325,-0.40570 +1.83592,0.95464,-1.53387,-1.16861,-1.19217,2.05347,-0.40593 +1.83791,0.95440,-1.53417,-1.16824,-1.19233,2.05364,-0.40612 +1.83990,0.95408,-1.53456,-1.16776,-1.19252,2.05388,-0.40637 +1.84190,0.95376,-1.53496,-1.16729,-1.19272,2.05411,-0.40662 +1.84389,0.95344,-1.53534,-1.16683,-1.19291,2.05434,-0.40687 +1.84588,0.95313,-1.53572,-1.16637,-1.19310,2.05457,-0.40711 +1.84787,0.95282,-1.53609,-1.16592,-1.19329,2.05479,-0.40735 +1.84986,0.95253,-1.53646,-1.16547,-1.19348,2.05501,-0.40758 +1.85185,0.95249,-1.53650,-1.16542,-1.19350,2.05504,-0.40761 +1.85384,0.95215,-1.53690,-1.16495,-1.19370,2.05529,-0.40787 +1.85583,0.95181,-1.53730,-1.16447,-1.19389,2.05554,-0.40813 +1.85783,0.95148,-1.53769,-1.16401,-1.19408,2.05578,-0.40839 +1.85982,0.95115,-1.53808,-1.16355,-1.19427,2.05602,-0.40864 +1.86181,0.95083,-1.53846,-1.16310,-1.19446,2.05625,-0.40889 +1.86380,0.95052,-1.53883,-1.16265,-1.19465,2.05648,-0.40914 +1.86579,0.95021,-1.53920,-1.16221,-1.19483,2.05670,-0.40938 +1.86778,0.94990,-1.53956,-1.16178,-1.19501,2.05693,-0.40962 +1.86977,0.94957,-1.53993,-1.16135,-1.19519,2.05717,-0.40987 +1.87176,0.94925,-1.54030,-1.16093,-1.19536,2.05741,-0.41013 +1.87376,0.94893,-1.54065,-1.16051,-1.19554,2.05764,-0.41037 +1.87575,0.94871,-1.54090,-1.16023,-1.19566,2.05780,-0.41055 +1.87774,0.94837,-1.54126,-1.15983,-1.19582,2.05805,-0.41081 +1.87973,0.94804,-1.54162,-1.15943,-1.19599,2.05829,-0.41107 +1.88172,0.94771,-1.54196,-1.15904,-1.19615,2.05853,-0.41133 +1.88371,0.94748,-1.54221,-1.15877,-1.19626,2.05870,-0.41151 +1.88570,0.94713,-1.54256,-1.15838,-1.19642,2.05895,-0.41178 +1.88769,0.94679,-1.54290,-1.15801,-1.19657,2.05920,-0.41205 +1.88969,0.94645,-1.54325,-1.15764,-1.19672,2.05945,-0.41231 +1.89168,0.94615,-1.54355,-1.15731,-1.19686,2.05966,-0.41254 +1.89367,0.94581,-1.54389,-1.15694,-1.19701,2.05991,-0.41281 +1.89566,0.94548,-1.54423,-1.15657,-1.19716,2.06015,-0.41307 +1.89765,0.94545,-1.54426,-1.15654,-1.19718,2.06018,-0.41309 +1.89964,0.94510,-1.54459,-1.15619,-1.19732,2.06043,-0.41336 +1.90163,0.94479,-1.54489,-1.15588,-1.19745,2.06065,-0.41360 +1.90362,0.94443,-1.54522,-1.15554,-1.19759,2.06092,-0.41389 +1.90562,0.94407,-1.54555,-1.15521,-1.19772,2.06118,-0.41416 +1.90761,0.94372,-1.54587,-1.15488,-1.19786,2.06143,-0.41444 +1.90960,0.94337,-1.54619,-1.15455,-1.19799,2.06169,-0.41471 +1.91159,0.94300,-1.54652,-1.15423,-1.19812,2.06196,-0.41500 +1.91358,0.94264,-1.54684,-1.15392,-1.19824,2.06222,-0.41528 +1.91557,0.94228,-1.54716,-1.15361,-1.19837,2.06248,-0.41556 +1.91756,0.94193,-1.54747,-1.15330,-1.19849,2.06273,-0.41584 +1.91955,0.94189,-1.54750,-1.15328,-1.19850,2.06276,-0.41587 +1.92155,0.94151,-1.54781,-1.15300,-1.19861,2.06304,-0.41616 +1.92354,0.94114,-1.54811,-1.15272,-1.19872,2.06331,-0.41646 +1.92553,0.94077,-1.54841,-1.15245,-1.19883,2.06358,-0.41674 +1.92752,0.94041,-1.54870,-1.15219,-1.19894,2.06384,-0.41703 +1.92951,0.94033,-1.54876,-1.15214,-1.19896,2.06390,-0.41709 +1.93150,0.93993,-1.54905,-1.15191,-1.19905,2.06419,-0.41741 +1.93349,0.93952,-1.54934,-1.15168,-1.19913,2.06448,-0.41772 +1.93548,0.93913,-1.54963,-1.15146,-1.19922,2.06477,-0.41803 +1.93748,0.93874,-1.54990,-1.15124,-1.19930,2.06505,-0.41833 +1.93947,0.93836,-1.55018,-1.15103,-1.19939,2.06533,-0.41863 +1.94146,0.93799,-1.55045,-1.15081,-1.19947,2.06560,-0.41892 +1.94345,0.93780,-1.55058,-1.15071,-1.19951,2.06573,-0.41907 +1.94544,0.93740,-1.55085,-1.15052,-1.19958,2.06603,-0.41938 +1.94743,0.93700,-1.55111,-1.15034,-1.19965,2.06631,-0.41969 +1.94942,0.93662,-1.55137,-1.15016,-1.19972,2.06659,-0.42000 +1.95141,0.93624,-1.55162,-1.14998,-1.19979,2.06687,-0.42029 +1.95341,0.93601,-1.55177,-1.14987,-1.19983,2.06703,-0.42047 +1.95540,0.93562,-1.55202,-1.14971,-1.19989,2.06731,-0.42078 +1.95739,0.93524,-1.55226,-1.14954,-1.19995,2.06759,-0.42108 +1.95938,0.93509,-1.55236,-1.14948,-1.19998,2.06770,-0.42119 +1.96137,0.93470,-1.55260,-1.14933,-1.20003,2.06798,-0.42150 +1.96336,0.93432,-1.55284,-1.14919,-1.20009,2.06826,-0.42180 +1.96535,0.93416,-1.55293,-1.14913,-1.20011,2.06837,-0.42192 +1.96734,0.93375,-1.55316,-1.14901,-1.20015,2.06867,-0.42225 +1.96933,0.93335,-1.55339,-1.14889,-1.20019,2.06896,-0.42256 +1.97133,0.93295,-1.55362,-1.14877,-1.20023,2.06925,-0.42287 +1.97332,0.93256,-1.55384,-1.14865,-1.20027,2.06953,-0.42318 +1.97531,0.93226,-1.55402,-1.14856,-1.20030,2.06975,-0.42342 +1.97730,0.93186,-1.55424,-1.14846,-1.20034,2.07004,-0.42373 +1.97929,0.93147,-1.55445,-1.14836,-1.20037,2.07032,-0.42404 +1.98128,0.93124,-1.55458,-1.14830,-1.20039,2.07048,-0.42422 +1.98327,0.93084,-1.55478,-1.14823,-1.20041,2.07078,-0.42453 +1.98526,0.93045,-1.55498,-1.14817,-1.20043,2.07106,-0.42485 +1.98726,0.93006,-1.55517,-1.14810,-1.20045,2.07134,-0.42515 +1.98925,0.92998,-1.55521,-1.14809,-1.20045,2.07140,-0.42521 +1.99124,0.92958,-1.55540,-1.14803,-1.20047,2.07169,-0.42553 +1.99323,0.92919,-1.55559,-1.14798,-1.20048,2.07197,-0.42583 +1.99522,0.92896,-1.55570,-1.14795,-1.20049,2.07214,-0.42602 +1.99721,0.92856,-1.55589,-1.14791,-1.20050,2.07242,-0.42633 +1.99920,0.92817,-1.55607,-1.14786,-1.20051,2.07271,-0.42664 +2.00119,0.92794,-1.55618,-1.14784,-1.20051,2.07287,-0.42682 +2.00319,0.92763,-1.55631,-1.14783,-1.20051,2.07310,-0.42707 +2.00518,0.92728,-1.55645,-1.14783,-1.20050,2.07335,-0.42734 +2.00717,0.92688,-1.55660,-1.14784,-1.20049,2.07364,-0.42766 +2.00916,0.92649,-1.55676,-1.14786,-1.20047,2.07392,-0.42797 +2.01115,0.92622,-1.55686,-1.14787,-1.20046,2.07412,-0.42818 +2.01314,0.92582,-1.55701,-1.14789,-1.20044,2.07441,-0.42850 +2.01513,0.92543,-1.55716,-1.14791,-1.20042,2.07469,-0.42880 +2.01712,0.92519,-1.55725,-1.14792,-1.20041,2.07486,-0.42899 +2.01912,0.92480,-1.55739,-1.14796,-1.20039,2.07514,-0.42930 +2.02111,0.92440,-1.55753,-1.14799,-1.20036,2.07543,-0.42961 +2.02310,0.92413,-1.55763,-1.14801,-1.20035,2.07562,-0.42983 +2.02509,0.92373,-1.55776,-1.14807,-1.20031,2.07592,-0.43015 +2.02708,0.92333,-1.55789,-1.14814,-1.20027,2.07620,-0.43046 +2.02907,0.92294,-1.55802,-1.14820,-1.20024,2.07648,-0.43077 +2.03106,0.92267,-1.55811,-1.14824,-1.20021,2.07668,-0.43099 +2.03305,0.92227,-1.55822,-1.14833,-1.20016,2.07697,-0.43130 +2.03505,0.92187,-1.55833,-1.14842,-1.20011,2.07725,-0.43162 +2.03704,0.92148,-1.55844,-1.14851,-1.20007,2.07753,-0.43193 +2.03903,0.92118,-1.55853,-1.14857,-1.20003,2.07776,-0.43217 +2.04102,0.92078,-1.55864,-1.14867,-1.19998,2.07804,-0.43248 +2.04301,0.92039,-1.55875,-1.14876,-1.19993,2.07832,-0.43279 +2.04500,0.92013,-1.55882,-1.14883,-1.19989,2.07851,-0.43300 +2.04699,0.91972,-1.55892,-1.14895,-1.19983,2.07880,-0.43332 +2.04898,0.91933,-1.55901,-1.14907,-1.19977,2.07909,-0.43363 +2.05098,0.91895,-1.55911,-1.14919,-1.19970,2.07936,-0.43394 +2.05297,0.91860,-1.55919,-1.14930,-1.19965,2.07961,-0.43421 +2.05496,0.91821,-1.55928,-1.14942,-1.19959,2.07989,-0.43452 +2.05695,0.91783,-1.55937,-1.14954,-1.19952,2.08017,-0.43483 +2.05894,0.91752,-1.55944,-1.14964,-1.19947,2.08039,-0.43507 +2.06093,0.91715,-1.55952,-1.14978,-1.19940,2.08066,-0.43537 +2.06292,0.91707,-1.55954,-1.14981,-1.19939,2.08071,-0.43543 +2.06491,0.91669,-1.55960,-1.14997,-1.19931,2.08099,-0.43573 +2.06691,0.91658,-1.55962,-1.15002,-1.19928,2.08107,-0.43582 +2.06890,0.91621,-1.55968,-1.15020,-1.19920,2.08134,-0.43611 +2.07089,0.91610,-1.55969,-1.15025,-1.19917,2.08142,-0.43620 +2.07288,0.91572,-1.55974,-1.15045,-1.19908,2.08168,-0.43650 +2.07487,0.91558,-1.55975,-1.15053,-1.19904,2.08179,-0.43662 +2.07686,0.91521,-1.55979,-1.15074,-1.19894,2.08206,-0.43691 +2.07885,0.91506,-1.55980,-1.15083,-1.19890,2.08216,-0.43703 +2.08084,0.91469,-1.55982,-1.15105,-1.19879,2.08243,-0.43732 +2.08284,0.91451,-1.55983,-1.15117,-1.19874,2.08256,-0.43746 +2.08483,0.91415,-1.55984,-1.15141,-1.19863,2.08282,-0.43775 +2.08682,0.91397,-1.55985,-1.15154,-1.19857,2.08295,-0.43790 +2.08881,0.91356,-1.55984,-1.15185,-1.19843,2.08324,-0.43822 +2.09080,0.91317,-1.55984,-1.15215,-1.19829,2.08352,-0.43853 +2.09279,0.91278,-1.55984,-1.15244,-1.19815,2.08380,-0.43884 +2.09478,0.91240,-1.55983,-1.15273,-1.19802,2.08408,-0.43915 +2.09677,0.91202,-1.55983,-1.15302,-1.19788,2.08435,-0.43945 +2.09877,0.91166,-1.55983,-1.15330,-1.19775,2.08461,-0.43974 +2.10076,0.91130,-1.55982,-1.15357,-1.19763,2.08487,-0.44003 +2.10275,0.91094,-1.55982,-1.15384,-1.19750,2.08513,-0.44031 +2.10474,0.91087,-1.55982,-1.15390,-1.19747,2.08518,-0.44037 +2.10673,0.91049,-1.55979,-1.15422,-1.19732,2.08545,-0.44067 +2.10872,0.91012,-1.55977,-1.15453,-1.19718,2.08572,-0.44097 +2.11071,0.90975,-1.55975,-1.15484,-1.19704,2.08598,-0.44126 +2.11270,0.90940,-1.55973,-1.15515,-1.19690,2.08623,-0.44154 +2.11470,0.90905,-1.55971,-1.15545,-1.19676,2.08649,-0.44183 +2.11669,0.90877,-1.55969,-1.15569,-1.19665,2.08669,-0.44205 +2.11868,0.90841,-1.55965,-1.15602,-1.19649,2.08694,-0.44233 +2.12067,0.90807,-1.55962,-1.15635,-1.19634,2.08719,-0.44261 +2.12266,0.90773,-1.55958,-1.15667,-1.19620,2.08743,-0.44288 +2.12465,0.90763,-1.55957,-1.15677,-1.19615,2.08751,-0.44296 +2.12664,0.90729,-1.55952,-1.15710,-1.19600,2.08775,-0.44323 +2.12863,0.90705,-1.55948,-1.15734,-1.19589,2.08792,-0.44342 +2.13063,0.90672,-1.55943,-1.15769,-1.19573,2.08816,-0.44369 +2.13262,0.90649,-1.55939,-1.15794,-1.19562,2.08833,-0.44387 +2.13461,0.90614,-1.55930,-1.15834,-1.19543,2.08857,-0.44415 +2.13660,0.90580,-1.55922,-1.15874,-1.19525,2.08882,-0.44442 +2.13859,0.90547,-1.55914,-1.15913,-1.19508,2.08906,-0.44469 +2.14058,0.90514,-1.55906,-1.15952,-1.19490,2.08929,-0.44495 +2.14257,0.90482,-1.55898,-1.15990,-1.19473,2.08952,-0.44521 +2.14456,0.90476,-1.55896,-1.15998,-1.19469,2.08957,-0.44526 +2.14656,0.90442,-1.55885,-1.16044,-1.19449,2.08981,-0.44553 +2.14855,0.90409,-1.55873,-1.16089,-1.19428,2.09005,-0.44580 +2.15054,0.90376,-1.55862,-1.16134,-1.19408,2.09028,-0.44606 +2.15253,0.90344,-1.55851,-1.16177,-1.19389,2.09051,-0.44632 +2.15452,0.90312,-1.55840,-1.16220,-1.19370,2.09074,-0.44657 +2.15651,0.90281,-1.55830,-1.16262,-1.19351,2.09096,-0.44682 +2.15850,0.90251,-1.55819,-1.16304,-1.19332,2.09118,-0.44706 +2.16049,0.90248,-1.55818,-1.16309,-1.19330,2.09120,-0.44709 +2.16249,0.90215,-1.55803,-1.16359,-1.19307,2.09144,-0.44735 +2.16448,0.90183,-1.55789,-1.16407,-1.19286,2.09166,-0.44761 +2.16647,0.90152,-1.55776,-1.16455,-1.19264,2.09189,-0.44786 +2.16846,0.90122,-1.55762,-1.16502,-1.19243,2.09211,-0.44810 +2.17045,0.90091,-1.55749,-1.16549,-1.19222,2.09232,-0.44835 +2.17244,0.90062,-1.55736,-1.16594,-1.19202,2.09254,-0.44858 +2.17443,0.90033,-1.55723,-1.16639,-1.19182,2.09274,-0.44882 +2.17642,0.90024,-1.55718,-1.16653,-1.19175,2.09281,-0.44889 +2.17841,0.89995,-1.55702,-1.16705,-1.19152,2.09301,-0.44912 +2.18041,0.89966,-1.55685,-1.16756,-1.19130,2.09322,-0.44935 +2.18240,0.89938,-1.55669,-1.16806,-1.19108,2.09342,-0.44958 +2.18439,0.89911,-1.55653,-1.16855,-1.19086,2.09362,-0.44980 +2.18638,0.89884,-1.55637,-1.16903,-1.19064,2.09381,-0.45002 +2.18837,0.89878,-1.55634,-1.16913,-1.19060,2.09385,-0.45006 +2.19036,0.89851,-1.55614,-1.16968,-1.19036,2.09405,-0.45028 +2.19235,0.89824,-1.55595,-1.17022,-1.19012,2.09424,-0.45050 +2.19434,0.89798,-1.55576,-1.17076,-1.18988,2.09443,-0.45071 +2.19634,0.89772,-1.55558,-1.17128,-1.18965,2.09461,-0.45092 +2.19833,0.89747,-1.55539,-1.17179,-1.18942,2.09480,-0.45112 +2.20032,0.89734,-1.55530,-1.17206,-1.18931,2.09489,-0.45122 +2.20231,0.89709,-1.55508,-1.17263,-1.18905,2.09507,-0.45143 +2.20430,0.89684,-1.55487,-1.17320,-1.18880,2.09525,-0.45163 +2.20629,0.89659,-1.55465,-1.17376,-1.18855,2.09542,-0.45183 +2.20828,0.89635,-1.55444,-1.17431,-1.18831,2.09560,-0.45202 +2.21027,0.89612,-1.55424,-1.17486,-1.18807,2.09577,-0.45221 +2.21227,0.89595,-1.55409,-1.17524,-1.18790,2.09588,-0.45235 +2.21426,0.89570,-1.55386,-1.17585,-1.18763,2.09607,-0.45255 +2.21625,0.89544,-1.55362,-1.17646,-1.18736,2.09625,-0.45275 +2.21824,0.89520,-1.55339,-1.17705,-1.18710,2.09642,-0.45295 +2.22023,0.89496,-1.55316,-1.17764,-1.18684,2.09659,-0.45315 +2.22222,0.89472,-1.55294,-1.17821,-1.18659,2.09676,-0.45334 +2.22421,0.89449,-1.55272,-1.17878,-1.18634,2.09693,-0.45353 +2.22620,0.89426,-1.55251,-1.17934,-1.18609,2.09709,-0.45371 +2.22820,0.89404,-1.55229,-1.17989,-1.18585,2.09725,-0.45389 +2.23019,0.89401,-1.55227,-1.17995,-1.18582,2.09727,-0.45391 +2.23218,0.89379,-1.55202,-1.18056,-1.18555,2.09743,-0.45409 +2.23417,0.89356,-1.55177,-1.18117,-1.18528,2.09759,-0.45427 +2.23616,0.89334,-1.55153,-1.18176,-1.18502,2.09775,-0.45445 +2.23815,0.89313,-1.55129,-1.18235,-1.18476,2.09791,-0.45462 +2.24014,0.89292,-1.55106,-1.18292,-1.18451,2.09806,-0.45480 +2.24213,0.89271,-1.55083,-1.18349,-1.18426,2.09821,-0.45496 +2.24413,0.89269,-1.55080,-1.18356,-1.18423,2.09822,-0.45498 +2.24612,0.89246,-1.55051,-1.18423,-1.18393,2.09838,-0.45516 +2.24811,0.89224,-1.55023,-1.18490,-1.18364,2.09854,-0.45534 +2.25010,0.89203,-1.54996,-1.18555,-1.18335,2.09869,-0.45552 +2.25209,0.89181,-1.54969,-1.18620,-1.18307,2.09885,-0.45569 +2.25408,0.89161,-1.54942,-1.18683,-1.18279,2.09900,-0.45585 +2.25607,0.89140,-1.54916,-1.18745,-1.18251,2.09914,-0.45602 +2.25806,0.89120,-1.54890,-1.18807,-1.18224,2.09928,-0.45618 +2.26006,0.89100,-1.54864,-1.18867,-1.18197,2.09943,-0.45634 +2.26205,0.89081,-1.54839,-1.18927,-1.18171,2.09956,-0.45650 +2.26404,0.89062,-1.54814,-1.18985,-1.18145,2.09970,-0.45665 +2.26603,0.89060,-1.54811,-1.18992,-1.18142,2.09971,-0.45666 +2.26802,0.89041,-1.54783,-1.19056,-1.18114,2.09985,-0.45682 +2.27001,0.89022,-1.54755,-1.19120,-1.18085,2.09999,-0.45697 +2.27200,0.89003,-1.54728,-1.19183,-1.18058,2.10012,-0.45712 +2.27399,0.88985,-1.54701,-1.19245,-1.18030,2.10025,-0.45727 +2.27599,0.88967,-1.54675,-1.19306,-1.18003,2.10038,-0.45742 +2.27798,0.88949,-1.54648,-1.19366,-1.17977,2.10051,-0.45756 +2.27997,0.88942,-1.54638,-1.19391,-1.17966,2.10056,-0.45762 +2.28196,0.88922,-1.54607,-1.19460,-1.17935,2.10071,-0.45778 +2.28395,0.88902,-1.54578,-1.19528,-1.17905,2.10085,-0.45795 +2.28594,0.88882,-1.54549,-1.19595,-1.17875,2.10099,-0.45810 +2.28793,0.88862,-1.54520,-1.19661,-1.17846,2.10113,-0.45826 +2.28992,0.88844,-1.54492,-1.19726,-1.17817,2.10126,-0.45841 +2.29192,0.88825,-1.54464,-1.19790,-1.17789,2.10140,-0.45856 +2.29391,0.88807,-1.54436,-1.19853,-1.17761,2.10153,-0.45871 +2.29590,0.88789,-1.54409,-1.19915,-1.17733,2.10165,-0.45885 +2.29789,0.88771,-1.54383,-1.19976,-1.17706,2.10178,-0.45900 +2.29988,0.88754,-1.54357,-1.20036,-1.17679,2.10190,-0.45914 +2.30187,0.88750,-1.54351,-1.20049,-1.17674,2.10193,-0.45916 +2.30386,0.88731,-1.54319,-1.20120,-1.17642,2.10206,-0.45932 +2.30585,0.88713,-1.54288,-1.20189,-1.17612,2.10220,-0.45947 +2.30785,0.88694,-1.54258,-1.20258,-1.17581,2.10233,-0.45962 +2.30984,0.88676,-1.54228,-1.20325,-1.17551,2.10245,-0.45976 +2.31183,0.88659,-1.54199,-1.20391,-1.17522,2.10258,-0.45990 +2.31382,0.88642,-1.54170,-1.20456,-1.17493,2.10270,-0.46004 +2.31581,0.88625,-1.54141,-1.20520,-1.17465,2.10282,-0.46018 +2.31780,0.88608,-1.54113,-1.20584,-1.17436,2.10294,-0.46031 +2.31979,0.88592,-1.54085,-1.20646,-1.17409,2.10306,-0.46044 +2.32178,0.88576,-1.54058,-1.20707,-1.17381,2.10317,-0.46057 +2.32378,0.88569,-1.54047,-1.20731,-1.17370,2.10322,-0.46062 +2.32577,0.88554,-1.54017,-1.20796,-1.17342,2.10333,-0.46075 +2.32776,0.88538,-1.53988,-1.20860,-1.17313,2.10344,-0.46087 +2.32975,0.88523,-1.53959,-1.20923,-1.17285,2.10355,-0.46100 +2.33174,0.88508,-1.53931,-1.20985,-1.17257,2.10366,-0.46112 +2.33373,0.88499,-1.53914,-1.21023,-1.17241,2.10372,-0.46119 +2.33572,0.88482,-1.53883,-1.21092,-1.17210,2.10384,-0.46133 +2.33771,0.88465,-1.53852,-1.21160,-1.17180,2.10396,-0.46146 +2.33971,0.88449,-1.53822,-1.21227,-1.17150,2.10408,-0.46159 +2.34170,0.88433,-1.53792,-1.21292,-1.17121,2.10419,-0.46172 +2.34369,0.88417,-1.53763,-1.21357,-1.17092,2.10430,-0.46185 +2.34568,0.88401,-1.53734,-1.21420,-1.17064,2.10441,-0.46197 +2.34767,0.88386,-1.53706,-1.21483,-1.17036,2.10452,-0.46210 +2.34966,0.88371,-1.53678,-1.21545,-1.17008,2.10463,-0.46222 +2.35165,0.88367,-1.53669,-1.21564,-1.16999,2.10466,-0.46225 +2.35364,0.88351,-1.53637,-1.21634,-1.16968,2.10478,-0.46238 +2.35564,0.88335,-1.53605,-1.21703,-1.16938,2.10489,-0.46251 +2.35763,0.88320,-1.53574,-1.21770,-1.16908,2.10500,-0.46263 +2.35962,0.88304,-1.53543,-1.21837,-1.16878,2.10511,-0.46276 +2.36161,0.88290,-1.53513,-1.21902,-1.16849,2.10521,-0.46287 +2.36360,0.88275,-1.53484,-1.21967,-1.16820,2.10531,-0.46299 +2.36559,0.88261,-1.53454,-1.22030,-1.16792,2.10542,-0.46311 +2.36758,0.88247,-1.53426,-1.22093,-1.16764,2.10552,-0.46322 +2.36957,0.88238,-1.53408,-1.22130,-1.16747,2.10557,-0.46329 +2.37157,0.88225,-1.53377,-1.22196,-1.16717,2.10567,-0.46340 +2.37356,0.88211,-1.53347,-1.22261,-1.16688,2.10577,-0.46350 +2.37555,0.88198,-1.53317,-1.22325,-1.16660,2.10586,-0.46361 +2.37754,0.88185,-1.53287,-1.22388,-1.16632,2.10596,-0.46371 +2.37953,0.88176,-1.53266,-1.22433,-1.16612,2.10602,-0.46379 +2.38152,0.88162,-1.53234,-1.22501,-1.16581,2.10611,-0.46389 +2.38351,0.88149,-1.53202,-1.22569,-1.16551,2.10621,-0.46400 +2.38550,0.88136,-1.53170,-1.22636,-1.16522,2.10630,-0.46410 +2.38750,0.88124,-1.53139,-1.22701,-1.16493,2.10639,-0.46421 +2.38949,0.88111,-1.53108,-1.22766,-1.16464,2.10648,-0.46430 +2.39148,0.88099,-1.53078,-1.22829,-1.16436,2.10656,-0.46440 +2.39347,0.88091,-1.53057,-1.22873,-1.16416,2.10662,-0.46447 +2.39546,0.88078,-1.53026,-1.22939,-1.16386,2.10672,-0.46457 +2.39745,0.88065,-1.52995,-1.23004,-1.16357,2.10681,-0.46468 +2.39944,0.88052,-1.52965,-1.23068,-1.16329,2.10690,-0.46478 +2.40143,0.88040,-1.52935,-1.23131,-1.16301,2.10698,-0.46488 +2.40342,0.88036,-1.52926,-1.23150,-1.16292,2.10701,-0.46491 +2.40542,0.88023,-1.52895,-1.23216,-1.16263,2.10711,-0.46501 +2.40741,0.88010,-1.52865,-1.23280,-1.16234,2.10720,-0.46512 +2.40940,0.87997,-1.52835,-1.23344,-1.16205,2.10729,-0.46522 +2.41139,0.87984,-1.52806,-1.23407,-1.16177,2.10738,-0.46532 +2.41338,0.87981,-1.52797,-1.23425,-1.16169,2.10741,-0.46535 +2.41537,0.87968,-1.52767,-1.23489,-1.16140,2.10750,-0.46546 +2.41736,0.87955,-1.52738,-1.23551,-1.16112,2.10759,-0.46556 +2.41935,0.87952,-1.52732,-1.23564,-1.16107,2.10761,-0.46558 +2.42135,0.87939,-1.52703,-1.23627,-1.16078,2.10770,-0.46568 +2.42334,0.87927,-1.52674,-1.23689,-1.16050,2.10779,-0.46578 +2.42533,0.87924,-1.52668,-1.23702,-1.16045,2.10781,-0.46581 +2.42732,0.87911,-1.52638,-1.23765,-1.16016,2.10790,-0.46591 +2.42931,0.87898,-1.52609,-1.23827,-1.15988,2.10799,-0.46601 +2.43130,0.87895,-1.52604,-1.23840,-1.15983,2.10801,-0.46603 +2.43329,0.87882,-1.52574,-1.23903,-1.15954,2.10810,-0.46614 +2.43528,0.87869,-1.52545,-1.23965,-1.15926,2.10820,-0.46625 +2.43728,0.87865,-1.52546,-1.23968,-1.15924,2.10823,-0.46628 +2.43927,0.87834,-1.52581,-1.23938,-1.15931,2.10845,-0.46653 +2.44126,0.87821,-1.52595,-1.23926,-1.15934,2.10853,-0.46663 +2.44325,0.87789,-1.52634,-1.23889,-1.15944,2.10876,-0.46688 +2.44524,0.87757,-1.52672,-1.23853,-1.15953,2.10898,-0.46714 +2.44723,0.87726,-1.52710,-1.23817,-1.15963,2.10920,-0.46739 +2.44922,0.87695,-1.52748,-1.23782,-1.15972,2.10942,-0.46763 +2.45121,0.87665,-1.52784,-1.23748,-1.15981,2.10963,-0.46787 +2.45321,0.87635,-1.52820,-1.23714,-1.15991,2.10984,-0.46811 +2.45520,0.87629,-1.52828,-1.23706,-1.15993,2.10988,-0.46816 +2.45719,0.87597,-1.52867,-1.23667,-1.16004,2.11011,-0.46841 +2.45918,0.87566,-1.52907,-1.23629,-1.16015,2.11033,-0.46866 +2.46117,0.87536,-1.52945,-1.23591,-1.16026,2.11054,-0.46891 +2.46316,0.87506,-1.52983,-1.23554,-1.16037,2.11075,-0.46915 +2.46515,0.87476,-1.53020,-1.23517,-1.16047,2.11096,-0.46939 +2.46714,0.87447,-1.53057,-1.23481,-1.16058,2.11117,-0.46962 +2.46914,0.87441,-1.53064,-1.23473,-1.16060,2.11121,-0.46967 +2.47113,0.87409,-1.53106,-1.23431,-1.16073,2.11144,-0.46993 +2.47312,0.87377,-1.53147,-1.23390,-1.16086,2.11166,-0.47018 +2.47511,0.87346,-1.53187,-1.23349,-1.16099,2.11188,-0.47043 +2.47710,0.87315,-1.53226,-1.23309,-1.16111,2.11209,-0.47068 +2.47909,0.87285,-1.53265,-1.23269,-1.16124,2.11231,-0.47092 +2.48108,0.87256,-1.53303,-1.23230,-1.16136,2.11251,-0.47116 +2.48307,0.87227,-1.53341,-1.23192,-1.16148,2.11272,-0.47139 +2.48507,0.87198,-1.53378,-1.23154,-1.16160,2.11292,-0.47162 +2.48706,0.87192,-1.53386,-1.23145,-1.16163,2.11296,-0.47167 +2.48905,0.87160,-1.53430,-1.23098,-1.16178,2.11319,-0.47193 +2.49104,0.87128,-1.53473,-1.23052,-1.16194,2.11341,-0.47219 +2.49303,0.87097,-1.53516,-1.23006,-1.16209,2.11363,-0.47244 +2.49502,0.87067,-1.53558,-1.22961,-1.16224,2.11384,-0.47269 +2.49701,0.87037,-1.53599,-1.22917,-1.16239,2.11406,-0.47293 +2.49900,0.87007,-1.53640,-1.22873,-1.16253,2.11426,-0.47317 +2.50100,0.86978,-1.53679,-1.22830,-1.16268,2.11447,-0.47341 +2.50299,0.86950,-1.53719,-1.22788,-1.16282,2.11467,-0.47364 +2.50498,0.86922,-1.53757,-1.22746,-1.16297,2.11487,-0.47386 +2.50697,0.86894,-1.53795,-1.22705,-1.16311,2.11506,-0.47409 +2.50896,0.86883,-1.53811,-1.22688,-1.16317,2.11514,-0.47418 +2.51095,0.86852,-1.53856,-1.22637,-1.16335,2.11536,-0.47443 +2.51294,0.86821,-1.53900,-1.22588,-1.16352,2.11557,-0.47468 +2.51493,0.86791,-1.53943,-1.22539,-1.16369,2.11578,-0.47492 +2.51693,0.86762,-1.53986,-1.22492,-1.16386,2.11599,-0.47516 +2.51892,0.86733,-1.54028,-1.22444,-1.16403,2.11619,-0.47540 +2.52091,0.86705,-1.54069,-1.22398,-1.16419,2.11639,-0.47563 +2.52290,0.86677,-1.54109,-1.22352,-1.16436,2.11659,-0.47586 +2.52489,0.86649,-1.54149,-1.22307,-1.16452,2.11679,-0.47608 +2.52688,0.86622,-1.54189,-1.22262,-1.16468,2.11698,-0.47630 +2.52887,0.86596,-1.54227,-1.22218,-1.16484,2.11716,-0.47652 +2.53086,0.86580,-1.54250,-1.22192,-1.16494,2.11728,-0.47665 +2.53286,0.86551,-1.54292,-1.22145,-1.16511,2.11748,-0.47689 +2.53485,0.86522,-1.54332,-1.22100,-1.16527,2.11768,-0.47712 +2.53684,0.86494,-1.54372,-1.22055,-1.16544,2.11788,-0.47735 +2.53883,0.86466,-1.54411,-1.22011,-1.16560,2.11807,-0.47758 +2.54082,0.86439,-1.54450,-1.21967,-1.16576,2.11827,-0.47780 +2.54281,0.86412,-1.54488,-1.21924,-1.16592,2.11846,-0.47802 +2.54480,0.86383,-1.54529,-1.21878,-1.16609,2.11866,-0.47827 +2.54679,0.86354,-1.54569,-1.21833,-1.16626,2.11887,-0.47851 +2.54879,0.86325,-1.54609,-1.21788,-1.16642,2.11907,-0.47874 +2.55078,0.86297,-1.54648,-1.21745,-1.16658,2.11927,-0.47897 +2.55277,0.86270,-1.54686,-1.21701,-1.16674,2.11946,-0.47920 +2.55476,0.86243,-1.54724,-1.21659,-1.16690,2.11965,-0.47942 +2.55675,0.86240,-1.54728,-1.21654,-1.16692,2.11967,-0.47944 +2.55874,0.86210,-1.54769,-1.21609,-1.16709,2.11988,-0.47969 +2.56073,0.86181,-1.54809,-1.21565,-1.16726,2.12009,-0.47993 +2.56272,0.86152,-1.54848,-1.21521,-1.16742,2.12029,-0.48017 +2.56472,0.86124,-1.54887,-1.21477,-1.16758,2.12049,-0.48040 +2.56671,0.86096,-1.54925,-1.21435,-1.16774,2.12069,-0.48063 +2.56870,0.86068,-1.54962,-1.21393,-1.16790,2.12088,-0.48086 +2.57069,0.86040,-1.55000,-1.21350,-1.16807,2.12108,-0.48109 +2.57268,0.86013,-1.55037,-1.21308,-1.16823,2.12127,-0.48132 +2.57467,0.86010,-1.55041,-1.21304,-1.16824,2.12129,-0.48134 +2.57666,0.85981,-1.55081,-1.21260,-1.16841,2.12150,-0.48158 +2.57865,0.85952,-1.55119,-1.21217,-1.16857,2.12170,-0.48182 +2.58065,0.85924,-1.55157,-1.21175,-1.16873,2.12190,-0.48205 +2.58264,0.85897,-1.55194,-1.21133,-1.16889,2.12209,-0.48228 +2.58463,0.85891,-1.55202,-1.21125,-1.16893,2.12213,-0.48233 +2.58662,0.85863,-1.55239,-1.21083,-1.16909,2.12233,-0.48256 +2.58861,0.85835,-1.55276,-1.21041,-1.16925,2.12252,-0.48279 +2.59060,0.85831,-1.55280,-1.21038,-1.16926,2.12255,-0.48282 +2.59259,0.85790,-1.55317,-1.21008,-1.16936,2.12284,-0.48316 +2.59458,0.85750,-1.55354,-1.20979,-1.16946,2.12312,-0.48350 +2.59658,0.85710,-1.55389,-1.20950,-1.16956,2.12340,-0.48382 +2.59857,0.85672,-1.55425,-1.20922,-1.16966,2.12367,-0.48414 +2.60056,0.85633,-1.55459,-1.20893,-1.16976,2.12394,-0.48446 +2.60255,0.85596,-1.55493,-1.20866,-1.16986,2.12420,-0.48477 +2.60454,0.85559,-1.55527,-1.20838,-1.16995,2.12446,-0.48508 +2.60653,0.85523,-1.55560,-1.20811,-1.17005,2.12471,-0.48538 +2.60852,0.85488,-1.55592,-1.20784,-1.17015,2.12496,-0.48567 +2.61051,0.85453,-1.55624,-1.20758,-1.17024,2.12520,-0.48596 +2.61250,0.85419,-1.55655,-1.20732,-1.17034,2.12544,-0.48625 +2.61450,0.85385,-1.55686,-1.20706,-1.17043,2.12568,-0.48653 +2.61649,0.85361,-1.55707,-1.20690,-1.17049,2.12585,-0.48673 +2.61848,0.85313,-1.55736,-1.20680,-1.17051,2.12618,-0.48713 +2.62047,0.85266,-1.55764,-1.20670,-1.17053,2.12651,-0.48752 +2.62246,0.85220,-1.55792,-1.20661,-1.17055,2.12683,-0.48790 +2.62445,0.85175,-1.55819,-1.20651,-1.17057,2.12715,-0.48828 +2.62644,0.85130,-1.55846,-1.20641,-1.17059,2.12746,-0.48865 +2.62843,0.85087,-1.55872,-1.20632,-1.17061,2.12776,-0.48901 +2.63043,0.85044,-1.55898,-1.20622,-1.17063,2.12806,-0.48937 +2.63242,0.85002,-1.55924,-1.20613,-1.17065,2.12835,-0.48972 +2.63441,0.84961,-1.55949,-1.20604,-1.17068,2.12864,-0.49006 +2.63640,0.84921,-1.55974,-1.20595,-1.17070,2.12892,-0.49040 +2.63839,0.84881,-1.55998,-1.20585,-1.17072,2.12920,-0.49074 +2.64038,0.84842,-1.56022,-1.20576,-1.17075,2.12947,-0.49106 +2.64237,0.84803,-1.56045,-1.20567,-1.17077,2.12974,-0.49138 +2.64436,0.84766,-1.56069,-1.20559,-1.17080,2.13000,-0.49170 +2.64636,0.84729,-1.56091,-1.20550,-1.17082,2.13026,-0.49201 +2.64835,0.84693,-1.56114,-1.20541,-1.17085,2.13052,-0.49231 +2.65034,0.84666,-1.56129,-1.20536,-1.17086,2.13070,-0.49254 +2.65233,0.84618,-1.56149,-1.20542,-1.17081,2.13104,-0.49294 +2.65432,0.84570,-1.56169,-1.20547,-1.17077,2.13137,-0.49334 +2.65631,0.84523,-1.56189,-1.20553,-1.17073,2.13170,-0.49373 +2.65830,0.84477,-1.56208,-1.20558,-1.17069,2.13202,-0.49412 +2.66029,0.84432,-1.56227,-1.20563,-1.17065,2.13233,-0.49450 +2.66229,0.84388,-1.56246,-1.20567,-1.17062,2.13264,-0.49487 +2.66428,0.84345,-1.56264,-1.20572,-1.17058,2.13294,-0.49524 +2.66627,0.84302,-1.56282,-1.20576,-1.17055,2.13324,-0.49559 +2.66826,0.84260,-1.56300,-1.20581,-1.17052,2.13353,-0.49595 +2.67025,0.84219,-1.56317,-1.20585,-1.17048,2.13382,-0.49629 +2.67224,0.84179,-1.56334,-1.20589,-1.17045,2.13410,-0.49663 +2.67423,0.84139,-1.56351,-1.20593,-1.17042,2.13437,-0.49697 +2.67622,0.84100,-1.56368,-1.20597,-1.17040,2.13465,-0.49730 +2.67822,0.84062,-1.56384,-1.20600,-1.17037,2.13491,-0.49762 +2.68021,0.84024,-1.56400,-1.20604,-1.17034,2.13517,-0.49794 +2.68220,0.83987,-1.56416,-1.20608,-1.17032,2.13543,-0.49825 +2.68419,0.83951,-1.56431,-1.20611,-1.17029,2.13568,-0.49856 +2.68618,0.83947,-1.56432,-1.20612,-1.17029,2.13572,-0.49859 +2.68817,0.83903,-1.56447,-1.20623,-1.17022,2.13602,-0.49896 +2.69016,0.83860,-1.56462,-1.20634,-1.17016,2.13632,-0.49933 +2.69215,0.83818,-1.56476,-1.20645,-1.17010,2.13661,-0.49968 +2.69415,0.83776,-1.56490,-1.20655,-1.17005,2.13690,-0.50004 +2.69614,0.83735,-1.56504,-1.20666,-1.16999,2.13719,-0.50038 +2.69813,0.83695,-1.56518,-1.20676,-1.16993,2.13746,-0.50072 +2.70012,0.83656,-1.56531,-1.20686,-1.16988,2.13774,-0.50105 +2.70211,0.83617,-1.56545,-1.20695,-1.16983,2.13801,-0.50138 +2.70410,0.83580,-1.56558,-1.20705,-1.16978,2.13827,-0.50170 +2.70609,0.83542,-1.56570,-1.20714,-1.16973,2.13853,-0.50202 +2.70808,0.83506,-1.56583,-1.20723,-1.16968,2.13878,-0.50233 +2.71008,0.83470,-1.56595,-1.20732,-1.16963,2.13903,-0.50263 +2.71207,0.83466,-1.56596,-1.20733,-1.16962,2.13906,-0.50267 +2.71406,0.83422,-1.56608,-1.20750,-1.16954,2.13937,-0.50304 +2.71605,0.83379,-1.56620,-1.20766,-1.16946,2.13966,-0.50340 +2.71804,0.83338,-1.56631,-1.20782,-1.16937,2.13995,-0.50376 +2.72003,0.83296,-1.56642,-1.20797,-1.16929,2.14024,-0.50411 +2.72202,0.83256,-1.56653,-1.20813,-1.16922,2.14052,-0.50445 +2.72401,0.83216,-1.56664,-1.20827,-1.16914,2.14079,-0.50479 +2.72601,0.83177,-1.56675,-1.20842,-1.16907,2.14107,-0.50512 +2.72800,0.83139,-1.56685,-1.20856,-1.16900,2.14133,-0.50544 +2.72999,0.83102,-1.56696,-1.20871,-1.16892,2.14159,-0.50576 +2.73198,0.83065,-1.56706,-1.20884,-1.16885,2.14185,-0.50608 +2.73397,0.83028,-1.56716,-1.20898,-1.16879,2.14210,-0.50639 +2.73596,0.82993,-1.56725,-1.20911,-1.16872,2.14235,-0.50669 +2.73795,0.82978,-1.56729,-1.20917,-1.16869,2.14245,-0.50681 +2.73994,0.82940,-1.56739,-1.20934,-1.16861,2.14272,-0.50714 +2.74194,0.82902,-1.56748,-1.20950,-1.16853,2.14298,-0.50747 +2.74393,0.82864,-1.56757,-1.20966,-1.16845,2.14324,-0.50779 +2.74592,0.82827,-1.56766,-1.20982,-1.16837,2.14350,-0.50810 +2.74791,0.82791,-1.56775,-1.20998,-1.16829,2.14375,-0.50841 +2.74990,0.82756,-1.56783,-1.21013,-1.16822,2.14399,-0.50871 +2.75189,0.82735,-1.56788,-1.21022,-1.16817,2.14414,-0.50890 +2.75388,0.82696,-1.56797,-1.21041,-1.16808,2.14441,-0.50922 +2.75587,0.82658,-1.56805,-1.21060,-1.16799,2.14467,-0.50955 +2.75787,0.82621,-1.56813,-1.21078,-1.16790,2.14493,-0.50987 +2.75986,0.82585,-1.56821,-1.21095,-1.16782,2.14518,-0.51018 +2.76185,0.82549,-1.56828,-1.21113,-1.16773,2.14543,-0.51048 +2.76384,0.82514,-1.56836,-1.21130,-1.16765,2.14567,-0.51079 +2.76583,0.82489,-1.56841,-1.21142,-1.16759,2.14584,-0.51100 +2.76782,0.82453,-1.56849,-1.21159,-1.16751,2.14609,-0.51130 +2.76981,0.82418,-1.56857,-1.21176,-1.16742,2.14633,-0.51160 +2.77180,0.82394,-1.56862,-1.21188,-1.16736,2.14650,-0.51181 +2.77380,0.82357,-1.56869,-1.21208,-1.16727,2.14676,-0.51213 +2.77579,0.82321,-1.56875,-1.21227,-1.16718,2.14700,-0.51243 +2.77778,0.82286,-1.56882,-1.21246,-1.16709,2.14725,-0.51274 +2.77977,0.82252,-1.56889,-1.21264,-1.16700,2.14749,-0.51303 +2.78176,0.82245,-1.56890,-1.21268,-1.16698,2.14754,-0.51309 +2.78375,0.82209,-1.56894,-1.21290,-1.16687,2.14778,-0.51339 +2.78574,0.82175,-1.56899,-1.21312,-1.16677,2.14802,-0.51369 +2.78773,0.82144,-1.56903,-1.21332,-1.16668,2.14823,-0.51396 +2.78973,0.82108,-1.56907,-1.21356,-1.16657,2.14848,-0.51426 +2.79172,0.82073,-1.56911,-1.21380,-1.16646,2.14872,-0.51456 +2.79371,0.82039,-1.56915,-1.21403,-1.16635,2.14896,-0.51486 +2.79570,0.82005,-1.56919,-1.21426,-1.16624,2.14920,-0.51515 +2.79769,0.81998,-1.56919,-1.21431,-1.16622,2.14924,-0.51521 +2.79968,0.81960,-1.56922,-1.21459,-1.16608,2.14951,-0.51554 +2.80167,0.81922,-1.56925,-1.21487,-1.16595,2.14976,-0.51586 +2.80366,0.81886,-1.56928,-1.21514,-1.16583,2.15002,-0.51618 +2.80566,0.81850,-1.56930,-1.21541,-1.16570,2.15026,-0.51649 +2.80765,0.81815,-1.56933,-1.21567,-1.16558,2.15051,-0.51679 +2.80964,0.81780,-1.56935,-1.21593,-1.16546,2.15075,-0.51709 +2.81163,0.81746,-1.56938,-1.21618,-1.16534,2.15098,-0.51738 +2.81362,0.81713,-1.56940,-1.21643,-1.16523,2.15121,-0.51767 +2.81561,0.81705,-1.56941,-1.21650,-1.16520,2.15127,-0.51773 +2.81760,0.81662,-1.56940,-1.21688,-1.16502,2.15156,-0.51810 +2.81959,0.81620,-1.56940,-1.21726,-1.16484,2.15185,-0.51847 +2.82159,0.81578,-1.56940,-1.21763,-1.16467,2.15214,-0.51882 +2.82358,0.81538,-1.56940,-1.21799,-1.16450,2.15242,-0.51918 +2.82557,0.81498,-1.56940,-1.21835,-1.16434,2.15269,-0.51952 +2.82756,0.81458,-1.56939,-1.21870,-1.16418,2.15296,-0.51986 +2.82955,0.81420,-1.56939,-1.21904,-1.16402,2.15323,-0.52019 +2.83154,0.81382,-1.56939,-1.21938,-1.16386,2.15349,-0.52052 +2.83353,0.81345,-1.56939,-1.21971,-1.16371,2.15374,-0.52084 +2.83552,0.81309,-1.56938,-1.22004,-1.16355,2.15399,-0.52115 +2.83751,0.81273,-1.56938,-1.22036,-1.16341,2.15424,-0.52146 +2.83951,0.81238,-1.56938,-1.22068,-1.16326,2.15448,-0.52176 +2.84150,0.81203,-1.56938,-1.22099,-1.16312,2.15472,-0.52206 +2.84349,0.81170,-1.56937,-1.22129,-1.16297,2.15495,-0.52235 +2.84548,0.81136,-1.56937,-1.22159,-1.16284,2.15518,-0.52264 +2.84747,0.81104,-1.56937,-1.22189,-1.16270,2.15540,-0.52292 +2.84946,0.81077,-1.56936,-1.22213,-1.16259,2.15559,-0.52316 +2.85145,0.81036,-1.56934,-1.22254,-1.16240,2.15587,-0.52351 +2.85344,0.80995,-1.56932,-1.22293,-1.16222,2.15615,-0.52386 +2.85544,0.80956,-1.56930,-1.22332,-1.16204,2.15642,-0.52420 +2.85743,0.80917,-1.56929,-1.22370,-1.16186,2.15669,-0.52454 +2.85942,0.80879,-1.56927,-1.22408,-1.16169,2.15695,-0.52487 +2.86141,0.80841,-1.56925,-1.22445,-1.16152,2.15721,-0.52520 +2.86340,0.80804,-1.56923,-1.22481,-1.16135,2.15746,-0.52552 +2.86539,0.80768,-1.56921,-1.22517,-1.16118,2.15771,-0.52583 +2.86738,0.80732,-1.56919,-1.22552,-1.16102,2.15795,-0.52614 +2.86937,0.80698,-1.56918,-1.22586,-1.16086,2.15819,-0.52644 +2.87137,0.80663,-1.56916,-1.22620,-1.16070,2.15843,-0.52674 +2.87336,0.80630,-1.56914,-1.22654,-1.16055,2.15866,-0.52703 +2.87535,0.80597,-1.56912,-1.22686,-1.16040,2.15888,-0.52732 +2.87734,0.80564,-1.56911,-1.22718,-1.16025,2.15911,-0.52760 +2.87933,0.80533,-1.56909,-1.22750,-1.16010,2.15933,-0.52788 +2.88132,0.80510,-1.56907,-1.22774,-1.16000,2.15948,-0.52808 +2.88331,0.80469,-1.56901,-1.22821,-1.15978,2.15976,-0.52843 +2.88530,0.80429,-1.56895,-1.22868,-1.15957,2.16004,-0.52878 +2.88730,0.80389,-1.56889,-1.22914,-1.15936,2.16031,-0.52912 +2.88929,0.80351,-1.56884,-1.22959,-1.15915,2.16057,-0.52946 +2.89128,0.80313,-1.56878,-1.23004,-1.15895,2.16083,-0.52979 +2.89327,0.80276,-1.56872,-1.23047,-1.15875,2.16108,-0.53011 +2.89526,0.80239,-1.56867,-1.23090,-1.15855,2.16133,-0.53043 +2.89725,0.80203,-1.56861,-1.23132,-1.15836,2.16158,-0.53074 +2.89924,0.80168,-1.56856,-1.23174,-1.15817,2.16182,-0.53105 +2.90123,0.80133,-1.56850,-1.23215,-1.15798,2.16206,-0.53135 +2.90323,0.80100,-1.56845,-1.23255,-1.15780,2.16229,-0.53165 +2.90522,0.80066,-1.56840,-1.23294,-1.15762,2.16252,-0.53194 +2.90721,0.80034,-1.56835,-1.23333,-1.15744,2.16274,-0.53222 +2.90920,0.80001,-1.56830,-1.23371,-1.15727,2.16296,-0.53250 +2.91119,0.79970,-1.56825,-1.23408,-1.15709,2.16318,-0.53278 +2.91318,0.79939,-1.56820,-1.23445,-1.15693,2.16339,-0.53305 +2.91517,0.79909,-1.56815,-1.23481,-1.15676,2.16360,-0.53332 +2.91716,0.79884,-1.56811,-1.23511,-1.15663,2.16376,-0.53353 +2.91916,0.79850,-1.56802,-1.23557,-1.15642,2.16400,-0.53383 +2.92115,0.79816,-1.56794,-1.23602,-1.15621,2.16423,-0.53413 +2.92314,0.79783,-1.56786,-1.23647,-1.15601,2.16446,-0.53442 +2.92513,0.79750,-1.56778,-1.23691,-1.15581,2.16468,-0.53470 +2.92712,0.79718,-1.56770,-1.23734,-1.15562,2.16490,-0.53499 +2.92911,0.79686,-1.56762,-1.23776,-1.15542,2.16512,-0.53526 +2.93110,0.79655,-1.56755,-1.23818,-1.15524,2.16533,-0.53553 +2.93309,0.79625,-1.56747,-1.23859,-1.15505,2.16553,-0.53580 +2.93509,0.79595,-1.56740,-1.23899,-1.15487,2.16574,-0.53606 +2.93708,0.79566,-1.56733,-1.23939,-1.15469,2.16594,-0.53632 +2.93907,0.79537,-1.56725,-1.23979,-1.15451,2.16614,-0.53657 +2.94106,0.79503,-1.56714,-1.24028,-1.15428,2.16637,-0.53686 +2.94305,0.79471,-1.56704,-1.24076,-1.15407,2.16659,-0.53715 +2.94504,0.79438,-1.56694,-1.24124,-1.15385,2.16681,-0.53743 +2.94703,0.79407,-1.56683,-1.24171,-1.15364,2.16702,-0.53771 +2.94902,0.79376,-1.56673,-1.24217,-1.15343,2.16724,-0.53798 +2.95102,0.79345,-1.56664,-1.24262,-1.15323,2.16744,-0.53825 +2.95301,0.79316,-1.56654,-1.24306,-1.15303,2.16765,-0.53851 +2.95500,0.79286,-1.56644,-1.24350,-1.15283,2.16785,-0.53877 +2.95699,0.79258,-1.56635,-1.24393,-1.15264,2.16804,-0.53902 +2.95898,0.79229,-1.56626,-1.24435,-1.15245,2.16824,-0.53927 +2.96097,0.79202,-1.56616,-1.24477,-1.15226,2.16842,-0.53951 +2.96296,0.79196,-1.56614,-1.24486,-1.15222,2.16846,-0.53956 +2.96495,0.79166,-1.56602,-1.24535,-1.15200,2.16867,-0.53983 +2.96695,0.79137,-1.56590,-1.24583,-1.15178,2.16887,-0.54009 +2.96894,0.79108,-1.56578,-1.24630,-1.15157,2.16906,-0.54034 +2.97093,0.79080,-1.56567,-1.24677,-1.15136,2.16926,-0.54059 +2.97292,0.79052,-1.56555,-1.24722,-1.15116,2.16945,-0.54083 +2.97491,0.79025,-1.56544,-1.24767,-1.15096,2.16963,-0.54107 +2.97690,0.78998,-1.56533,-1.24811,-1.15076,2.16981,-0.54131 +2.97889,0.78984,-1.56527,-1.24834,-1.15066,2.16991,-0.54143 +2.98088,0.78953,-1.56511,-1.24892,-1.15040,2.17012,-0.54170 +2.98288,0.78923,-1.56494,-1.24948,-1.15015,2.17032,-0.54197 +2.98487,0.78893,-1.56479,-1.25003,-1.14991,2.17053,-0.54223 +2.98686,0.78864,-1.56463,-1.25057,-1.14967,2.17073,-0.54249 +2.98885,0.78835,-1.56448,-1.25111,-1.14943,2.17092,-0.54274 +2.99084,0.78807,-1.56432,-1.25163,-1.14919,2.17111,-0.54299 +2.99283,0.78779,-1.56418,-1.25215,-1.14896,2.17130,-0.54323 +2.99482,0.78752,-1.56403,-1.25266,-1.14874,2.17149,-0.54347 +2.99681,0.78725,-1.56388,-1.25316,-1.14851,2.17167,-0.54371 +2.99881,0.78699,-1.56374,-1.25365,-1.14829,2.17184,-0.54394 +3.00080,0.78674,-1.56360,-1.25414,-1.14808,2.17202,-0.54417 +3.00279,0.78649,-1.56346,-1.25461,-1.14787,2.17219,-0.54439 +3.00478,0.78628,-1.56335,-1.25499,-1.14769,2.17233,-0.54457 +3.00677,0.78601,-1.56319,-1.25554,-1.14745,2.17251,-0.54481 +3.00876,0.78575,-1.56302,-1.25607,-1.14722,2.17269,-0.54504 +3.01075,0.78548,-1.56286,-1.25659,-1.14698,2.17287,-0.54527 +3.01274,0.78523,-1.56271,-1.25711,-1.14676,2.17304,-0.54550 +3.01474,0.78498,-1.56255,-1.25762,-1.14653,2.17322,-0.54572 +3.01673,0.78473,-1.56240,-1.25811,-1.14631,2.17338,-0.54594 +3.01872,0.78449,-1.56225,-1.25860,-1.14609,2.17355,-0.54615 +3.02071,0.78429,-1.56213,-1.25900,-1.14591,2.17368,-0.54633 +3.02270,0.78403,-1.56195,-1.25955,-1.14567,2.17386,-0.54656 +3.02469,0.78377,-1.56177,-1.26010,-1.14542,2.17403,-0.54679 +3.02668,0.78352,-1.56160,-1.26064,-1.14519,2.17421,-0.54701 +3.02867,0.78327,-1.56143,-1.26117,-1.14495,2.17437,-0.54723 +3.03067,0.78303,-1.56127,-1.26169,-1.14472,2.17454,-0.54745 +3.03266,0.78279,-1.56110,-1.26220,-1.14449,2.17470,-0.54766 +3.03465,0.78255,-1.56094,-1.26270,-1.14427,2.17486,-0.54786 +3.03664,0.78237,-1.56081,-1.26310,-1.14409,2.17499,-0.54803 +3.03863,0.78213,-1.56064,-1.26363,-1.14385,2.17515,-0.54824 +3.04062,0.78189,-1.56047,-1.26415,-1.14362,2.17531,-0.54845 +3.04261,0.78166,-1.56030,-1.26466,-1.14340,2.17547,-0.54866 +3.04460,0.78143,-1.56014,-1.26516,-1.14317,2.17562,-0.54886 +3.04659,0.78140,-1.56012,-1.26522,-1.14315,2.17564,-0.54888 +3.04859,0.78117,-1.55994,-1.26575,-1.14291,2.17580,-0.54909 +3.05058,0.78093,-1.55977,-1.26628,-1.14268,2.17596,-0.54930 +3.05257,0.78071,-1.55960,-1.26679,-1.14245,2.17611,-0.54950 +3.05456,0.78048,-1.55943,-1.26730,-1.14222,2.17627,-0.54970 +3.05655,0.78046,-1.55941,-1.26735,-1.14220,2.17628,-0.54972 +3.05854,0.78023,-1.55924,-1.26787,-1.14197,2.17644,-0.54992 +3.06053,0.78001,-1.55907,-1.26838,-1.14174,2.17659,-0.55012 +3.06252,0.77999,-1.55905,-1.26844,-1.14172,2.17660,-0.55014 +3.06452,0.77975,-1.55883,-1.26903,-1.14145,2.17676,-0.55035 +3.06651,0.77952,-1.55863,-1.26961,-1.14120,2.17692,-0.55055 +3.06850,0.77929,-1.55842,-1.27018,-1.14095,2.17707,-0.55076 +3.07049,0.77907,-1.55822,-1.27075,-1.14070,2.17722,-0.55095 +3.07248,0.77885,-1.55802,-1.27130,-1.14045,2.17737,-0.55115 +3.07447,0.77863,-1.55783,-1.27185,-1.14021,2.17752,-0.55134 +3.07646,0.77842,-1.55763,-1.27238,-1.13997,2.17766,-0.55153 +3.07845,0.77825,-1.55747,-1.27282,-1.13978,2.17777,-0.55167 +3.08045,0.77804,-1.55721,-1.27347,-1.13950,2.17792,-0.55186 +3.08244,0.77784,-1.55695,-1.27412,-1.13922,2.17806,-0.55204 +3.08443,0.77764,-1.55670,-1.27475,-1.13894,2.17819,-0.55222 +3.08642,0.77744,-1.55644,-1.27538,-1.13867,2.17833,-0.55240 +3.08841,0.77724,-1.55620,-1.27599,-1.13840,2.17846,-0.55257 +3.09040,0.77705,-1.55595,-1.27659,-1.13814,2.17859,-0.55274 +3.09239,0.77687,-1.55572,-1.27719,-1.13788,2.17871,-0.55291 +3.09438,0.77668,-1.55548,-1.27777,-1.13763,2.17884,-0.55307 +3.09638,0.77650,-1.55525,-1.27834,-1.13737,2.17896,-0.55323 +3.09837,0.77633,-1.55501,-1.27893,-1.13712,2.17908,-0.55339 +3.10036,0.77616,-1.55465,-1.27970,-1.13679,2.17919,-0.55353 +3.10235,0.77600,-1.55430,-1.28045,-1.13647,2.17930,-0.55368 +3.10434,0.77585,-1.55396,-1.28119,-1.13616,2.17941,-0.55382 +3.10633,0.77569,-1.55362,-1.28192,-1.13585,2.17951,-0.55396 +3.10832,0.77554,-1.55329,-1.28264,-1.13554,2.17961,-0.55409 +3.11031,0.77539,-1.55296,-1.28334,-1.13524,2.17971,-0.55422 +3.11231,0.77525,-1.55264,-1.28404,-1.13494,2.17981,-0.55435 +3.11430,0.77510,-1.55232,-1.28472,-1.13465,2.17991,-0.55448 +3.11629,0.77496,-1.55201,-1.28539,-1.13436,2.18000,-0.55460 +3.11828,0.77483,-1.55171,-1.28605,-1.13407,2.18010,-0.55473 +3.12027,0.77469,-1.55141,-1.28670,-1.13379,2.18019,-0.55485 +3.12226,0.77456,-1.55111,-1.28734,-1.13352,2.18028,-0.55496 +3.12425,0.77443,-1.55082,-1.28797,-1.13325,2.18036,-0.55508 +3.12624,0.77431,-1.55053,-1.28859,-1.13298,2.18045,-0.55519 +3.12824,0.77418,-1.55025,-1.28920,-1.13271,2.18053,-0.55530 +3.13023,0.77415,-1.55015,-1.28940,-1.13263,2.18056,-0.55533 +3.13222,0.77403,-1.54975,-1.29021,-1.13229,2.18063,-0.55543 +3.13421,0.77393,-1.54935,-1.29100,-1.13195,2.18071,-0.55553 +3.13620,0.77382,-1.54895,-1.29178,-1.13162,2.18078,-0.55563 +3.13819,0.77371,-1.54857,-1.29254,-1.13130,2.18085,-0.55572 +3.14018,0.77361,-1.54819,-1.29330,-1.13098,2.18092,-0.55581 +3.14217,0.77351,-1.54781,-1.29404,-1.13066,2.18099,-0.55590 +3.14417,0.77341,-1.54744,-1.29477,-1.13035,2.18106,-0.55599 +3.14616,0.77332,-1.54708,-1.29549,-1.13005,2.18112,-0.55607 +3.14815,0.77322,-1.54673,-1.29620,-1.12974,2.18119,-0.55616 +3.15014,0.77313,-1.54638,-1.29689,-1.12945,2.18125,-0.55624 +3.15213,0.77304,-1.54603,-1.29758,-1.12915,2.18131,-0.55632 +3.15412,0.77295,-1.54569,-1.29825,-1.12887,2.18137,-0.55640 +3.15611,0.77286,-1.54536,-1.29891,-1.12858,2.18143,-0.55647 +3.15810,0.77278,-1.54503,-1.29956,-1.12830,2.18149,-0.55655 +3.16010,0.77270,-1.54471,-1.30020,-1.12802,2.18154,-0.55662 +3.16209,0.77262,-1.54439,-1.30083,-1.12775,2.18160,-0.55669 +3.16408,0.77258,-1.54422,-1.30116,-1.12761,2.18163,-0.55673 +3.16607,0.77252,-1.54379,-1.30197,-1.12727,2.18167,-0.55678 +3.16806,0.77245,-1.54337,-1.30276,-1.12694,2.18171,-0.55684 +3.17005,0.77240,-1.54295,-1.30354,-1.12661,2.18175,-0.55689 +3.17204,0.77234,-1.54254,-1.30430,-1.12629,2.18179,-0.55694 +3.17403,0.77228,-1.54213,-1.30506,-1.12597,2.18183,-0.55699 +3.17603,0.77223,-1.54173,-1.30580,-1.12565,2.18187,-0.55704 +3.17802,0.77217,-1.54134,-1.30653,-1.12534,2.18190,-0.55709 +3.18001,0.77212,-1.54096,-1.30724,-1.12504,2.18194,-0.55713 +3.18200,0.77207,-1.54058,-1.30795,-1.12474,2.18197,-0.55718 +3.18399,0.77202,-1.54021,-1.30864,-1.12444,2.18201,-0.55722 +3.18598,0.77197,-1.53984,-1.30933,-1.12415,2.18204,-0.55727 +3.18797,0.77192,-1.53948,-1.31000,-1.12386,2.18207,-0.55731 +3.18996,0.77188,-1.53913,-1.31066,-1.12358,2.18211,-0.55735 +3.19196,0.77183,-1.53878,-1.31131,-1.12330,2.18214,-0.55739 +3.19395,0.77179,-1.53844,-1.31195,-1.12302,2.18217,-0.55742 +3.19594,0.77176,-1.53819,-1.31241,-1.12282,2.18219,-0.55745 +3.19793,0.77175,-1.53773,-1.31321,-1.12249,2.18219,-0.55746 +3.19992,0.77174,-1.53728,-1.31400,-1.12216,2.18220,-0.55746 +3.20191,0.77173,-1.53683,-1.31478,-1.12183,2.18220,-0.55747 +3.20390,0.77173,-1.53639,-1.31554,-1.12151,2.18221,-0.55748 +3.20589,0.77172,-1.53596,-1.31630,-1.12119,2.18222,-0.55748 +3.20789,0.77171,-1.53554,-1.31704,-1.12088,2.18222,-0.55749 +3.20988,0.77171,-1.53512,-1.31776,-1.12057,2.18223,-0.55749 +3.21187,0.77170,-1.53471,-1.31848,-1.12027,2.18223,-0.55749 +3.21386,0.77170,-1.53431,-1.31919,-1.11997,2.18223,-0.55750 +3.21585,0.77169,-1.53391,-1.31988,-1.11967,2.18224,-0.55750 +3.21784,0.77169,-1.53352,-1.32056,-1.11938,2.18224,-0.55750 +3.21983,0.77169,-1.53314,-1.32123,-1.11909,2.18224,-0.55750 +3.22182,0.77168,-1.53276,-1.32189,-1.11881,2.18224,-0.55750 +3.22382,0.77168,-1.53239,-1.32254,-1.11853,2.18225,-0.55750 +3.22581,0.77168,-1.53203,-1.32318,-1.11826,2.18225,-0.55751 +3.22780,0.77168,-1.53176,-1.32365,-1.11806,2.18225,-0.55750 +3.22979,0.77172,-1.53123,-1.32451,-1.11770,2.18222,-0.55747 +3.23178,0.77175,-1.53072,-1.32536,-1.11735,2.18220,-0.55743 +3.23377,0.77179,-1.53021,-1.32620,-1.11700,2.18218,-0.55740 +3.23576,0.77183,-1.52972,-1.32702,-1.11666,2.18215,-0.55737 +3.23775,0.77186,-1.52923,-1.32783,-1.11632,2.18213,-0.55733 +3.23975,0.77190,-1.52875,-1.32863,-1.11599,2.18210,-0.55730 +3.24174,0.77194,-1.52828,-1.32941,-1.11566,2.18208,-0.55727 +3.24373,0.77197,-1.52781,-1.33018,-1.11533,2.18206,-0.55723 +3.24572,0.77201,-1.52735,-1.33094,-1.11502,2.18203,-0.55720 +3.24771,0.77204,-1.52690,-1.33168,-1.11470,2.18201,-0.55717 +3.24970,0.77208,-1.52646,-1.33242,-1.11439,2.18198,-0.55713 +3.25169,0.77211,-1.52603,-1.33314,-1.11408,2.18196,-0.55710 +3.25368,0.77215,-1.52560,-1.33385,-1.11378,2.18194,-0.55707 +3.25568,0.77218,-1.52518,-1.33455,-1.11349,2.18192,-0.55703 +3.25767,0.77222,-1.52477,-1.33524,-1.11319,2.18189,-0.55700 +3.25966,0.77225,-1.52436,-1.33591,-1.11290,2.18187,-0.55697 +3.26165,0.77229,-1.52396,-1.33658,-1.11262,2.18185,-0.55694 +3.26364,0.77232,-1.52357,-1.33724,-1.11234,2.18182,-0.55690 +3.26563,0.77236,-1.52318,-1.33788,-1.11206,2.18180,-0.55687 +3.26762,0.77239,-1.52280,-1.33851,-1.11179,2.18178,-0.55684 +3.26961,0.77242,-1.52244,-1.33910,-1.11154,2.18176,-0.55681 +3.27160,0.77252,-1.52188,-1.33998,-1.11118,2.18169,-0.55672 +3.27360,0.77261,-1.52133,-1.34085,-1.11082,2.18163,-0.55664 +3.27559,0.77270,-1.52078,-1.34170,-1.11047,2.18157,-0.55656 +3.27758,0.77279,-1.52025,-1.34253,-1.11012,2.18151,-0.55648 +3.27957,0.77288,-1.51972,-1.34336,-1.10978,2.18145,-0.55640 +3.28156,0.77296,-1.51921,-1.34417,-1.10944,2.18140,-0.55632 +3.28355,0.77305,-1.51870,-1.34496,-1.10911,2.18134,-0.55624 +3.28554,0.77313,-1.51820,-1.34575,-1.10878,2.18128,-0.55616 +3.28753,0.77322,-1.51771,-1.34652,-1.10846,2.18123,-0.55609 +3.28953,0.77330,-1.51723,-1.34728,-1.10814,2.18117,-0.55601 +3.29152,0.77338,-1.51675,-1.34802,-1.10783,2.18112,-0.55594 +3.29351,0.77346,-1.51628,-1.34876,-1.10752,2.18106,-0.55586 +3.29550,0.77354,-1.51582,-1.34948,-1.10721,2.18101,-0.55579 +3.29749,0.77362,-1.51537,-1.35019,-1.10691,2.18095,-0.55571 +3.29948,0.77370,-1.51493,-1.35089,-1.10662,2.18090,-0.55564 +3.30147,0.77378,-1.51449,-1.35158,-1.10633,2.18085,-0.55557 +3.30346,0.77385,-1.51406,-1.35225,-1.10604,2.18080,-0.55550 +3.30546,0.77393,-1.51364,-1.35292,-1.10575,2.18075,-0.55543 +3.30745,0.77400,-1.51323,-1.35358,-1.10547,2.18070,-0.55536 +3.30944,0.77408,-1.51282,-1.35422,-1.10520,2.18065,-0.55529 +3.31143,0.77415,-1.51242,-1.35486,-1.10493,2.18060,-0.55523 +3.31342,0.77422,-1.51202,-1.35548,-1.10466,2.18055,-0.55516 +3.31541,0.77429,-1.51163,-1.35610,-1.10439,2.18050,-0.55509 +3.31740,0.77433,-1.51147,-1.35636,-1.10428,2.18048,-0.55506 +3.31939,0.77443,-1.51094,-1.35717,-1.10394,2.18041,-0.55497 +3.32139,0.77454,-1.51042,-1.35796,-1.10361,2.18034,-0.55487 +3.32338,0.77464,-1.50991,-1.35874,-1.10329,2.18027,-0.55478 +3.32537,0.77474,-1.50941,-1.35951,-1.10297,2.18020,-0.55468 +3.32736,0.77485,-1.50892,-1.36027,-1.10265,2.18013,-0.55459 +3.32935,0.77495,-1.50844,-1.36102,-1.10234,2.18006,-0.55450 +3.33134,0.77504,-1.50796,-1.36175,-1.10203,2.18000,-0.55441 +3.33333,0.77514,-1.50749,-1.36247,-1.10172,2.17993,-0.55432 +3.33532,0.77524,-1.50703,-1.36318,-1.10142,2.17987,-0.55423 +3.33732,0.77533,-1.50658,-1.36388,-1.10113,2.17980,-0.55414 +3.33931,0.77543,-1.50614,-1.36456,-1.10084,2.17974,-0.55406 +3.34130,0.77552,-1.50570,-1.36524,-1.10055,2.17968,-0.55397 +3.34329,0.77561,-1.50527,-1.36590,-1.10027,2.17961,-0.55389 +3.34528,0.77570,-1.50485,-1.36656,-1.09999,2.17955,-0.55380 +3.34727,0.77579,-1.50443,-1.36720,-1.09971,2.17949,-0.55372 +3.34926,0.77588,-1.50402,-1.36783,-1.09944,2.17943,-0.55364 +3.35125,0.77597,-1.50362,-1.36846,-1.09918,2.17937,-0.55356 +3.35325,0.77605,-1.50323,-1.36907,-1.09891,2.17932,-0.55348 +3.35524,0.77614,-1.50284,-1.36967,-1.09865,2.17926,-0.55340 +3.35723,0.77615,-1.50278,-1.36975,-1.09862,2.17925,-0.55339 +3.35922,0.77628,-1.50224,-1.37056,-1.09828,2.17916,-0.55327 +3.36121,0.77641,-1.50171,-1.37136,-1.09795,2.17907,-0.55315 +3.36320,0.77654,-1.50119,-1.37214,-1.09763,2.17899,-0.55304 +3.36519,0.77667,-1.50067,-1.37292,-1.09731,2.17890,-0.55292 +3.36718,0.77679,-1.50017,-1.37367,-1.09699,2.17882,-0.55281 +3.36918,0.77691,-1.49967,-1.37442,-1.09668,2.17873,-0.55270 +3.37117,0.77703,-1.49918,-1.37516,-1.09637,2.17865,-0.55259 +3.37316,0.77715,-1.49870,-1.37588,-1.09607,2.17857,-0.55248 +3.37515,0.77727,-1.49822,-1.37659,-1.09577,2.17849,-0.55237 +3.37714,0.77739,-1.49776,-1.37729,-1.09548,2.17841,-0.55226 +3.37913,0.77750,-1.49730,-1.37798,-1.09518,2.17834,-0.55216 +3.38112,0.77761,-1.49685,-1.37865,-1.09490,2.17826,-0.55205 +3.38311,0.77773,-1.49641,-1.37932,-1.09462,2.17818,-0.55195 +3.38511,0.77784,-1.49598,-1.37997,-1.09434,2.17811,-0.55185 +3.38710,0.77795,-1.49555,-1.38062,-1.09406,2.17803,-0.55175 +3.38909,0.77805,-1.49513,-1.38125,-1.09379,2.17796,-0.55165 +3.39108,0.77816,-1.49472,-1.38188,-1.09353,2.17789,-0.55156 +3.39307,0.77826,-1.49431,-1.38249,-1.09326,2.17782,-0.55146 +3.39506,0.77837,-1.49391,-1.38310,-1.09300,2.17775,-0.55136 +3.39705,0.77847,-1.49352,-1.38369,-1.09275,2.17768,-0.55127 +3.39904,0.77850,-1.49339,-1.38388,-1.09267,2.17766,-0.55124 +3.40104,0.77861,-1.49293,-1.38458,-1.09237,2.17758,-0.55114 +3.40303,0.77872,-1.49247,-1.38527,-1.09208,2.17751,-0.55104 +3.40502,0.77883,-1.49202,-1.38596,-1.09179,2.17743,-0.55094 +3.40701,0.77894,-1.49158,-1.38663,-1.09151,2.17736,-0.55084 +3.40900,0.77904,-1.49115,-1.38728,-1.09123,2.17729,-0.55074 +3.41099,0.77915,-1.49072,-1.38793,-1.09095,2.17722,-0.55065 +3.41298,0.77925,-1.49030,-1.38857,-1.09068,2.17715,-0.55055 +3.41497,0.77935,-1.48989,-1.38920,-1.09041,2.17708,-0.55046 +3.41697,0.77945,-1.48948,-1.38981,-1.09015,2.17701,-0.55037 +3.41896,0.77955,-1.48908,-1.39042,-1.08989,2.17694,-0.55028 +3.42095,0.77965,-1.48869,-1.39102,-1.08963,2.17688,-0.55019 +3.42294,0.77970,-1.48849,-1.39133,-1.08950,2.17684,-0.55014 +3.42493,0.77983,-1.48798,-1.39209,-1.08918,2.17675,-0.55002 +3.42692,0.77996,-1.48748,-1.39283,-1.08887,2.17667,-0.54990 +3.42891,0.78009,-1.48698,-1.39357,-1.08857,2.17658,-0.54979 +3.43090,0.78021,-1.48650,-1.39429,-1.08827,2.17649,-0.54967 +3.43290,0.78034,-1.48602,-1.39500,-1.08797,2.17641,-0.54956 +3.43489,0.78046,-1.48556,-1.39569,-1.08768,2.17633,-0.54945 +3.43688,0.78058,-1.48510,-1.39638,-1.08739,2.17624,-0.54934 +3.43887,0.78070,-1.48464,-1.39706,-1.08710,2.17616,-0.54923 +3.44086,0.78082,-1.48420,-1.39772,-1.08682,2.17608,-0.54912 +3.44285,0.78093,-1.48376,-1.39837,-1.08655,2.17600,-0.54902 +3.44484,0.78105,-1.48333,-1.39902,-1.08627,2.17592,-0.54891 +3.44683,0.78116,-1.48291,-1.39965,-1.08601,2.17585,-0.54881 +3.44883,0.78127,-1.48249,-1.40027,-1.08574,2.17577,-0.54871 +3.45082,0.78138,-1.48209,-1.40088,-1.08548,2.17570,-0.54861 +3.45281,0.78149,-1.48168,-1.40149,-1.08522,2.17562,-0.54851 +3.45480,0.78159,-1.48129,-1.40208,-1.08497,2.17555,-0.54841 +3.45679,0.78167,-1.48101,-1.40250,-1.08479,2.17550,-0.54834 +3.45878,0.78181,-1.48052,-1.40322,-1.08449,2.17540,-0.54821 +3.46077,0.78194,-1.48003,-1.40393,-1.08419,2.17531,-0.54809 +3.46276,0.78208,-1.47956,-1.40462,-1.08390,2.17522,-0.54797 +3.46476,0.78221,-1.47910,-1.40531,-1.08362,2.17513,-0.54785 +3.46675,0.78234,-1.47864,-1.40598,-1.08333,2.17504,-0.54773 +3.46874,0.78247,-1.47819,-1.40664,-1.08306,2.17496,-0.54761 +3.47073,0.78259,-1.47774,-1.40730,-1.08278,2.17487,-0.54750 +3.47272,0.78272,-1.47731,-1.40794,-1.08251,2.17478,-0.54739 +3.47471,0.78284,-1.47688,-1.40857,-1.08224,2.17470,-0.54727 +3.47670,0.78296,-1.47646,-1.40919,-1.08198,2.17462,-0.54716 +3.47869,0.78308,-1.47605,-1.40980,-1.08172,2.17454,-0.54705 +3.48068,0.78320,-1.47564,-1.41040,-1.08147,2.17446,-0.54695 +3.48268,0.78332,-1.47524,-1.41099,-1.08121,2.17438,-0.54684 +3.48467,0.78343,-1.47485,-1.41157,-1.08097,2.17430,-0.54673 +3.48666,0.78346,-1.47476,-1.41170,-1.08091,2.17428,-0.54671 +3.48865,0.78361,-1.47425,-1.41243,-1.08061,2.17417,-0.54657 +3.49064,0.78377,-1.47376,-1.41314,-1.08032,2.17407,-0.54643 +3.49263,0.78392,-1.47327,-1.41384,-1.08003,2.17396,-0.54629 +3.49462,0.78407,-1.47279,-1.41453,-1.07974,2.17386,-0.54616 +3.49661,0.78422,-1.47232,-1.41521,-1.07946,2.17376,-0.54602 +3.49861,0.78436,-1.47186,-1.41587,-1.07918,2.17366,-0.54589 +3.50060,0.78451,-1.47140,-1.41653,-1.07891,2.17356,-0.54576 +3.50259,0.78465,-1.47095,-1.41718,-1.07864,2.17347,-0.54563 +3.50458,0.78479,-1.47051,-1.41781,-1.07837,2.17337,-0.54551 +3.50657,0.78493,-1.47008,-1.41843,-1.07811,2.17328,-0.54538 +3.50856,0.78506,-1.46966,-1.41905,-1.07785,2.17319,-0.54526 +3.51055,0.78520,-1.46924,-1.41965,-1.07760,2.17309,-0.54514 +3.51254,0.78533,-1.46883,-1.42025,-1.07735,2.17300,-0.54502 +3.51454,0.78546,-1.46842,-1.42083,-1.07710,2.17292,-0.54490 +3.51653,0.78559,-1.46803,-1.42141,-1.07685,2.17283,-0.54478 +3.51852,0.78567,-1.46778,-1.42176,-1.07671,2.17277,-0.54471 +3.52051,0.78583,-1.46732,-1.42241,-1.07644,2.17266,-0.54456 +3.52250,0.78599,-1.46686,-1.42306,-1.07617,2.17255,-0.54441 +3.52449,0.78615,-1.46641,-1.42369,-1.07591,2.17244,-0.54427 +3.52648,0.78631,-1.46597,-1.42431,-1.07565,2.17234,-0.54413 +3.52847,0.78646,-1.46553,-1.42492,-1.07539,2.17223,-0.54399 +3.53047,0.78661,-1.46510,-1.42553,-1.07514,2.17213,-0.54385 +3.53246,0.78676,-1.46468,-1.42612,-1.07489,2.17203,-0.54372 +3.53445,0.78691,-1.46427,-1.42670,-1.07464,2.17193,-0.54358 +3.53644,0.78705,-1.46386,-1.42727,-1.07440,2.17183,-0.54345 +3.53843,0.78720,-1.46346,-1.42784,-1.07416,2.17173,-0.54332 +3.54042,0.78729,-1.46321,-1.42819,-1.07402,2.17167,-0.54324 +3.54241,0.78749,-1.46268,-1.42891,-1.07372,2.17153,-0.54306 +3.54440,0.78770,-1.46215,-1.42963,-1.07344,2.17139,-0.54288 +3.54640,0.78790,-1.46164,-1.43033,-1.07315,2.17125,-0.54270 +3.54839,0.78810,-1.46113,-1.43102,-1.07287,2.17112,-0.54252 +3.55038,0.78829,-1.46063,-1.43170,-1.07260,2.17099,-0.54235 +3.55237,0.78848,-1.46014,-1.43236,-1.07232,2.17085,-0.54217 +3.55436,0.78867,-1.45966,-1.43302,-1.07205,2.17073,-0.54201 +3.55635,0.78886,-1.45919,-1.43366,-1.07179,2.17060,-0.54184 +3.55834,0.78904,-1.45872,-1.43430,-1.07153,2.17047,-0.54167 +3.56033,0.78922,-1.45826,-1.43492,-1.07127,2.17035,-0.54151 +3.56233,0.78940,-1.45781,-1.43554,-1.07102,2.17023,-0.54135 +3.56432,0.78957,-1.45737,-1.43614,-1.07077,2.17011,-0.54120 +3.56631,0.78974,-1.45693,-1.43674,-1.07052,2.16999,-0.54104 +3.56830,0.78991,-1.45651,-1.43732,-1.07027,2.16988,-0.54089 +3.57029,0.79008,-1.45609,-1.43790,-1.07003,2.16976,-0.54074 +3.57228,0.79025,-1.45567,-1.43847,-1.06980,2.16965,-0.54059 +3.57427,0.79041,-1.45527,-1.43902,-1.06956,2.16954,-0.54044 +3.57626,0.79057,-1.45487,-1.43957,-1.06933,2.16943,-0.54030 +3.57826,0.79064,-1.45470,-1.43979,-1.06924,2.16938,-0.54024 +3.58025,0.79083,-1.45426,-1.44039,-1.06899,2.16925,-0.54006 +3.58224,0.79102,-1.45381,-1.44098,-1.06875,2.16912,-0.53989 +3.58423,0.79121,-1.45338,-1.44156,-1.06851,2.16899,-0.53973 +3.58622,0.79139,-1.45295,-1.44213,-1.06828,2.16887,-0.53956 +3.58821,0.79157,-1.45254,-1.44269,-1.06804,2.16874,-0.53940 +3.59020,0.79175,-1.45212,-1.44324,-1.06781,2.16862,-0.53924 +3.59219,0.79193,-1.45172,-1.44378,-1.06759,2.16850,-0.53908 +3.59419,0.79210,-1.45132,-1.44432,-1.06736,2.16838,-0.53893 +3.59618,0.79214,-1.45124,-1.44443,-1.06732,2.16836,-0.53889 +3.59817,0.79234,-1.45081,-1.44498,-1.06709,2.16822,-0.53871 +3.60016,0.79254,-1.45039,-1.44553,-1.06686,2.16808,-0.53853 +3.60215,0.79274,-1.44997,-1.44607,-1.06664,2.16795,-0.53836 +3.60414,0.79293,-1.44957,-1.44660,-1.06642,2.16782,-0.53818 +3.60613,0.79312,-1.44917,-1.44712,-1.06621,2.16768,-0.53801 +3.60812,0.79322,-1.44896,-1.44738,-1.06610,2.16762,-0.53792 +3.61012,0.79344,-1.44851,-1.44795,-1.06586,2.16747,-0.53773 +3.61211,0.79366,-1.44807,-1.44851,-1.06564,2.16732,-0.53753 +3.61410,0.79388,-1.44764,-1.44907,-1.06541,2.16717,-0.53734 +3.61609,0.79409,-1.44721,-1.44961,-1.06519,2.16702,-0.53715 +3.61808,0.79430,-1.44679,-1.45014,-1.06497,2.16688,-0.53696 +3.62007,0.79450,-1.44638,-1.45067,-1.06475,2.16674,-0.53678 +3.62206,0.79471,-1.44597,-1.45119,-1.06454,2.16660,-0.53660 +3.62405,0.79491,-1.44558,-1.45170,-1.06433,2.16647,-0.53642 +3.62605,0.79495,-1.44549,-1.45180,-1.06429,2.16644,-0.53638 +3.62804,0.79517,-1.44508,-1.45232,-1.06407,2.16629,-0.53619 +3.63003,0.79538,-1.44467,-1.45283,-1.06386,2.16614,-0.53600 +3.63202,0.79559,-1.44427,-1.45334,-1.06365,2.16600,-0.53581 +3.63401,0.79578,-1.44391,-1.45379,-1.06347,2.16587,-0.53564 +3.63600,0.79602,-1.44346,-1.45434,-1.06325,2.16570,-0.53543 +3.63799,0.79626,-1.44302,-1.45488,-1.06303,2.16554,-0.53522 +3.63998,0.79650,-1.44258,-1.45541,-1.06281,2.16538,-0.53501 +3.64198,0.79673,-1.44216,-1.45594,-1.06260,2.16522,-0.53480 +3.64397,0.79695,-1.44174,-1.45645,-1.06239,2.16507,-0.53460 +3.64596,0.79718,-1.44133,-1.45696,-1.06218,2.16491,-0.53441 +3.64795,0.79740,-1.44092,-1.45746,-1.06198,2.16476,-0.53421 +3.64994,0.79761,-1.44053,-1.45795,-1.06177,2.16461,-0.53402 +3.65193,0.79768,-1.44041,-1.45810,-1.06171,2.16457,-0.53396 +3.65392,0.79791,-1.43999,-1.45860,-1.06151,2.16441,-0.53375 +3.65591,0.79815,-1.43959,-1.45910,-1.06131,2.16425,-0.53355 +3.65791,0.79837,-1.43919,-1.45958,-1.06111,2.16410,-0.53334 +3.65990,0.79858,-1.43883,-1.46002,-1.06093,2.16395,-0.53316 +3.66189,0.79884,-1.43839,-1.46054,-1.06073,2.16377,-0.53293 +3.66388,0.79910,-1.43796,-1.46104,-1.06052,2.16360,-0.53270 +3.66587,0.79936,-1.43753,-1.46154,-1.06032,2.16342,-0.53247 +3.66786,0.79961,-1.43711,-1.46203,-1.06013,2.16325,-0.53225 +3.66985,0.79986,-1.43670,-1.46251,-1.05993,2.16308,-0.53203 +3.67184,0.80011,-1.43630,-1.46299,-1.05974,2.16291,-0.53181 +3.67384,0.80035,-1.43591,-1.46345,-1.05955,2.16275,-0.53160 +3.67583,0.80051,-1.43563,-1.46378,-1.05942,2.16263,-0.53145 +3.67782,0.80076,-1.43523,-1.46424,-1.05923,2.16246,-0.53123 +3.67981,0.80100,-1.43484,-1.46470,-1.05904,2.16230,-0.53102 +3.68180,0.80125,-1.43445,-1.46516,-1.05886,2.16213,-0.53080 +3.68379,0.80150,-1.43405,-1.46562,-1.05867,2.16196,-0.53058 +3.68578,0.80175,-1.43366,-1.46607,-1.05849,2.16178,-0.53036 +3.68777,0.80200,-1.43327,-1.46652,-1.05831,2.16161,-0.53014 +3.68977,0.80203,-1.43323,-1.46657,-1.05829,2.16160,-0.53012 +3.69176,0.80228,-1.43283,-1.46702,-1.05811,2.16142,-0.52989 +3.69375,0.80253,-1.43244,-1.46747,-1.05793,2.16125,-0.52967 +3.69574,0.80279,-1.43205,-1.46792,-1.05775,2.16107,-0.52944 +3.69773,0.80305,-1.43166,-1.46836,-1.05757,2.16089,-0.52922 +3.69972,0.80331,-1.43127,-1.46880,-1.05739,2.16072,-0.52899 +3.70171,0.80357,-1.43088,-1.46924,-1.05721,2.16054,-0.52876 +3.70370,0.80359,-1.43084,-1.46929,-1.05719,2.16052,-0.52874 +3.70569,0.80386,-1.43045,-1.46973,-1.05702,2.16034,-0.52850 +3.70769,0.80412,-1.43006,-1.47016,-1.05684,2.16016,-0.52827 +3.70968,0.80415,-1.43002,-1.47021,-1.05682,2.16014,-0.52825 +3.71167,0.80441,-1.42960,-1.47069,-1.05663,2.15996,-0.52802 +3.71366,0.80467,-1.42919,-1.47117,-1.05644,2.15978,-0.52779 +3.71565,0.80492,-1.42878,-1.47164,-1.05625,2.15961,-0.52757 +3.71764,0.80517,-1.42838,-1.47210,-1.05607,2.15944,-0.52735 +3.71963,0.80542,-1.42799,-1.47255,-1.05589,2.15927,-0.52713 +3.72162,0.80547,-1.42791,-1.47265,-1.05585,2.15923,-0.52709 +3.72362,0.80570,-1.42747,-1.47319,-1.05563,2.15907,-0.52688 +3.72561,0.80593,-1.42704,-1.47372,-1.05542,2.15891,-0.52668 +3.72760,0.80616,-1.42662,-1.47425,-1.05521,2.15876,-0.52648 +3.72959,0.80639,-1.42620,-1.47476,-1.05500,2.15860,-0.52628 +3.73158,0.80661,-1.42579,-1.47527,-1.05480,2.15845,-0.52609 +3.73357,0.80682,-1.42539,-1.47577,-1.05459,2.15830,-0.52589 +3.73556,0.80702,-1.42503,-1.47622,-1.05441,2.15817,-0.52572 +3.73755,0.80723,-1.42454,-1.47686,-1.05416,2.15802,-0.52554 +3.73955,0.80743,-1.42407,-1.47749,-1.05391,2.15788,-0.52536 +3.74154,0.80764,-1.42360,-1.47810,-1.05366,2.15774,-0.52518 +3.74353,0.80784,-1.42314,-1.47871,-1.05342,2.15760,-0.52500 +3.74552,0.80804,-1.42269,-1.47930,-1.05318,2.15746,-0.52482 +3.74751,0.80824,-1.42224,-1.47989,-1.05294,2.15732,-0.52465 +3.74950,0.80843,-1.42181,-1.48046,-1.05271,2.15719,-0.52448 +3.75149,0.80862,-1.42138,-1.48103,-1.05248,2.15706,-0.52431 +3.75348,0.80881,-1.42096,-1.48159,-1.05225,2.15693,-0.52415 +3.75548,0.80899,-1.42054,-1.48214,-1.05203,2.15680,-0.52399 +3.75747,0.80917,-1.42014,-1.48268,-1.05181,2.15667,-0.52383 +3.75946,0.80935,-1.41973,-1.48321,-1.05159,2.15655,-0.52367 +3.76145,0.80946,-1.41949,-1.48353,-1.05146,2.15648,-0.52357 +3.76344,0.80963,-1.41903,-1.48418,-1.05120,2.15636,-0.52342 +3.76543,0.80980,-1.41857,-1.48481,-1.05095,2.15624,-0.52327 +3.76742,0.80996,-1.41812,-1.48543,-1.05070,2.15613,-0.52313 +3.76941,0.81013,-1.41768,-1.48604,-1.05045,2.15601,-0.52298 +3.77141,0.81029,-1.41725,-1.48664,-1.05021,2.15590,-0.52284 +3.77340,0.81045,-1.41682,-1.48723,-1.04997,2.15579,-0.52270 +3.77539,0.81060,-1.41640,-1.48781,-1.04973,2.15568,-0.52256 +3.77738,0.81076,-1.41599,-1.48838,-1.04950,2.15557,-0.52242 +3.77937,0.81091,-1.41558,-1.48894,-1.04927,2.15546,-0.52229 +3.78136,0.81106,-1.41519,-1.48949,-1.04904,2.15536,-0.52216 +3.78335,0.81115,-1.41494,-1.48984,-1.04890,2.15530,-0.52208 +3.78534,0.81127,-1.41444,-1.49058,-1.04860,2.15521,-0.52197 +3.78734,0.81139,-1.41394,-1.49132,-1.04830,2.15513,-0.52186 +3.78933,0.81151,-1.41345,-1.49204,-1.04801,2.15504,-0.52175 +3.79132,0.81163,-1.41298,-1.49275,-1.04772,2.15496,-0.52165 +3.79331,0.81175,-1.41250,-1.49345,-1.04744,2.15487,-0.52154 +3.79530,0.81187,-1.41204,-1.49413,-1.04716,2.15479,-0.52144 +3.79729,0.81198,-1.41159,-1.49481,-1.04688,2.15471,-0.52133 +3.79928,0.81210,-1.41114,-1.49547,-1.04661,2.15463,-0.52123 +3.80127,0.81221,-1.41070,-1.49612,-1.04634,2.15455,-0.52113 +3.80327,0.81232,-1.41027,-1.49676,-1.04608,2.15447,-0.52103 +3.80526,0.81243,-1.40985,-1.49740,-1.04582,2.15440,-0.52094 +3.80725,0.81253,-1.40943,-1.49802,-1.04556,2.15432,-0.52084 +3.80924,0.81264,-1.40902,-1.49863,-1.04531,2.15425,-0.52074 +3.81123,0.81275,-1.40862,-1.49923,-1.04506,2.15417,-0.52065 +3.81322,0.81285,-1.40822,-1.49982,-1.04482,2.15410,-0.52056 +3.81521,0.81295,-1.40783,-1.50040,-1.04458,2.15403,-0.52047 +3.81720,0.81305,-1.40745,-1.50097,-1.04434,2.15396,-0.52038 +3.81920,0.81314,-1.40706,-1.50155,-1.04410,2.15389,-0.52029 +3.82119,0.81320,-1.40683,-1.50190,-1.04395,2.15385,-0.52024 +3.82318,0.81329,-1.40644,-1.50249,-1.04371,2.15379,-0.52016 +3.82517,0.81338,-1.40605,-1.50308,-1.04346,2.15372,-0.52007 +3.82716,0.81348,-1.40567,-1.50365,-1.04322,2.15366,-0.51999 +3.82915,0.81356,-1.40529,-1.50424,-1.04298,2.15360,-0.51992 +3.83114,0.81361,-1.40507,-1.50458,-1.04284,2.15356,-0.51987 +3.83313,0.81368,-1.40469,-1.50517,-1.04259,2.15351,-0.51981 +3.83513,0.81372,-1.40447,-1.50552,-1.04244,2.15348,-0.51977 +3.83712,0.81379,-1.40409,-1.50611,-1.04220,2.15343,-0.51971 +3.83911,0.81383,-1.40383,-1.50652,-1.04203,2.15340,-0.51967 +3.84110,0.81391,-1.40345,-1.50710,-1.04178,2.15335,-0.51960 +3.84309,0.81394,-1.40330,-1.50733,-1.04169,2.15332,-0.51957 +3.84508,0.81402,-1.40292,-1.50791,-1.04145,2.15326,-0.51949 +3.84707,0.81407,-1.40277,-1.50813,-1.04135,2.15323,-0.51945 +3.84906,0.81432,-1.40236,-1.50861,-1.04116,2.15306,-0.51924 +3.85106,0.81456,-1.40195,-1.50909,-1.04098,2.15290,-0.51903 +3.85305,0.81480,-1.40156,-1.50956,-1.04079,2.15273,-0.51882 +3.85504,0.81489,-1.40144,-1.50969,-1.04074,2.15267,-0.51874 +3.85703,0.81531,-1.40102,-1.51002,-1.04063,2.15238,-0.51837 +3.85902,0.81573,-1.40061,-1.51034,-1.04051,2.15209,-0.51801 +3.86101,0.81615,-1.40020,-1.51066,-1.04040,2.15181,-0.51765 +3.86300,0.81655,-1.39981,-1.51098,-1.04029,2.15153,-0.51730 +3.86499,0.81695,-1.39942,-1.51129,-1.04018,2.15126,-0.51696 +3.86699,0.81735,-1.39903,-1.51160,-1.04007,2.15098,-0.51662 +3.86898,0.81774,-1.39866,-1.51190,-1.03996,2.15072,-0.51628 +3.87097,0.81812,-1.39829,-1.51220,-1.03985,2.15046,-0.51595 +3.87296,0.81849,-1.39793,-1.51249,-1.03974,2.15020,-0.51563 +3.87495,0.81886,-1.39757,-1.51278,-1.03964,2.14995,-0.51531 +3.87694,0.81923,-1.39722,-1.51306,-1.03953,2.14970,-0.51499 +3.87893,0.81958,-1.39687,-1.51334,-1.03943,2.14945,-0.51469 +3.88092,0.81994,-1.39654,-1.51361,-1.03933,2.14921,-0.51438 +3.88292,0.82011,-1.39641,-1.51368,-1.03930,2.14909,-0.51423 +3.88491,0.82080,-1.39614,-1.51355,-1.03938,2.14862,-0.51365 +3.88690,0.82147,-1.39587,-1.51342,-1.03946,2.14816,-0.51307 +3.88889,0.82213,-1.39561,-1.51329,-1.03954,2.14771,-0.51250 +3.89088,0.82278,-1.39536,-1.51316,-1.03961,2.14726,-0.51194 +3.89287,0.82342,-1.39511,-1.51304,-1.03968,2.14682,-0.51140 +3.89486,0.82405,-1.39487,-1.51292,-1.03975,2.14639,-0.51086 +3.89685,0.82467,-1.39463,-1.51280,-1.03982,2.14596,-0.51033 +3.89885,0.82528,-1.39439,-1.51268,-1.03989,2.14555,-0.50981 +3.90084,0.82588,-1.39416,-1.51257,-1.03995,2.14513,-0.50930 +3.90283,0.82647,-1.39393,-1.51246,-1.04002,2.14473,-0.50879 +3.90482,0.82705,-1.39371,-1.51235,-1.04008,2.14433,-0.50830 +3.90681,0.82762,-1.39349,-1.51224,-1.04014,2.14394,-0.50781 +3.90880,0.82818,-1.39328,-1.51213,-1.04020,2.14355,-0.50733 +3.91079,0.82873,-1.39307,-1.51203,-1.04026,2.14317,-0.50687 +3.91278,0.82927,-1.39287,-1.51193,-1.04031,2.14280,-0.50640 +3.91477,0.82980,-1.39266,-1.51183,-1.04037,2.14243,-0.50595 +3.91677,0.83033,-1.39247,-1.51173,-1.04042,2.14207,-0.50550 +3.91876,0.83084,-1.39227,-1.51163,-1.04047,2.14172,-0.50507 +3.92075,0.83135,-1.39208,-1.51154,-1.04052,2.14137,-0.50464 +3.92274,0.83184,-1.39190,-1.51145,-1.04057,2.14103,-0.50421 +3.92473,0.83233,-1.39171,-1.51136,-1.04062,2.14069,-0.50380 +3.92672,0.83281,-1.39153,-1.51127,-1.04067,2.14035,-0.50339 +3.92871,0.83328,-1.39136,-1.51118,-1.04071,2.14003,-0.50298 +3.93070,0.83375,-1.39118,-1.51109,-1.04076,2.13971,-0.50259 +3.93270,0.83421,-1.39101,-1.51101,-1.04080,2.13939,-0.50220 +3.93469,0.83465,-1.39085,-1.51093,-1.04084,2.13908,-0.50182 +3.93668,0.83510,-1.39068,-1.51085,-1.04088,2.13877,-0.50144 +3.93867,0.83553,-1.39052,-1.51077,-1.04092,2.13847,-0.50107 +3.94066,0.83596,-1.39037,-1.51069,-1.04096,2.13817,-0.50071 +3.94265,0.83638,-1.39021,-1.51062,-1.04100,2.13788,-0.50036 +3.94464,0.83679,-1.39006,-1.51054,-1.04104,2.13759,-0.50000 +3.94663,0.83719,-1.38991,-1.51047,-1.04107,2.13731,-0.49966 +3.94863,0.83729,-1.38989,-1.51043,-1.04109,2.13725,-0.49958 +3.95062,0.83785,-1.38980,-1.51012,-1.04123,2.13686,-0.49911 +3.95261,0.83840,-1.38972,-1.50982,-1.04136,2.13648,-0.49864 +3.95460,0.83894,-1.38964,-1.50952,-1.04149,2.13610,-0.49819 +3.95659,0.83947,-1.38956,-1.50923,-1.04162,2.13574,-0.49774 +3.95858,0.83999,-1.38948,-1.50895,-1.04175,2.13538,-0.49730 +3.96057,0.84050,-1.38941,-1.50866,-1.04188,2.13502,-0.49687 +3.96256,0.84100,-1.38933,-1.50839,-1.04200,2.13467,-0.49644 +3.96456,0.84150,-1.38926,-1.50811,-1.04212,2.13433,-0.49602 +3.96655,0.84198,-1.38919,-1.50785,-1.04224,2.13399,-0.49561 +3.96854,0.84246,-1.38912,-1.50758,-1.04235,2.13366,-0.49521 +3.97053,0.84293,-1.38905,-1.50732,-1.04247,2.13333,-0.49481 +3.97252,0.84339,-1.38899,-1.50707,-1.04258,2.13301,-0.49442 +3.97451,0.84385,-1.38892,-1.50682,-1.04269,2.13269,-0.49404 +3.97650,0.84429,-1.38886,-1.50658,-1.04279,2.13238,-0.49367 +3.97849,0.84473,-1.38880,-1.50634,-1.04290,2.13207,-0.49330 +3.98049,0.84516,-1.38874,-1.50610,-1.04300,2.13177,-0.49293 +3.98248,0.84558,-1.38868,-1.50587,-1.04310,2.13148,-0.49258 +3.98447,0.84600,-1.38862,-1.50564,-1.04320,2.13119,-0.49223 +3.98646,0.84641,-1.38857,-1.50541,-1.04330,2.13090,-0.49188 +3.98845,0.84681,-1.38851,-1.50519,-1.04339,2.13062,-0.49155 +3.99044,0.84720,-1.38846,-1.50498,-1.04349,2.13034,-0.49121 +3.99243,0.84759,-1.38840,-1.50476,-1.04358,2.13007,-0.49089 +3.99442,0.84779,-1.38838,-1.50464,-1.04363,2.12993,-0.49072 +3.99642,0.84829,-1.38838,-1.50426,-1.04380,2.12958,-0.49030 +3.99841,0.84878,-1.38837,-1.50389,-1.04396,2.12924,-0.48989 +4.00040,0.84926,-1.38837,-1.50352,-1.04412,2.12891,-0.48949 +4.00239,0.84973,-1.38836,-1.50315,-1.04428,2.12858,-0.48909 +4.00438,0.85019,-1.38836,-1.50280,-1.04443,2.12826,-0.48871 +4.00637,0.85065,-1.38836,-1.50245,-1.04458,2.12794,-0.48833 +4.00836,0.85109,-1.38835,-1.50210,-1.04473,2.12763,-0.48795 +4.01035,0.85153,-1.38835,-1.50176,-1.04488,2.12732,-0.48758 +4.01235,0.85196,-1.38835,-1.50143,-1.04502,2.12702,-0.48722 +4.01434,0.85239,-1.38835,-1.50111,-1.04516,2.12672,-0.48687 +4.01633,0.85280,-1.38835,-1.50078,-1.04530,2.12643,-0.48652 +4.01832,0.85321,-1.38835,-1.50047,-1.04543,2.12614,-0.48618 +4.02031,0.85362,-1.38835,-1.50016,-1.04557,2.12586,-0.48584 +4.02230,0.85401,-1.38835,-1.49985,-1.04570,2.12558,-0.48551 +4.02429,0.85440,-1.38834,-1.49955,-1.04583,2.12531,-0.48519 +4.02628,0.85478,-1.38835,-1.49926,-1.04595,2.12504,-0.48487 +4.02828,0.85516,-1.38835,-1.49897,-1.04608,2.12478,-0.48455 +4.03027,0.85552,-1.38835,-1.49869,-1.04620,2.12452,-0.48425 +4.03226,0.85575,-1.38835,-1.49850,-1.04628,2.12436,-0.48406 +4.03425,0.85623,-1.38840,-1.49805,-1.04647,2.12402,-0.48366 +4.03624,0.85670,-1.38845,-1.49760,-1.04667,2.12369,-0.48327 +4.03823,0.85716,-1.38849,-1.49716,-1.04685,2.12337,-0.48289 +4.04022,0.85761,-1.38854,-1.49673,-1.04704,2.12305,-0.48251 +4.04221,0.85805,-1.38859,-1.49631,-1.04722,2.12274,-0.48214 +4.04421,0.85849,-1.38863,-1.49590,-1.04740,2.12244,-0.48178 +4.04620,0.85892,-1.38868,-1.49549,-1.04758,2.12214,-0.48142 +4.04819,0.85934,-1.38872,-1.49508,-1.04775,2.12184,-0.48107 +4.05018,0.85975,-1.38877,-1.49469,-1.04792,2.12155,-0.48073 +4.05217,0.86016,-1.38881,-1.49430,-1.04809,2.12126,-0.48039 +4.05416,0.86056,-1.38886,-1.49392,-1.04825,2.12098,-0.48006 +4.05615,0.86095,-1.38890,-1.49355,-1.04841,2.12071,-0.47974 +4.05814,0.86134,-1.38894,-1.49318,-1.04857,2.12043,-0.47942 +4.06014,0.86171,-1.38899,-1.49281,-1.04873,2.12017,-0.47910 +4.06213,0.86209,-1.38903,-1.49246,-1.04888,2.11991,-0.47879 +4.06412,0.86245,-1.38907,-1.49211,-1.04903,2.11965,-0.47849 +4.06611,0.86281,-1.38911,-1.49176,-1.04918,2.11940,-0.47819 +4.06810,0.86316,-1.38915,-1.49143,-1.04933,2.11915,-0.47790 +4.07009,0.86351,-1.38919,-1.49109,-1.04947,2.11890,-0.47762 +4.07208,0.86362,-1.38921,-1.49098,-1.04952,2.11882,-0.47752 +4.07407,0.86403,-1.38928,-1.49055,-1.04970,2.11853,-0.47718 +4.07607,0.86444,-1.38935,-1.49012,-1.04989,2.11825,-0.47684 +4.07806,0.86484,-1.38941,-1.48969,-1.05007,2.11796,-0.47651 +4.08005,0.86523,-1.38948,-1.48928,-1.05025,2.11769,-0.47619 +4.08204,0.86562,-1.38955,-1.48887,-1.05043,2.11741,-0.47587 +4.08403,0.86600,-1.38961,-1.48847,-1.05060,2.11715,-0.47556 +4.08602,0.86637,-1.38968,-1.48807,-1.05077,2.11688,-0.47525 +4.08801,0.86674,-1.38974,-1.48768,-1.05094,2.11662,-0.47495 +4.09000,0.86710,-1.38980,-1.48730,-1.05111,2.11637,-0.47465 +4.09200,0.86745,-1.38986,-1.48693,-1.05127,2.11612,-0.47436 +4.09399,0.86780,-1.38993,-1.48656,-1.05143,2.11588,-0.47407 +4.09598,0.86814,-1.38999,-1.48620,-1.05159,2.11564,-0.47379 +4.09797,0.86847,-1.39005,-1.48584,-1.05174,2.11540,-0.47352 +4.09996,0.86854,-1.39006,-1.48576,-1.05177,2.11535,-0.47346 +4.10195,0.86893,-1.39016,-1.48531,-1.05197,2.11508,-0.47314 +4.10394,0.86931,-1.39025,-1.48486,-1.05216,2.11481,-0.47283 +4.10593,0.86968,-1.39034,-1.48442,-1.05235,2.11455,-0.47253 +4.10793,0.87004,-1.39043,-1.48399,-1.05254,2.11429,-0.47223 +4.10992,0.87040,-1.39052,-1.48357,-1.05272,2.11404,-0.47193 +4.11191,0.87075,-1.39060,-1.48316,-1.05290,2.11379,-0.47165 +4.11390,0.87109,-1.39069,-1.48275,-1.05307,2.11355,-0.47136 +4.11589,0.87143,-1.39078,-1.48235,-1.05325,2.11331,-0.47108 +4.11788,0.87176,-1.39086,-1.48195,-1.05342,2.11307,-0.47081 +4.11987,0.87209,-1.39094,-1.48156,-1.05359,2.11284,-0.47054 +4.12186,0.87241,-1.39102,-1.48118,-1.05375,2.11261,-0.47028 +4.12386,0.87248,-1.39104,-1.48109,-1.05379,2.11256,-0.47022 +4.12585,0.87288,-1.39116,-1.48059,-1.05401,2.11228,-0.46989 +4.12784,0.87327,-1.39128,-1.48009,-1.05422,2.11200,-0.46957 +4.12983,0.87366,-1.39140,-1.47960,-1.05444,2.11173,-0.46926 +4.13182,0.87403,-1.39151,-1.47912,-1.05464,2.11147,-0.46895 +4.13381,0.87440,-1.39162,-1.47864,-1.05485,2.11120,-0.46865 +4.13580,0.87477,-1.39173,-1.47818,-1.05505,2.11095,-0.46835 +4.13779,0.87512,-1.39184,-1.47772,-1.05525,2.11069,-0.46806 +4.13978,0.87547,-1.39195,-1.47727,-1.05544,2.11045,-0.46777 +4.14178,0.87582,-1.39206,-1.47683,-1.05564,2.11020,-0.46749 +4.14377,0.87615,-1.39216,-1.47639,-1.05583,2.10996,-0.46722 +4.14576,0.87649,-1.39226,-1.47597,-1.05601,2.10973,-0.46694 +4.14775,0.87681,-1.39236,-1.47555,-1.05619,2.10950,-0.46668 +4.14974,0.87713,-1.39246,-1.47513,-1.05637,2.10927,-0.46642 +4.15173,0.87745,-1.39256,-1.47473,-1.05655,2.10904,-0.46616 +4.15372,0.87774,-1.39266,-1.47434,-1.05672,2.10884,-0.46592 +4.15571,0.87816,-1.39283,-1.47372,-1.05699,2.10854,-0.46558 +4.15771,0.87858,-1.39301,-1.47311,-1.05725,2.10825,-0.46524 +4.15970,0.87899,-1.39318,-1.47251,-1.05751,2.10796,-0.46491 +4.16169,0.87939,-1.39335,-1.47192,-1.05776,2.10767,-0.46458 +4.16368,0.87978,-1.39351,-1.47134,-1.05802,2.10739,-0.46426 +4.16567,0.88017,-1.39367,-1.47077,-1.05826,2.10712,-0.46395 +4.16766,0.88055,-1.39383,-1.47021,-1.05851,2.10685,-0.46364 +4.16965,0.88092,-1.39399,-1.46965,-1.05875,2.10659,-0.46333 +4.17164,0.88129,-1.39415,-1.46911,-1.05898,2.10633,-0.46304 +4.17364,0.88165,-1.39430,-1.46858,-1.05921,2.10607,-0.46274 +4.17563,0.88200,-1.39445,-1.46805,-1.05944,2.10582,-0.46246 +4.17762,0.88234,-1.39460,-1.46753,-1.05967,2.10557,-0.46218 +4.17961,0.88268,-1.39475,-1.46703,-1.05989,2.10533,-0.46190 +4.18160,0.88302,-1.39490,-1.46653,-1.06010,2.10510,-0.46163 +4.18359,0.88335,-1.39504,-1.46603,-1.06032,2.10486,-0.46136 +4.18558,0.88367,-1.39518,-1.46555,-1.06053,2.10463,-0.46110 +4.18757,0.88399,-1.39532,-1.46508,-1.06074,2.10441,-0.46084 +4.18957,0.88430,-1.39545,-1.46461,-1.06094,2.10419,-0.46059 +4.19156,0.88460,-1.39559,-1.46415,-1.06114,2.10397,-0.46035 +4.19355,0.88490,-1.39572,-1.46370,-1.06134,2.10376,-0.46010 +4.19554,0.88519,-1.39585,-1.46325,-1.06153,2.10355,-0.45986 +4.19753,0.88548,-1.39598,-1.46282,-1.06172,2.10334,-0.45963 +4.19952,0.88558,-1.39603,-1.46266,-1.06179,2.10327,-0.45955 +4.20151,0.88597,-1.39628,-1.46194,-1.06210,2.10300,-0.45924 +4.20350,0.88635,-1.39652,-1.46124,-1.06240,2.10272,-0.45893 +4.20550,0.88673,-1.39676,-1.46055,-1.06269,2.10246,-0.45862 +4.20749,0.88710,-1.39700,-1.45987,-1.06298,2.10219,-0.45832 +4.20948,0.88746,-1.39723,-1.45920,-1.06327,2.10194,-0.45803 +4.21147,0.88782,-1.39746,-1.45854,-1.06355,2.10168,-0.45774 +4.21346,0.88817,-1.39769,-1.45789,-1.06383,2.10144,-0.45746 +4.21545,0.88851,-1.39791,-1.45726,-1.06410,2.10119,-0.45719 +4.21744,0.88885,-1.39813,-1.45663,-1.06437,2.10095,-0.45691 +4.21943,0.88918,-1.39835,-1.45602,-1.06464,2.10072,-0.45665 +4.22143,0.88950,-1.39856,-1.45541,-1.06490,2.10049,-0.45639 +4.22342,0.88982,-1.39877,-1.45482,-1.06515,2.10026,-0.45613 +4.22541,0.89013,-1.39897,-1.45423,-1.06541,2.10004,-0.45588 +4.22740,0.89044,-1.39918,-1.45365,-1.06565,2.09982,-0.45563 +4.22939,0.89074,-1.39938,-1.45309,-1.06590,2.09960,-0.45539 +4.23138,0.89103,-1.39957,-1.45253,-1.06614,2.09939,-0.45515 +4.23337,0.89132,-1.39977,-1.45198,-1.06638,2.09919,-0.45492 +4.23536,0.89161,-1.39996,-1.45144,-1.06661,2.09898,-0.45469 +4.23736,0.89189,-1.40015,-1.45091,-1.06684,2.09878,-0.45446 +4.23935,0.89216,-1.40033,-1.45039,-1.06707,2.09859,-0.45424 +4.24134,0.89243,-1.40051,-1.44988,-1.06729,2.09839,-0.45403 +4.24333,0.89270,-1.40069,-1.44938,-1.06751,2.09821,-0.45381 +4.24532,0.89296,-1.40087,-1.44888,-1.06772,2.09802,-0.45361 +4.24731,0.89321,-1.40104,-1.44839,-1.06794,2.09784,-0.45340 +4.24930,0.89342,-1.40119,-1.44798,-1.06812,2.09769,-0.45323 +4.25129,0.89377,-1.40148,-1.44724,-1.06843,2.09744,-0.45295 +4.25329,0.89411,-1.40176,-1.44650,-1.06875,2.09720,-0.45268 +4.25528,0.89444,-1.40203,-1.44578,-1.06905,2.09696,-0.45241 +4.25727,0.89477,-1.40230,-1.44508,-1.06936,2.09673,-0.45215 +4.25926,0.89509,-1.40257,-1.44438,-1.06966,2.09650,-0.45189 +4.26125,0.89541,-1.40284,-1.44370,-1.06995,2.09627,-0.45164 +4.26324,0.89572,-1.40310,-1.44302,-1.07024,2.09605,-0.45139 +4.26523,0.89602,-1.40335,-1.44236,-1.07053,2.09584,-0.45115 +4.26722,0.89632,-1.40360,-1.44171,-1.07081,2.09562,-0.45091 +4.26922,0.89661,-1.40385,-1.44107,-1.07108,2.09541,-0.45068 +4.27121,0.89690,-1.40409,-1.44044,-1.07136,2.09521,-0.45045 +4.27320,0.89718,-1.40433,-1.43982,-1.07163,2.09501,-0.45022 +4.27519,0.89745,-1.40457,-1.43921,-1.07189,2.09481,-0.45000 +4.27718,0.89773,-1.40480,-1.43860,-1.07215,2.09462,-0.44978 +4.27917,0.89799,-1.40503,-1.43801,-1.07241,2.09443,-0.44957 +4.28116,0.89825,-1.40525,-1.43743,-1.07266,2.09424,-0.44936 +4.28315,0.89851,-1.40548,-1.43686,-1.07291,2.09406,-0.44916 +4.28515,0.89876,-1.40569,-1.43630,-1.07315,2.09388,-0.44896 +4.28714,0.89901,-1.40591,-1.43575,-1.07339,2.09370,-0.44876 +4.28913,0.89925,-1.40612,-1.43520,-1.07363,2.09352,-0.44857 +4.29112,0.89949,-1.40633,-1.43467,-1.07386,2.09335,-0.44838 +4.29311,0.89972,-1.40653,-1.43414,-1.07409,2.09319,-0.44819 +4.29510,0.89995,-1.40673,-1.43363,-1.07432,2.09302,-0.44801 +4.29709,0.90016,-1.40692,-1.43314,-1.07453,2.09287,-0.44784 +4.29908,0.90046,-1.40724,-1.43238,-1.07485,2.09266,-0.44760 +4.30108,0.90076,-1.40755,-1.43163,-1.07518,2.09245,-0.44736 +4.30307,0.90105,-1.40786,-1.43089,-1.07549,2.09224,-0.44713 +4.30506,0.90133,-1.40816,-1.43016,-1.07580,2.09204,-0.44691 +4.30705,0.90161,-1.40846,-1.42944,-1.07611,2.09184,-0.44669 +4.30904,0.90188,-1.40875,-1.42874,-1.07641,2.09164,-0.44647 +4.31103,0.90215,-1.40904,-1.42805,-1.07671,2.09145,-0.44626 +4.31302,0.90241,-1.40933,-1.42737,-1.07701,2.09126,-0.44605 +4.31501,0.90267,-1.40960,-1.42670,-1.07730,2.09108,-0.44584 +4.31701,0.90292,-1.40988,-1.42604,-1.07758,2.09090,-0.44564 +4.31900,0.90317,-1.41015,-1.42539,-1.07786,2.09072,-0.44544 +4.32099,0.90341,-1.41042,-1.42475,-1.07814,2.09054,-0.44525 +4.32298,0.90365,-1.41068,-1.42412,-1.07841,2.09037,-0.44506 +4.32497,0.90389,-1.41094,-1.42351,-1.07868,2.09021,-0.44487 +4.32696,0.90412,-1.41119,-1.42290,-1.07894,2.09004,-0.44469 +4.32895,0.90434,-1.41144,-1.42230,-1.07920,2.08988,-0.44451 +4.33094,0.90456,-1.41168,-1.42171,-1.07946,2.08972,-0.44434 +4.33294,0.90478,-1.41193,-1.42114,-1.07971,2.08956,-0.44417 +4.33493,0.90499,-1.41216,-1.42057,-1.07996,2.08941,-0.44400 +4.33692,0.90520,-1.41240,-1.42001,-1.08020,2.08926,-0.44383 +4.33891,0.90541,-1.41263,-1.41946,-1.08044,2.08911,-0.44367 +4.34090,0.90561,-1.41286,-1.41892,-1.08068,2.08897,-0.44351 +4.34289,0.90576,-1.41302,-1.41852,-1.08085,2.08886,-0.44340 +4.34488,0.90602,-1.41333,-1.41780,-1.08116,2.08867,-0.44319 +4.34687,0.90628,-1.41363,-1.41709,-1.08147,2.08849,-0.44298 +4.34886,0.90654,-1.41393,-1.41639,-1.08177,2.08831,-0.44278 +4.35086,0.90679,-1.41422,-1.41570,-1.08207,2.08813,-0.44258 +4.35285,0.90703,-1.41450,-1.41502,-1.08236,2.08795,-0.44239 +4.35484,0.90727,-1.41479,-1.41436,-1.08265,2.08778,-0.44220 +4.35683,0.90751,-1.41507,-1.41370,-1.08294,2.08761,-0.44201 +4.35882,0.90774,-1.41534,-1.41306,-1.08322,2.08744,-0.44183 +4.36081,0.90797,-1.41561,-1.41242,-1.08350,2.08728,-0.44165 +4.36280,0.90819,-1.41587,-1.41180,-1.08377,2.08712,-0.44147 +4.36479,0.90841,-1.41613,-1.41119,-1.08404,2.08696,-0.44130 +4.36679,0.90862,-1.41639,-1.41058,-1.08430,2.08681,-0.44113 +4.36878,0.90883,-1.41664,-1.40999,-1.08456,2.08666,-0.44096 +4.37077,0.90904,-1.41689,-1.40940,-1.08482,2.08651,-0.44080 +4.37276,0.90924,-1.41714,-1.40883,-1.08507,2.08636,-0.44064 +4.37475,0.90944,-1.41738,-1.40826,-1.08532,2.08622,-0.44048 +4.37674,0.90964,-1.41762,-1.40771,-1.08556,2.08608,-0.44033 +4.37873,0.90983,-1.41785,-1.40716,-1.08581,2.08594,-0.44018 +4.38072,0.90989,-1.41792,-1.40699,-1.08588,2.08590,-0.44013 +4.38272,0.91012,-1.41820,-1.40633,-1.08617,2.08574,-0.43995 +4.38471,0.91034,-1.41848,-1.40569,-1.08645,2.08558,-0.43978 +4.38670,0.91056,-1.41875,-1.40505,-1.08673,2.08542,-0.43960 +4.38869,0.91078,-1.41902,-1.40443,-1.08700,2.08526,-0.43943 +4.39068,0.91099,-1.41928,-1.40382,-1.08727,2.08511,-0.43927 +4.39267,0.91119,-1.41954,-1.40322,-1.08753,2.08496,-0.43910 +4.39466,0.91140,-1.41979,-1.40262,-1.08779,2.08482,-0.43894 +4.39665,0.91160,-1.42005,-1.40204,-1.08805,2.08467,-0.43879 +4.39865,0.91179,-1.42029,-1.40147,-1.08830,2.08453,-0.43863 +4.40064,0.91199,-1.42053,-1.40090,-1.08855,2.08439,-0.43848 +4.40263,0.91217,-1.42077,-1.40034,-1.08880,2.08426,-0.43834 +4.40462,0.91231,-1.42095,-1.39994,-1.08897,2.08416,-0.43823 +4.40661,0.91251,-1.42126,-1.39925,-1.08928,2.08402,-0.43807 +4.40860,0.91271,-1.42158,-1.39856,-1.08957,2.08387,-0.43791 +4.41059,0.91291,-1.42188,-1.39788,-1.08987,2.08373,-0.43776 +4.41258,0.91310,-1.42219,-1.39722,-1.09015,2.08359,-0.43760 +4.41458,0.91329,-1.42248,-1.39656,-1.09044,2.08345,-0.43746 +4.41657,0.91348,-1.42278,-1.39592,-1.09072,2.08332,-0.43731 +4.41856,0.91366,-1.42306,-1.39529,-1.09099,2.08319,-0.43717 +4.42055,0.91384,-1.42335,-1.39466,-1.09127,2.08306,-0.43703 +4.42254,0.91402,-1.42363,-1.39405,-1.09153,2.08293,-0.43689 +4.42453,0.91419,-1.42390,-1.39345,-1.09180,2.08281,-0.43675 +4.42652,0.91436,-1.42417,-1.39285,-1.09206,2.08269,-0.43662 +4.42851,0.91452,-1.42444,-1.39227,-1.09231,2.08257,-0.43649 +4.43051,0.91469,-1.42470,-1.39169,-1.09257,2.08245,-0.43637 +4.43250,0.91480,-1.42488,-1.39129,-1.09274,2.08237,-0.43628 +4.43449,0.91498,-1.42516,-1.39067,-1.09301,2.08224,-0.43614 +4.43648,0.91515,-1.42544,-1.39006,-1.09328,2.08212,-0.43600 +4.43847,0.91532,-1.42571,-1.38947,-1.09354,2.08199,-0.43587 +4.44046,0.91549,-1.42598,-1.38888,-1.09380,2.08187,-0.43574 +4.44245,0.91566,-1.42624,-1.38830,-1.09406,2.08175,-0.43561 +4.44444,0.91582,-1.42650,-1.38773,-1.09431,2.08164,-0.43548 +4.44644,0.91585,-1.42655,-1.38761,-1.09436,2.08162,-0.43546 +4.44843,0.91601,-1.42685,-1.38698,-1.09463,2.08150,-0.43533 +4.45042,0.91618,-1.42713,-1.38636,-1.09490,2.08138,-0.43520 +4.45241,0.91634,-1.42742,-1.38575,-1.09517,2.08127,-0.43508 +4.45440,0.91649,-1.42770,-1.38515,-1.09543,2.08115,-0.43496 +4.45639,0.91664,-1.42797,-1.38456,-1.09569,2.08104,-0.43484 +4.45838,0.91679,-1.42824,-1.38398,-1.09594,2.08093,-0.43472 +4.46037,0.91684,-1.42832,-1.38381,-1.09602,2.08090,-0.43468 +4.46237,0.91700,-1.42860,-1.38320,-1.09629,2.08079,-0.43456 +4.46436,0.91716,-1.42888,-1.38260,-1.09655,2.08067,-0.43444 +4.46635,0.91731,-1.42915,-1.38201,-1.09681,2.08056,-0.43432 +4.46834,0.91746,-1.42942,-1.38143,-1.09706,2.08046,-0.43420 +4.47033,0.91749,-1.42948,-1.38131,-1.09711,2.08043,-0.43418 +4.47232,0.91764,-1.42980,-1.38064,-1.09740,2.08033,-0.43406 +4.47431,0.91779,-1.43012,-1.37999,-1.09769,2.08022,-0.43395 +4.47630,0.91793,-1.43043,-1.37934,-1.09797,2.08012,-0.43384 +4.47830,0.91807,-1.43074,-1.37870,-1.09824,2.08002,-0.43373 +4.48029,0.91821,-1.43104,-1.37808,-1.09851,2.07992,-0.43362 +4.48228,0.91834,-1.43134,-1.37746,-1.09878,2.07982,-0.43352 +4.48427,0.91847,-1.43163,-1.37686,-1.09904,2.07973,-0.43341 +4.48626,0.91860,-1.43192,-1.37626,-1.09930,2.07963,-0.43331 +4.48825,0.91868,-1.43209,-1.37590,-1.09946,2.07958,-0.43325 +4.49024,0.91881,-1.43240,-1.37527,-1.09973,2.07949,-0.43316 +4.49223,0.91893,-1.43270,-1.37465,-1.10000,2.07940,-0.43306 +4.49423,0.91905,-1.43300,-1.37404,-1.10027,2.07931,-0.43297 +4.49622,0.91917,-1.43330,-1.37344,-1.10053,2.07922,-0.43287 +4.49821,0.91924,-1.43348,-1.37308,-1.10069,2.07917,-0.43282 +4.50020,0.91936,-1.43383,-1.37239,-1.10098,2.07909,-0.43273 +4.50219,0.91947,-1.43417,-1.37172,-1.10127,2.07901,-0.43264 +4.50418,0.91958,-1.43450,-1.37106,-1.10156,2.07892,-0.43255 +4.50617,0.91969,-1.43483,-1.37040,-1.10184,2.07885,-0.43247 +4.50816,0.91980,-1.43516,-1.36976,-1.10211,2.07877,-0.43238 +4.51016,0.91991,-1.43548,-1.36913,-1.10239,2.07869,-0.43230 +4.51215,0.92001,-1.43579,-1.36851,-1.10266,2.07862,-0.43222 +4.51414,0.92011,-1.43610,-1.36790,-1.10292,2.07854,-0.43215 +4.51613,0.92020,-1.43638,-1.36735,-1.10316,2.07848,-0.43208 +4.51812,0.92029,-1.43673,-1.36667,-1.10345,2.07841,-0.43201 +4.52011,0.92038,-1.43708,-1.36601,-1.10373,2.07835,-0.43194 +4.52210,0.92047,-1.43742,-1.36536,-1.10401,2.07828,-0.43187 +4.52409,0.92055,-1.43775,-1.36472,-1.10429,2.07822,-0.43180 +4.52609,0.92064,-1.43808,-1.36409,-1.10456,2.07816,-0.43174 +4.52808,0.92072,-1.43840,-1.36346,-1.10483,2.07810,-0.43167 +4.53007,0.92080,-1.43872,-1.36285,-1.10509,2.07804,-0.43161 +4.53206,0.92081,-1.43876,-1.36278,-1.10512,2.07804,-0.43161 +4.53405,0.92087,-1.43916,-1.36204,-1.10543,2.07799,-0.43156 +4.53604,0.92093,-1.43956,-1.36131,-1.10574,2.07795,-0.43151 +4.53803,0.92099,-1.43995,-1.36059,-1.10604,2.07791,-0.43147 +4.54002,0.92105,-1.44034,-1.35989,-1.10634,2.07786,-0.43142 +4.54202,0.92110,-1.44071,-1.35919,-1.10664,2.07782,-0.43138 +4.54401,0.92116,-1.44109,-1.35851,-1.10693,2.07778,-0.43134 +4.54600,0.92121,-1.44145,-1.35784,-1.10722,2.07774,-0.43130 +4.54799,0.92126,-1.44181,-1.35717,-1.10750,2.07771,-0.43126 +4.54998,0.92131,-1.44217,-1.35652,-1.10778,2.07767,-0.43122 +4.55197,0.92136,-1.44252,-1.35588,-1.10805,2.07763,-0.43118 +4.55396,0.92141,-1.44286,-1.35525,-1.10832,2.07760,-0.43115 +4.55595,0.92146,-1.44320,-1.35463,-1.10859,2.07756,-0.43111 +4.55795,0.92146,-1.44324,-1.35455,-1.10862,2.07756,-0.43111 +4.55994,0.92148,-1.44368,-1.35379,-1.10894,2.07755,-0.43110 +4.56193,0.92149,-1.44410,-1.35304,-1.10925,2.07754,-0.43109 +4.56392,0.92151,-1.44453,-1.35231,-1.10956,2.07753,-0.43108 +4.56591,0.92152,-1.44494,-1.35158,-1.10986,2.07751,-0.43107 +4.56790,0.92154,-1.44535,-1.35087,-1.11016,2.07750,-0.43106 +4.56989,0.92155,-1.44575,-1.35017,-1.11046,2.07749,-0.43105 +4.57188,0.92156,-1.44614,-1.34948,-1.11075,2.07748,-0.43104 +4.57387,0.92158,-1.44653,-1.34880,-1.11104,2.07747,-0.43103 +4.57587,0.92159,-1.44691,-1.34813,-1.11132,2.07747,-0.43102 +4.57786,0.92160,-1.44729,-1.34747,-1.11160,2.07746,-0.43102 +4.57985,0.92161,-1.44766,-1.34682,-1.11188,2.07745,-0.43101 +4.58184,0.92162,-1.44802,-1.34618,-1.11215,2.07744,-0.43100 +4.58383,0.92163,-1.44838,-1.34555,-1.11242,2.07743,-0.43100 +4.58582,0.92162,-1.44846,-1.34541,-1.11248,2.07744,-0.43100 +4.58781,0.92157,-1.44893,-1.34465,-1.11280,2.07747,-0.43104 +4.58980,0.92152,-1.44939,-1.34389,-1.11311,2.07751,-0.43109 +4.59180,0.92147,-1.44985,-1.34315,-1.11341,2.07755,-0.43113 +4.59379,0.92142,-1.45029,-1.34242,-1.11372,2.07758,-0.43117 +4.59578,0.92137,-1.45073,-1.34170,-1.11402,2.07762,-0.43121 +4.59777,0.92132,-1.45116,-1.34099,-1.11431,2.07765,-0.43125 +4.59976,0.92127,-1.45159,-1.34029,-1.11460,2.07769,-0.43129 +4.60175,0.92122,-1.45201,-1.33961,-1.11489,2.07772,-0.43133 +4.60374,0.92117,-1.45242,-1.33893,-1.11517,2.07776,-0.43137 +4.60573,0.92112,-1.45282,-1.33827,-1.11545,2.07779,-0.43141 +4.60773,0.92108,-1.45322,-1.33761,-1.11573,2.07782,-0.43145 +4.60972,0.92103,-1.45361,-1.33697,-1.11600,2.07786,-0.43149 +4.61171,0.92098,-1.45400,-1.33633,-1.11627,2.07789,-0.43152 +4.61370,0.92093,-1.45438,-1.33569,-1.11654,2.07793,-0.43157 +4.61569,0.92084,-1.45486,-1.33494,-1.11685,2.07799,-0.43164 +4.61768,0.92075,-1.45534,-1.33420,-1.11715,2.07806,-0.43171 +4.61967,0.92065,-1.45580,-1.33347,-1.11746,2.07812,-0.43179 +4.62166,0.92057,-1.45626,-1.33274,-1.11775,2.07819,-0.43186 +4.62366,0.92048,-1.45670,-1.33204,-1.11805,2.07825,-0.43193 +4.62565,0.92039,-1.45714,-1.33134,-1.11834,2.07831,-0.43200 +4.62764,0.92030,-1.45758,-1.33065,-1.11863,2.07837,-0.43207 +4.62963,0.92022,-1.45801,-1.32997,-1.11891,2.07843,-0.43214 +4.63162,0.92013,-1.45843,-1.32931,-1.11919,2.07849,-0.43221 +4.63361,0.92005,-1.45884,-1.32865,-1.11946,2.07855,-0.43227 +4.63560,0.91997,-1.45924,-1.32800,-1.11973,2.07861,-0.43234 +4.63759,0.91989,-1.45964,-1.32737,-1.12000,2.07867,-0.43240 +4.63959,0.91981,-1.46004,-1.32674,-1.12027,2.07873,-0.43247 +4.64158,0.91974,-1.46033,-1.32629,-1.12046,2.07877,-0.43252 +4.64357,0.91955,-1.46090,-1.32546,-1.12079,2.07891,-0.43268 +4.64556,0.91936,-1.46146,-1.32464,-1.12112,2.07905,-0.43283 +4.64755,0.91917,-1.46201,-1.32384,-1.12144,2.07918,-0.43298 +4.64954,0.91899,-1.46255,-1.32304,-1.12176,2.07931,-0.43312 +4.65153,0.91880,-1.46308,-1.32226,-1.12208,2.07944,-0.43327 +4.65352,0.91862,-1.46360,-1.32149,-1.12239,2.07957,-0.43341 +4.65552,0.91845,-1.46412,-1.32074,-1.12270,2.07970,-0.43355 +4.65751,0.91827,-1.46463,-1.31999,-1.12300,2.07982,-0.43369 +4.65950,0.91810,-1.46512,-1.31926,-1.12330,2.07994,-0.43382 +4.66149,0.91794,-1.46561,-1.31854,-1.12360,2.08006,-0.43396 +4.66348,0.91777,-1.46610,-1.31783,-1.12389,2.08018,-0.43409 +4.66547,0.91761,-1.46657,-1.31712,-1.12418,2.08029,-0.43422 +4.66746,0.91745,-1.46704,-1.31643,-1.12446,2.08041,-0.43435 +4.66945,0.91729,-1.46750,-1.31576,-1.12475,2.08052,-0.43447 +4.67145,0.91714,-1.46795,-1.31509,-1.12502,2.08063,-0.43460 +4.67344,0.91698,-1.46839,-1.31443,-1.12530,2.08074,-0.43472 +4.67543,0.91683,-1.46883,-1.31378,-1.12557,2.08085,-0.43484 +4.67742,0.91669,-1.46926,-1.31314,-1.12584,2.08096,-0.43496 +4.67941,0.91654,-1.46968,-1.31251,-1.12610,2.08106,-0.43508 +4.68140,0.91640,-1.47009,-1.31189,-1.12636,2.08116,-0.43519 +4.68339,0.91626,-1.47050,-1.31128,-1.12662,2.08126,-0.43531 +4.68538,0.91612,-1.47090,-1.31068,-1.12687,2.08136,-0.43542 +4.68738,0.91606,-1.47107,-1.31044,-1.12697,2.08141,-0.43547 +4.68937,0.91588,-1.47152,-1.30979,-1.12724,2.08153,-0.43561 +4.69136,0.91570,-1.47196,-1.30915,-1.12751,2.08166,-0.43575 +4.69335,0.91553,-1.47239,-1.30852,-1.12777,2.08178,-0.43589 +4.69534,0.91536,-1.47282,-1.30790,-1.12803,2.08191,-0.43602 +4.69733,0.91519,-1.47324,-1.30729,-1.12828,2.08203,-0.43616 +4.69932,0.91503,-1.47365,-1.30669,-1.12853,2.08214,-0.43629 +4.70131,0.91487,-1.47406,-1.30610,-1.12878,2.08226,-0.43642 +4.70331,0.91473,-1.47439,-1.30563,-1.12898,2.08236,-0.43653 +4.70530,0.91449,-1.47488,-1.30496,-1.12925,2.08253,-0.43672 +4.70729,0.91426,-1.47535,-1.30431,-1.12952,2.08269,-0.43691 +4.70928,0.91403,-1.47582,-1.30366,-1.12978,2.08286,-0.43709 +4.71127,0.91381,-1.47629,-1.30302,-1.13004,2.08302,-0.43727 +4.71326,0.91358,-1.47674,-1.30240,-1.13030,2.08318,-0.43745 +4.71525,0.91337,-1.47719,-1.30178,-1.13055,2.08333,-0.43762 +4.71724,0.91315,-1.47763,-1.30117,-1.13080,2.08349,-0.43779 +4.71924,0.91294,-1.47806,-1.30058,-1.13105,2.08364,-0.43796 +4.72123,0.91273,-1.47849,-1.29999,-1.13130,2.08378,-0.43813 +4.72322,0.91253,-1.47891,-1.29941,-1.13154,2.08393,-0.43829 +4.72521,0.91233,-1.47932,-1.29883,-1.13178,2.08407,-0.43845 +4.72720,0.91213,-1.47972,-1.29827,-1.13201,2.08422,-0.43861 +4.72919,0.91199,-1.48001,-1.29788,-1.13218,2.08432,-0.43872 +4.73118,0.91175,-1.48045,-1.29729,-1.13242,2.08449,-0.43892 +4.73317,0.91151,-1.48088,-1.29671,-1.13266,2.08466,-0.43911 +4.73517,0.91128,-1.48131,-1.29614,-1.13289,2.08482,-0.43929 +4.73716,0.91105,-1.48173,-1.29558,-1.13312,2.08499,-0.43948 +4.73915,0.91083,-1.48214,-1.29502,-1.13335,2.08515,-0.43966 +4.74114,0.91061,-1.48255,-1.29448,-1.13358,2.08531,-0.43983 +4.74313,0.91039,-1.48295,-1.29394,-1.13381,2.08546,-0.44001 +4.74512,0.91032,-1.48308,-1.29377,-1.13388,2.08552,-0.44007 +4.74711,0.91001,-1.48357,-1.29314,-1.13413,2.08573,-0.44031 +4.74910,0.90971,-1.48406,-1.29252,-1.13438,2.08595,-0.44055 +4.75110,0.90942,-1.48454,-1.29191,-1.13462,2.08616,-0.44078 +4.75309,0.90913,-1.48501,-1.29131,-1.13486,2.08636,-0.44102 +4.75508,0.90885,-1.48547,-1.29072,-1.13510,2.08656,-0.44124 +4.75707,0.90857,-1.48593,-1.29013,-1.13534,2.08676,-0.44147 +4.75906,0.90830,-1.48638,-1.28956,-1.13558,2.08696,-0.44169 +4.76105,0.90803,-1.48682,-1.28899,-1.13581,2.08715,-0.44190 +4.76304,0.90776,-1.48725,-1.28843,-1.13604,2.08734,-0.44211 +4.76503,0.90750,-1.48767,-1.28789,-1.13626,2.08753,-0.44232 +4.76703,0.90725,-1.48809,-1.28734,-1.13649,2.08771,-0.44253 +4.76902,0.90699,-1.48851,-1.28681,-1.13671,2.08789,-0.44273 +4.77101,0.90675,-1.48891,-1.28629,-1.13693,2.08807,-0.44293 +4.77300,0.90650,-1.48931,-1.28577,-1.13714,2.08824,-0.44313 +4.77499,0.90628,-1.48967,-1.28530,-1.13733,2.08840,-0.44330 +4.77698,0.90599,-1.49012,-1.28473,-1.13757,2.08861,-0.44354 +4.77897,0.90571,-1.49057,-1.28416,-1.13780,2.08881,-0.44376 +4.78096,0.90543,-1.49101,-1.28360,-1.13803,2.08901,-0.44399 +4.78295,0.90516,-1.49144,-1.28305,-1.13825,2.08920,-0.44421 +4.78495,0.90489,-1.49187,-1.28251,-1.13847,2.08940,-0.44443 +4.78694,0.90462,-1.49229,-1.28198,-1.13870,2.08959,-0.44464 +4.78893,0.90436,-1.49270,-1.28145,-1.13891,2.08977,-0.44485 +4.79092,0.90410,-1.49310,-1.28094,-1.13913,2.08996,-0.44506 +4.79291,0.90385,-1.49350,-1.28043,-1.13934,2.09014,-0.44526 +4.79490,0.90361,-1.49389,-1.27993,-1.13955,2.09032,-0.44546 +4.79689,0.90355,-1.49398,-1.27982,-1.13959,2.09035,-0.44550 +4.79888,0.90327,-1.49439,-1.27930,-1.13981,2.09055,-0.44573 +4.80088,0.90300,-1.49481,-1.27878,-1.14002,2.09075,-0.44595 +4.80287,0.90273,-1.49521,-1.27827,-1.14023,2.09094,-0.44617 +4.80486,0.90247,-1.49561,-1.27777,-1.14044,2.09113,-0.44638 +4.80685,0.90221,-1.49600,-1.27728,-1.14064,2.09132,-0.44659 +4.80884,0.90197,-1.49636,-1.27684,-1.14083,2.09148,-0.44678 +4.81083,0.90170,-1.49676,-1.27634,-1.14103,2.09168,-0.44700 +4.81282,0.90143,-1.49716,-1.27584,-1.14124,2.09187,-0.44722 +4.81481,0.90116,-1.49755,-1.27536,-1.14144,2.09206,-0.44744 +4.81681,0.90090,-1.49793,-1.27488,-1.14164,2.09225,-0.44765 +4.81880,0.90062,-1.49834,-1.27439,-1.14184,2.09245,-0.44788 +4.82079,0.90034,-1.49873,-1.27390,-1.14204,2.09265,-0.44810 +4.82278,0.90007,-1.49912,-1.27342,-1.14224,2.09285,-0.44832 +4.82477,0.89980,-1.49950,-1.27295,-1.14244,2.09304,-0.44854 +4.82676,0.89977,-1.49955,-1.27290,-1.14246,2.09306,-0.44856 +4.82875,0.89946,-1.49997,-1.27240,-1.14266,2.09328,-0.44881 +4.83074,0.89916,-1.50039,-1.27190,-1.14287,2.09350,-0.44906 +4.83274,0.89886,-1.50080,-1.27141,-1.14307,2.09371,-0.44930 +4.83473,0.89856,-1.50120,-1.27093,-1.14326,2.09392,-0.44954 +4.83672,0.89827,-1.50159,-1.27045,-1.14346,2.09413,-0.44977 +4.83871,0.89799,-1.50198,-1.26998,-1.14365,2.09433,-0.45000 +4.84070,0.89771,-1.50237,-1.26952,-1.14385,2.09453,-0.45023 +4.84269,0.89748,-1.50267,-1.26915,-1.14400,2.09469,-0.45041 +4.84468,0.89711,-1.50310,-1.26869,-1.14418,2.09496,-0.45072 +4.84667,0.89674,-1.50352,-1.26824,-1.14436,2.09522,-0.45101 +4.84867,0.89638,-1.50394,-1.26779,-1.14454,2.09548,-0.45130 +4.85066,0.89602,-1.50435,-1.26735,-1.14471,2.09573,-0.45159 +4.85265,0.89568,-1.50475,-1.26692,-1.14489,2.09598,-0.45187 +4.85464,0.89533,-1.50514,-1.26649,-1.14506,2.09622,-0.45215 +4.85663,0.89500,-1.50553,-1.26607,-1.14523,2.09646,-0.45242 +4.85862,0.89467,-1.50591,-1.26565,-1.14540,2.09670,-0.45269 +4.86061,0.89434,-1.50628,-1.26524,-1.14556,2.09693,-0.45295 +4.86260,0.89402,-1.50665,-1.26484,-1.14573,2.09716,-0.45321 +4.86460,0.89371,-1.50701,-1.26444,-1.14589,2.09738,-0.45347 +4.86659,0.89340,-1.50737,-1.26405,-1.14605,2.09760,-0.45372 +4.86858,0.89337,-1.50741,-1.26401,-1.14607,2.09763,-0.45375 +4.87057,0.89301,-1.50780,-1.26360,-1.14623,2.09788,-0.45403 +4.87256,0.89266,-1.50818,-1.26320,-1.14640,2.09813,-0.45432 +4.87455,0.89232,-1.50856,-1.26280,-1.14655,2.09837,-0.45460 +4.87654,0.89198,-1.50893,-1.26241,-1.14671,2.09861,-0.45487 +4.87853,0.89165,-1.50929,-1.26203,-1.14687,2.09885,-0.45514 +4.88053,0.89132,-1.50965,-1.26165,-1.14702,2.09908,-0.45541 +4.88252,0.89100,-1.51000,-1.26128,-1.14718,2.09931,-0.45567 +4.88451,0.89077,-1.51025,-1.26102,-1.14728,2.09947,-0.45585 +4.88650,0.89040,-1.51061,-1.26068,-1.14742,2.09974,-0.45616 +4.88849,0.89002,-1.51097,-1.26034,-1.14755,2.10001,-0.45646 +4.89048,0.88966,-1.51132,-1.26000,-1.14768,2.10027,-0.45676 +4.89247,0.88930,-1.51166,-1.25967,-1.14782,2.10052,-0.45705 +4.89446,0.88895,-1.51200,-1.25935,-1.14795,2.10077,-0.45734 +4.89646,0.88860,-1.51234,-1.25903,-1.14808,2.10102,-0.45762 +4.89845,0.88826,-1.51267,-1.25871,-1.14820,2.10126,-0.45790 +4.90044,0.88805,-1.51286,-1.25853,-1.14828,2.10141,-0.45807 +4.90243,0.88765,-1.51319,-1.25826,-1.14838,2.10169,-0.45839 +4.90442,0.88725,-1.51352,-1.25799,-1.14848,2.10198,-0.45872 +4.90641,0.88686,-1.51384,-1.25773,-1.14858,2.10225,-0.45903 +4.90840,0.88648,-1.51416,-1.25747,-1.14868,2.10253,-0.45935 +4.91039,0.88610,-1.51447,-1.25722,-1.14878,2.10279,-0.45965 +4.91239,0.88573,-1.51477,-1.25697,-1.14888,2.10306,-0.45996 +4.91438,0.88537,-1.51507,-1.25672,-1.14898,2.10331,-0.46025 +4.91637,0.88501,-1.51537,-1.25648,-1.14908,2.10357,-0.46054 +4.91836,0.88494,-1.51543,-1.25643,-1.14910,2.10362,-0.46061 +4.92035,0.88453,-1.51572,-1.25625,-1.14917,2.10391,-0.46094 +4.92234,0.88412,-1.51600,-1.25606,-1.14924,2.10420,-0.46127 +4.92433,0.88372,-1.51628,-1.25587,-1.14931,2.10448,-0.46160 +4.92632,0.88334,-1.51656,-1.25569,-1.14937,2.10476,-0.46191 +4.92832,0.88295,-1.51683,-1.25551,-1.14944,2.10503,-0.46223 +4.93031,0.88258,-1.51709,-1.25534,-1.14951,2.10530,-0.46253 +4.93230,0.88221,-1.51736,-1.25516,-1.14958,2.10556,-0.46284 +4.93429,0.88217,-1.51738,-1.25515,-1.14958,2.10559,-0.46287 +4.93628,0.88175,-1.51763,-1.25504,-1.14962,2.10588,-0.46321 +4.93827,0.88135,-1.51787,-1.25493,-1.14966,2.10617,-0.46354 +4.94026,0.88095,-1.51810,-1.25482,-1.14970,2.10645,-0.46386 +4.94225,0.88056,-1.51834,-1.25471,-1.14974,2.10673,-0.46418 +4.94425,0.88018,-1.51857,-1.25460,-1.14978,2.10700,-0.46450 +4.94624,0.87983,-1.51877,-1.25451,-1.14981,2.10724,-0.46478 +4.94823,0.87942,-1.51899,-1.25445,-1.14983,2.10753,-0.46512 +4.95022,0.87901,-1.51921,-1.25439,-1.14985,2.10782,-0.46545 +4.95221,0.87861,-1.51942,-1.25432,-1.14986,2.10811,-0.46578 +4.95420,0.87822,-1.51963,-1.25426,-1.14988,2.10838,-0.46610 +4.95619,0.87783,-1.51983,-1.25420,-1.14990,2.10866,-0.46642 +4.95818,0.87756,-1.51998,-1.25416,-1.14992,2.10885,-0.46664 +4.96018,0.87717,-1.52017,-1.25413,-1.14992,2.10913,-0.46697 +4.96217,0.87677,-1.52036,-1.25410,-1.14993,2.10941,-0.46729 +4.96416,0.87639,-1.52055,-1.25407,-1.14993,2.10968,-0.46761 +4.96615,0.87620,-1.52064,-1.25406,-1.14994,2.10982,-0.46777 +4.96814,0.87580,-1.52082,-1.25406,-1.14993,2.11010,-0.46809 +4.97013,0.87540,-1.52099,-1.25406,-1.14992,2.11038,-0.46842 +4.97212,0.87502,-1.52116,-1.25405,-1.14992,2.11065,-0.46873 +4.97411,0.87483,-1.52125,-1.25406,-1.14991,2.11079,-0.46889 +4.97611,0.87443,-1.52141,-1.25409,-1.14989,2.11107,-0.46922 +4.97810,0.87403,-1.52157,-1.25411,-1.14987,2.11135,-0.46955 +4.98009,0.87365,-1.52172,-1.25414,-1.14986,2.11162,-0.46986 +4.98208,0.87338,-1.52183,-1.25416,-1.14984,2.11181,-0.47008 +4.98407,0.87300,-1.52197,-1.25421,-1.14982,2.11208,-0.47040 +4.98606,0.87296,-1.52199,-1.25421,-1.14982,2.11211,-0.47043 +4.98805,0.87258,-1.52212,-1.25428,-1.14978,2.11237,-0.47074 +4.99004,0.87254,-1.52213,-1.25429,-1.14978,2.11240,-0.47078 +4.99204,0.87216,-1.52225,-1.25437,-1.14974,2.11267,-0.47109 +4.99403,0.87208,-1.52227,-1.25439,-1.14973,2.11272,-0.47115 +4.99602,0.87171,-1.52238,-1.25449,-1.14968,2.11299,-0.47146 +4.99801,0.87163,-1.52240,-1.25451,-1.14967,2.11305,-0.47153 +5.00000,0.87125,-1.52250,-1.25463,-1.14961,2.11331,-0.47184 diff --git a/python/examples/path_in_pixels.csv b/python/examples/path_in_pixels.csv index 4ec83a9f25609bc316da683202a4869aa939e42b..9fb1c44bd83f471c457909b87ea6269a70756529 100644 --- a/python/examples/path_in_pixels.csv +++ b/python/examples/path_in_pixels.csv @@ -1,109 +1,298 @@ -0.32221,0.57748 -0.32221,0.57879 -0.31776,0.59062 -0.29848,0.61165 -0.28810,0.62480 -0.28068,0.63137 -0.27623,0.63794 -0.25844,0.64977 -0.24805,0.65503 -0.23619,0.65897 -0.21542,0.66423 -0.19763,0.66686 -0.17983,0.67080 -0.16352,0.67212 -0.14275,0.67212 -0.12644,0.67212 -0.11754,0.67080 -0.11012,0.66686 -0.10271,0.66554 -0.09381,0.66160 -0.08343,0.65240 -0.07453,0.63794 -0.06711,0.62743 -0.06266,0.62085 -0.05970,0.61428 -0.05970,0.59982 -0.06266,0.58799 -0.06711,0.57222 -0.07453,0.55513 -0.08194,0.54198 -0.08936,0.52884 -0.09974,0.51569 -0.11309,0.49729 -0.11457,0.49203 -0.11754,0.48678 -0.12644,0.48020 -0.14720,0.47495 -0.16796,0.46969 -0.18428,0.46574 -0.19466,0.45917 -0.20801,0.45129 -0.21987,0.43946 -0.23471,0.42631 -0.24805,0.41317 -0.26288,0.39608 -0.27030,0.38293 -0.27623,0.36979 -0.28068,0.35401 -0.28958,0.33561 -0.29551,0.31195 -0.29700,0.30275 -0.29700,0.29881 -0.29700,0.29618 -0.29996,0.33035 -0.30590,0.35270 -0.31331,0.37110 -0.32221,0.39213 -0.33111,0.40922 -0.34149,0.42105 -0.35039,0.43288 -0.36374,0.44734 -0.37560,0.45786 -0.38450,0.47232 -0.39785,0.48415 -0.40823,0.49466 -0.42010,0.50255 -0.43344,0.51569 -0.44234,0.52621 -0.44976,0.53673 -0.45569,0.54724 -0.46014,0.55644 -0.46459,0.56696 -0.47052,0.57616 -0.47646,0.58799 -0.47794,0.59719 -0.47942,0.61691 -0.47942,0.64451 -0.47942,0.67080 -0.47942,0.68263 -0.47794,0.68921 -0.45866,0.68921 -0.44828,0.68921 -0.43789,0.68789 -0.42455,0.68789 -0.41416,0.68789 -0.40378,0.68789 -0.39488,0.68526 -0.38598,0.68263 -0.38005,0.68132 -0.37560,0.67869 -0.36670,0.67212 -0.35780,0.66554 -0.34742,0.65503 -0.34446,0.64846 -0.34149,0.64320 -0.34001,0.63794 -0.33852,0.63400 -0.33704,0.62085 -0.33704,0.61034 -0.33556,0.59851 -0.33556,0.58536 -0.33407,0.58010 -0.33259,0.57485 -0.33111,0.56959 -0.32814,0.56564 -0.32814,0.56433 -0.32814,0.56170 -0.32518,0.56039 -0.32518,0.56039 +0.10535,0.77914 +0.10535,0.78062 +0.10535,0.78210 +0.10975,0.78952 +0.11561,0.79990 +0.12440,0.80880 +0.13466,0.81473 +0.14198,0.82215 +0.14784,0.82660 +0.15663,0.83253 +0.16249,0.83698 +0.18300,0.85033 +0.19472,0.85626 +0.21084,0.86071 +0.22109,0.86219 +0.23282,0.86367 +0.24454,0.86516 +0.25626,0.86516 +0.26651,0.86516 +0.27677,0.86367 +0.28409,0.86219 +0.29581,0.85923 +0.30753,0.85478 +0.31779,0.84884 +0.32805,0.84439 +0.33684,0.83995 +0.34270,0.83550 +0.34856,0.83253 +0.35149,0.82956 +0.35588,0.82660 +0.36028,0.82215 +0.36467,0.81770 +0.36907,0.81177 +0.37493,0.80583 +0.37932,0.79990 +0.38518,0.78952 +0.38958,0.78210 +0.39397,0.77469 +0.39837,0.76727 +0.40569,0.75837 +0.41009,0.74948 +0.43060,0.75393 +0.44672,0.75689 +0.45990,0.75986 +0.47016,0.76134 +0.48041,0.76282 +0.48920,0.76579 +0.49946,0.76876 +0.51704,0.77766 +0.52290,0.78062 +0.52876,0.78359 +0.53462,0.78655 +0.54195,0.79100 +0.55074,0.79545 +0.55953,0.79990 +0.57564,0.80583 +0.58297,0.80880 +0.59029,0.81177 +0.59615,0.81473 +0.60201,0.81622 +0.60641,0.81918 +0.60934,0.82066 +0.61227,0.82066 +0.61520,0.82215 +0.62106,0.82511 +0.62546,0.82808 +0.63278,0.83105 +0.64304,0.83698 +0.65036,0.83995 +0.66062,0.84439 +0.67820,0.85181 +0.68552,0.85478 +0.69138,0.85626 +0.69578,0.85774 +0.70017,0.85923 +0.70604,0.86071 +0.71043,0.86219 +0.71776,0.86219 +0.72362,0.86219 +0.73094,0.86219 +0.73534,0.86219 +0.74120,0.86219 +0.74413,0.86071 +0.74706,0.85923 +0.74999,0.85774 +0.75145,0.85774 +0.75292,0.85626 +0.75585,0.85478 +0.75878,0.85329 +0.76171,0.85033 +0.76610,0.84588 +0.76903,0.84291 +0.77050,0.84143 +0.77196,0.83995 +0.77489,0.83698 +0.77636,0.83550 +0.77782,0.83253 +0.77929,0.83105 +0.78075,0.82956 +0.78075,0.82808 +0.78075,0.82808 +0.78075,0.82660 +0.78075,0.82660 +0.78222,0.82511 +0.78368,0.82363 +0.78515,0.82215 +0.78661,0.81918 +0.78808,0.81622 +0.78954,0.81473 +0.79101,0.81177 +0.79247,0.81028 +0.79247,0.80880 +0.79247,0.80732 +0.79247,0.80583 +0.79247,0.80583 +0.79247,0.80435 +0.79247,0.80287 +0.79247,0.80138 +0.79247,0.79990 +0.79247,0.79990 +0.79540,0.79397 +0.79687,0.78952 +0.79687,0.78655 +0.79687,0.78507 +0.79687,0.78359 +0.79687,0.77914 +0.79687,0.77321 +0.79687,0.76727 +0.79540,0.76282 +0.79394,0.75837 +0.79247,0.75393 +0.79247,0.74799 +0.79101,0.74354 +0.78954,0.73613 +0.78808,0.73168 +0.78808,0.72426 +0.78661,0.71685 +0.78515,0.71388 +0.78515,0.70795 +0.78368,0.70202 +0.78222,0.69905 +0.78075,0.69460 +0.78075,0.69164 +0.78075,0.68867 +0.78075,0.68719 +0.78075,0.68570 +0.78075,0.68422 +0.78075,0.68422 +0.78075,0.68274 +0.78075,0.68422 +0.78222,0.68570 +0.78515,0.69164 +0.78808,0.69757 +0.79394,0.70202 +0.79540,0.70498 +0.79687,0.70647 +0.79834,0.70795 +0.79980,0.70943 +0.80859,0.71537 +0.81592,0.71833 +0.81885,0.71981 +0.82324,0.72278 +0.82471,0.72278 +0.82617,0.72278 +0.82764,0.72278 +0.83203,0.72575 +0.83643,0.72723 +0.84229,0.72871 +0.84961,0.73168 +0.85694,0.73465 +0.86133,0.73465 +0.86573,0.73465 +0.87012,0.73465 +0.87159,0.73465 +0.87159,0.73465 +0.87452,0.73465 +0.87598,0.73465 +0.88624,0.72130 +0.89650,0.70498 +0.90529,0.69015 +0.91115,0.68125 +0.91701,0.67236 +0.91994,0.66791 +0.92287,0.66346 +0.92433,0.66197 +0.92580,0.65901 +0.92580,0.65604 +0.92726,0.65308 +0.93019,0.64714 +0.93605,0.63379 +0.94191,0.62193 +0.94631,0.60710 +0.94777,0.59820 +0.94924,0.58930 +0.94924,0.58337 +0.94924,0.57299 +0.94924,0.56706 +0.94924,0.56112 +0.94924,0.55816 +0.94924,0.55519 +0.94924,0.55371 +0.94924,0.55371 +0.94777,0.54778 +0.94338,0.54036 +0.93459,0.52998 +0.92580,0.51960 +0.91701,0.51070 +0.90675,0.50328 +0.89357,0.49290 +0.87745,0.48252 +0.86573,0.47362 +0.85254,0.46472 +0.84668,0.45879 +0.83643,0.45137 +0.82764,0.44544 +0.81738,0.43951 +0.81006,0.43654 +0.79687,0.43061 +0.79101,0.42913 +0.78661,0.42913 +0.78075,0.42764 +0.77782,0.42764 +0.77196,0.42616 +0.76903,0.42616 +0.76317,0.42616 +0.76171,0.42616 +0.76024,0.42616 +0.75878,0.42616 +0.75731,0.42616 +0.75585,0.42616 +0.75438,0.42616 +0.75292,0.42616 +0.74999,0.42320 +0.74706,0.41726 +0.74120,0.40836 +0.73680,0.40095 +0.73094,0.38760 +0.73094,0.38612 +0.72948,0.38464 +0.72948,0.38315 +0.72948,0.38167 +0.72948,0.38019 +0.72801,0.38019 +0.72655,0.38019 +0.71483,0.39353 +0.70164,0.41133 +0.68552,0.45286 +0.67966,0.47510 +0.67527,0.49142 +0.67087,0.50773 +0.66794,0.51811 +0.66648,0.52701 +0.66355,0.53888 +0.66062,0.55816 +0.66062,0.58040 +0.66062,0.60117 +0.66208,0.62045 +0.66208,0.63528 +0.66208,0.64418 +0.66501,0.65456 +0.66501,0.65901 +0.66648,0.66346 +0.66648,0.66642 +0.66941,0.67236 +0.67087,0.67532 +0.67380,0.68125 +0.67673,0.68570 +0.68259,0.69312 +0.68992,0.70053 +0.70017,0.70647 +0.70897,0.71240 +0.72655,0.71981 +0.73241,0.72130 +0.74266,0.72278 +0.74852,0.72278 +0.76024,0.72426 +0.76757,0.72575 +0.77196,0.72575 +0.77489,0.72575 +0.77782,0.72575 +0.78368,0.72575 +0.79394,0.72130 +0.79980,0.71981 +0.80566,0.71537 +0.81152,0.70943 +0.81592,0.70350 +0.81885,0.69757 +0.82178,0.69312 +0.82324,0.69015 +0.82471,0.68719 +0.82617,0.68422 +0.82617,0.68274 +0.82617,0.68125 +0.82617,0.67977 +0.82617,0.67977 +0.82617,0.67829 +0.82617,0.67680 +0.82617,0.67680 diff --git a/python/examples/planar_dragging_via_top_contact_force.py b/python/examples/planar_dragging_via_top_contact_force.py new file mode 100644 index 0000000000000000000000000000000000000000..653485e12bab015a78ed1aa23026942f106f4259 --- /dev/null +++ b/python/examples/planar_dragging_via_top_contact_force.py @@ -0,0 +1,253 @@ +import pinocchio as pin +import numpy as np +import matplotlib.pyplot as plt +import copy +import argparse +import time +from functools import partial +from ur_simple_control.util.get_model import get_model +from ur_simple_control.visualize.visualize import plotFromDict +from ur_simple_control.util.draw_path import drawPath +from ur_simple_control.dmp.dmp import DMP, NoTC,TCVelAccConstrained +# TODO merge these clik files as well, they don't deserve to be separate +# TODO but first you need to clean up clik.py as specified there +from ur_simple_control.clik.clik_point_to_point import getClikController, moveL, moveUntilContact +from ur_simple_control.clik.clik_trajectory_following import map2DPathTo3DPlane, clikCartesianPathIntoJointPath +from ur_simple_control.managers import ControlLoopManager, RobotManager +from ur_simple_control.util.calib_board_hacks import calibratePlane, getSpeedInDirectionOfN +from ur_simple_control.visualize.visualize import plotFromDict +from ur_simple_control.basics.basics import moveJ + +####################################################################### +# arguments # +####################################################################### + +def getArgs(): + ####################################################################### + # generic arguments # + ####################################################################### + parser = argparse.ArgumentParser(description='Make a drawing on screen,\ + watch the robot do it on the whiteboard.', + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + # TODO this one won't really work but let's leave it here for the future + parser.add_argument('--simulation', action=argparse.BooleanOptionalAction, + help="whether you are running the UR simulator. \ + NOTE: doesn't actually work because it's not a physics simulator", \ + default=False) + parser.add_argument('--pinocchio-only', action=argparse.BooleanOptionalAction, + help="whether you want to just integrate with pinocchio.\ + NOTE: doesn't actually work because it's not a physics simulator", \ + default=False) + parser.add_argument('--visualize', action=argparse.BooleanOptionalAction, + help="whether you want to visualize with gepetto, but \ + NOTE: not implemented yet", default=False) + parser.add_argument('--gripper', action=argparse.BooleanOptionalAction, \ + help="whether you're using the gripper", default=False) + parser.add_argument('--acceleration', type=float, \ + help="robot's joints acceleration. scalar positive constant, \ + max 1.7, and default 0.4. \ + BE CAREFUL WITH THIS. the urscript doc says this is 'lead axis acceleration'.\ + TODO: check what this means", default=0.3) + parser.add_argument('--speed-slider', type=float,\ + help="cap robot's speed with the speed slider \ + to something between 0 and 1, 1.0 by default because for dmp. \ + BE CAREFUL WITH THIS.", default=1.0) + parser.add_argument('--max-iterations', type=int, \ + help="maximum allowable iteration number (it runs at 500Hz)", default=50000) + ####################################################################### + # your controller specific arguments # + ####################################################################### + # not applicable here, but leaving it in the case it becomes applicable + # it's also in the robot manager even though it shouldn't be + parser.add_argument('--past-window-size', type=int, \ + help="how many timesteps of past data you want to save", default=5) + parser.add_argument('--goal-error', type=float, \ + help="the final position error you are happy with. NOTE: not used here", \ + default=1e-3) + # TODO: test the interaction of this and the overall demo + parser.add_argument('--tikhonov-damp', type=float, \ + help="damping scalar in tiknohov regularization.\ + This is used when generating the joint trajectory from the drawing.", \ + default=1e-2) + # TODO add the rest + parser.add_argument('--clik-controller', type=str, \ + help="select which click algorithm you want", \ + default='dampedPseudoinverse', \ + choices=['dampedPseudoinverse', 'jacobianTranspose']) + # maybe you want to scale the control signal + parser.add_argument('--controller-speed-scaling', type=float, \ + default='1.0', help='not actually_used atm') + ############################# + # dmp specific arguments # + ############################# + parser.add_argument('--temporal-coupling', action=argparse.BooleanOptionalAction, \ + help="whether you want to use temporal coupling", default=True) + parser.add_argument('--kp', type=float, \ + help="proportial control constant for position errors", \ + default=1.0) + parser.add_argument('--tau0', type=float, \ + help="total time needed for trajectory. if you use temporal coupling,\ + you can still follow the path even if it's too fast", \ + default=5) + parser.add_argument('--gamma-nominal', type=float, \ + help="positive constant for tuning temporal coupling: the higher,\ + the fast the return rate to nominal tau", \ + default=1.0) + parser.add_argument('--gamma-a', type=float, \ + help="positive constant for tuning temporal coupling, potential term", \ + default=0.5) + parser.add_argument('--eps-tc', type=float, \ + help="temporal coupling term, should be small", \ + default=0.001) + parser.add_argument('--alpha', type=float, \ + help="force feedback proportional coefficient", \ + default=0.007) + # TODO add low pass filtering and make it's parameters arguments too + ####################################################################### + # task specific arguments # + ####################################################################### + # TODO measure this for the new board + parser.add_argument('--board-width', type=float, \ + help="width of the board (in meters) the robot will write on", \ + default=0.5) + parser.add_argument('--board-height', type=float, \ + help="height of the board (in meters) the robot will write on", \ + default=0.35) + parser.add_argument('--calibration', action=argparse.BooleanOptionalAction, \ + help="whether you want to do calibration", default=False) + parser.add_argument('--draw-new', action=argparse.BooleanOptionalAction, \ + help="whether draw a new picture, or use the saved path path_in_pixels.csv", default=True) + parser.add_argument('--pick_up_marker', action=argparse.BooleanOptionalAction, \ + help=""" + whether the robot should pick up the marker. + NOTE: THIS IS FROM A PREDEFINED LOCATION. + """, default=True) + parser.add_argument('--find-marker-offset', action=argparse.BooleanOptionalAction, \ + help=""" + whether you want to do find marker offset (recalculate TCP + based on the marker""", default=False) + parser.add_argument('--n-calibration-tests', type=int, \ + help="number of calibration tests you want to run", default=10) + parser.add_argument('--clik-goal-error', type=float, \ + help="the clik error you are happy with", default=1e-2) + parser.add_argument('--max-init-clik-iterations', type=int, \ + help="number of max clik iterations to get to the first point", default=10000) + parser.add_argument('--max-running-clik-iterations', type=int, \ + help="number of max clik iterations between path points", default=1000) + args = parser.parse_args() + if args.gripper and args.simulation: + raise NotImplementedError('Did not figure out how to put the gripper in \ + the simulation yet, sorry :/ . You can have only 1 these flags right now') + return args + + + + +####################################################################### +# control loop # +####################################################################### + +# feedforward velocity, feedback position and force for impedance +def controller(): + pass + + +# control loop to be passed to ControlLoopManager +def controlLoopPlanarDragging(wrench_offset, dmp, tc, controller, robot, i, past_data): + breakFlag = False + # TODO rename this into something less confusing + save_past_dict = {} + log_item = {} + dmp.step(robot.dt) # dmp step + # temporal coupling step + tau = dmp.tau + tc.update(dmp, robot.dt) * robot.dt + dmp.set_tau(tau) + q = robot.getQ() + Z = np.diag(np.ones(6)) + + wrench = robot.getWrench() + wrench = wrench - wrench_offset + wrench = np.average(np.array(past_data['wrench']), axis=0) + + # first-order low pass filtering + # beta is a smoothing coefficient, smaller values smooth more, has to be in [0,1] + beta = 0.007 + #wrench = beta * wrench + (1 - beta) * past_data['wrench'][-1] + + wrench = robot.getMtool().toDualActionMatrix().T @ wrench + wrench = Z @ robot.getWrench() + # deepcopy for good coding practise (and correctness here) + save_past_dict['wrench'] = copy.deepcopy(wrench) + # rolling average + if i % 100 == 0: + print(wrench) + pin.forwardKinematics(robot.model, robot.data, q) + J = pin.computeJointJacobian(robot.model, robot.data, q, robot.JOINT_ID) + dq = robot.getQd()[:6].reshape((6,1)) + # get joitn + tau = J.T @ wrench + tau = tau[:6].reshape((6,1)) + # compute control law: + #vel_cmd = dmp.vel + args.kp * (dmp.pos - q[:6].reshape((6,1))) + args.alpha * tau + vel_cmd = np.zeros(6) + robot.sendQd(vel_cmd) + + # TODO find a better criterion for stopping + if (np.linalg.norm(dmp.vel) < 0.0001) and (i > 5000): + breakFlag = True + # immediatelly stop if something weird happened (some non-convergence) + if np.isnan(vel_cmd[0]): + breakFlag = True + + # log what you said you'd log + # TODO fix the q6 situation (hide this) + log_item['wrench'] = wrench[:6].reshape((6,)) + + return breakFlag, save_past_dict, log_item + +if __name__ == "__main__": + ####################################################################### + # software setup # + ####################################################################### + args = getArgs() + clikController = getClikController(args) + robot = RobotManager(args) + + # calibrate FT first + wrench_offset = robot.calibrateFT() + + speed_down = np.array([0,0,-1,0,0,0]) + moveUntilContact(args, robot, speed_down) + m_goal_up = robot.getMtool() + m_goal_up.translation[2] += 0.1 + moveL(args, robot, m_goal_up) + + # controlLoopManager will populate the queue with these initial values +# save_past_dict = { +# 'wrench' : np.zeros(6), +# } +# # here you give it it's initial value +# log_dict = { +# 'wrench': np.zeros((args.max_iterations, 6)), +# } +# controlLoop = partial(controlLoopPlanarDragging, wrench_offset, dmp, tc, controller, robot) +# loop_manager = ControlLoopManager(robot, controlLoop, args, save_past_dict, log_dict) +# ####################################################################### +# # physical setup # +# ####################################################################### +# # TODO: add marker picking +# # get up from the board +# current_pose = robot.getMtool() +# # and now we can actually run +# log_dict, final_iteration = loop_manager.run() +# mtool = robot.getMtool() +# mtool.translation[1] = mtool.translation[1] - 0.1 +# moveL(args, robot, mtool) + + plotFromDict(log_dict, args) + robot.stopHandler(None, None) + robot.stopHandler(None, None) + robot.stopHandler(None, None) + # plot results + plotFromDict(log_dict, args) + # TODO: add some math to analyze path precision diff --git a/python/examples/point_impedance_control.py b/python/examples/point_impedance_control.py index 901e1b4e539c3017f564268715eee48eb00f25c4..78ad110f6da290dcc60383b431910c6b4154b84a 100644 --- a/python/examples/point_impedance_control.py +++ b/python/examples/point_impedance_control.py @@ -15,35 +15,12 @@ from ur_simple_control.clik.clik_point_to_point import getClikController, moveL, from ur_simple_control.clik.clik_trajectory_following import map2DPathTo3DPlane, clikCartesianPathIntoJointPath from ur_simple_control.managers import ControlLoopManager, RobotManager from ur_simple_control.util.calib_board_hacks import calibratePlane, getSpeedInDirectionOfN -from ur_simple_control.visualize.visualize import plotFromDict from ur_simple_control.basics.basics import moveJ ####################################################################### # arguments # ####################################################################### -def calibrateFT(robot): - ft_readings = [] - for i in range(2000): - start = time.time() - q = robot.rtde_receive.getActualQ() - ft = robot.rtde_receive.getActualTCPForce() - tau = robot.rtde_control.getJointTorques() - current = robot.rtde_receive.getActualCurrent() - #print("current", current) - #print("getActualTCPForce", ft) - #print("tau", tau) - ft_readings.append(ft) - end = time.time() - diff = end - start - if diff < robot.dt: - time.sleep(robot.dt - diff) - - ft_readings = np.array(ft_readings) - avg = np.average(ft_readings, axis=0) - print("average ft time", avg) - return avg - def getArgs(): ####################################################################### # generic arguments # @@ -75,7 +52,7 @@ def getArgs(): to something between 0 and 1, 1.0 by default because for dmp. \ BE CAREFUL WITH THIS.", default=1.0) parser.add_argument('--max-iterations', type=int, \ - help="maximum allowable iteration number (it runs at 500Hz)", default=50000) + help="maximum allowable iteration number (it runs at 500Hz)", default=500000) ####################################################################### # your controller specific arguments # ####################################################################### @@ -159,6 +136,8 @@ def getArgs(): help="number of max clik iterations to get to the first point", default=10000) parser.add_argument('--max-running-clik-iterations', type=int, \ help="number of max clik iterations between path points", default=1000) + parser.add_argument('--debug-prints', action=argparse.BooleanOptionalAction, \ + help="print some debug info", default=False) args = parser.parse_args() if args.gripper and args.simulation: @@ -167,11 +146,6 @@ def getArgs(): return args -# go and pick up the marker -def getMarker(q_init): - pass - - ####################################################################### # control loop # ####################################################################### @@ -180,23 +154,6 @@ def getMarker(q_init): def controller(): pass -# TODO: -# regarding saving data you have 2 options: -# 1) explicitely return what you want to save - you can't magically read local variables -# 2) make controlLoop a class and then save handle the saving behind the scenes - -# now you these variables are saved in a class so they're not local variables -# option 1 is clearly more hands-on and thus worse -# option 2 introduces a third big class and makes everything convoluted. -# for now, we go for option 1) because it's simpler to implement and deal with. -# but in the future, implementing 2) should be tried. you really have to try -# to do it cleanly to see how good/bad it is. -# in that case you'd most likely want to inherit ControlLoopManager and go from there. -# you'd still need to specify what you're saving with self.that_variable so no matter -# there's no running away from that in any case. -# it's 1) for now, it's the only non-idealy-clean part of this solution, and it's ok really. -# TODO but also look into something fancy like some decorator or something and try -# to find option 3) - # control loop to be passed to ControlLoopManager def controlLoopPointImpedance(wrench_offset, q_init, controller, robot, i, past_data): breakFlag = False @@ -204,56 +161,78 @@ def controlLoopPointImpedance(wrench_offset, q_init, controller, robot, i, past_ save_past_dict = {} log_item = {} q = robot.getQ() - # TODO look into UR code/api for estimating the same - # based on currents in the joints. - # it's probably worse, but maybe some sensor fusion-type thing - # is actually better, who knows. - # also you probably want to do the fusion of that onto tau (got from J.T @ wrench) - # evil hack because wrench is not zeros (why? - no idea whatsoever) + Mtool = robot.getMtool() wrench = robot.getWrench() log_item['wrench_raw'] = wrench.reshape((6,)) wrench = wrench - wrench_offset - # deepcopy for good coding practise (and correctness here) save_past_dict['wrench'] = copy.deepcopy(wrench) + # deepcopy for good coding practise (and correctness here) +# save_past_dict['wrench'] = copy.deepcopy(wrench) # rolling average #wrench = np.average(np.array(past_data['wrench']), axis=0) # first-order low pass filtering instead # beta is a smoothing coefficient, smaller values smooth more, has to be in [0,1] - beta = 0.01 + beta = 0.1 wrench = beta * wrench + (1 - beta) * past_data['wrench'][-1] #Z = np.diag(np.array([0.6, 0.6, 1.0, 0.5, 0.5, 0.5])) #Z = np.diag(np.array([0.6, 1.0, 0.6, 0.5, 0.5, 0.5])) #Z = np.diag(np.array([1.0, 1.0, 0.1, 1.0, 1.0, 1.0])) #Z = np.diag(np.ones(6)) - copy_wrench = copy.deepcopy(wrench) + #copy_wrench = copy.deepcopy(wrench) # wrench[1] = - #Z = np.diag(np.array([1.0, 1.0, -1.0, 1.0, 1.0, 1.0])) - Z = np.diag(np.ones(6)) - #Z = np.diag(np.array([0.0, 1.0, 0.0, 0.0, 0.0, 0.0])) + Z = np.diag(np.array([1.0, 1.0, 2.0, 1.0, 1.0, 1.0])) + #Z = np.diag(np.ones(6)) + ##### TODO try this cartesian test + #spatial_x = pin.SE3().setIdentity() + #spatial_x.translation = np.array([1.0, 0.0, 0.0]) + #Z = Mtool.actInv(spatial_x).vector + #Z = np.diag(np.array([1.0, 0.0, 0.0, 0.0, 0.0, 0.0])) #Z = np.diag(np.array([1.0, 0.6, 1.0, 0.5, 0.5, 0.5])) # the robot gives the wrench in the base frame for some unknown reason - wrench = robot.getMtool().toDualActionMatrix().T @ wrench + #wrench = robot.getMtool().toDualActionMatrix().T @ wrench + mapping = np.zeros((6,6)) + mapping[0:3, 0:3] = Mtool.rotation + mapping[3:6, 3:6] = Mtool.rotation + #TODO # this might be expressed in the spatial frame + wrench = mapping.T @ wrench + wrench = Z @ wrench if i % 25 == 0: - for w in wrench: - if w < 0: - print(np.round(w, 3), end=", ") - else: - print(np.round(w, 3), end=', ') - print("") + #print(Z) + print("================================") + print(*wrench.round(1)) +# if i % 25 == 0: +# for w in wrench: +# if w < 0: +# print(np.round(w, 3), end=", ") +# else: +# print(np.round(w, 3), end=', ') +# print("") pin.forwardKinematics(robot.model, robot.data, q) + # this jacobian starts at the end of the end-effector. + # but the wrench is probably modified wrt tip of the end effector + # because we defined the load in the ur inteface thing. + # so that might cause some offset. + # test for this: + # when i touch the f/t sensor directly, it gives on linear force, + # when i touch it at the tip of the end-effector, then it give both linear force + # and torque. so that means there's no memeing going on with internally transforming the wrench. + # plus the f/t sensor has no way of knowing where the contact is anyway, so you can't account + # for this even if you wanted to. + + # this jacobian might be wrong J = pin.computeJointJacobian(robot.model, robot.data, q, robot.JOINT_ID) dq = robot.getQd()[:6].reshape((6,1)) # get joint tau = J.T @ wrench + if i % 25 == 0: + print(*tau.round(1)) tau = tau[:6].reshape((6,1)) # compute control law: # - feedback the position - #print(q_init[:6]) - #print(q[:6]) - #print(args.alpha * tau) - vel_cmd = args.kp * (q_init[:6].reshape((6,1)) - q[:6].reshape((6,1))) + args.alpha * tau - args.kv * dq - #print(vel_cmd) + # kv is not needed if we're running velocity control + vel_cmd = args.kp * (q_init[:6].reshape((6,1)) - q[:6].reshape((6,1))) + args.alpha * tau + #vel_cmd = np.zeros(6) robot.sendQd(vel_cmd) # immediatelly stop if something weird happened (some non-convergence) @@ -277,7 +256,7 @@ if __name__ == "__main__": robot = RobotManager(args) # calibrate FT first - wrench_offset = calibrateFT(robot) + wrench_offset = robot.calibrateFT() # TODO and NOTE the weight, TCP and inertial matrix needs to be set on the robot # you already found an API in rtde_control for this, just put it in initialization @@ -307,13 +286,10 @@ if __name__ == "__main__": # and now we can actually run log_dict, final_iteration = loop_manager.run() - for i in range(300): - vel_cmd = np.zeros(6) - self.rtde_control.speedJ(vel_cmd, 0.1, 1.0 / 500) #plotFromDict(log_dict, args) - # plot results - plotFromDict(log_dict, args) - robot.stopHandler(None, None) + # plotting is now initiated in stophandler because then we get the plot + # even if we end sooner + loop_manager.stopHandler(log_dict, args) # TODO: add some math to analyze path precision diff --git a/python/examples/test_gripper.py b/python/examples/test_gripper.py index b23d38505573512f11ff7d4f5db8c3250f5f90fd..366a6a583b562b14ff7c0dd4ac137ea6ee860e98 100644 --- a/python/examples/test_gripper.py +++ b/python/examples/test_gripper.py @@ -58,6 +58,43 @@ def get_args(): the simulation yet, sorry :/ . You can have only 1 these flags right now') return args +def readFromGripper(robot): + did = 0 + robot.gripper.move_and_wait_for_pos(0,255,1) + time.sleep(2) + robot.gripper.move_and_wait_for_pos(255,255,1) + time.sleep(2) + # real value + #offset_open = 218 + offset_open = 255 + + for i in range(5): + robot.gripper.move_and_wait_for_pos(offset_open, 1, 1) + print("dropping", offset_open) + print("current_position", robot.gripper.get_current_position()) + time.sleep(4) + +# exit() + + robot.gripper.move_and_wait_for_pos(255, 1, 255) + print("holding", 255) + print("current_position", robot.gripper.get_current_position()) + did += 1 + time.sleep(5) +# for i in range(255): +# start = time.time() +# robot.gripper.move_and_wait_for_pos(offset - i, 255, 10) +# print(offset - i, robot.gripper.get_current_position()) +# did += 1 +# end = time.time() +# #time.sleep(10/125 - (end - start)) +# time.sleep(5) +# print("read", did, "times") +# robot.gripper.move(255, 255, 255) +# for i in range(1250): +# print(i, robot.gripper.get_current_position()) +# did += 1 +# time.sleep(1/125) # TODO: when this makes some sense, @@ -164,14 +201,17 @@ def gripperTorsionalSlipControlLoop(robot, clik_controller, i, past_data): if __name__ == "__main__": args = get_args() robot = RobotManager(args) - controlLoop = partial(gripperPositionControlLoop, robot, clik_controller) - log_dict = { - 'x' : np.zeros((args.max_iterations, 1)), - 'xd' : np.zeros((args.max_iterations, 1)), - 'xdd' : np.zeros((args.max_iterations, 1)), - } - # we're not using any past data or logging, hence the empty arguments - loop_manager = ControlLoopManager(robot, controlLoop, args, {}, log_dict) - log_dict, final_iteration = loop_manager.run() - saveLog(log_dict, final_iteration, args) + readFromGripper(robot) + + # real stuff for later +# controlLoop = partial(gripperPositionControlLoop, robot, clik_controller) +# log_dict = { +# 'x' : np.zeros((args.max_iterations, 1)), +# 'xd' : np.zeros((args.max_iterations, 1)), +# 'xdd' : np.zeros((args.max_iterations, 1)), +# } +# # we're not using any past data or logging, hence the empty arguments +# loop_manager = ControlLoopManager(robot, controlLoop, args, {}, log_dict) +# log_dict, final_iteration = loop_manager.run() +# saveLog(log_dict, final_iteration, args) diff --git a/python/ur_simple_control.egg-info/PKG-INFO b/python/ur_simple_control.egg-info/PKG-INFO index b15b402cdc66b7291a2d30d186c855ea27331755..84b865bdb559c9c6924c033eb1baba2982422ea7 100644 --- a/python/ur_simple_control.egg-info/PKG-INFO +++ b/python/ur_simple_control.egg-info/PKG-INFO @@ -1,5 +1,5 @@ Metadata-Version: 2.1 -Name: ur-simple-control +Name: ur_simple_control Version: 0.1 Summary: Collection of control algorithms for the UR5e arm based on the ur_rtde interface for communication and pinocchio for calculations. Home-page: https://gitlab.control.lth.se/marko-g/ur_simple_control diff --git a/python/ur_simple_control/__pycache__/__init__.cpython-311.pyc b/python/ur_simple_control/__pycache__/__init__.cpython-311.pyc new file mode 100644 index 0000000000000000000000000000000000000000..6730f1e95d99f25500f6b1680857af2968134e4f Binary files /dev/null and b/python/ur_simple_control/__pycache__/__init__.cpython-311.pyc differ diff --git a/python/ur_simple_control/__pycache__/managers.cpython-310.pyc b/python/ur_simple_control/__pycache__/managers.cpython-310.pyc index 2fc97dcccb20512aad35f4827b79036aaa833b93..e9b96271a7b765d8cd998b4bf188ba6f4beb244c 100644 Binary files a/python/ur_simple_control/__pycache__/managers.cpython-310.pyc and b/python/ur_simple_control/__pycache__/managers.cpython-310.pyc differ diff --git a/python/ur_simple_control/__pycache__/managers.cpython-311.pyc b/python/ur_simple_control/__pycache__/managers.cpython-311.pyc new file mode 100644 index 0000000000000000000000000000000000000000..2d434f1f67bac8ac32904caaf55e1e0b9754ddce Binary files /dev/null and b/python/ur_simple_control/__pycache__/managers.cpython-311.pyc differ diff --git a/python/ur_simple_control/basics/__pycache__/__init__.cpython-311.pyc b/python/ur_simple_control/basics/__pycache__/__init__.cpython-311.pyc new file mode 100644 index 0000000000000000000000000000000000000000..365e03849ae95513d34c4a86d71412c495a29df3 Binary files /dev/null and b/python/ur_simple_control/basics/__pycache__/__init__.cpython-311.pyc differ diff --git a/python/ur_simple_control/basics/__pycache__/basics.cpython-311.pyc b/python/ur_simple_control/basics/__pycache__/basics.cpython-311.pyc new file mode 100644 index 0000000000000000000000000000000000000000..bd8ded4dfba677133962cb31a6759bb16044798a Binary files /dev/null and b/python/ur_simple_control/basics/__pycache__/basics.cpython-311.pyc differ diff --git a/python/ur_simple_control/clik/__pycache__/__init__.cpython-311.pyc b/python/ur_simple_control/clik/__pycache__/__init__.cpython-311.pyc new file mode 100644 index 0000000000000000000000000000000000000000..46c82e11fbe0ff3bb421e7f1e4c8aec6e35c9363 Binary files /dev/null and b/python/ur_simple_control/clik/__pycache__/__init__.cpython-311.pyc differ diff --git a/python/ur_simple_control/clik/__pycache__/clik_point_to_point.cpython-310.pyc b/python/ur_simple_control/clik/__pycache__/clik_point_to_point.cpython-310.pyc index 6f41384a5420130817fc7462a78e18e0eb2c3140..a6897fb47e96610168c614014758de098891cfc6 100644 Binary files a/python/ur_simple_control/clik/__pycache__/clik_point_to_point.cpython-310.pyc and b/python/ur_simple_control/clik/__pycache__/clik_point_to_point.cpython-310.pyc differ diff --git a/python/ur_simple_control/clik/__pycache__/clik_point_to_point.cpython-311.pyc b/python/ur_simple_control/clik/__pycache__/clik_point_to_point.cpython-311.pyc new file mode 100644 index 0000000000000000000000000000000000000000..6b95c52eca9803e3be3409010974b2933bc51953 Binary files /dev/null and b/python/ur_simple_control/clik/__pycache__/clik_point_to_point.cpython-311.pyc differ diff --git a/python/ur_simple_control/clik/__pycache__/clik_trajectory_following.cpython-310.pyc b/python/ur_simple_control/clik/__pycache__/clik_trajectory_following.cpython-310.pyc index 322e8243ac4f9a77b5dd3edd6ae80436ae5961e4..58f6cc2b5c5644230f8fe348836183f1c435f437 100644 Binary files a/python/ur_simple_control/clik/__pycache__/clik_trajectory_following.cpython-310.pyc and b/python/ur_simple_control/clik/__pycache__/clik_trajectory_following.cpython-310.pyc differ diff --git a/python/ur_simple_control/clik/__pycache__/clik_trajectory_following.cpython-311.pyc b/python/ur_simple_control/clik/__pycache__/clik_trajectory_following.cpython-311.pyc new file mode 100644 index 0000000000000000000000000000000000000000..612d7bda706bce4f89d7d0a106fc828bd606beb5 Binary files /dev/null and b/python/ur_simple_control/clik/__pycache__/clik_trajectory_following.cpython-311.pyc differ diff --git a/python/ur_simple_control/clik/clik_point_to_point.py b/python/ur_simple_control/clik/clik_point_to_point.py index a0470fa1c6214b7d780ffc98eb36ff5a5a3b04e3..c101839febbabbe17622dd0e81741568b74af6cd 100644 --- a/python/ur_simple_control/clik/clik_point_to_point.py +++ b/python/ur_simple_control/clik/clik_point_to_point.py @@ -182,10 +182,12 @@ def moveUntilContactControlLoop(speed, robot, clik_controller, i, past_data): pin.forwardKinematics(robot.model, robot.data, q) # break if wrench is nonzero basically wrench = robot.getWrench() -# print(np.linalg.norm(wrench)) + # TODO: move this to the robot class + wrench = wrench - robot.wrench_offset # TODO: remove magick number # it is empirical bla bla, but make it an argument at least if np.linalg.norm(wrench) > 4.2: + print("hit with", np.linalg.norm(wrench)) breakFlag = True # pin.computeJointJacobian is much different than the C++ version lel J = pin.computeJointJacobian(robot.model, robot.data, q, robot.JOINT_ID) @@ -209,7 +211,7 @@ def moveUntilContact(args, robot, speed): log_dict, final_iteration = loop_manager.run() # TODO: remove, this isn't doing anything time.sleep(0.01) - print("Colision detected!!") + print("Collision detected!!") """ moveL diff --git a/python/ur_simple_control/clik/clik_trajectory_following.py b/python/ur_simple_control/clik/clik_trajectory_following.py index 99b082c78a14545b8acabcedb3cac47525b4fc5f..63c2779b1aa8996b7372b34b8a82ca83052695ef 100644 --- a/python/ur_simple_control/clik/clik_trajectory_following.py +++ b/python/ur_simple_control/clik/clik_trajectory_following.py @@ -87,7 +87,8 @@ def clikCartesianPathIntoJointPath(path, args, robot, \ for i in range(len(path)): path[i] = transf_body_to_task_frame.act(path[i]) # TODO remove print, write a test for this instead - print(path) + if args.debug_prints: + print(path) # TODO: finish this # - pass clik alg as argument @@ -112,7 +113,8 @@ def clikCartesianPathIntoJointPath(path, args, robot, \ err_vector = pin.log6(SEerror).vector if np.linalg.norm(err_vector) < args.clik_goal_error: if not n_iter == args.max_init_clik_iterations: - print("converged in", i) + if args.debug_prints: + print("converged in", i) break J = pin.computeJointJacobian(robot.model, robot.data, q, robot.JOINT_ID) qd = clikController(J, err_vector) @@ -126,7 +128,11 @@ def clikCartesianPathIntoJointPath(path, args, robot, \ n_iter = args.max_running_clik_iterations else: if i == args.max_running_clik_iterations - 1: - print("DID NOT CONVERGE") + print("DID NOT CONVERGE -- exiting") + robot.stopHandler(None, None) + robot.stopHandler(None, None) + robot.stopHandler(None, None) + exit() ############################################## # save the obtained joint-space trajectory # diff --git a/python/ur_simple_control/dmp/__pycache__/__init__.cpython-311.pyc b/python/ur_simple_control/dmp/__pycache__/__init__.cpython-311.pyc new file mode 100644 index 0000000000000000000000000000000000000000..6d20d4dc491caffb2381d4d29f6e5fa47875ecf5 Binary files /dev/null and b/python/ur_simple_control/dmp/__pycache__/__init__.cpython-311.pyc differ diff --git a/python/ur_simple_control/dmp/__pycache__/dmp.cpython-311.pyc b/python/ur_simple_control/dmp/__pycache__/dmp.cpython-311.pyc new file mode 100644 index 0000000000000000000000000000000000000000..58f7080212cb9966c81870f3342bd6193b1976c6 Binary files /dev/null and b/python/ur_simple_control/dmp/__pycache__/dmp.cpython-311.pyc differ diff --git a/python/ur_simple_control/managers.py b/python/ur_simple_control/managers.py index 9e4962bb904975d1e1bfa87854041db75fff5b25..c20166aab0bc98946cde3be2c72e066686766143 100644 --- a/python/ur_simple_control/managers.py +++ b/python/ur_simple_control/managers.py @@ -17,6 +17,7 @@ import copy import signal from ur_simple_control.util.get_model import get_model from collections import deque +from ur_simple_control.visualize.visualize import plotFromDict """ general notes @@ -99,6 +100,7 @@ Other info: """ class ControlLoopManager: def __init__(self, robot_manager, controlLoop, args, save_past_dict, log_dict): + signal.signal(signal.SIGINT, self.stopHandler) self.max_iterations = args.max_iterations # NOTE the robot manager is all over the place, # there might be a better design approach to that @@ -133,6 +135,7 @@ class ControlLoopManager: this is done via the breakFlag """ def run(self): + self.final_iteration = 0 for i in range(self.max_iterations): start = time.time() # TODO make the arguments to controlLoop kwargs or whatever @@ -165,11 +168,12 @@ class ControlLoopManager: end = time.time() diff = end - start if self.robot_manager.dt < diff: - print("missed deadline by", diff - self.robot_manager.dt) + if self.args.debug_prints: + print("missed deadline by", diff - self.robot_manager.dt) continue else: time.sleep(self.robot_manager.dt - diff) - final_iteration = i + self.final_iteration = i # TODO: provide a debug flag for this # if i < self.max_iterations -1: # print("success in", i, "iterations!") @@ -179,8 +183,31 @@ class ControlLoopManager: # if not self.args.pinocchio_only: # self.robot_manager.stopHandler(None, None) - return self.log_dict, final_iteration + return self.log_dict, self.final_iteration + """ + stopHandler + ----------- + TODO: make ifs for simulation too + can have self as first argument apparently. + upon receiving SIGINT it sends zeros for speed commands to + stop the robot + """ + def stopHandler(self, signum, frame): + #plotFromDict(signum, frame) + print('sending 300 speedjs full of zeros and exiting') + for i in range(300): + vel_cmd = np.zeros(6) + self.robot_manager.rtde_control.speedJ(vel_cmd, 0.1, 1.0 / 500) + # hopefully this actually stops it + self.robot_manager.rtde_control.speedStop(1) + print("sending a stopj as well") + self.robot_manager.rtde_control.stopJ(1) + print("putting it to freedrive for good measure too") + self.robot_manager.rtde_control.freedriveMode() + plotFromDict(self.log_dict, self.final_iteration, self.args) + self.robot_manager.rtde_control.endFreedriveMode() + exit() """ robotmanager: @@ -215,7 +242,7 @@ class RobotManager: # if you just stop it the program with Ctrl-C, it will continue running # the last speedj lmao. # there's also an actual stop command, but sending 0s works so i'm not changing it - signal.signal(signal.SIGINT, self.stopHandler) + #signal.signal(signal.SIGINT, self.stopHandler) self.args = args self.pinocchio_only = args.pinocchio_only @@ -237,8 +264,11 @@ class RobotManager: #viz.initViewer() #viz.loadViewerModel() #viz.display(q0) + # TODO: make general if self.gripper_flag and not self.pinocchio_only: self.gripper = RobotiqGripper() + self.gripper.connect("192.168.1.102", 63352) + self.gripper.activate() # TODO: this is obviously at least a partial redundancy w.r.t. the pinocchio data object # however i have no time to investigate what i get or don't get there # so i'll just leave this be. but fix this!!!! we don't want to duplicate information!! @@ -262,7 +292,9 @@ class RobotManager: if args.gripper: self.gripper.connect("192.168.1.102", 63352) # this is a blocking call - self.gripper.activate() + # this isn't actually needed and it's annoying + # TODO: test after rebooting the robot +# self.gripper.activate() else: self.rtde_control = RTDEControlInterface("127.0.0.1") self.rtde_receive = RTDEReceiveInterface("127.0.0.1") @@ -300,23 +332,43 @@ class RobotManager: # error limit # TODO this is clik specific, put it in a better place self.goal_error = args.goal_error + # this is probably the right place to manage this + self.wrench_offset = np.zeros(6) + + """ - stopHandler + calibrateFT ----------- - TODO: make ifs for simulation too - can have self as first argument apparently. - upon receiving SIGINT it sends zeros for speed commands to - stop the robot + Read from the f/t sensor a bit, average the results + and return the result. + This can be used to offset the bias of the f/t sensor. + NOTE: this is not an ideal solution. + ALSO TODO: test whether the offset changes when + the manipulator is in different poses. """ - def stopHandler(self, signum, frame): - print('sending 300 speedjs full of zeros and exiting') - for i in range(300): - vel_cmd = np.zeros(6) - self.rtde_control.speedJ(vel_cmd, 0.1, 1.0 / 500) - # hopefully this actually stops it - self.rtde_control.speedStop(self.acceleration) - exit() + def calibrateFT(self): + ft_readings = [] + print("Will read from f/t sensors for a some number of seconds") + print("and give you the average.") + print("Use this as offset.") + for i in range(2000): + start = time.time() + q = self.rtde_receive.getActualQ() + ft = self.rtde_receive.getActualTCPForce() + tau = self.rtde_control.getJointTorques() + current = self.rtde_receive.getActualCurrent() + ft_readings.append(ft) + end = time.time() + diff = end - start + if diff < self.dt: + time.sleep(self.dt - diff) + + ft_readings = np.array(ft_readings) + avg = np.average(ft_readings, axis=0) + self.wrench_offset = avg + print("average ft time", avg) + return avg """ step diff --git a/python/ur_simple_control/robot_descriptions/__pycache__/__init__.cpython-311.pyc b/python/ur_simple_control/robot_descriptions/__pycache__/__init__.cpython-311.pyc new file mode 100644 index 0000000000000000000000000000000000000000..0b438269c81061782619270835f25ca18b5845e3 Binary files /dev/null and b/python/ur_simple_control/robot_descriptions/__pycache__/__init__.cpython-311.pyc differ diff --git a/python/ur_simple_control/robot_descriptions/urdf/__pycache__/__init__.cpython-311.pyc b/python/ur_simple_control/robot_descriptions/urdf/__pycache__/__init__.cpython-311.pyc new file mode 100644 index 0000000000000000000000000000000000000000..d70d22745d75183a65543fa1b8c7a0c8298cd164 Binary files /dev/null and b/python/ur_simple_control/robot_descriptions/urdf/__pycache__/__init__.cpython-311.pyc differ diff --git a/python/ur_simple_control/util/__pycache__/__init__.cpython-311.pyc b/python/ur_simple_control/util/__pycache__/__init__.cpython-311.pyc new file mode 100644 index 0000000000000000000000000000000000000000..cc7e2ef70b43104b84abbcf2d7964c31e18b8618 Binary files /dev/null and b/python/ur_simple_control/util/__pycache__/__init__.cpython-311.pyc differ diff --git a/python/ur_simple_control/util/__pycache__/calib_board_hacks.cpython-310.pyc b/python/ur_simple_control/util/__pycache__/calib_board_hacks.cpython-310.pyc index 381e01577542314df3b46fd5df48a3467ae9ca1f..44996bbae02787198a7d90d6c360db1d72f5434c 100644 Binary files a/python/ur_simple_control/util/__pycache__/calib_board_hacks.cpython-310.pyc and b/python/ur_simple_control/util/__pycache__/calib_board_hacks.cpython-310.pyc differ diff --git a/python/ur_simple_control/util/__pycache__/calib_board_hacks.cpython-311.pyc b/python/ur_simple_control/util/__pycache__/calib_board_hacks.cpython-311.pyc new file mode 100644 index 0000000000000000000000000000000000000000..57e83edc7c7b02ed7d437219bc112d7cbf82253b Binary files /dev/null and b/python/ur_simple_control/util/__pycache__/calib_board_hacks.cpython-311.pyc differ diff --git a/python/ur_simple_control/util/__pycache__/draw_path.cpython-311.pyc b/python/ur_simple_control/util/__pycache__/draw_path.cpython-311.pyc new file mode 100644 index 0000000000000000000000000000000000000000..23e3c67c35826439c4c8181d26cb517804e294a3 Binary files /dev/null and b/python/ur_simple_control/util/__pycache__/draw_path.cpython-311.pyc differ diff --git a/python/ur_simple_control/util/__pycache__/freedrive.cpython-311.pyc b/python/ur_simple_control/util/__pycache__/freedrive.cpython-311.pyc new file mode 100644 index 0000000000000000000000000000000000000000..ab42d0ed7150f7f0ccd976b8ca6494a1da93e2a5 Binary files /dev/null and b/python/ur_simple_control/util/__pycache__/freedrive.cpython-311.pyc differ diff --git a/python/ur_simple_control/util/__pycache__/get_model.cpython-311.pyc b/python/ur_simple_control/util/__pycache__/get_model.cpython-311.pyc new file mode 100644 index 0000000000000000000000000000000000000000..4f5e2990e6644b46ae0420a9cac8ef5da6c2e1ed Binary files /dev/null and b/python/ur_simple_control/util/__pycache__/get_model.cpython-311.pyc differ diff --git a/python/ur_simple_control/util/__pycache__/logging_utils.cpython-311.pyc b/python/ur_simple_control/util/__pycache__/logging_utils.cpython-311.pyc new file mode 100644 index 0000000000000000000000000000000000000000..759cafe5cf649d89b5731ceaa655e38fdaa3a52f Binary files /dev/null and b/python/ur_simple_control/util/__pycache__/logging_utils.cpython-311.pyc differ diff --git a/python/ur_simple_control/util/__pycache__/robotiq_gripper.cpython-310.pyc b/python/ur_simple_control/util/__pycache__/robotiq_gripper.cpython-310.pyc index 9310cab2c4819c34952aa62d53df3b15536a6460..746f37b9141da8c59acadece47171aa6ef7f727c 100644 Binary files a/python/ur_simple_control/util/__pycache__/robotiq_gripper.cpython-310.pyc and b/python/ur_simple_control/util/__pycache__/robotiq_gripper.cpython-310.pyc differ diff --git a/python/ur_simple_control/util/__pycache__/robotiq_gripper.cpython-311.pyc b/python/ur_simple_control/util/__pycache__/robotiq_gripper.cpython-311.pyc new file mode 100644 index 0000000000000000000000000000000000000000..fd1cbb042ac4e18c03f4548f12b5ef3c475a0fd8 Binary files /dev/null and b/python/ur_simple_control/util/__pycache__/robotiq_gripper.cpython-311.pyc differ diff --git a/python/ur_simple_control/util/calib_board_hacks.py b/python/ur_simple_control/util/calib_board_hacks.py index 66b5d42bcffdbcbabbb6e6dc946a13b30e02c9cc..0fa20509cc0893b0b75a56e04267d1bcb91f4ee3 100644 --- a/python/ur_simple_control/util/calib_board_hacks.py +++ b/python/ur_simple_control/util/calib_board_hacks.py @@ -175,16 +175,22 @@ def handleUserToHandleTCPPose(robot): continue robot.rtde_control.endFreedriveMode() -def getSpeedInDirectionOfN(R): +def getSpeedInDirectionOfN(R, board_axis): # TODO: make this general + # TODO: FIX WHAT YOU MEAN BY Y AND Z + ############ # this is for z - #z_of_rot = R[:,2] - #speed = np.array([z_of_rot[0], z_of_rot[1], z_of_rot[2], 0, 0, 0]) + if board_axis == 'y': + z_of_rot = R[:,2] + speed = np.array([z_of_rot[0], z_of_rot[1], z_of_rot[2], 0, 0, 0]) + ############ # this is for y - y_of_rot = R[:,1] - # try z again - #z_of_rot = R[:,2] - speed = np.array([y_of_rot[0], y_of_rot[1], y_of_rot[2], 0, 0, 0]) + elif board_axis == 'z': + y_of_rot = R[:,1] + speed = np.array([y_of_rot[0], y_of_rot[1], y_of_rot[2], 0, 0, 0]) + else: + print("you passed", board_axis, ", but it has to be 'z' or 'y'") + exit() # make speed small no matter what speed = speed / np.linalg.norm(speed) # nice 'n' slow @@ -192,6 +198,7 @@ def getSpeedInDirectionOfN(R): speed = speed / 40 #speed[2] = -1 * speed[2] speed = -1 * speed + print("going in", speed, "direction") return speed # TODO @@ -230,7 +237,7 @@ def calibratePlane(args, robot, plane_width, plane_height, n_tests): R = copy.deepcopy(R_initial_estimate) # go in the TCP z direction - speed = getSpeedInDirectionOfN(R_initial_estimate) + speed = getSpeedInDirectionOfN(R_initial_estimate, args.board_axis) print("speed", speed) # get q, do forward kinematics, get current TCP R @@ -254,9 +261,11 @@ def calibratePlane(args, robot, plane_width, plane_height, n_tests): # go back up (assuming top-left is highest incline) # TODO: make this assumption an argument, or print it at least # THIS IS Z - #new_pose.translation[2] = init_pose.translation[2] + if args.board_axis == 'z': + new_pose.translation[2] = init_pose.translation[2] # THIS IS Y - new_pose.translation[1] = init_pose.translation[1] + if args.board_axis == 'y': + new_pose.translation[1] = init_pose.translation[1] moveL(args, robot, new_pose) q = robot.getQ() pin.forwardKinematics(robot.model, robot.data, np.array(q)) @@ -264,9 +273,11 @@ def calibratePlane(args, robot, plane_width, plane_height, n_tests): # this is also an ugly ugly hack new_pose.translation[0] = init_pose.translation[0] + np.random.random() * plane_width # THIS IS Z - #new_pose.translation[1] = init_pose.translation[1] - np.random.random() * plane_height + if args.board_axis == 'z': + new_pose.translation[1] = init_pose.translation[1] - np.random.random() * plane_height # THIS IS Y - new_pose.translation[2] = init_pose.translation[2] - np.random.random() * plane_height + if args.board_axis == 'y': + new_pose.translation[2] = init_pose.translation[2] - np.random.random() * plane_height moveL(args, robot, new_pose) # fix orientation new_pose.rotation = R @@ -275,7 +286,7 @@ def calibratePlane(args, robot, plane_width, plane_height, n_tests): if i > 2: n = fitNormalVector(positions) R = constructFrameFromNormalVector(R_initial_estimate, n) - speed = getSpeedInDirectionOfN(R) + speed = getSpeedInDirectionOfN(R, args.board_axis) print("finished estimating R") @@ -283,9 +294,11 @@ def calibratePlane(args, robot, plane_width, plane_height, n_tests): new_pose = copy.deepcopy(current_pose) # go back up # Z - new_pose.translation[2] = init_pose.translation[2] + if args.board_axis == 'z': + new_pose.translation[2] = init_pose.translation[2] # Y - new_pose.translation[1] = init_pose.translation[1] + if args.board_axis == 'y': + new_pose.translation[1] = init_pose.translation[1] moveL(args, robot, new_pose) # go back to the same spot new_pose.translation[0] = init_pose.translation[0] @@ -299,7 +312,7 @@ def calibratePlane(args, robot, plane_width, plane_height, n_tests): # --> now you're ready to measure the translation vector correctly # for this we want to go directly into the board print("i'll estimate the translation vector now") - speed = getSpeedInDirectionOfN(R) + speed = getSpeedInDirectionOfN(R, args.board_axis) moveUntilContact(args, robot, speed) diff --git a/python/ur_simple_control/util/ft_calibration.py b/python/ur_simple_control/util/ft_calibration.py new file mode 100644 index 0000000000000000000000000000000000000000..a8af630c823260fe5833cfba6cbdef69310e3b83 --- /dev/null +++ b/python/ur_simple_control/util/ft_calibration.py @@ -0,0 +1,19 @@ + +def calibrateFT(robot): + ft_readings = [] + for i in range(2000): + start = time.time() + q = robot.rtde_receive.getActualQ() + ft = robot.rtde_receive.getActualTCPForce() + tau = robot.rtde_control.getJointTorques() + current = robot.rtde_receive.getActualCurrent() + ft_readings.append(ft) + end = time.time() + diff = end - start + if diff < robot.dt: + time.sleep(robot.dt - diff) + + ft_readings = np.array(ft_readings) + avg = np.average(ft_readings, axis=0) + print("average ft time", avg) + return avg diff --git a/python/ur_simple_control/visualize/__pycache__/__init__.cpython-311.pyc b/python/ur_simple_control/visualize/__pycache__/__init__.cpython-311.pyc new file mode 100644 index 0000000000000000000000000000000000000000..aba675302559b05bdf8aa8c563b486bbf526fd1f Binary files /dev/null and b/python/ur_simple_control/visualize/__pycache__/__init__.cpython-311.pyc differ diff --git a/python/ur_simple_control/visualize/__pycache__/make_run.cpython-311.pyc b/python/ur_simple_control/visualize/__pycache__/make_run.cpython-311.pyc new file mode 100644 index 0000000000000000000000000000000000000000..23e19ea34b35ec3423378895ac32ab709f55df04 Binary files /dev/null and b/python/ur_simple_control/visualize/__pycache__/make_run.cpython-311.pyc differ diff --git a/python/ur_simple_control/visualize/__pycache__/visualize.cpython-311.pyc b/python/ur_simple_control/visualize/__pycache__/visualize.cpython-311.pyc new file mode 100644 index 0000000000000000000000000000000000000000..1b8fab368fc8d0086e4066c6ee5f220f2bd77329 Binary files /dev/null and b/python/ur_simple_control/visualize/__pycache__/visualize.cpython-311.pyc differ diff --git a/python/ur_simple_control/visualize/manipulator_visual_motion_analyzer.py b/python/ur_simple_control/visualize/manipulator_visual_motion_analyzer.py index 10555675ccaa8555886d274389b1e1e238457a95..b4b9380a88a1498e52b9345abd85ba72d4b23ce0 100644 --- a/python/ur_simple_control/visualize/manipulator_visual_motion_analyzer.py +++ b/python/ur_simple_control/visualize/manipulator_visual_motion_analyzer.py @@ -876,8 +876,8 @@ if __name__ == "__main__": root = Tk() # TODO: change to something different obviously # or add a button to load or something, idc - log_data_file_name = "/home/gospodar/lund/praxis/ur_simple_control/python/examples/data/clik_run_001.pickle" - args_file_name = "/home/gospodar/lund/praxis/ur_simple_control/python/examples/data/clik_run_001_args.pickle" + log_data_file_name = "/home/gospodar/lund/praxis/projects/ur_simple_control/python/examples/data/clik_run_001.pickle" + args_file_name = "/home/gospodar/lund/praxis/projects/ur_simple_control/python/examples/data/clik_run_001_args.pickle" log_data, args = loadRunForAnalysis(log_data_file_name, args_file_name) log_data = cleanUpRun(log_data, log_data['qs'].shape[0], 200) robot = RobotManager(args) diff --git a/python/ur_simple_control/visualize/robot_stuff/__pycache__/InverseKinematics.cpython-311.pyc b/python/ur_simple_control/visualize/robot_stuff/__pycache__/InverseKinematics.cpython-311.pyc index e19567ae0945d05a0ef9d5b7593f2eaf8ca7e1b2..81bc2f37aa231c526f812026231dd727fce4febf 100644 Binary files a/python/ur_simple_control/visualize/robot_stuff/__pycache__/InverseKinematics.cpython-311.pyc and b/python/ur_simple_control/visualize/robot_stuff/__pycache__/InverseKinematics.cpython-311.pyc differ diff --git a/python/ur_simple_control/visualize/robot_stuff/__pycache__/drawing.cpython-311.pyc b/python/ur_simple_control/visualize/robot_stuff/__pycache__/drawing.cpython-311.pyc index 60bcda8221c70f3842b39da90028011be8e56d07..d2a79d892789ed5d043d63dd60327e7406378152 100644 Binary files a/python/ur_simple_control/visualize/robot_stuff/__pycache__/drawing.cpython-311.pyc and b/python/ur_simple_control/visualize/robot_stuff/__pycache__/drawing.cpython-311.pyc differ diff --git a/python/ur_simple_control/visualize/robot_stuff/__pycache__/drawing_for_anim.cpython-311.pyc b/python/ur_simple_control/visualize/robot_stuff/__pycache__/drawing_for_anim.cpython-311.pyc index b39611c8807a0497f50ad6faa2f76392b6793fb9..f2d4b539a9e209f4ee72fd81e1ec94f5f4debed2 100644 Binary files a/python/ur_simple_control/visualize/robot_stuff/__pycache__/drawing_for_anim.cpython-311.pyc and b/python/ur_simple_control/visualize/robot_stuff/__pycache__/drawing_for_anim.cpython-311.pyc differ diff --git a/python/ur_simple_control/visualize/robot_stuff/__pycache__/follow_curve.cpython-311.pyc b/python/ur_simple_control/visualize/robot_stuff/__pycache__/follow_curve.cpython-311.pyc index 8bf02d5aa7da680701e2164359fa19bae13fb63f..d6b1db7ea7b8d7d51b137c9a5a6167e09fd8afef 100644 Binary files a/python/ur_simple_control/visualize/robot_stuff/__pycache__/follow_curve.cpython-311.pyc and b/python/ur_simple_control/visualize/robot_stuff/__pycache__/follow_curve.cpython-311.pyc differ diff --git a/python/ur_simple_control/visualize/robot_stuff/__pycache__/forw_kinm.cpython-311.pyc b/python/ur_simple_control/visualize/robot_stuff/__pycache__/forw_kinm.cpython-311.pyc index ec97b7a1cca924c836514e165d58713cb9915c19..8ce06754984bf102f517d67911f123d9a2450c28 100644 Binary files a/python/ur_simple_control/visualize/robot_stuff/__pycache__/forw_kinm.cpython-311.pyc and b/python/ur_simple_control/visualize/robot_stuff/__pycache__/forw_kinm.cpython-311.pyc differ diff --git a/python/ur_simple_control/visualize/robot_stuff/__pycache__/inv_kinm.cpython-310.pyc b/python/ur_simple_control/visualize/robot_stuff/__pycache__/inv_kinm.cpython-310.pyc index 5b9bd3eda81c325bc8d9dfa41bbea95983485ac7..0398efc8bf587f5cf7d0449ca7d5ed8ffd8d2425 100644 Binary files a/python/ur_simple_control/visualize/robot_stuff/__pycache__/inv_kinm.cpython-310.pyc and b/python/ur_simple_control/visualize/robot_stuff/__pycache__/inv_kinm.cpython-310.pyc differ diff --git a/python/ur_simple_control/visualize/robot_stuff/__pycache__/inv_kinm.cpython-311.pyc b/python/ur_simple_control/visualize/robot_stuff/__pycache__/inv_kinm.cpython-311.pyc index 523e8c16464f8c63490ac3fca3f2ef086e483ae1..a1a7d7b3fee4c24af42dbb9f56b128ccd3d51e72 100644 Binary files a/python/ur_simple_control/visualize/robot_stuff/__pycache__/inv_kinm.cpython-311.pyc and b/python/ur_simple_control/visualize/robot_stuff/__pycache__/inv_kinm.cpython-311.pyc differ diff --git a/python/ur_simple_control/visualize/robot_stuff/__pycache__/joint_as_hom_mat.cpython-311.pyc b/python/ur_simple_control/visualize/robot_stuff/__pycache__/joint_as_hom_mat.cpython-311.pyc index 936a5cf11707e3e29e66b708b2fad513c0bec527..ae7fe28baef2a29d9ffc9307fdb9eb5dad48b285 100644 Binary files a/python/ur_simple_control/visualize/robot_stuff/__pycache__/joint_as_hom_mat.cpython-311.pyc and b/python/ur_simple_control/visualize/robot_stuff/__pycache__/joint_as_hom_mat.cpython-311.pyc differ diff --git a/python/ur_simple_control/visualize/robot_stuff/__pycache__/utils.cpython-311.pyc b/python/ur_simple_control/visualize/robot_stuff/__pycache__/utils.cpython-311.pyc index ac5e6c96318a30402f6390f79b59f8d9d753523f..bd0beaf38e2640efba3ad16919ec4d6a81f2961c 100644 Binary files a/python/ur_simple_control/visualize/robot_stuff/__pycache__/utils.cpython-311.pyc and b/python/ur_simple_control/visualize/robot_stuff/__pycache__/utils.cpython-311.pyc differ diff --git a/python/ur_simple_control/visualize/robot_stuff/__pycache__/webots_api_helper_funs.cpython-311.pyc b/python/ur_simple_control/visualize/robot_stuff/__pycache__/webots_api_helper_funs.cpython-311.pyc index fd4d62b162bb90fbf4b4b0b69abfcdf75bcc9425..6bb8b3b96da35c8c2f45694c13c101e1c2ba64e3 100644 Binary files a/python/ur_simple_control/visualize/robot_stuff/__pycache__/webots_api_helper_funs.cpython-311.pyc and b/python/ur_simple_control/visualize/robot_stuff/__pycache__/webots_api_helper_funs.cpython-311.pyc differ diff --git a/python/ur_simple_control/visualize/robot_stuff/inv_kinm.py b/python/ur_simple_control/visualize/robot_stuff/inv_kinm.py index 2906bfd60219df5c7150a1d3d26425a7b1f71318..ce04720a5bf41d6bdb496fc7bf1e4787a1674d82 100644 --- a/python/ur_simple_control/visualize/robot_stuff/inv_kinm.py +++ b/python/ur_simple_control/visualize/robot_stuff/inv_kinm.py @@ -7,8 +7,9 @@ from matplotlib.animation import FuncAnimation import matplotlib.colors as colr import sys import scipy.optimize -from qpsolvers import solve_qp -from qpsolvers import dense_solvers +# TODO put this back after you fix your installation +#from qpsolvers import solve_qp +#from qpsolvers import dense_solvers from scipy.linalg import sqrtm diff --git a/python/ur_simple_control/visualize/visualize.py b/python/ur_simple_control/visualize/visualize.py index ccee92a3c92e458720304dcb1c464e7413d65845..9e8c4677057aac406452ba5de2875c71a717da25 100644 --- a/python/ur_simple_control/visualize/visualize.py +++ b/python/ur_simple_control/visualize/visualize.py @@ -5,12 +5,12 @@ import matplotlib.pyplot as plt # make plot_data a dictionary. # every key is one subplot, and it's value # is what you plot -def plotFromDict(plot_data, args): +def plotFromDict(plot_data, final_iteration, args): # TODO cut zeros from data # TODO: replace with actual time # --> you should be able to extract/construct this from dmp data # or some timing - t = np.arange(args.max_iterations) + t = np.arange(final_iteration) # TODO make the plot number assignment general n_cols = 2 n_rows = 2 @@ -18,10 +18,10 @@ def plotFromDict(plot_data, args): subplot_col_row = str(n_cols) + str(n_rows) ax_dict ={} # TODO: choose a nice color palette - colors = plt.cm.jet(np.linspace(0, 1, len(plot_data))) for i, data_key in enumerate(plot_data): + colors = plt.cm.jet(np.linspace(0, 1, plot_data[data_key].shape[1])) ax_dict[data_key] = plt.subplot(int(subplot_col_row + str(i + 1))) for j in range(plot_data[data_key].shape[1]): - ax_dict[data_key].plot(t, plot_data[data_key][:,j], color=colors[i], label=data_key) + ax_dict[data_key].plot(t, plot_data[data_key][:final_iteration,j], color=colors[j], label=data_key + "_" + str(j)) ax_dict[data_key].legend() plt.show()